diff --git a/.github/ISSUE_TEMPLATE/bug-report.md b/.github/ISSUE_TEMPLATE/bug-report.md new file mode 100644 index 000000000..9f15b2b7c --- /dev/null +++ b/.github/ISSUE_TEMPLATE/bug-report.md @@ -0,0 +1,35 @@ +--- +name: "Bug Report" +about: Submit a bug report to help us improve GTSAM +--- + + + + + + + +## Description + + + +## Steps to reproduce + +1. +2. + + + +## Expected behavior + + + +## Environment + + + + + +## Additional information + + \ No newline at end of file diff --git a/.github/ISSUE_TEMPLATE/feature-request.md b/.github/ISSUE_TEMPLATE/feature-request.md new file mode 100644 index 000000000..e1e13650a --- /dev/null +++ b/.github/ISSUE_TEMPLATE/feature-request.md @@ -0,0 +1,24 @@ +--- +name: "Feature Request" +about: Submit a proposal/request for a new GTSAM feature +--- + +## Feature + + + +## Motivation + + + +## Pitch + + + +## Alternatives + + + +## Additional context + + \ No newline at end of file diff --git a/.github/ISSUE_TEMPLATE/questions-help-support.md b/.github/ISSUE_TEMPLATE/questions-help-support.md new file mode 100644 index 000000000..49dcefbd0 --- /dev/null +++ b/.github/ISSUE_TEMPLATE/questions-help-support.md @@ -0,0 +1,5 @@ +--- +name: "Questions/Help/Support" +--- + +Please post questions and support requests in the [GTSAM Google group](https://groups.google.com/forum/#!forum/gtsam-users) and not on Github. diff --git a/.gitignore b/.gitignore index 42bd27466..1d89cac25 100644 --- a/.gitignore +++ b/.gitignore @@ -1,4 +1,5 @@ /build* +/debug* .idea *.pyc *.DS_Store @@ -7,7 +8,6 @@ /examples/Data/pose3example-rewritten.txt *.txt.user *.txt.user.6d59f0c -/python-build/ *.pydevproject cython/venv cython/gtsam.cpp @@ -19,3 +19,5 @@ cython/gtsam_wrapper.pxd .env /.vs/ /CMakeSettings.json +# for QtCreator: +CMakeLists.txt.user* diff --git a/.travis.sh b/.travis.sh new file mode 100755 index 000000000..3cec20f53 --- /dev/null +++ b/.travis.sh @@ -0,0 +1,85 @@ +#!/bin/bash + +# common tasks before either build or test +function prepare () +{ + set -e # Make sure any error makes the script to return an error code + set -x # echo + + SOURCE_DIR=`pwd` + BUILD_DIR=build + + #env + git clean -fd || true + rm -fr $BUILD_DIR || true + mkdir $BUILD_DIR && cd $BUILD_DIR + + if [ -z "$CMAKE_BUILD_TYPE" ]; then + CMAKE_BUILD_TYPE=Debug + fi + + if [ -z "$GTSAM_ALLOW_DEPRECATED_SINCE_V4" ]; then + GTSAM_ALLOW_DEPRECATED_SINCE_V4=OFF + fi + + if [ ! -z "$GCC_VERSION" ]; then + sudo update-alternatives --install /usr/bin/gcc gcc /usr/bin/gcc-$GCC_VERSION 60 \ + --slave /usr/bin/g++ g++ /usr/bin/g++-$GCC_VERSION + sudo update-alternatives --set gcc /usr/bin/gcc-$GCC_VERSION + fi +} + +# common tasks after either build or test +function finish () +{ + # Print ccache stats + ccache -s + + cd $SOURCE_DIR +} + +# compile the code with the intent of populating the cache +function build () +{ + prepare + + cmake $SOURCE_DIR \ + -DCMAKE_BUILD_TYPE=$CMAKE_BUILD_TYPE \ + -DGTSAM_BUILD_TESTS=OFF \ + -DGTSAM_BUILD_UNSTABLE=$GTSAM_BUILD_UNSTABLE \ + -DGTSAM_BUILD_EXAMPLES_ALWAYS=ON \ + -DGTSAM_ALLOW_DEPRECATED_SINCE_V4=$GTSAM_ALLOW_DEPRECATED_SINCE_V4 + + # Actual build: + VERBOSE=1 make -j2 + + finish +} + +# run the tests +function test () +{ + prepare + + cmake $SOURCE_DIR \ + -DCMAKE_BUILD_TYPE=$CMAKE_BUILD_TYPE \ + -DGTSAM_BUILD_TESTS=ON \ + -DGTSAM_BUILD_UNSTABLE=$GTSAM_BUILD_UNSTABLE \ + -DGTSAM_BUILD_EXAMPLES_ALWAYS=OFF \ + -DGTSAM_ALLOW_DEPRECATED_SINCE_V4=OFF + + # Actual build: + make -j2 check + + finish +} + +# select between build or test +case $1 in + -b) + build + ;; + -t) + test + ;; +esac diff --git a/.travis.yml b/.travis.yml new file mode 100644 index 000000000..1e2d6760a --- /dev/null +++ b/.travis.yml @@ -0,0 +1,113 @@ +language: cpp +cache: ccache +sudo: required +dist: xenial + +addons: + apt: + sources: + - ubuntu-toolchain-r-test + packages: + - g++-8 + - clang-3.8 + - build-essential + - pkg-config + - cmake + - libpython-dev python-numpy + - libboost-all-dev + +# before_install: +# - if [ "$TRAVIS_OS_NAME" == "osx" ]; then brew update ; fi + +install: + - if [ "$TRAVIS_OS_NAME" == "osx" ]; then HOMEBREW_NO_AUTO_UPDATE=1 brew install ccache ; fi + - if [ "$TRAVIS_OS_NAME" == "osx" ]; then export PATH="/usr/local/opt/ccache/libexec:$PATH" ; fi + +# We first do the compile stage specified below, then the matrix expansion specified after. +stages: + - compile + - test + +# Compile stage without building examples/tests to populate the caches. +jobs: + include: +# on Mac, GCC + - stage: compile + os: osx + compiler: gcc + env: CMAKE_BUILD_TYPE=Debug GTSAM_BUILD_UNSTABLE=OFF + script: bash .travis.sh -b + - stage: compile + os: osx + compiler: gcc + env: CMAKE_BUILD_TYPE=Release + script: bash .travis.sh -b +# on Mac, CLANG + - stage: compile + os: osx + compiler: clang + env: CMAKE_BUILD_TYPE=Debug GTSAM_BUILD_UNSTABLE=OFF + script: bash .travis.sh -b + - stage: compile + os: osx + compiler: clang + env: CMAKE_BUILD_TYPE=Release + script: bash .travis.sh -b +# on Linux, GCC + - stage: compile + os: linux + compiler: gcc + env: CMAKE_BUILD_TYPE=Debug GTSAM_BUILD_UNSTABLE=OFF + script: bash .travis.sh -b + - stage: compile + os: linux + compiler: gcc + env: CMAKE_BUILD_TYPE=Release + script: bash .travis.sh -b +# on Linux, CLANG + - stage: compile + os: linux + compiler: clang + env: CMAKE_BUILD_TYPE=Debug GTSAM_BUILD_UNSTABLE=OFF + script: bash .travis.sh -b + - stage: compile + os: linux + compiler: clang + env: CMAKE_BUILD_TYPE=Release + script: bash .travis.sh -b +# on Linux, with deprecated ON to make sure that path still compiles + - stage: compile + os: linux + compiler: clang + env: CMAKE_BUILD_TYPE=Debug GTSAM_BUILD_UNSTABLE=OFF GTSAM_ALLOW_DEPRECATED_SINCE_V4=ON + script: bash .travis.sh -b + +# Matrix configuration: +os: + - osx + - linux +compiler: + - gcc + - clang +env: + global: + - MAKEFLAGS="-j2" + - CCACHE_SLOPPINESS=pch_defines,time_macros + - GTSAM_ALLOW_DEPRECATED_SINCE_V4=OFF + - GTSAM_BUILD_UNSTABLE=ON + matrix: + - CMAKE_BUILD_TYPE=Debug GTSAM_BUILD_UNSTABLE=OFF + - CMAKE_BUILD_TYPE=Release +script: + - bash .travis.sh -t + +matrix: + exclude: + # Exclude g++ debug on Linux as it consistently times out + - os: linux + compiler: gcc + env : CMAKE_BUILD_TYPE=Debug GTSAM_BUILD_UNSTABLE=OFF + # Exclude clang on Linux/clang in release until issue #57 is solved + - os: linux + compiler: clang + env : CMAKE_BUILD_TYPE=Release diff --git a/CMakeLists.txt b/CMakeLists.txt index 5930742ea..738a434f2 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,6 +1,5 @@ - project(GTSAM CXX C) -cmake_minimum_required(VERSION 2.8.4) +cmake_minimum_required(VERSION 3.0) # new feature to Cmake Version > 2.8.12 # Mac ONLY. Define Relative Path on Mac OS @@ -47,6 +46,17 @@ else() set(GTSAM_UNSTABLE_AVAILABLE 0) endif() +# ---------------------------------------------------------------------------- +# Uninstall target, for "make uninstall" +# ---------------------------------------------------------------------------- +configure_file( + "${CMAKE_CURRENT_SOURCE_DIR}/cmake/cmake_uninstall.cmake.in" + "${CMAKE_CURRENT_BINARY_DIR}/cmake_uninstall.cmake" + IMMEDIATE @ONLY) + +add_custom_target(uninstall + "${CMAKE_COMMAND}" -P "${CMAKE_CURRENT_BINARY_DIR}/cmake_uninstall.cmake") + ############################################################################### # Set up options @@ -55,44 +65,56 @@ endif() if(GTSAM_UNSTABLE_AVAILABLE) option(GTSAM_BUILD_UNSTABLE "Enable/Disable libgtsam_unstable" ON) endif() -option(GTSAM_BUILD_STATIC_LIBRARY "Build a static gtsam library, instead of shared" OFF) +option(BUILD_SHARED_LIBS "Build shared gtsam library, instead of static" ON) option(GTSAM_USE_QUATERNIONS "Enable/Disable using an internal Quaternion representation for rotations instead of rotation matrices. If enable, Rot3::EXPMAP is enforced by default." OFF) option(GTSAM_POSE3_EXPMAP "Enable/Disable using Pose3::EXPMAP as the default mode. If disabled, Pose3::FIRST_ORDER will be used." OFF) option(GTSAM_ROT3_EXPMAP "Ignore if GTSAM_USE_QUATERNIONS is OFF (Rot3::EXPMAP by default). Otherwise, enable Rot3::EXPMAP, or if disabled, use Rot3::CAYLEY." OFF) option(GTSAM_ENABLE_CONSISTENCY_CHECKS "Enable/Disable expensive consistency checks" OFF) option(GTSAM_WITH_TBB "Use Intel Threaded Building Blocks (TBB) if available" ON) -option(GTSAM_WITH_EIGEN_MKL "Eigen will use Intel MKL if available" ON) -option(GTSAM_WITH_EIGEN_MKL_OPENMP "Eigen, when using Intel MKL, will also use OpenMP for multithreading if available" ON) +option(GTSAM_WITH_EIGEN_MKL "Eigen will use Intel MKL if available" OFF) +option(GTSAM_WITH_EIGEN_MKL_OPENMP "Eigen, when using Intel MKL, will also use OpenMP for multithreading if available" OFF) option(GTSAM_THROW_CHEIRALITY_EXCEPTION "Throw exception when a triangulated point is behind a camera" ON) -option(GTSAM_BUILD_PYTHON "Enable/Disable building & installation of Python module" OFF) option(GTSAM_ALLOW_DEPRECATED_SINCE_V4 "Allow use of methods/functions deprecated in GTSAM 4" ON) -option(GTSAM_TYPEDEF_POINTS_TO_VECTORS "Typdef Point2 and Point3 to Eigen::Vector equivalents" OFF) +option(GTSAM_TYPEDEF_POINTS_TO_VECTORS "Typedef Point2 and Point3 to Eigen::Vector equivalents" OFF) option(GTSAM_SUPPORT_NESTED_DISSECTION "Support Metis-based nested dissection" ON) option(GTSAM_TANGENT_PREINTEGRATION "Use new ImuFactor with integration on tangent space" ON) if(NOT MSVC AND NOT XCODE_VERSION) option(GTSAM_BUILD_WITH_CCACHE "Use ccache compiler cache" ON) endif() +if(NOT MSVC AND NOT XCODE_VERSION) + # Set the build type to upper case for downstream use + string(TOUPPER "${CMAKE_BUILD_TYPE}" CMAKE_BUILD_TYPE_UPPER) + + # Set the GTSAM_BUILD_TAG variable. + # If build type is Release, set to blank (""), else set to the build type. + if("${CMAKE_BUILD_TYPE_UPPER}" STREQUAL "RELEASE") + set(GTSAM_BUILD_TAG "") # Don't create release mode tag on installed directory + else() + set(GTSAM_BUILD_TAG "${CMAKE_BUILD_TYPE}") + endif() +endif() + # Options relating to MATLAB wrapper # TODO: Check for matlab mex binary before handling building of binaries option(GTSAM_INSTALL_MATLAB_TOOLBOX "Enable/Disable installation of matlab toolbox" OFF) option(GTSAM_INSTALL_CYTHON_TOOLBOX "Enable/Disable installation of Cython toolbox" OFF) option(GTSAM_BUILD_WRAP "Enable/Disable building of matlab/cython wrap utility (necessary for matlab/cython interface)" ON) +set(GTSAM_PYTHON_VERSION "Default" CACHE STRING "The version of python to build the cython wrapper for (or Default)") # Check / set dependent variables for MATLAB wrapper if((GTSAM_INSTALL_MATLAB_TOOLBOX OR GTSAM_INSTALL_CYTHON_TOOLBOX) AND NOT GTSAM_BUILD_WRAP) message(FATAL_ERROR "GTSAM_INSTALL_MATLAB_TOOLBOX or GTSAM_INSTALL_CYTHON_TOOLBOX is enabled, please also enable GTSAM_BUILD_WRAP") endif() +if((GTSAM_INSTALL_MATLAB_TOOLBOX OR GTSAM_INSTALL_CYTHON_TOOLBOX) AND GTSAM_BUILD_TYPE_POSTFIXES) + set(CURRENT_POSTFIX ${CMAKE_${CMAKE_BUILD_TYPE_UPPER}_POSTFIX}) +endif() if(GTSAM_INSTALL_WRAP AND NOT GTSAM_BUILD_WRAP) message(FATAL_ERROR "GTSAM_INSTALL_WRAP is enabled, please also enable GTSAM_BUILD_WRAP") endif() -if(GTSAM_INSTALL_MATLAB_TOOLBOX AND GTSAM_BUILD_STATIC_LIBRARY) - message(FATAL_ERROR "GTSAM_INSTALL_MATLAB_TOOLBOX and GTSAM_BUILD_STATIC_LIBRARY are both enabled. The MATLAB wrapper cannot be compiled with a static GTSAM library because mex modules are themselves shared libraries. If you want a self-contained mex module, enable GTSAM_MEX_BUILD_STATIC_MODULE instead of GTSAM_BUILD_STATIC_LIBRARY.") -endif() - -if(GTSAM_BUILD_PYTHON AND GTSAM_ALLOW_DEPRECATED_SINCE_V4) - message(FATAL_ERROR "GTSAM_BUILD_PYTHON and GTSAM_ALLOW_DEPRECATED_SINCE_V4 are both enabled. The python module cannot be compiled with deprecated functions turned on. Turn one of the two options off.") +if(GTSAM_INSTALL_MATLAB_TOOLBOX AND NOT BUILD_SHARED_LIBS) + message(FATAL_ERROR "GTSAM_INSTALL_MATLAB_TOOLBOX and BUILD_SHARED_LIBS=OFF. The MATLAB wrapper cannot be compiled with a static GTSAM library because mex modules are themselves shared libraries. If you want a self-contained mex module, enable GTSAM_MEX_BUILD_STATIC_MODULE instead of BUILD_SHARED_LIBS=OFF.") endif() if(GTSAM_INSTALL_MATLAB_TOOLBOX AND GTSAM_TYPEDEF_POINTS_TO_VECTORS) @@ -121,16 +143,27 @@ if(MSVC) # If we use Boost shared libs, disable auto linking. # Some libraries, at least Boost Program Options, rely on this to export DLL symbols. if(NOT Boost_USE_STATIC_LIBS) - add_definitions(-DBOOST_ALL_NO_LIB) - add_definitions(-DBOOST_ALL_DYN_LINK) + list_append_cache(GTSAM_COMPILE_DEFINITIONS_PUBLIC BOOST_ALL_NO_LIB BOOST_ALL_DYN_LINK) endif() # Virtual memory range for PCH exceeded on VS2015 if(MSVC_VERSION LESS 1910) # older than VS2017 - add_definitions(-Zm295) + list_append_cache(GTSAM_COMPILE_OPTIONS_PRIVATE -Zm295) endif() endif() -find_package(Boost 1.43 COMPONENTS serialization system filesystem thread program_options date_time timer chrono regex) +# If building DLLs in MSVC, we need to avoid EIGEN_STATIC_ASSERT() +# or explicit instantiation will generate build errors. +# See: https://bitbucket.org/gtborg/gtsam/issues/417/fail-to-build-on-msvc-2017 +# +if(MSVC AND BUILD_SHARED_LIBS) + list_append_cache(GTSAM_COMPILE_DEFINITIONS_PUBLIC EIGEN_NO_STATIC_ASSERT) +endif() + +# Store these in variables so they are automatically replicated in GTSAMConfig.cmake and such. +set(BOOST_FIND_MINIMUM_VERSION 1.43) +set(BOOST_FIND_MINIMUM_COMPONENTS serialization system filesystem thread program_options date_time timer chrono regex) + +find_package(Boost ${BOOST_FIND_MINIMUM_VERSION} COMPONENTS ${BOOST_FIND_MINIMUM_COMPONENTS}) # Required components if(NOT Boost_SERIALIZATION_LIBRARY OR NOT Boost_SYSTEM_LIBRARY OR NOT Boost_FILESYSTEM_LIBRARY OR @@ -138,17 +171,39 @@ if(NOT Boost_SERIALIZATION_LIBRARY OR NOT Boost_SYSTEM_LIBRARY OR NOT Boost_FILE message(FATAL_ERROR "Missing required Boost components >= v1.43, please install/upgrade Boost or configure your search paths.") endif() -option(GTSAM_DISABLE_NEW_TIMERS "Disables using Boost.chrono for timing" OFF) # Allow for not using the timer libraries on boost < 1.48 (GTSAM timing code falls back to old timer library) +option(GTSAM_DISABLE_NEW_TIMERS "Disables using Boost.chrono for timing" OFF) + +# JLBC: This was once updated to target-based names (Boost::xxx), but it caused +# problems with Boost versions newer than FindBoost.cmake was prepared to handle, +# so we downgraded this to classic filenames-based variables, and manually adding +# the target_include_directories(xxx ${Boost_INCLUDE_DIR}) set(GTSAM_BOOST_LIBRARIES - ${Boost_SERIALIZATION_LIBRARY} ${Boost_SYSTEM_LIBRARY} ${Boost_FILESYSTEM_LIBRARY} - ${Boost_THREAD_LIBRARY} ${Boost_DATE_TIME_LIBRARY} ${Boost_REGEX_LIBRARY}) + optimized ${Boost_SERIALIZATION_LIBRARY_RELEASE} + optimized ${Boost_SYSTEM_LIBRARY_RELEASE} + optimized ${Boost_FILESYSTEM_LIBRARY_RELEASE} + optimized ${Boost_THREAD_LIBRARY_RELEASE} + optimized ${Boost_DATE_TIME_LIBRARY_RELEASE} + optimized ${Boost_REGEX_LIBRARY_RELEASE} + debug ${Boost_SERIALIZATION_LIBRARY_DEBUG} + debug ${Boost_SYSTEM_LIBRARY_DEBUG} + debug ${Boost_FILESYSTEM_LIBRARY_DEBUG} + debug ${Boost_THREAD_LIBRARY_DEBUG} + debug ${Boost_DATE_TIME_LIBRARY_DEBUG} + debug ${Boost_REGEX_LIBRARY_DEBUG} +) +message(STATUS "GTSAM_BOOST_LIBRARIES: ${GTSAM_BOOST_LIBRARIES}") if (GTSAM_DISABLE_NEW_TIMERS) message("WARNING: GTSAM timing instrumentation manually disabled") - add_definitions(-DGTSAM_DISABLE_NEW_TIMERS) + list_append_cache(GTSAM_COMPILE_DEFINITIONS_PUBLIC DGTSAM_DISABLE_NEW_TIMERS) else() if(Boost_TIMER_LIBRARY) - list(APPEND GTSAM_BOOST_LIBRARIES ${Boost_TIMER_LIBRARY} ${Boost_CHRONO_LIBRARY}) + list(APPEND GTSAM_BOOST_LIBRARIES + optimized ${Boost_TIMER_LIBRARY_RELEASE} + optimized ${Boost_CHRONO_LIBRARY_RELEASE} + debug ${Boost_TIMER_LIBRARY_DEBUG} + debug ${Boost_CHRONO_LIBRARY_DEBUG} + ) else() list(APPEND GTSAM_BOOST_LIBRARIES rt) # When using the header-only boost timer library, need -lrt message("WARNING: GTSAM timing instrumentation will use the older, less accurate, Boost timer library because boost older than 1.48 was found.") @@ -158,29 +213,19 @@ endif() if(NOT (${Boost_VERSION} LESS 105600)) message("Ignoring Boost restriction on optional lvalue assignment from rvalues") - add_definitions(-DBOOST_OPTIONAL_ALLOW_BINDING_TO_RVALUES -DBOOST_OPTIONAL_CONFIG_ALLOW_BINDING_TO_RVALUES) + list_append_cache(GTSAM_COMPILE_DEFINITIONS_PUBLIC BOOST_OPTIONAL_ALLOW_BINDING_TO_RVALUES BOOST_OPTIONAL_CONFIG_ALLOW_BINDING_TO_RVALUES) endif() ############################################################################### # Find TBB -find_package(TBB) +find_package(TBB 4.4 COMPONENTS tbb tbbmalloc) # Set up variables if we're using TBB if(TBB_FOUND AND GTSAM_WITH_TBB) set(GTSAM_USE_TBB 1) # This will go into config.h - include_directories(BEFORE ${TBB_INCLUDE_DIRS}) - set(GTSAM_TBB_LIBRARIES "") - if(TBB_DEBUG_LIBRARIES) - foreach(lib ${TBB_LIBRARIES}) - list(APPEND GTSAM_TBB_LIBRARIES optimized "${lib}") - endforeach() - foreach(lib ${TBB_DEBUG_LIBRARIES}) - list(APPEND GTSAM_TBB_LIBRARIES debug "${lib}") - endforeach() - else() - set(GTSAM_TBB_LIBRARIES ${TBB_LIBRARIES}) - endif() - list(APPEND GTSAM_ADDITIONAL_LIBRARIES ${GTSAM_TBB_LIBRARIES}) + # all definitions and link requisites will go via imported targets: + # tbb & tbbmalloc + list(APPEND GTSAM_ADDITIONAL_LIBRARIES tbb tbbmalloc) else() set(GTSAM_USE_TBB 0) # This will go into config.h endif() @@ -218,7 +263,6 @@ find_package(MKL) if(MKL_FOUND AND GTSAM_WITH_EIGEN_MKL) set(GTSAM_USE_EIGEN_MKL 1) # This will go into config.h set(EIGEN_USE_MKL_ALL 1) # This will go into config.h - it makes Eigen use MKL - include_directories(${MKL_INCLUDE_DIR}) list(APPEND GTSAM_ADDITIONAL_LIBRARIES ${MKL_LIBRARIES}) # --no-as-needed is required with gcc according to the MKL link advisor @@ -237,7 +281,7 @@ find_package(OpenMP) # do this here to generate correct message if disabled if(GTSAM_WITH_EIGEN_MKL AND GTSAM_WITH_EIGEN_MKL_OPENMP AND GTSAM_USE_EIGEN_MKL) if(OPENMP_FOUND AND GTSAM_USE_EIGEN_MKL AND GTSAM_WITH_EIGEN_MKL_OPENMP) set(GTSAM_USE_EIGEN_MKL_OPENMP 1) # This will go into config.h - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${OpenMP_CXX_FLAGS}") + list_append_cache(GTSAM_COMPILE_OPTIONS_PUBLIC ${OpenMP_CXX_FLAGS}) endif() endif() @@ -253,10 +297,9 @@ option(GTSAM_USE_SYSTEM_EIGEN "Find and use system-installed Eigen. If 'off', us # Switch for using system Eigen or GTSAM-bundled Eigen if(GTSAM_USE_SYSTEM_EIGEN) find_package(Eigen3 REQUIRED) - include_directories(AFTER "${EIGEN3_INCLUDE_DIR}") # Use generic Eigen include paths e.g. - set(GTSAM_EIGEN_INCLUDE_PREFIX "${EIGEN3_INCLUDE_DIR}") + set(GTSAM_EIGEN_INCLUDE_FOR_INSTALL "${EIGEN3_INCLUDE_DIR}") # check if MKL is also enabled - can have one or the other, but not both! # Note: Eigen >= v3.2.5 includes our patches @@ -270,28 +313,52 @@ if(GTSAM_USE_SYSTEM_EIGEN) message(FATAL_ERROR "MKL does not work with Eigen 3.3.4 because of a bug in Eigen. See http://eigen.tuxfamily.org/bz/show_bug.cgi?id=1527. Disable GTSAM_USE_SYSTEM_EIGEN to use GTSAM's copy of Eigen, disable GTSAM_WITH_EIGEN_MKL, or upgrade/patch your installation of Eigen.") endif() + # The actual include directory (for BUILD cmake target interface): + set(GTSAM_EIGEN_INCLUDE_FOR_BUILD "${EIGEN3_INCLUDE_DIR}") else() # Use bundled Eigen include path. # Clear any variables set by FindEigen3 if(EIGEN3_INCLUDE_DIR) set(EIGEN3_INCLUDE_DIR NOTFOUND CACHE STRING "" FORCE) endif() - # Add the bundled version of eigen to the include path so that it can still be included - # with #include - include_directories(BEFORE "gtsam/3rdparty/Eigen/") # set full path to be used by external projects # this will be added to GTSAM_INCLUDE_DIR by gtsam_extra.cmake.in - set(GTSAM_EIGEN_INCLUDE_PREFIX "${CMAKE_INSTALL_PREFIX}/include/gtsam/3rdparty/Eigen/") + set(GTSAM_EIGEN_INCLUDE_FOR_INSTALL "include/gtsam/3rdparty/Eigen/") + # The actual include directory (for BUILD cmake target interface): + set(GTSAM_EIGEN_INCLUDE_FOR_BUILD "${CMAKE_SOURCE_DIR}/gtsam/3rdparty/Eigen/") endif() +# Detect Eigen version: +set(EIGEN_VER_H "${GTSAM_EIGEN_INCLUDE_FOR_BUILD}/Eigen/src/Core/util/Macros.h") +if (EXISTS ${EIGEN_VER_H}) + file(READ "${EIGEN_VER_H}" STR_EIGEN_VERSION) + + # Extract the Eigen version from the Macros.h file, lines "#define EIGEN_WORLD_VERSION XX", etc... + + string(REGEX MATCH "EIGEN_WORLD_VERSION[ ]+[0-9]+" GTSAM_EIGEN_VERSION_WORLD "${STR_EIGEN_VERSION}") + string(REGEX MATCH "[0-9]+" GTSAM_EIGEN_VERSION_WORLD "${GTSAM_EIGEN_VERSION_WORLD}") + + string(REGEX MATCH "EIGEN_MAJOR_VERSION[ ]+[0-9]+" GTSAM_EIGEN_VERSION_MAJOR "${STR_EIGEN_VERSION}") + string(REGEX MATCH "[0-9]+" GTSAM_EIGEN_VERSION_MAJOR "${GTSAM_EIGEN_VERSION_MAJOR}") + + string(REGEX MATCH "EIGEN_MINOR_VERSION[ ]+[0-9]+" GTSAM_EIGEN_VERSION_MINOR "${STR_EIGEN_VERSION}") + string(REGEX MATCH "[0-9]+" GTSAM_EIGEN_VERSION_MINOR "${GTSAM_EIGEN_VERSION_MINOR}") + + set(GTSAM_EIGEN_VERSION "${GTSAM_EIGEN_VERSION_WORLD}.${GTSAM_EIGEN_VERSION_MAJOR}.${GTSAM_EIGEN_VERSION_MINOR}") + + message(STATUS "Found Eigen version: ${GTSAM_EIGEN_VERSION}") +else() + message(WARNING "Cannot determine Eigen version, missing file: `${EIGEN_VER_H}`") +endif () + if (MSVC) - if (NOT GTSAM_BUILD_STATIC_LIBRARY) + if (BUILD_SHARED_LIBS) # mute eigen static assert to avoid errors in shared lib - add_definitions(-DEIGEN_NO_STATIC_ASSERT) + list_append_cache(GTSAM_COMPILE_DEFINITIONS_PUBLIC EIGEN_NO_STATIC_ASSERT) endif() - add_definitions(/wd4244) # Disable loss of precision which is thrown all over our Eigen + list_append_cache(GTSAM_COMPILE_OPTIONS_PRIVATE "/wd4244") # Disable loss of precision which is thrown all over our Eigen endif() ############################################################################### @@ -332,52 +399,29 @@ elseif("${GTSAM_DEFAULT_ALLOCATOR}" STREQUAL "tcmalloc") list(APPEND GTSAM_ADDITIONAL_LIBRARIES "tcmalloc") endif() -# Include boost - use 'BEFORE' so that a specific boost specified to CMake -# takes precedence over a system-installed one. -include_directories(BEFORE SYSTEM ${Boost_INCLUDE_DIR}) - -if(GTSAM_SUPPORT_NESTED_DISSECTION) - set(METIS_INCLUDE_DIRECTORIES - gtsam/3rdparty/metis/include - gtsam/3rdparty/metis/libmetis - gtsam/3rdparty/metis/GKlib) -else() - set(METIS_INCLUDE_DIRECTORIES) -endif() - -# Add includes for source directories 'BEFORE' boost and any system include -# paths so that the compiler uses GTSAM headers in our source directory instead -# of any previously installed GTSAM headers. -include_directories(BEFORE - gtsam/3rdparty/SuiteSparse_config - gtsam/3rdparty/CCOLAMD/Include - ${METIS_INCLUDE_DIRECTORIES} - ${PROJECT_SOURCE_DIR} - ${PROJECT_BINARY_DIR} # So we can include generated config header files - CppUnitLite) - if(MSVC) - add_definitions(-D_CRT_SECURE_NO_WARNINGS -D_SCL_SECURE_NO_WARNINGS) - add_definitions(/wd4251 /wd4275 /wd4251 /wd4661 /wd4344 /wd4503) # Disable non-DLL-exported base class and other warnings - add_definitions(/bigobj) # Allow large object files for template-based code + list_append_cache(GTSAM_COMPILE_DEFINITIONS_PRIVATE _CRT_SECURE_NO_WARNINGS _SCL_SECURE_NO_WARNINGS) + list_append_cache(GTSAM_COMPILE_OPTIONS_PRIVATE /wd4251 /wd4275 /wd4251 /wd4661 /wd4344 /wd4503) # Disable non-DLL-exported base class and other warnings + list_append_cache(GTSAM_COMPILE_OPTIONS_PRIVATE /bigobj) # Allow large object files for template-based code endif() # GCC 4.8+ complains about local typedefs which we use for shared_ptr etc. if(CMAKE_CXX_COMPILER_ID STREQUAL "GNU") if (NOT CMAKE_CXX_COMPILER_VERSION VERSION_LESS 4.8) - add_definitions(-Wno-unused-local-typedefs) + list_append_cache(GTSAM_COMPILE_OPTIONS_PRIVATE -Wno-unused-local-typedefs) endif() endif() # As of XCode 7, clang also complains about this if(CMAKE_CXX_COMPILER_ID STREQUAL "Clang") if (NOT CMAKE_CXX_COMPILER_VERSION VERSION_LESS 7.0) - add_definitions(-Wno-unused-local-typedefs) + list_append_cache(GTSAM_COMPILE_OPTIONS_PRIVATE -Wno-unused-local-typedefs) endif() endif() if(GTSAM_ENABLE_CONSISTENCY_CHECKS) - add_definitions(-DGTSAM_EXTRA_CONSISTENCY_CHECKS) + # This should be made PUBLIC if GTSAM_EXTRA_CONSISTENCY_CHECKS is someday used in a public .h + list_append_cache(GTSAM_COMPILE_DEFINITIONS_PRIVATE GTSAM_EXTRA_CONSISTENCY_CHECKS) endif() ############################################################################### @@ -413,20 +457,6 @@ if (GTSAM_INSTALL_MATLAB_TOOLBOX) add_subdirectory(matlab) endif() -# Python wrap -if (GTSAM_BUILD_PYTHON) - include(GtsamPythonWrap) - - # NOTE: The automatic generation of python wrapper from the gtsampy.h interface is - # not working yet, so we're using a handwritten wrapper files on python/handwritten. - # Once the python wrapping from the interface file is working, you can _swap_ the - # comments on the next lines - - # wrap_and_install_python(gtsampy.h "${GTSAM_ADDITIONAL_LIBRARIES}" "") - add_subdirectory(python) - -endif() - # Cython wrap if (GTSAM_INSTALL_CYTHON_TOOLBOX) set(GTSAM_INSTALL_CYTHON_TOOLBOX 1) @@ -489,6 +519,9 @@ message(STATUS "===============================================================" message(STATUS "================ Configuration Options ======================") message(STATUS " CMAKE_CXX_COMPILER_ID type : ${CMAKE_CXX_COMPILER_ID}") message(STATUS " CMAKE_CXX_COMPILER_VERSION : ${CMAKE_CXX_COMPILER_VERSION}") +message(STATUS " CMake version : ${CMAKE_VERSION}") +message(STATUS " CMake generator : ${CMAKE_GENERATOR}") +message(STATUS " CMake build tool : ${CMAKE_BUILD_TOOL}") message(STATUS "Build flags ") print_config_flag(${GTSAM_BUILD_TESTS} "Build Tests ") print_config_flag(${GTSAM_BUILD_EXAMPLES_ALWAYS} "Build examples with 'make all' ") @@ -496,22 +529,23 @@ print_config_flag(${GTSAM_BUILD_TIMING_ALWAYS} "Build timing scripts wit if (DOXYGEN_FOUND) print_config_flag(${GTSAM_BUILD_DOCS} "Build Docs ") endif() -print_config_flag(${GTSAM_BUILD_STATIC_LIBRARY} "Build static GTSAM library instead of shared") +print_config_flag(${BUILD_SHARED_LIBS} "Build shared GTSAM libraries ") print_config_flag(${GTSAM_BUILD_TYPE_POSTFIXES} "Put build type in library name ") if(GTSAM_UNSTABLE_AVAILABLE) print_config_flag(${GTSAM_BUILD_UNSTABLE} "Build libgtsam_unstable ") endif() -string(TOUPPER "${CMAKE_BUILD_TYPE}" cmake_build_type_toupper) + if(NOT MSVC AND NOT XCODE_VERSION) + print_config_flag(${GTSAM_BUILD_WITH_MARCH_NATIVE} "Build for native architecture ") message(STATUS " Build type : ${CMAKE_BUILD_TYPE}") - message(STATUS " C compilation flags : ${CMAKE_C_FLAGS} ${CMAKE_C_FLAGS_${cmake_build_type_toupper}}") - message(STATUS " C++ compilation flags : ${CMAKE_CXX_FLAGS} ${CMAKE_CXX_FLAGS_${cmake_build_type_toupper}}") -endif() -if(GTSAM_USE_SYSTEM_EIGEN) - message(STATUS " Use System Eigen : Yes") -else() - message(STATUS " Use System Eigen : No") + message(STATUS " C compilation flags : ${CMAKE_C_FLAGS} ${CMAKE_C_FLAGS_${CMAKE_BUILD_TYPE_UPPER}}") + message(STATUS " C++ compilation flags : ${CMAKE_CXX_FLAGS} ${CMAKE_CXX_FLAGS_${CMAKE_BUILD_TYPE_UPPER}}") endif() + +print_build_options_for_target(gtsam) + +message(STATUS " Use System Eigen : ${GTSAM_USE_SYSTEM_EIGEN} (Using version: ${GTSAM_EIGEN_VERSION})") + if(GTSAM_USE_TBB) message(STATUS " Use Intel TBB : Yes") elseif(TBB_FOUND) @@ -559,42 +593,30 @@ print_config_flag(${GTSAM_ENABLE_CONSISTENCY_CHECKS} "Runtime consistency chec print_config_flag(${GTSAM_ROT3_EXPMAP} "Rot3 retract is full ExpMap ") print_config_flag(${GTSAM_POSE3_EXPMAP} "Pose3 retract is full ExpMap ") print_config_flag(${GTSAM_ALLOW_DEPRECATED_SINCE_V4} "Deprecated in GTSAM 4 allowed ") -print_config_flag(${GTSAM_TYPEDEF_POINTS_TO_VECTORS} "Point3 is typedef to Vector3 ") +print_config_flag(${GTSAM_TYPEDEF_POINTS_TO_VECTORS} "Point3 is typedef to Vector3 ") print_config_flag(${GTSAM_SUPPORT_NESTED_DISSECTION} "Metis-based Nested Dissection ") print_config_flag(${GTSAM_TANGENT_PREINTEGRATION} "Use tangent-space preintegration") +print_config_flag(${GTSAM_BUILD_WRAP} "Build Wrap ") message(STATUS "MATLAB toolbox flags ") print_config_flag(${GTSAM_INSTALL_MATLAB_TOOLBOX} "Install matlab toolbox ") -print_config_flag(${GTSAM_BUILD_WRAP} "Build Wrap ") - -message(STATUS "Python module flags ") - -if(GTSAM_PYTHON_WARNINGS) - message(STATUS " Build python module : No - dependencies missing") -else() - print_config_flag(${GTSAM_BUILD_PYTHON} "Build python module ") -endif() -if(GTSAM_BUILD_PYTHON) - message(STATUS " Python version : ${GTSAM_PYTHON_VERSION}") -endif() message(STATUS "Cython toolbox flags ") print_config_flag(${GTSAM_INSTALL_CYTHON_TOOLBOX} "Install Cython toolbox ") -print_config_flag(${GTSAM_BUILD_WRAP} "Build Wrap ") +if(GTSAM_INSTALL_CYTHON_TOOLBOX) + message(STATUS " Python version : ${GTSAM_PYTHON_VERSION}") +endif() message(STATUS "===============================================================") # Print warnings at the end if(GTSAM_WITH_TBB AND NOT TBB_FOUND) - message(WARNING "TBB was not found - this is ok, but note that GTSAM parallelization will be disabled. Set GTSAM_WITH_TBB to 'Off' to avoid this warning.") + message(WARNING "TBB 4.4 or newer was not found - this is ok, but note that GTSAM parallelization will be disabled. Set GTSAM_WITH_TBB to 'Off' to avoid this warning.") endif() if(GTSAM_WITH_EIGEN_MKL AND NOT MKL_FOUND) - message(WARNING "MKL was not found - this is ok, but note that MKL yields better performance. Set GTSAM_WITH_EIGEN_MKL to 'Off' to disable this warning.") + message(WARNING "MKL was not found - this is ok, but note that MKL will be disabled. Set GTSAM_WITH_EIGEN_MKL to 'Off' to disable this warning. See INSTALL.md for notes on performance.") endif() if(GTSAM_WITH_EIGEN_MKL_OPENMP AND NOT OPENMP_FOUND AND MKL_FOUND) - message(WARNING "Your compiler does not support OpenMP - this is ok, but performance may be improved with OpenMP. Set GTSAM_WITH_EIGEN_MKL_OPENMP to 'Off' to avoid this warning.") -endif() -if(GTSAM_BUILD_PYTHON AND GTSAM_PYTHON_WARNINGS) - message(WARNING "${GTSAM_PYTHON_WARNINGS}") + message(WARNING "Your compiler does not support OpenMP. Set GTSAM_WITH_EIGEN_MKL_OPENMP to 'Off' to avoid this warning. See INSTALL.md for notes on performance.") endif() # Include CPack *after* all flags diff --git a/CppUnitLite/CMakeLists.txt b/CppUnitLite/CMakeLists.txt index 35ecd71f8..72651aca9 100644 --- a/CppUnitLite/CMakeLists.txt +++ b/CppUnitLite/CMakeLists.txt @@ -6,6 +6,7 @@ file(GLOB cppunitlite_src "*.cpp") add_library(CppUnitLite STATIC ${cppunitlite_src} ${cppunitlite_headers}) list(APPEND GTSAM_EXPORTED_TARGETS CppUnitLite) set(GTSAM_EXPORTED_TARGETS "${GTSAM_EXPORTED_TARGETS}" PARENT_SCOPE) +target_include_directories(CppUnitLite PUBLIC ${Boost_INCLUDE_DIR}) # boost/lexical_cast.h gtsam_assign_source_folders("${cppunitlite_headers};${cppunitlite_src}") # MSVC project structure diff --git a/CppUnitLite/Failure.h b/CppUnitLite/Failure.h index 67ac5ba38..c3aa702e9 100644 --- a/CppUnitLite/Failure.h +++ b/CppUnitLite/Failure.h @@ -1,6 +1,6 @@ /* ---------------------------------------------------------------------------- - * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * GTSAM Copyright 2010, Georgia Tech Research Corporation, * Atlanta, Georgia 30332-0415 * All Rights Reserved * Authors: Frank Dellaert, et al. (see THANKS for the full author list) diff --git a/CppUnitLite/Test.cpp b/CppUnitLite/Test.cpp index 481fceb07..78995a219 100644 --- a/CppUnitLite/Test.cpp +++ b/CppUnitLite/Test.cpp @@ -1,6 +1,6 @@ /* ---------------------------------------------------------------------------- - * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * GTSAM Copyright 2010, Georgia Tech Research Corporation, * Atlanta, Georgia 30332-0415 * All Rights Reserved * Authors: Frank Dellaert, et al. (see THANKS for the full author list) @@ -36,7 +36,7 @@ Test *Test::getNext() const } void Test::setNext(Test *test) -{ +{ next_ = test; } @@ -46,9 +46,9 @@ bool Test::check(long expected, long actual, TestResult& result, const std::stri return true; result.addFailure ( Failure ( - name_, + name_, boost::lexical_cast (__FILE__), - __LINE__, + __LINE__, boost::lexical_cast (expected), boost::lexical_cast (actual))); @@ -63,10 +63,10 @@ bool Test::check(const std::string& expected, const std::string& actual, TestRes return true; result.addFailure ( Failure ( - name_, + name_, boost::lexical_cast (__FILE__), - __LINE__, - expected, + __LINE__, + expected, actual)); return false; diff --git a/CppUnitLite/Test.h b/CppUnitLite/Test.h index 23d1e2573..b1fb0cf08 100644 --- a/CppUnitLite/Test.h +++ b/CppUnitLite/Test.h @@ -1,6 +1,6 @@ /* ---------------------------------------------------------------------------- - * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * GTSAM Copyright 2010, Georgia Tech Research Corporation, * Atlanta, Georgia 30332-0415 * All Rights Reserved * Authors: Frank Dellaert, et al. (see THANKS for the full author list) @@ -12,7 +12,7 @@ /////////////////////////////////////////////////////////////////////////////// // // TEST.H -// +// // This file contains the Test class along with the macros which make effective // in the harness. // @@ -66,7 +66,7 @@ protected: virtual ~testGroup##testName##Test () {};\ void run (TestResult& result_);} \ testGroup##testName##Instance; \ - void testGroup##testName##Test::run (TestResult& result_) + void testGroup##testName##Test::run (TestResult& result_) /** * Declare friend in a class to test its private methods diff --git a/CppUnitLite/TestHarness.h b/CppUnitLite/TestHarness.h index 273309aa5..65dc0d3f9 100644 --- a/CppUnitLite/TestHarness.h +++ b/CppUnitLite/TestHarness.h @@ -1,6 +1,6 @@ /* ---------------------------------------------------------------------------- - * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * GTSAM Copyright 2010, Georgia Tech Research Corporation, * Atlanta, Georgia 30332-0415 * All Rights Reserved * Authors: Frank Dellaert, et al. (see THANKS for the full author list) @@ -12,7 +12,7 @@ /////////////////////////////////////////////////////////////////////////////// // // TESTHARNESS.H -// +// // The primary include file for the framework. // /////////////////////////////////////////////////////////////////////////////// diff --git a/CppUnitLite/TestRegistry.cpp b/CppUnitLite/TestRegistry.cpp index b493e81a6..2a123c88f 100644 --- a/CppUnitLite/TestRegistry.cpp +++ b/CppUnitLite/TestRegistry.cpp @@ -1,6 +1,6 @@ /* ---------------------------------------------------------------------------- - * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * GTSAM Copyright 2010, Georgia Tech Research Corporation, * Atlanta, Georgia 30332-0415 * All Rights Reserved * Authors: Frank Dellaert, et al. (see THANKS for the full author list) @@ -18,26 +18,26 @@ #include "TestResult.h" #include "TestRegistry.h" -void TestRegistry::addTest (Test *test) +void TestRegistry::addTest (Test *test) { instance ().add (test); } -int TestRegistry::runAllTests (TestResult& result) +int TestRegistry::runAllTests (TestResult& result) { return instance ().run (result); } -TestRegistry& TestRegistry::instance () +TestRegistry& TestRegistry::instance () { static TestRegistry registry; return registry; } -void TestRegistry::add (Test *test) +void TestRegistry::add (Test *test) { if (tests == 0) { test->setNext(0); @@ -52,7 +52,7 @@ void TestRegistry::add (Test *test) } -int TestRegistry::run (TestResult& result) +int TestRegistry::run (TestResult& result) { result.testsStarted (); diff --git a/CppUnitLite/TestRegistry.h b/CppUnitLite/TestRegistry.h index 56db991ad..5c3ebc280 100644 --- a/CppUnitLite/TestRegistry.h +++ b/CppUnitLite/TestRegistry.h @@ -1,6 +1,6 @@ /* ---------------------------------------------------------------------------- - * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * GTSAM Copyright 2010, Georgia Tech Research Corporation, * Atlanta, Georgia 30332-0415 * All Rights Reserved * Authors: Frank Dellaert, et al. (see THANKS for the full author list) @@ -12,9 +12,9 @@ /////////////////////////////////////////////////////////////////////////////// // // TESTREGISTRY.H -// -// TestRegistry is a singleton collection of all the tests to run in a system. -// +// +// TestRegistry is a singleton collection of all the tests to run in a system. +// /////////////////////////////////////////////////////////////////////////////// #ifndef TESTREGISTRY_H @@ -38,7 +38,7 @@ private: void add (Test *test); int run (TestResult& result); - + Test *tests; Test *lastTest; diff --git a/CppUnitLite/TestResult.cpp b/CppUnitLite/TestResult.cpp index 2519c94a9..594590d9e 100644 --- a/CppUnitLite/TestResult.cpp +++ b/CppUnitLite/TestResult.cpp @@ -1,6 +1,6 @@ /* ---------------------------------------------------------------------------- - * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * GTSAM Copyright 2010, Georgia Tech Research Corporation, * Atlanta, Georgia 30332-0415 * All Rights Reserved * Authors: Frank Dellaert, et al. (see THANKS for the full author list) @@ -22,12 +22,12 @@ TestResult::TestResult () } -void TestResult::testsStarted () +void TestResult::testsStarted () { } -void TestResult::addFailure (const Failure& failure) +void TestResult::addFailure (const Failure& failure) { if (failure.lineNumber < 0) // allow for no line number fprintf (stdout, "%s%s%s%s\n", @@ -48,7 +48,7 @@ void TestResult::addFailure (const Failure& failure) } -void TestResult::testsEnded () +void TestResult::testsEnded () { if (failureCount > 0) fprintf (stdout, "There were %d failures\n", failureCount); diff --git a/CppUnitLite/TestResult.h b/CppUnitLite/TestResult.h index b64b40d75..3897d2990 100644 --- a/CppUnitLite/TestResult.h +++ b/CppUnitLite/TestResult.h @@ -1,6 +1,6 @@ /* ---------------------------------------------------------------------------- - * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * GTSAM Copyright 2010, Georgia Tech Research Corporation, * Atlanta, Georgia 30332-0415 * All Rights Reserved * Authors: Frank Dellaert, et al. (see THANKS for the full author list) @@ -12,10 +12,10 @@ /////////////////////////////////////////////////////////////////////////////// // // TESTRESULT.H -// +// // A TestResult is a collection of the history of some test runs. Right now // it just collects failures. -// +// /////////////////////////////////////////////////////////////////////////////// #ifndef TESTRESULT_H @@ -26,12 +26,12 @@ class Failure; class TestResult { public: - TestResult (); + TestResult (); virtual ~TestResult() {}; virtual void testsStarted (); virtual void addFailure (const Failure& failure); virtual void testsEnded (); - + int getFailureCount() {return failureCount;} private: diff --git a/DEVELOP b/DEVELOP deleted file mode 100644 index 483197bc8..000000000 --- a/DEVELOP +++ /dev/null @@ -1,19 +0,0 @@ -Information for developers - -Coding Conventions: - -* Classes are Uppercase, methods and functions lowerMixedCase -* We use a modified K&R Style, with 2-space tabs, inserting spaces for tabs -* Use meaningful variable names, e.g., measurement not msm - - -Windows: - -On Windows it is necessary to explicitly export all functions from the library -which should be externally accessible. To do this, include the macro -GTSAM_EXPORT in your class or function definition. - -For example: -class GTSAM_EXPORT MyClass { ... }; - -GTSAM_EXPORT myFunction(); \ No newline at end of file diff --git a/DEVELOP.md b/DEVELOP.md new file mode 100644 index 000000000..133f3ea11 --- /dev/null +++ b/DEVELOP.md @@ -0,0 +1,19 @@ +# Information for Developers + +### Coding Conventions + +* Classes are Uppercase, methods and functions lowerMixedCase. +* We use a modified K&R Style, with 2-space tabs, inserting spaces for tabs. +* Use meaningful variable names, e.g. `measurement` not `msm`. + + +### Windows + +On Windows it is necessary to explicitly export all functions from the library which should be externally accessible. To do this, include the macro `GTSAM_EXPORT` in your class or function definition. + +For example: +```cpp +class GTSAM_EXPORT MyClass { ... }; + +GTSAM_EXPORT myFunction(); +``` diff --git a/GTSAM-Concepts.md b/GTSAM-Concepts.md index 366a58a09..a6cfee984 100644 --- a/GTSAM-Concepts.md +++ b/GTSAM-Concepts.md @@ -97,12 +97,24 @@ Note that in the Lie group case, the usual valid expressions for Retract and Loc For Lie groups, the `exponential map` above is the most obvious mapping: it associates straight lines in the tangent space with geodesics on the manifold -(and it's inverse, the log map). However, there are two cases in which we deviate from this: +(and it's inverse, the log map). However, there are several cases in which we deviate from this: However, the exponential map is unnecessarily expensive for use in optimization. Hence, in GTSAM there is the option to provide a cheaper chart by means of the `ChartAtOrigin` struct in a class. This is done for *SE(2)*, *SO(3)* and *SE(3)* (see `Pose2`, `Rot3`, `Pose3`) Most Lie groups we care about are *Matrix groups*, continuous sub-groups of *GL(n)*, the group of *n x n* invertible matrices. In this case, a lot of the derivatives calculations needed can be standardized, and this is done by the `LieGroup` superclass. You only need to provide an `AdjointMap` method. +A CRTP helper class `LieGroup` is available that can take a class and create some of the Lie group methods automatically. The class needs: + +* operator* : implements group operator +* inverse: implements group inverse +* AdjointMap: maps tangent vectors according to group element +* Expmap/Logmap: exponential map and its inverse +* ChartAtOrigin: struct where you define Retract/Local at origin + +To use, simply derive, but also say `using LieGroup::inverse` so you get an inverse with a derivative. + +Finally, to create the traits automatically you can use `internal::LieGroupTraits` + Vector Space ------------ diff --git a/INSTALL b/INSTALL deleted file mode 100644 index c71dcd4f9..000000000 --- a/INSTALL +++ /dev/null @@ -1,146 +0,0 @@ -Quickstart - -In the root library folder execute: - -$] mkdir build -$] cd build -$] cmake .. -$] make check (optional, runs unit tests) -$] make install - -Important Installation Notes ----------------------------- - -1) -GTSAM requires the following libraries to be installed on your system: - - BOOST version 1.43 or greater (install through Linux repositories or MacPorts) - - Cmake version 2.6 or higher - - Support for XCode 4.3 command line tools on Mac requires CMake 2.8.8 or higher - -Optional dependent libraries: - - If TBB is installed and detectable by CMake GTSAM will use it automatically. - Ensure that CMake prints "Use Intel TBB : Yes". To disable the use of TBB, - disable the CMake flag GTSAM_WITH_TBB (enabled by default). On Ubuntu, TBB - may be installed from the Ubuntu repositories, and for other platforms it - may be downloaded from https://www.threadingbuildingblocks.org/ - -Tested compilers: - -- GCC 4.2-4.7 -- OSX Clang 2.9-5.0 -- OSX GCC 4.2 -- MSVC 2010, 2012 - -Tested systems: - -- Ubuntu 11.04 - 13.10 -- MacOS 10.6 - 10.9 -- Windows 7, 8, 8.1 - -Known issues: - -- MSVC 2013 is not yet supported because it cannot build the serialization module - of Boost 1.55 (or earlier). - -2) -GTSAM makes extensive use of debug assertions, and we highly recommend you work -in Debug mode while developing (enabled by default). Likewise, it is imperative -that you switch to release mode when running finished code and for timing. GTSAM -will run up to 10x faster in Release mode! See the end of this document for -additional debugging tips. - -3) -GTSAM has Doxygen documentation. To generate, run 'make doc' from your -build directory. - -4) -The instructions below install the library to the default system install path and -build all components. From a terminal, starting in the root library folder, -execute commands as follows for an out-of-source build: - -$] mkdir build -$] cd build -$] cmake .. -$] make check (optional, runs unit tests) -$] make install - -This will build the library and unit tests, run all of the unit tests, -and then install the library itself. - -- CMake Configuration Options and Details - -GTSAM has a number of options that can be configured, which is best done with -one of the following: - - ccmake the curses GUI for cmake - cmake-gui a real GUI for cmake - -Important Options: - -CMAKE_BUILD_TYPE: We support several build configurations for GTSAM (case insensitive) - Debug (default) All error checking options on, no optimization. Use for development. - Release Optimizations turned on, no debug symbols. - Timing Adds ENABLE_TIMING flag to provide statistics on operation - Profiling Standard configuration for use during profiling - RelWithDebInfo Same as Release, but with the -g flag for debug symbols - -CMAKE_INSTALL_PREFIX: The install folder. The default is typically /usr/local/ -To configure to install to your home directory, you could execute: -$] cmake -DCMAKE_INSTALL_PREFIX:PATH=$HOME .. - -GTSAM_TOOLBOX_INSTALL_PATH: The Matlab toolbox will be installed in a subdirectory -of this folder, called 'gtsam'. -$] cmake -DGTSAM_TOOLBOX_INSTALL_PATH:PATH=$HOME/toolbox .. - -GTSAM_BUILD_CONVENIENCE_LIBRARIES: This is a build option to allow for tests in -subfolders to be linked against convenience libraries rather than the full libgtsam. -Set with the command line as follows: -$] cmake -DGTSAM_BUILD_CONVENIENCE_LIBRARIES:OPTION=ON .. - ON (Default) This builds convenience libraries and links tests against them. This - option is suggested for gtsam developers, as it is possible to build - and run tests without first building the rest of the library, and - speeds up compilation for a single test. The downside of this option - is that it will build the entire library again to build the full - libgtsam library, so build/install will be slower. - OFF This will build all of libgtsam before any of the tests, and then - link all of the tests at once. This option is best for users of GTSAM, - as it avoids rebuilding the entirety of gtsam an extra time. - -GTSAM_BUILD_UNSTABLE: Enable build and install for libgtsam_unstable library. -Set with the command line as follows: -$] cmake -DGTSAM_BUILD_UNSTABLE:OPTION=ON .. - ON When enabled, libgtsam_unstable will be built and installed with the - same options as libgtsam. In addition, if tests are enabled, the - unit tests will be built as well. The Matlab toolbox will also - be generated if the matlab toolbox is enabled, installing into a - folder called "gtsam_unstable". - OFF (Default) If disabled, no gtsam_unstable code will be included in build or install. - -Check - -"make check" will build and run all of the tests. Note that the tests will only be -built when using the "check" targets, to prevent "make install" from building the tests -unnecessarily. You can also run "make timing" to build all of the timing scripts. -To run check on a particular module only, run "make check.[subfolder]", so to run -just the geometry tests, run "make check.geometry". Individual tests can be run by -appending ".run" to the name of the test, for example, to run testMatrix, run -"make testMatrix.run". - -MEX_COMMAND: Path to the mex compiler. Defaults to assume the path is included in your -shell's PATH environment variable. mex is installed with matlab at -$MATLABROOT/bin/mex - -$MATLABROOT can be found by executing the command 'matlabroot' in MATLAB - -Debugging tips: - -Another useful debugging symbol is _GLIBCXX_DEBUG, which enables debug checks -and safe containers in the standard C++ library and makes problems much easier -to find. - -NOTE: The native Snow Leopard g++ compiler/library contains a bug that makes -it impossible to use _GLIBCXX_DEBUG. MacPorts g++ compilers do work with it though. - -NOTE: If _GLIBCXX_DEBUG is used to compile gtsam, anything that links against -gtsam will need to be compiled with _GLIBCXX_DEBUG as well, due to the use of -header-only Eigen. diff --git a/INSTALL.md b/INSTALL.md new file mode 100644 index 000000000..b8f73f153 --- /dev/null +++ b/INSTALL.md @@ -0,0 +1,195 @@ +# Quickstart + +In the root library folder execute: + +```sh +$ mkdir build +$ cd build +$ cmake .. +$ make check # (optional, runs unit tests) +$ make install +``` + +## Important Installation Notes + +1. GTSAM requires the following libraries to be installed on your system: + - BOOST version 1.43 or greater (install through Linux repositories or MacPorts) + - Cmake version 3.0 or higher + - Support for XCode 4.3 command line tools on Mac requires CMake 2.8.8 or higher + + Optional dependent libraries: + - If TBB is installed and detectable by CMake GTSAM will use it automatically. + Ensure that CMake prints "Use Intel TBB : Yes". To disable the use of TBB, + disable the CMake flag GTSAM_WITH_TBB (enabled by default). On Ubuntu, TBB + may be installed from the Ubuntu repositories, and for other platforms it + may be downloaded from https://www.threadingbuildingblocks.org/ + - GTSAM may be configured to use MKL by toggling `GTSAM_WITH_EIGEN_MKL` and + `GTSAM_WITH_EIGEN_MKL_OPENMP` to `ON`; however, best performance is usually + achieved with MKL disabled. We therefore advise you to benchmark your problem + before using MKL. + + Tested compilers: + + - GCC 4.2-7.3 + - OS X Clang 2.9-10.0 + - OS X GCC 4.2 + - MSVC 2010, 2012, 2017 + + Tested systems: + + - Ubuntu 16.04 - 18.04 + - MacOS 10.6 - 10.14 + - Windows 7, 8, 8.1, 10 + + Known issues: + + - MSVC 2013 is not yet supported because it cannot build the serialization module + of Boost 1.55 (or earlier). + +2. GTSAM makes extensive use of debug assertions, and we highly recommend you work +in Debug mode while developing (enabled by default). Likewise, it is imperative +that you switch to release mode when running finished code and for timing. GTSAM +will run up to 10x faster in Release mode! See the end of this document for +additional debugging tips. + +3. GTSAM has Doxygen documentation. To generate, run 'make doc' from your +build directory. + +4. The instructions below install the library to the default system install path and +build all components. From a terminal, starting in the root library folder, +execute commands as follows for an out-of-source build: + + ```sh + $ mkdir build + $ cd build + $ cmake .. + $ make check (optional, runs unit tests) + $ make install + ``` + + This will build the library and unit tests, run all of the unit tests, + and then install the library itself. + +## CMake Configuration Options and Details + +GTSAM has a number of options that can be configured, which is best done with +one of the following: + + - ccmake the curses GUI for cmake + - cmake-gui a real GUI for cmake + +### Important Options: + +#### CMAKE_BUILD_TYPE +We support several build configurations for GTSAM (case insensitive) + +```cmake -DCMAKE_BUILD_TYPE=[Option] ..``` + + - Debug (default) All error checking options on, no optimization. Use for development. + - Release Optimizations turned on, no debug symbols. + - Timing Adds ENABLE_TIMING flag to provide statistics on operation + - Profiling Standard configuration for use during profiling + - RelWithDebInfo Same as Release, but with the -g flag for debug symbols + +#### CMAKE_INSTALL_PREFIX + +The install folder. The default is typically `/usr/local/`. +To configure to install to your home directory, you could execute: + +```cmake -DCMAKE_INSTALL_PREFIX:PATH=$HOME ..``` + +#### GTSAM_TOOLBOX_INSTALL_PATH + +The Matlab toolbox will be installed in a subdirectory +of this folder, called 'gtsam'. + +```cmake -DGTSAM_TOOLBOX_INSTALL_PATH:PATH=$HOME/toolbox ..``` + +#### GTSAM_BUILD_CONVENIENCE_LIBRARIES + +This is a build option to allow for tests in subfolders to be linked against convenience libraries rather than the full libgtsam. +Set with the command line as follows: + +```cmake -DGTSAM_BUILD_CONVENIENCE_LIBRARIES:OPTION=ON ..``` + - ON (Default): This builds convenience libraries and links tests against them. This option is suggested for gtsam developers, as it is possible to build and run tests without first building the rest of the library, and speeds up compilation for a single test. The downside of this option is that it will build the entire library again to build the full libgtsam library, so build/install will be slower. + - OFF: This will build all of libgtsam before any of the tests, and then link all of the tests at once. This option is best for users of GTSAM, as it avoids rebuilding the entirety of gtsam an extra time. + +#### GTSAM_BUILD_UNSTABLE + +Enable build and install for libgtsam_unstable library. +Set with the command line as follows: + +```cmake -DGTSAM_BUILD_UNSTABLE:OPTION=ON ..``` + + ON: When enabled, libgtsam_unstable will be built and installed with the same options as libgtsam. In addition, if tests are enabled, the unit tests will be built as well. The Matlab toolbox will also be generated if the matlab toolbox is enabled, installing into a folder called `gtsam_unstable`. + OFF (Default) If disabled, no `gtsam_unstable` code will be included in build or install. + +## Check + +`make check` will build and run all of the tests. Note that the tests will only be +built when using the "check" targets, to prevent `make install` from building the tests +unnecessarily. You can also run `make timing` to build all of the timing scripts. +To run check on a particular module only, run `make check.[subfolder]`, so to run +just the geometry tests, run `make check.geometry`. Individual tests can be run by +appending `.run` to the name of the test, for example, to run testMatrix, run +`make testMatrix.run`. + +MEX_COMMAND: Path to the mex compiler. Defaults to assume the path is included in your shell's PATH environment variable. mex is installed with matlab at `$MATLABROOT/bin/mex` + +$MATLABROOT can be found by executing the command `matlabroot` in MATLAB + +## Performance + +Here are some tips to get the best possible performance out of GTSAM. + +1. Build in `Release` mode. GTSAM will run up to 10x faster compared to `Debug` mode. +2. Enable TBB. On modern processors with multiple cores, this can easily speed up + optimization by 30-50%. Please note that this may not be true for very small + problems where the overhead of dispatching work to multiple threads outweighs + the benefit. We recommend that you benchmark your problem with/without TBB. +3. Add `-march=native` to `GTSAM_CMAKE_CXX_FLAGS`. A performance gain of + 25-30% can be expected on modern processors. Note that this affects the portability + of your executable. It may not run when copied to another system with older/different + processor architecture. + Also note that all dependent projects *must* be compiled with the same flag, or + seg-faults and other undefined behavior may result. +4. Possibly enable MKL. Please note that our benchmarks have shown that this helps only + in very limited cases, and actually hurts performance in the usual case. We therefore + recommend that you do *not* enable MKL, unless you have benchmarked it on + your problem and have verified that it improves performance. + + +## Debugging tips + +Another useful debugging symbol is _GLIBCXX_DEBUG, which enables debug checks and safe containers in the standard C++ library and makes problems much easier to find. + +NOTE: The native Snow Leopard g++ compiler/library contains a bug that makes it impossible to use _GLIBCXX_DEBUG. MacPorts g++ compilers do work with it though. + +NOTE: If _GLIBCXX_DEBUG is used to compile gtsam, anything that links against gtsam will need to be compiled with _GLIBCXX_DEBUG as well, due to the use of header-only Eigen. + + +## Installing MKL on Linux + +Intel has a guide for installing MKL on Linux through APT repositories at . + +After following the instructions, add the following to your `~/.bashrc` (and afterwards, open a new terminal before compiling GTSAM): +`LD_PRELOAD` need only be set if you are building the cython wrapper to use GTSAM from python. +```sh +source /opt/intel/mkl/bin/mklvars.sh intel64 +export LD_PRELOAD="$LD_PRELOAD:/opt/intel/mkl/lib/intel64/libmkl_core.so:/opt/intel/mkl/lib/intel64/libmkl_sequential.so" +``` +To use MKL in GTSAM pass the flag `-DGTSAM_WITH_EIGEN_MKL=ON` to cmake. + + +The `LD_PRELOAD` fix seems to be related to a well known problem with MKL which leads to lots of undefined symbol errors, for example: +- +- +- + +Failing to specify `LD_PRELOAD` may lead to errors such as: +`ImportError: /opt/intel/mkl/lib/intel64/libmkl_vml_avx2.so: undefined symbol: mkl_serv_getenv` +or +`Intel MKL FATAL ERROR: Cannot load libmkl_avx2.so or libmkl_def.so.` +when importing GTSAM using the cython wrapper in python. + + diff --git a/README.md b/README.md index 02ed5149c..68bae879e 100644 --- a/README.md +++ b/README.md @@ -1,8 +1,8 @@ -README - Georgia Tech Smoothing and Mapping library -=================================================== +[![Build Status](https://travis-ci.com/borglab/gtsam.svg?branch=develop)](https://travis-ci.com/borglab/gtsam/) -What is GTSAM? --------------- +# README - Georgia Tech Smoothing and Mapping library + +## What is GTSAM? GTSAM is a library of C++ classes that implement smoothing and mapping (SAM) in robotics and vision, using factor graphs and Bayes @@ -13,12 +13,11 @@ On top of the C++ library, GTSAM includes a MATLAB interface (enable GTSAM_INSTALL_MATLAB_TOOLBOX in CMake to build it). A Python interface is under development. -Quickstart ----------- +## Quickstart In the root library folder execute: -``` +```sh #!bash $ mkdir build $ cd build @@ -30,51 +29,50 @@ $ make install Prerequisites: - [Boost](http://www.boost.org/users/download/) >= 1.43 (Ubuntu: `sudo apt-get install libboost-all-dev`) -- [CMake](http://www.cmake.org/cmake/resources/software.html) >= 2.6 (Ubuntu: `sudo apt-get install cmake`) +- [CMake](http://www.cmake.org/cmake/resources/software.html) >= 3.0 (Ubuntu: `sudo apt-get install cmake`) - A modern compiler, i.e., at least gcc 4.7.3 on Linux. Optional prerequisites - used automatically if findable by CMake: - [Intel Threaded Building Blocks (TBB)](http://www.threadingbuildingblocks.org/) (Ubuntu: `sudo apt-get install libtbb-dev`) -- [Intel Math Kernel Library (MKL)](http://software.intel.com/en-us/intel-mkl) +- [Intel Math Kernel Library (MKL)](http://software.intel.com/en-us/intel-mkl) (Ubuntu: [installing using APT](https://software.intel.com/en-us/articles/installing-intel-free-libs-and-python-apt-repo)) + - See [INSTALL.md](INSTALL.md) for more installation information + - Note that MKL may not provide a speedup in all cases. Make sure to benchmark your problem with and without MKL. -GTSAM 4 Compatibility ---------------------- +## GTSAM 4 Compatibility GTSAM 4 will introduce several new features, most notably Expressions and a python toolbox. We will also deprecate some legacy functionality and wrongly named methods, but by default the flag GTSAM_ALLOW_DEPRECATED_SINCE_V4 is enabled, allowing anyone to just pull V4 and compile. To build the python toolbox, however, you will have to explicitly disable that flag. Also, GTSAM 4 introduces traits, a C++ technique that allows optimizing with non-GTSAM types. That opens the door to retiring geometric types such as Point2 and Point3 to pure Eigen types, which we will also do. A significant change which will not trigger a compile error is that zero-initializing of Point2 and Point3 will be deprecated, so please be aware that this might render functions using their default constructor incorrect. -The Preintegrated IMU Factor ----------------------------- +## The Preintegrated IMU Factor GTSAM includes a state of the art IMU handling scheme based on -- Todd Lupton and Salah Sukkarieh, "Visual-Inertial-Aided Navigation for High-Dynamic Motion in Built Environments Without Initial Conditions", TRO, 28(1):61-76, 2012. +- Todd Lupton and Salah Sukkarieh, "Visual-Inertial-Aided Navigation for High-Dynamic Motion in Built Environments Without Initial Conditions", TRO, 28(1):61-76, 2012. [[link]](https://ieeexplore.ieee.org/document/6092505) Our implementation improves on this using integration on the manifold, as detailed in -- Luca Carlone, Zsolt Kira, Chris Beall, Vadim Indelman, and Frank Dellaert, "Eliminating conditionally independent sets in factor graphs: a unifying perspective based on smart factors", Int. Conf. on Robotics and Automation (ICRA), 2014. -- Christian Forster, Luca Carlone, Frank Dellaert, and Davide Scaramuzza, "IMU Preintegration on Manifold for Efficient Visual-Inertial Maximum-a-Posteriori Estimation", Robotics: Science and Systems (RSS), 2015. +- Luca Carlone, Zsolt Kira, Chris Beall, Vadim Indelman, and Frank Dellaert, "Eliminating conditionally independent sets in factor graphs: a unifying perspective based on smart factors", Int. Conf. on Robotics and Automation (ICRA), 2014. [[link]](https://ieeexplore.ieee.org/abstract/document/6907483) +- Christian Forster, Luca Carlone, Frank Dellaert, and Davide Scaramuzza, "IMU Preintegration on Manifold for Efficient Visual-Inertial Maximum-a-Posteriori Estimation", Robotics: Science and Systems (RSS), 2015. [[link]](http://www.roboticsproceedings.org/rss11/p06.pdf) If you are using the factor in academic work, please cite the publications above. In GTSAM 4 a new and more efficient implementation, based on integrating on the NavState tangent space and detailed in docs/ImuFactor.pdf, is enabled by default. To switch to the RSS 2015 version, set the flag **GTSAM_TANGENT_PREINTEGRATION** to OFF. -Additional Information ----------------------- +## Additional Information There is a [`GTSAM users Google group`](https://groups.google.com/forum/#!forum/gtsam-users) for general discussion. -Read about important [`GTSAM-Concepts`](GTSAM-Concepts.md) here. A primer on GTSAM Expressions, -which support (superfast) automatic differentiation, +Read about important [`GTSAM-Concepts`](GTSAM-Concepts.md) here. A primer on GTSAM Expressions, +which support (superfast) automatic differentiation, can be found on the [GTSAM wiki on BitBucket](https://bitbucket.org/gtborg/gtsam/wiki/Home). -See the [`INSTALL`](INSTALL) file for more detailed installation instructions. +See the [`INSTALL`](INSTALL.md) file for more detailed installation instructions. GTSAM is open source under the BSD license, see the [`LICENSE`](LICENSE) and [`LICENSE.BSD`](LICENSE.BSD) files. Please see the [`examples/`](examples) directory and the [`USAGE`](USAGE.md) file for examples on how to use GTSAM. -GTSAM was developed in the lab of [Frank Dellaert](http://www.cc.gatech.edu/~dellaert) at the [Georgia Institute of Technology](http://www.gatech.edu), with the help of many contributors over the years, see [THANKS](THANKS). \ No newline at end of file +GTSAM was developed in the lab of [Frank Dellaert](http://www.cc.gatech.edu/~dellaert) at the [Georgia Institute of Technology](http://www.gatech.edu), with the help of many contributors over the years, see [THANKS](THANKS). diff --git a/THANKS b/THANKS.md similarity index 95% rename from THANKS rename to THANKS.md index f84cfa185..7db7daaf3 100644 --- a/THANKS +++ b/THANKS.md @@ -1,5 +1,6 @@ GTSAM was made possible by the efforts of many collaborators at Georgia Tech, listed below with their current afffiliation, if they left Tech: +* Jeremy Aguilon, Facebook * Sungtae An * Doru Balcan, Bank of America * Chris Beall @@ -26,6 +27,7 @@ GTSAM was made possible by the efforts of many collaborators at Georgia Tech, li * Natesh Srinivasan * Alex Trevor * Stephen Williams, BossaNova +* Matthew Broadway at ETH, Zurich diff --git a/USAGE.md b/USAGE.md index 0493db680..f8e462550 100644 --- a/USAGE.md +++ b/USAGE.md @@ -1,48 +1,42 @@ -USAGE - Georgia Tech Smoothing and Mapping library -=================================== -What is this file? +# GTSAM USAGE - This file explains how to make use of the library for common SLAM tasks, - using a visual SLAM implementation as an example. +This file explains how to make use of the library for common SLAM tasks, using a visual SLAM implementation as an example. + +## Getting Started + +### Install - -Getting Started ---------------------------------------------------- -Install: - Follow the installation instructions in the README file to build and - install gtsam, as well as running tests to ensure the library is working - properly. +Follow the installation instructions in the README file to build and install gtsam, as well as running tests to ensure the library is working properly. -Compiling/Linking with gtsam: - The installation creates a binary "libgtsam" at the installation prefix, - and an include folder "gtsam". These are the only required includes, but - the library has also been designed to make use of XML serialization through - the Boost.serialization library, which requires the the Boost.serialization - headers and binaries to be linked. - - If you use CMake for your project, you can use the CMake scripts in the - cmake folder for finding GTSAM, CppUnitLite, and Wrap. +### Compiling/Linking with GTSAM -Examples: - To see how the library works, examine the unit tests provided. +The installation creates a binary `libgtsam` at the installation prefix, and an include folder `gtsam`. These are the only required includes, but the library has also been designed to make use of XML serialization through the `Boost.serialization` library, which requires the the Boost.serialization headers and binaries to be linked. + +If you use CMake for your project, you can use the CMake scripts in the cmake folder for finding `GTSAM`, `CppUnitLite`, and `Wrap`. + +### Examples + +To see how the library works, examine the unit tests provided. +## Overview -Overview ---------------------------------------------------- -The GTSAM library has three primary components necessary for the construction -of factor graph representation and optimization which users will need to -adapt to their particular problem. +The GTSAM library has three primary components necessary for the construction of factor graph representation and optimization which users will need to adapt to their particular problem. + +* FactorGraph + + A factor graph contains a set of variables to solve for (i.e., robot poses, landmark poses, etc.) and a set of constraints between these variables, which make up factors. + +* Values: + + Values is a single object containing labeled values for all of the variables. Currently, all variables are labeled with strings, but the type or organization of the variables can change. + +* Factors -* FactorGraph: - A factor graph contains a set of variables to solve for (i.e., robot poses, landmark poses, etc.) and a set of constraints between these variables, which make up factors. -* Values: - Values is a single object containing labeled values for all of the variables. Currently, all variables are labeled with strings, but the type or organization of the variables can change -* Factors: A nonlinear factor expresses a constraint between variables, which in the SLAM example, is a measurement such as a visual reading on a landmark or odometry. The library is organized according to the following directory structure: - 3rdparty local copies of third party libraries - Eigen3 and CCOLAMD + 3rdparty local copies of third party libraries e.g. Eigen3 and CCOLAMD base provides some base Math and data structures, as well as test-related utilities geometry points, poses, tensors, etc inference core graphical model inference such as factor graphs, junction trees, Bayes nets, Bayes trees diff --git a/Using-GTSAM-EXPORT.md b/Using-GTSAM-EXPORT.md new file mode 100644 index 000000000..41eccc178 --- /dev/null +++ b/Using-GTSAM-EXPORT.md @@ -0,0 +1,37 @@ +# Using GTSAM_EXPORT + +To create a DLL in windows, the `GTSAM_EXPORT` keyword has been created and needs to be applied to different methods and classes in the code to expose this code outside of the DLL. However, there are several intricacies that make this more difficult than it sounds. In general, if you follow the following three rules, GTSAM_EXPORT should work properly. The rest of the document also describes (1) the common error message encountered when you are not following these rules and (2) the reasoning behind these usage rules. + +## Usage Rules +1. Put `GTSAM_EXPORT` in front of any function that you want exported in the DLL _if and only if_ that function is declared in a .cpp file, not just a .h file. +2. Use `GTSAM_EXPORT` in a class definition (i.e. `class GSTAM_EXPORT MyClass {...}`) only if: + * At least one of the functions inside that class is declared in a .cpp file and not just the .h file. + * You can `GTSAM_EXPORT` any class it inherits from as well. (Note that this implictly requires the class does not derive from a "header-only" class. Note that Eigen is a "header-only" library, so if your class derives from Eigen, _do not_ use `GTSAM_EXPORT` in the class definition!) +3. If you have defined a class using `GTSAM_EXPORT`, do not use `GTSAM_EXPORT` in any of its individual function declarations. (Note that you _can_ put `GTSAM_EXPORT` in the definition of individual functions within a class as long as you don't put `GTSAM_EXPORT` in the class definition.) + +## When is GTSAM_EXPORT being used incorrectly +Unfortunately, using `GTSAM_EXPORT` incorrectly often does not cause a compiler or linker error in the library that is being compiled, but only when you try to use that DLL in a different library. For example, an error in gtsam/base will often show up when compiling the check_base_program or the MATLAB wrapper, but not when compiling/linking gtsam itself. The most common errors will say something like: + +``` +Error LNK2019 unresolved external symbol "public: void __cdecl gtsam::SO3::print(class std::basic_string,class std::allocator > const &)const " (?print@SO3@gtsam@@QEBAXAEBV?$basic_string@DU?$char_traits@D@std@@V?$allocator@D@2@@std@@@Z) referenced in function "public: static void __cdecl gtsam::Testable::Print(class gtsam::SO3 const &,class std::basic_string,class std::allocator > const &)" (?Print@?$Testable@VSO3@gtsam@@@gtsam@@SAXAEBVSO3@2@AEBV?$basic_string@DU?$char_traits@D@std@@V?$allocator@D@2@@std@@@Z) check_geometry_program C:\AFIT\lib\gtsam\build\gtsam\geometry\tests\testSO3.obj +``` + +Let's analyze this error statement. First, there is an unresolved symbol `gtsam::SO3::print`. This can occur because _either_ `GTSAM_EXPORT` was not added to the print function definition when it should have been, _OR_ because `GTSAM_EXPORT` was added to the print function definition when it is fully declared in the header. This error was detected while compiling `check_geometry_program` and pulling in `...\testSO3.obj`. Specifically, within the function call `gtsam::Testable::Print (...)`. Note that this error did _not_ occur when compiling the library that actually has SO3 inside of it. + +## But Why? +I believe that how the compiler/linker interacts with GTSAM_EXPORT can be explained by understanding the rules that MSVC operates under. + +But first, we need to understand exactly what `GTSAM_EXPORT` is. `GTSAM_EXPORT` is a `#define` macro that is created by CMAKE when GTSAM is being compiled on a Windows machine. Inside the GTSAM project, GTSAM export will be set to a "dllexport" command. A "dllexport" command tells the compiler that this function should go into the DLL and be visible externally. In any other library, `GTSAM_EXPORT` will be set to a "dllimport" command, telling the linker it should find this function in a DLL somewhere. This leads to the first rule the compiler uses. (Note that I say "compiler rules" when the rules may actually be in the linker, but I am conflating the two terms here when I speak of the "compiler rules".) + +***Compiler Rule #1*** If a `dllimport` command is used in defining a function or class, that function or class _must_ be found in a DLL. + +Rule #1 doesn't seem very bad, until you combine it with rule #2 + +***Compiler Rule #2*** Anything declared in a header file is not included in a DLL. + +When these two rules are combined, you get some very confusing results. For example, a class which is completely defined in a header (e.g. LieMatrix) cannot use `GTSAM_EXPORT` in its definition. If LieMatrix is defined with `GTSAM_EXPORT`, then the compiler _must_ find LieMatrix in a DLL. Because LieMatrix is a header-only class, however, it can't find it, leading to a very confusing "I can't find this symbol" type of error. Note that the linker says it can't find the symbol even though the compiler found the header file that completely defines the class. + +Also note that when a class that you want to export inherits from another class that is not exportable, this can cause significant issues. According to this [MSVC Warning page](https://docs.microsoft.com/en-us/cpp/error-messages/compiler-warnings/compiler-warning-level-2-c4275?view=vs-2019), it may not strictly be a rule, but we have seen several linker errors when a class that is defined with `GTSAM_EXPORT` extended an Eigen class. In general, it appears that any inheritance of non-exportable class by an exportable class is a bad idea. + +## Conclusion +Hopefully, this little document clarifies when `GTSAM_EXPORT` should and should not be used whenever future GTSAM code is being written. Following the usage rules above, we have been able to get all of the libraries, together with their test and wrapping libraries, to compile/link successfully. \ No newline at end of file diff --git a/bitbucket-pipelines.yml b/bitbucket-pipelines.yml deleted file mode 100644 index 9a94aa86c..000000000 --- a/bitbucket-pipelines.yml +++ /dev/null @@ -1,15 +0,0 @@ -# Built from sample configuration for C++ – Make. -# Check https://confluence.atlassian.com/x/5Q4SMw for more examples. -# ----- -# Our custom docker image from Docker Hub as the build environment. -image: dellaert/ubuntu-boost-tbb-eigen3:bionic - -pipelines: - default: - - step: - script: # Modify the commands below to build your repository. - - mkdir build - - cd build - - cmake -DGTSAM_USE_SYSTEM_EIGEN=OFF -DGTSAM_USE_EIGEN_MKL=OFF .. - - make -j2 - - make -j2 check \ No newline at end of file diff --git a/cmake/Config.cmake.in b/cmake/Config.cmake.in index 5f3956f07..9bd188037 100644 --- a/cmake/Config.cmake.in +++ b/cmake/Config.cmake.in @@ -1,7 +1,7 @@ # - Config file for @CMAKE_PROJECT_NAME@ # It defines the following variables # @PACKAGE_NAME@_INCLUDE_DIR - include directories for @CMAKE_PROJECT_NAME@ - + # Compute paths get_filename_component(OUR_CMAKE_DIR "${CMAKE_CURRENT_LIST_FILE}" PATH) if(EXISTS "${OUR_CMAKE_DIR}/CMakeCache.txt") @@ -11,7 +11,16 @@ else() # Find installed library set(@PACKAGE_NAME@_INCLUDE_DIR "${OUR_CMAKE_DIR}/@CONF_REL_INCLUDE_DIR@" CACHE PATH "@PACKAGE_NAME@ include directory") endif() - + +# Find dependencies, required by cmake exported targets: +include(CMakeFindDependencyMacro) +# Allow using cmake < 3.8 +if(${CMAKE_VERSION} VERSION_LESS "3.8.0") +find_package(Boost @BOOST_FIND_MINIMUM_VERSION@ COMPONENTS @BOOST_FIND_MINIMUM_COMPONENTS@) +else() +find_dependency(Boost @BOOST_FIND_MINIMUM_VERSION@ COMPONENTS @BOOST_FIND_MINIMUM_COMPONENTS@) +endif() + # Load exports include(${OUR_CMAKE_DIR}/@PACKAGE_NAME@-exports.cmake) diff --git a/cmake/FindCython.cmake b/cmake/FindCython.cmake index 23afb00e6..e5a32c30d 100644 --- a/cmake/FindCython.cmake +++ b/cmake/FindCython.cmake @@ -29,10 +29,15 @@ # Use the Cython executable that lives next to the Python executable # if it is a local installation. -find_package( PythonInterp ) +if(GTSAM_PYTHON_VERSION STREQUAL "Default") + find_package(PythonInterp) +else() + find_package(PythonInterp ${GTSAM_PYTHON_VERSION} EXACT) +endif() + if ( PYTHONINTERP_FOUND ) execute_process( COMMAND "${PYTHON_EXECUTABLE}" "-c" - "import Cython; print Cython.__path__" + "import Cython; print(Cython.__path__[0])" RESULT_VARIABLE RESULT OUTPUT_VARIABLE CYTHON_PATH OUTPUT_STRIP_TRAILING_WHITESPACE @@ -51,7 +56,7 @@ endif () # RESULT=0 means ok if ( NOT RESULT ) execute_process( COMMAND "${PYTHON_EXECUTABLE}" "-c" - "import Cython; print Cython.__version__" + "import Cython; print(Cython.__version__)" RESULT_VARIABLE RESULT OUTPUT_VARIABLE CYTHON_VAR_OUTPUT ERROR_VARIABLE CYTHON_VAR_OUTPUT diff --git a/cmake/FindMKL.cmake b/cmake/FindMKL.cmake index cbe46a908..32e183baa 100644 --- a/cmake/FindMKL.cmake +++ b/cmake/FindMKL.cmake @@ -206,6 +206,15 @@ ELSEIF(MKL_ROOT_DIR) # UNIX and macOS ) ENDIF() + IF(NOT MKL_LAPACK_LIBRARY) + FIND_LIBRARY(MKL_LAPACK_LIBRARY + mkl_intel_lp64 + PATHS + ${MKL_ROOT_DIR}/lib/${MKL_ARCH_DIR} + ${MKL_ROOT_DIR}/lib/ + ) + ENDIF() + # iomp5 IF("${MKL_ARCH_DIR}" STREQUAL "32") IF(UNIX AND NOT APPLE) diff --git a/cmake/FindNumPy.cmake b/cmake/FindNumPy.cmake index eafed165e..4f5743aa6 100644 --- a/cmake/FindNumPy.cmake +++ b/cmake/FindNumPy.cmake @@ -40,9 +40,17 @@ # Finding NumPy involves calling the Python interpreter if(NumPy_FIND_REQUIRED) + if(GTSAM_PYTHON_VERSION STREQUAL "Default") find_package(PythonInterp REQUIRED) + else() + find_package(PythonInterp ${GTSAM_PYTHON_VERSION} EXACT REQUIRED) + endif() else() + if(GTSAM_PYTHON_VERSION STREQUAL "Default") find_package(PythonInterp) + else() + find_package(PythonInterp ${GTSAM_PYTHON_VERSION} EXACT) + endif() endif() if(NOT PYTHONINTERP_FOUND) diff --git a/cmake/FindTBB.cmake b/cmake/FindTBB.cmake index f39d64601..76fe944f5 100644 --- a/cmake/FindTBB.cmake +++ b/cmake/FindTBB.cmake @@ -1,13 +1,6 @@ -# Locate Intel Threading Building Blocks include paths and libraries -# FindTBB.cmake can be found at https://code.google.com/p/findtbb/ -# Written by Hannes Hofmann -# Improvements by Gino van den Bergen , -# Florian Uhlig , -# Jiri Marsik - -# The MIT License +# The MIT License (MIT) # -# Copyright (c) 2011 Hannes Hofmann +# Copyright (c) 2015 Justus Calvin # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -16,295 +9,306 @@ # copies of the Software, and to permit persons to whom the Software is # furnished to do so, subject to the following conditions: # -# The above copyright notice and this permission notice shall be included in -# all copies or substantial portions of the Software. +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. # # THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR # IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, # FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE # AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER # LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN -# THE SOFTWARE. +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. -# GvdB: This module uses the environment variable TBB_ARCH_PLATFORM which defines architecture and compiler. -# e.g. "ia32/vc8" or "em64t/cc4.1.0_libc2.4_kernel2.6.16.21" -# TBB_ARCH_PLATFORM is set by the build script tbbvars[.bat|.sh|.csh], which can be found -# in the TBB installation directory (TBB_INSTALL_DIR). # -# GvdB: Mac OS X distribution places libraries directly in lib directory. +# FindTBB +# ------- # -# For backwards compatibility, you may explicitely set the CMake variables TBB_ARCHITECTURE and TBB_COMPILER. -# TBB_ARCHITECTURE [ ia32 | em64t | itanium ] -# which architecture to use -# TBB_COMPILER e.g. vc9 or cc3.2.3_libc2.3.2_kernel2.4.21 or cc4.0.1_os10.4.9 -# which compiler to use (detected automatically on Windows) +# Find TBB include directories and libraries. +# +# Usage: +# +# find_package(TBB [major[.minor]] [EXACT] +# [QUIET] [REQUIRED] +# [[COMPONENTS] [components...]] +# [OPTIONAL_COMPONENTS components...]) +# +# where the allowed components are tbbmalloc and tbb_preview. Users may modify +# the behavior of this module with the following variables: +# +# * TBB_ROOT_DIR - The base directory the of TBB installation. +# * TBB_INCLUDE_DIR - The directory that contains the TBB headers files. +# * TBB_LIBRARY - The directory that contains the TBB library files. +# * TBB__LIBRARY - The path of the TBB the corresponding TBB library. +# These libraries, if specified, override the +# corresponding library search results, where +# may be tbb, tbb_debug, tbbmalloc, tbbmalloc_debug, +# tbb_preview, or tbb_preview_debug. +# * TBB_USE_DEBUG_BUILD - The debug version of tbb libraries, if present, will +# be used instead of the release version. +# +# Users may modify the behavior of this module with the following environment +# variables: +# +# * TBB_INSTALL_DIR +# * TBBROOT +# * LIBRARY_PATH +# +# This module will set the following variables: +# +# * TBB_FOUND - Set to false, or undefined, if we haven’t found, or +# don’t want to use TBB. +# * TBB__FOUND - If False, optional part of TBB sytem is +# not available. +# * TBB_VERSION - The full version string +# * TBB_VERSION_MAJOR - The major version +# * TBB_VERSION_MINOR - The minor version +# * TBB_INTERFACE_VERSION - The interface version number defined in +# tbb/tbb_stddef.h. +# * TBB__LIBRARY_RELEASE - The path of the TBB release version of +# , where may be tbb, tbb_debug, +# tbbmalloc, tbbmalloc_debug, tbb_preview, or +# tbb_preview_debug. +# * TBB__LIBRARY_DEGUG - The path of the TBB release version of +# , where may be tbb, tbb_debug, +# tbbmalloc, tbbmalloc_debug, tbb_preview, or +# tbb_preview_debug. +# +# The following varibles should be used to build and link with TBB: +# +# * TBB_INCLUDE_DIRS - The include directory for TBB. +# * TBB_LIBRARIES - The libraries to link against to use TBB. +# * TBB_LIBRARIES_RELEASE - The release libraries to link against to use TBB. +# * TBB_LIBRARIES_DEBUG - The debug libraries to link against to use TBB. +# * TBB_DEFINITIONS - Definitions to use when compiling code that uses +# TBB. +# * TBB_DEFINITIONS_RELEASE - Definitions to use when compiling release code that +# uses TBB. +# * TBB_DEFINITIONS_DEBUG - Definitions to use when compiling debug code that +# uses TBB. +# +# This module will also create the "tbb" target that may be used when building +# executables and libraries. -# This module respects -# TBB_INSTALL_DIR or $ENV{TBB21_INSTALL_DIR} or $ENV{TBB_INSTALL_DIR} +include(FindPackageHandleStandardArgs) -# This module defines -# TBB_INCLUDE_DIRS, where to find task_scheduler_init.h, etc. -# TBB_LIBRARY_DIRS, where to find libtbb, libtbbmalloc -# TBB_DEBUG_LIBRARY_DIRS, where to find libtbb_debug, libtbbmalloc_debug -# TBB_INSTALL_DIR, the base TBB install directory -# TBB_LIBRARIES, the libraries to link against to use TBB. -# TBB_DEBUG_LIBRARIES, the libraries to link against to use TBB with debug symbols. -# TBB_FOUND, If false, don't try to use TBB. -# TBB_INTERFACE_VERSION, as defined in tbb/tbb_stddef.h +if(NOT TBB_FOUND) + ################################## + # Check the build type + ################################## -if (WIN32) - # has em64t/vc8 em64t/vc9 - # has ia32/vc7.1 ia32/vc8 ia32/vc9 - set(_TBB_DEFAULT_INSTALL_DIR "C:/Program Files/Intel/TBB") - set(_TBB_LIB_NAME "tbb") - set(_TBB_LIB_MALLOC_NAME "${_TBB_LIB_NAME}malloc") - set(_TBB_LIB_DEBUG_NAME "${_TBB_LIB_NAME}_debug") - set(_TBB_LIB_MALLOC_DEBUG_NAME "${_TBB_LIB_MALLOC_NAME}_debug") - if (MSVC71) - set (_TBB_COMPILER "vc7.1") - set (TBB_COMPILER "vc7.1") - endif(MSVC71) - if (MSVC80) - set(_TBB_COMPILER "vc8") - set(TBB_COMPILER "vc8") - endif(MSVC80) - if (MSVC90) - set(_TBB_COMPILER "vc9") - set(TBB_COMPILER "vc9") - endif(MSVC90) - if(MSVC10) - set(_TBB_COMPILER "vc10") - set(TBB_COMPILER "vc10") - endif(MSVC10) - if(MSVC11) - set(_TBB_COMPILER "vc11") - set(TBB_COMPILER "vc11") - endif(MSVC11) - if(MSVC14) - set(_TBB_COMPILER "vc14") - set(TBB_COMPILER "vc14") - endif(MSVC14) - # Todo: add other Windows compilers such as ICL. - if(TBB_ARCHITECTURE) - set(_TBB_ARCHITECTURE ${TBB_ARCHITECTURE}) - elseif("$ENV{TBB_ARCH_PLATFORM}" STREQUAL "") - # Try to guess the architecture - if(CMAKE_CL_64) - set(_TBB_ARCHITECTURE intel64) - set(TBB_ARCHITECTURE intel64) - else() - set(_TBB_ARCHITECTURE ia32) - set(TBB_ARCHITECTURE ia32) - endif() - endif() -endif (WIN32) + if(NOT DEFINED TBB_USE_DEBUG_BUILD) + if(CMAKE_BUILD_TYPE MATCHES "(Debug|DEBUG|debug|RelWithDebInfo|RELWITHDEBINFO|relwithdebinfo)") + set(TBB_BUILD_TYPE DEBUG) + else() + set(TBB_BUILD_TYPE RELEASE) + endif() + elseif(TBB_USE_DEBUG_BUILD) + set(TBB_BUILD_TYPE DEBUG) + else() + set(TBB_BUILD_TYPE RELEASE) + endif() -if (UNIX) - if (APPLE) - # MAC - set(_TBB_DEFAULT_INSTALL_DIR "/Library/Frameworks/Intel_TBB.framework/Versions") - # libs: libtbb.dylib, libtbbmalloc.dylib, *_debug - set(_TBB_LIB_NAME "tbb") - set(_TBB_LIB_MALLOC_NAME "${_TBB_LIB_NAME}malloc") - set(_TBB_LIB_DEBUG_NAME "${_TBB_LIB_NAME}_debug") - set(_TBB_LIB_MALLOC_DEBUG_NAME "${_TBB_LIB_MALLOC_NAME}_debug") - # default flavor on apple: ia32/cc4.0.1_os10.4.9 - # Jiri: There is no reason to presume there is only one flavor and - # that user's setting of variables should be ignored. - if(NOT TBB_COMPILER) - set(_TBB_COMPILER "cc4.0.1_os10.4.9") - elseif (NOT TBB_COMPILER) - set(_TBB_COMPILER ${TBB_COMPILER}) - endif(NOT TBB_COMPILER) - if(NOT TBB_ARCHITECTURE) - set(_TBB_ARCHITECTURE "ia32") - elseif(NOT TBB_ARCHITECTURE) - set(_TBB_ARCHITECTURE ${TBB_ARCHITECTURE}) - endif(NOT TBB_ARCHITECTURE) - else (APPLE) - # LINUX - set(_TBB_DEFAULT_INSTALL_DIR "/opt/intel/tbb" "/usr/local/include" "/usr/include") - set(_TBB_LIB_NAME "tbb") - set(_TBB_LIB_MALLOC_NAME "${_TBB_LIB_NAME}malloc") - set(_TBB_LIB_DEBUG_NAME "${_TBB_LIB_NAME}_debug") - set(_TBB_LIB_MALLOC_DEBUG_NAME "${_TBB_LIB_MALLOC_NAME}_debug") - # has em64t/cc3.2.3_libc2.3.2_kernel2.4.21 em64t/cc3.3.3_libc2.3.3_kernel2.6.5 em64t/cc3.4.3_libc2.3.4_kernel2.6.9 em64t/cc4.1.0_libc2.4_kernel2.6.16.21 - # has ia32/* - # has itanium/* - set(_TBB_COMPILER ${TBB_COMPILER}) - set(_TBB_ARCHITECTURE ${TBB_ARCHITECTURE}) - endif (APPLE) -endif (UNIX) + ################################## + # Set the TBB search directories + ################################## -if (CMAKE_SYSTEM MATCHES "SunOS.*") -# SUN -# not yet supported -# has em64t/cc3.4.3_kernel5.10 -# has ia32/* -endif (CMAKE_SYSTEM MATCHES "SunOS.*") + # Define search paths based on user input and environment variables + set(TBB_SEARCH_DIR ${TBB_ROOT_DIR} $ENV{TBB_INSTALL_DIR} $ENV{TBBROOT}) + # Define the search directories based on the current platform + if(CMAKE_SYSTEM_NAME STREQUAL "Windows") + set(TBB_DEFAULT_SEARCH_DIR "C:/Program Files/Intel/TBB" + "C:/Program Files (x86)/Intel/TBB") -#-- Clear the public variables -set (TBB_FOUND "NO") + # Set the target architecture + if(CMAKE_SIZEOF_VOID_P EQUAL 8) + set(TBB_ARCHITECTURE "intel64") + else() + set(TBB_ARCHITECTURE "ia32") + endif() + # Set the TBB search library path search suffix based on the version of VC + if(WINDOWS_STORE) + set(TBB_LIB_PATH_SUFFIX "lib/${TBB_ARCHITECTURE}/vc11_ui") + elseif(MSVC14) + set(TBB_LIB_PATH_SUFFIX "lib/${TBB_ARCHITECTURE}/vc14") + elseif(MSVC12) + set(TBB_LIB_PATH_SUFFIX "lib/${TBB_ARCHITECTURE}/vc12") + elseif(MSVC11) + set(TBB_LIB_PATH_SUFFIX "lib/${TBB_ARCHITECTURE}/vc11") + elseif(MSVC10) + set(TBB_LIB_PATH_SUFFIX "lib/${TBB_ARCHITECTURE}/vc10") + endif() -#-- Find TBB install dir and set ${_TBB_INSTALL_DIR} and cached ${TBB_INSTALL_DIR} -# first: use CMake variable TBB_INSTALL_DIR -if (TBB_INSTALL_DIR) - set (_TBB_INSTALL_DIR ${TBB_INSTALL_DIR}) -endif (TBB_INSTALL_DIR) -# second: use environment variable -if (NOT _TBB_INSTALL_DIR) - if (NOT "$ENV{TBB_INSTALL_DIR}" STREQUAL "") - set (_TBB_INSTALL_DIR $ENV{TBB_INSTALL_DIR}) - endif (NOT "$ENV{TBB_INSTALL_DIR}" STREQUAL "") - # Intel recommends setting TBB21_INSTALL_DIR - if (NOT "$ENV{TBB21_INSTALL_DIR}" STREQUAL "") - set (_TBB_INSTALL_DIR $ENV{TBB21_INSTALL_DIR}) - endif (NOT "$ENV{TBB21_INSTALL_DIR}" STREQUAL "") - if (NOT "$ENV{TBB22_INSTALL_DIR}" STREQUAL "") - set (_TBB_INSTALL_DIR $ENV{TBB22_INSTALL_DIR}) - endif (NOT "$ENV{TBB22_INSTALL_DIR}" STREQUAL "") - if (NOT "$ENV{TBB30_INSTALL_DIR}" STREQUAL "") - set (_TBB_INSTALL_DIR $ENV{TBB30_INSTALL_DIR}) - endif (NOT "$ENV{TBB30_INSTALL_DIR}" STREQUAL "") -endif (NOT _TBB_INSTALL_DIR) -# third: try to find path automatically -if (NOT _TBB_INSTALL_DIR) - if (_TBB_DEFAULT_INSTALL_DIR) - set (_TBB_INSTALL_DIR ${_TBB_DEFAULT_INSTALL_DIR}) - endif (_TBB_DEFAULT_INSTALL_DIR) -endif (NOT _TBB_INSTALL_DIR) -# sanity check -if (NOT _TBB_INSTALL_DIR) - message (STATUS "TBB: Unable to find Intel TBB install directory. ${_TBB_INSTALL_DIR}") -else (NOT _TBB_INSTALL_DIR) -# finally: set the cached CMake variable TBB_INSTALL_DIR -if (NOT TBB_INSTALL_DIR) - set (TBB_INSTALL_DIR ${_TBB_INSTALL_DIR} CACHE PATH "Intel TBB install directory") - mark_as_advanced(TBB_INSTALL_DIR) -endif (NOT TBB_INSTALL_DIR) + # Add the library path search suffix for the VC independent version of TBB + list(APPEND TBB_LIB_PATH_SUFFIX "lib/${TBB_ARCHITECTURE}/vc_mt") + elseif(CMAKE_SYSTEM_NAME STREQUAL "Darwin") + # OS X + set(TBB_DEFAULT_SEARCH_DIR "/opt/intel/tbb") -#-- A macro to rewrite the paths of the library. This is necessary, because -# find_library() always found the em64t/vc9 version of the TBB libs -macro(TBB_CORRECT_LIB_DIR var_name) -# if (NOT "${_TBB_ARCHITECTURE}" STREQUAL "em64t") - string(REPLACE em64t "${_TBB_ARCHITECTURE}" ${var_name} ${${var_name}}) -# endif (NOT "${_TBB_ARCHITECTURE}" STREQUAL "em64t") - string(REPLACE ia32 "${_TBB_ARCHITECTURE}" ${var_name} ${${var_name}}) - string(REPLACE vc7.1 "${_TBB_COMPILER}" ${var_name} ${${var_name}}) - string(REPLACE vc8 "${_TBB_COMPILER}" ${var_name} ${${var_name}}) - string(REPLACE vc9 "${_TBB_COMPILER}" ${var_name} ${${var_name}}) - string(REPLACE vc10 "${_TBB_COMPILER}" ${var_name} ${${var_name}}) - string(REPLACE vc11 "${_TBB_COMPILER}" ${var_name} ${${var_name}}) -endmacro(TBB_CORRECT_LIB_DIR var_content) + # TODO: Check to see which C++ library is being used by the compiler. + if(NOT ${CMAKE_SYSTEM_VERSION} VERSION_LESS 13.0) + # The default C++ library on OS X 10.9 and later is libc++ + set(TBB_LIB_PATH_SUFFIX "lib/libc++" "lib") + else() + set(TBB_LIB_PATH_SUFFIX "lib") + endif() + elseif(CMAKE_SYSTEM_NAME STREQUAL "Linux") + # Linux + set(TBB_DEFAULT_SEARCH_DIR "/opt/intel/tbb") + # TODO: Check compiler version to see the suffix should be /gcc4.1 or + # /gcc4.1. For now, assume that the compiler is more recent than + # gcc 4.4.x or later. + if(CMAKE_SYSTEM_PROCESSOR STREQUAL "x86_64") + set(TBB_LIB_PATH_SUFFIX "lib/intel64/gcc4.4") + elseif(CMAKE_SYSTEM_PROCESSOR MATCHES "^i.86$") + set(TBB_LIB_PATH_SUFFIX "lib/ia32/gcc4.4") + endif() + endif() -#-- Look for include directory and set ${TBB_INCLUDE_DIR} -set (TBB_INC_SEARCH_DIR ${_TBB_INSTALL_DIR}/include) -# Jiri: tbbvars now sets the CPATH environment variable to the directory -# containing the headers. -find_path(TBB_INCLUDE_DIR - tbb/task_scheduler_init.h - PATHS ${TBB_INC_SEARCH_DIR} ENV CPATH -) -mark_as_advanced(TBB_INCLUDE_DIR) + ################################## + # Find the TBB include dir + ################################## + find_path(TBB_INCLUDE_DIRS tbb/tbb.h + HINTS ${TBB_INCLUDE_DIR} ${TBB_SEARCH_DIR} + PATHS ${TBB_DEFAULT_SEARCH_DIR} + PATH_SUFFIXES include) -#-- Look for libraries -# GvdB: $ENV{TBB_ARCH_PLATFORM} is set by the build script tbbvars[.bat|.sh|.csh] -if (NOT $ENV{TBB_ARCH_PLATFORM} STREQUAL "") - set (_TBB_LIBRARY_DIR - ${_TBB_INSTALL_DIR}/lib/$ENV{TBB_ARCH_PLATFORM} - ${_TBB_INSTALL_DIR}/$ENV{TBB_ARCH_PLATFORM}/lib - ) -endif (NOT $ENV{TBB_ARCH_PLATFORM} STREQUAL "") -# Jiri: This block isn't mutually exclusive with the previous one -# (hence no else), instead I test if the user really specified -# the variables in question. -if ((NOT ${TBB_ARCHITECTURE} STREQUAL "") AND (NOT ${TBB_COMPILER} STREQUAL "")) - # HH: deprecated - message(STATUS "[Warning] FindTBB.cmake: The use of TBB_ARCHITECTURE and TBB_COMPILER is deprecated and may not be supported in future versions. Please set \$ENV{TBB_ARCH_PLATFORM} (using tbbvars.[bat|csh|sh]).") - # Jiri: It doesn't hurt to look in more places, so I store the hints from - # ENV{TBB_ARCH_PLATFORM} and the TBB_ARCHITECTURE and TBB_COMPILER - # variables and search them both. - set ( - _TBB_LIBRARY_DIR "${_TBB_INSTALL_DIR}/${_TBB_ARCHITECTURE}/${_TBB_COMPILER}/lib" ${_TBB_LIBRARY_DIR} - _TBB_LIBRARY_DIR "${_TBB_INSTALL_DIR}/lib/${_TBB_ARCHITECTURE}/${_TBB_COMPILER}" ${_TBB_LIBRARY_DIR} - ) -endif ((NOT ${TBB_ARCHITECTURE} STREQUAL "") AND (NOT ${TBB_COMPILER} STREQUAL "")) + ################################## + # Set version strings + ################################## -# GvdB: Mac OS X distribution places libraries directly in lib directory. -list(APPEND _TBB_LIBRARY_DIR ${_TBB_INSTALL_DIR}/lib) + if(TBB_INCLUDE_DIRS) + file(READ "${TBB_INCLUDE_DIRS}/tbb/tbb_stddef.h" _tbb_version_file) + string(REGEX REPLACE ".*#define TBB_VERSION_MAJOR ([0-9]+).*" "\\1" + TBB_VERSION_MAJOR "${_tbb_version_file}") + string(REGEX REPLACE ".*#define TBB_VERSION_MINOR ([0-9]+).*" "\\1" + TBB_VERSION_MINOR "${_tbb_version_file}") + string(REGEX REPLACE ".*#define TBB_INTERFACE_VERSION ([0-9]+).*" "\\1" + TBB_INTERFACE_VERSION "${_tbb_version_file}") + set(TBB_VERSION "${TBB_VERSION_MAJOR}.${TBB_VERSION_MINOR}") + endif() -# Jiri: No reason not to check the default paths. From recent versions, -# tbbvars has started exporting the LIBRARY_PATH and LD_LIBRARY_PATH -# variables, which now point to the directories of the lib files. -# It all makes more sense to use the ${_TBB_LIBRARY_DIR} as a HINTS -# argument instead of the implicit PATHS as it isn't hard-coded -# but computed by system introspection. Searching the LIBRARY_PATH -# and LD_LIBRARY_PATH environment variables is now even more important -# that tbbvars doesn't export TBB_ARCH_PLATFORM and it facilitates -# the use of TBB built from sources. -find_library(TBB_LIBRARY ${_TBB_LIB_NAME} HINTS ${_TBB_LIBRARY_DIR} - PATHS ENV LIBRARY_PATH ENV LD_LIBRARY_PATH) -find_library(TBB_MALLOC_LIBRARY ${_TBB_LIB_MALLOC_NAME} HINTS ${_TBB_LIBRARY_DIR} - PATHS ENV LIBRARY_PATH ENV LD_LIBRARY_PATH) + ################################## + # Find TBB components + ################################## -#Extract path from TBB_LIBRARY name -get_filename_component(TBB_LIBRARY_DIR ${TBB_LIBRARY} PATH) + if(TBB_VERSION VERSION_LESS 4.3) + set(TBB_SEARCH_COMPOMPONENTS tbb_preview tbbmalloc tbb) + else() + set(TBB_SEARCH_COMPOMPONENTS tbb_preview tbbmalloc_proxy tbbmalloc tbb) + endif() -#TBB_CORRECT_LIB_DIR(TBB_LIBRARY) -#TBB_CORRECT_LIB_DIR(TBB_MALLOC_LIBRARY) -mark_as_advanced(TBB_LIBRARY TBB_MALLOC_LIBRARY) + # Find each component + foreach(_comp ${TBB_SEARCH_COMPOMPONENTS}) + if(";${TBB_FIND_COMPONENTS};tbb;" MATCHES ";${_comp};") -#-- Look for debug libraries -# Jiri: Changed the same way as for the release libraries. -find_library(TBB_LIBRARY_DEBUG ${_TBB_LIB_DEBUG_NAME} HINTS ${_TBB_LIBRARY_DIR} - PATHS ENV LIBRARY_PATH ENV LD_LIBRARY_PATH) -find_library(TBB_MALLOC_LIBRARY_DEBUG ${_TBB_LIB_MALLOC_DEBUG_NAME} HINTS ${_TBB_LIBRARY_DIR} - PATHS ENV LIBRARY_PATH ENV LD_LIBRARY_PATH) + # Search for the libraries + find_library(TBB_${_comp}_LIBRARY_RELEASE ${_comp} + HINTS ${TBB_LIBRARY} ${TBB_SEARCH_DIR} + PATHS ${TBB_DEFAULT_SEARCH_DIR} ENV LIBRARY_PATH + PATH_SUFFIXES ${TBB_LIB_PATH_SUFFIX}) -# Jiri: Self-built TBB stores the debug libraries in a separate directory. -# Extract path from TBB_LIBRARY_DEBUG name -get_filename_component(TBB_LIBRARY_DEBUG_DIR ${TBB_LIBRARY_DEBUG} PATH) + find_library(TBB_${_comp}_LIBRARY_DEBUG ${_comp}_debug + HINTS ${TBB_LIBRARY} ${TBB_SEARCH_DIR} + PATHS ${TBB_DEFAULT_SEARCH_DIR} ENV LIBRARY_PATH + PATH_SUFFIXES ${TBB_LIB_PATH_SUFFIX}) -#TBB_CORRECT_LIB_DIR(TBB_LIBRARY_DEBUG) -#TBB_CORRECT_LIB_DIR(TBB_MALLOC_LIBRARY_DEBUG) -mark_as_advanced(TBB_LIBRARY_DEBUG TBB_MALLOC_LIBRARY_DEBUG) + if(TBB_${_comp}_LIBRARY_DEBUG) + list(APPEND TBB_LIBRARIES_DEBUG "${TBB_${_comp}_LIBRARY_DEBUG}") + endif() + if(TBB_${_comp}_LIBRARY_RELEASE) + list(APPEND TBB_LIBRARIES_RELEASE "${TBB_${_comp}_LIBRARY_RELEASE}") + endif() + if(TBB_${_comp}_LIBRARY_${TBB_BUILD_TYPE} AND NOT TBB_${_comp}_LIBRARY) + set(TBB_${_comp}_LIBRARY "${TBB_${_comp}_LIBRARY_${TBB_BUILD_TYPE}}") + endif() + if(TBB_${_comp}_LIBRARY AND EXISTS "${TBB_${_comp}_LIBRARY}") + set(TBB_${_comp}_FOUND TRUE) + else() + set(TBB_${_comp}_FOUND FALSE) + endif() -if (TBB_INCLUDE_DIR) - if (TBB_LIBRARY) - set (TBB_FOUND "YES") - set (TBB_LIBRARIES ${TBB_LIBRARY} ${TBB_MALLOC_LIBRARY} ${TBB_LIBRARIES}) - set (TBB_DEBUG_LIBRARIES ${TBB_LIBRARY_DEBUG} ${TBB_MALLOC_LIBRARY_DEBUG} ${TBB_DEBUG_LIBRARIES}) - set (TBB_INCLUDE_DIRS ${TBB_INCLUDE_DIR} CACHE PATH "TBB include directory" FORCE) - set (TBB_LIBRARY_DIRS ${TBB_LIBRARY_DIR} CACHE PATH "TBB library directory" FORCE) - # Jiri: Self-built TBB stores the debug libraries in a separate directory. - set (TBB_DEBUG_LIBRARY_DIRS ${TBB_LIBRARY_DEBUG_DIR} CACHE PATH "TBB debug library directory" FORCE) - mark_as_advanced(TBB_INCLUDE_DIRS TBB_LIBRARY_DIRS TBB_DEBUG_LIBRARY_DIRS TBB_LIBRARIES TBB_DEBUG_LIBRARIES) - message(STATUS "Found Intel TBB") - endif (TBB_LIBRARY) -endif (TBB_INCLUDE_DIR) + # Mark internal variables as advanced + mark_as_advanced(TBB_${_comp}_LIBRARY_RELEASE) + mark_as_advanced(TBB_${_comp}_LIBRARY_DEBUG) + mark_as_advanced(TBB_${_comp}_LIBRARY) -if (NOT TBB_FOUND) - message(STATUS "TBB: Intel TBB NOT found!") - message(STATUS "TBB: Looked for Threading Building Blocks in ${_TBB_INSTALL_DIR}") - # do only throw fatal, if this pkg is REQUIRED - if (TBB_FIND_REQUIRED) - message(FATAL_ERROR "Could NOT find TBB library.") - endif (TBB_FIND_REQUIRED) -endif (NOT TBB_FOUND) + endif() + endforeach() -endif (NOT _TBB_INSTALL_DIR) + ################################## + # Set compile flags and libraries + ################################## -if (TBB_FOUND) - set(TBB_INTERFACE_VERSION 0) - FILE(READ "${TBB_INCLUDE_DIRS}/tbb/tbb_stddef.h" _TBB_VERSION_CONTENTS) - STRING(REGEX REPLACE ".*#define TBB_INTERFACE_VERSION ([0-9]+).*" "\\1" TBB_INTERFACE_VERSION "${_TBB_VERSION_CONTENTS}") - set(TBB_INTERFACE_VERSION "${TBB_INTERFACE_VERSION}") -endif (TBB_FOUND) \ No newline at end of file + set(TBB_DEFINITIONS_RELEASE "") + set(TBB_DEFINITIONS_DEBUG "-DTBB_USE_DEBUG=1") + + if(TBB_LIBRARIES_${TBB_BUILD_TYPE}) + set(TBB_DEFINITIONS "${TBB_DEFINITIONS_${TBB_BUILD_TYPE}}") + set(TBB_LIBRARIES "${TBB_LIBRARIES_${TBB_BUILD_TYPE}}") + elseif(TBB_LIBRARIES_RELEASE) + set(TBB_DEFINITIONS "${TBB_DEFINITIONS_RELEASE}") + set(TBB_LIBRARIES "${TBB_LIBRARIES_RELEASE}") + elseif(TBB_LIBRARIES_DEBUG) + set(TBB_DEFINITIONS "${TBB_DEFINITIONS_DEBUG}") + set(TBB_LIBRARIES "${TBB_LIBRARIES_DEBUG}") + endif() + + find_package_handle_standard_args(TBB + REQUIRED_VARS TBB_INCLUDE_DIRS TBB_LIBRARIES + HANDLE_COMPONENTS + VERSION_VAR TBB_VERSION) + + ################################## + # Create targets + ################################## + + if(NOT CMAKE_VERSION VERSION_LESS 3.0 AND TBB_FOUND) + # Start fix to support different targets for tbb, tbbmalloc, etc. + # (Jose Luis Blanco, Jan 2019) + # Iterate over tbb, tbbmalloc, etc. + foreach(libname ${TBB_SEARCH_COMPOMPONENTS}) + if ((NOT TBB_${libname}_LIBRARY_RELEASE) AND (NOT TBB_${libname}_LIBRARY_DEBUG)) + continue() + endif() + + add_library(${libname} SHARED IMPORTED) + + set_target_properties(${libname} PROPERTIES + INTERFACE_INCLUDE_DIRECTORIES ${TBB_INCLUDE_DIRS} + IMPORTED_LOCATION ${TBB_${libname}_LIBRARY_RELEASE}) + if(TBB_${libname}_LIBRARY_RELEASE AND TBB_${libname}_LIBRARY_DEBUG) + set_target_properties(${libname} PROPERTIES + INTERFACE_COMPILE_DEFINITIONS "$<$,$>:TBB_USE_DEBUG=1>" + IMPORTED_LOCATION_DEBUG ${TBB_${libname}_LIBRARY_DEBUG} + IMPORTED_LOCATION_RELWITHDEBINFO ${TBB_${libname}_LIBRARY_DEBUG} + IMPORTED_LOCATION_RELEASE ${TBB_${libname}_LIBRARY_RELEASE} + IMPORTED_LOCATION_MINSIZEREL ${TBB_${libname}_LIBRARY_RELEASE} + ) + elseif(TBB_${libname}_LIBRARY_RELEASE) + set_target_properties(${libname} PROPERTIES IMPORTED_LOCATION ${TBB_${libname}_LIBRARY_RELEASE}) + else() + set_target_properties(${libname} PROPERTIES + INTERFACE_COMPILE_DEFINITIONS "${TBB_DEFINITIONS_DEBUG}" + IMPORTED_LOCATION ${TBB_${libname}_LIBRARY_DEBUG} + ) + endif() + endforeach() + # End of fix to support different targets + endif() + + mark_as_advanced(TBB_INCLUDE_DIRS TBB_LIBRARIES) + + unset(TBB_ARCHITECTURE) + unset(TBB_BUILD_TYPE) + unset(TBB_LIB_PATH_SUFFIX) + unset(TBB_DEFAULT_SEARCH_DIR) + +endif() diff --git a/cmake/GtsamBuildTypes.cmake b/cmake/GtsamBuildTypes.cmake index e9521c257..aa35fea05 100644 --- a/cmake/GtsamBuildTypes.cmake +++ b/cmake/GtsamBuildTypes.cmake @@ -1,7 +1,45 @@ +# function: list_append_cache(var [new_values ...]) +# Like "list(APPEND ...)" but working for CACHE variables. +# ----------------------------------------------------------- +function(list_append_cache var) + set(cur_value ${${var}}) + list(APPEND cur_value ${ARGN}) + get_property(MYVAR_DOCSTRING CACHE ${var} PROPERTY HELPSTRING) + set(${var} "${cur_value}" CACHE STRING "${MYVAR_DOCSTRING}" FORCE) +endfunction() + +# function: append_config_if_not_empty(TARGET_VARIABLE build_type) +# Auxiliary function used to merge configuration-specific flags into the +# global variables that will actually be send to cmake targets. +# ----------------------------------------------------------- +function(append_config_if_not_empty TARGET_VARIABLE_ build_type) + string(TOUPPER "${build_type}" build_type_toupper) + set(flags_variable_name "${TARGET_VARIABLE_}_${build_type_toupper}") + set(flags_ ${${flags_variable_name}}) + if (NOT "${flags_}" STREQUAL "") + if (${build_type_toupper} STREQUAL "COMMON") + # Special "COMMON" configuration type, just append without CMake expression: + list_append_cache(${TARGET_VARIABLE_} "${flags_}") + else() + # Regular configuration type: + list_append_cache(${TARGET_VARIABLE_} "$<$:${flags_}>") + endif() + endif() +endfunction() + + # Add install prefix to search path list(APPEND CMAKE_PREFIX_PATH "${CMAKE_INSTALL_PREFIX}") + +# Set up build types for MSVC and XCode +set(GTSAM_CMAKE_CONFIGURATION_TYPES Debug Release Timing Profiling RelWithDebInfo MinSizeRel + CACHE STRING "Build types available to MSVC and XCode") +mark_as_advanced(FORCE GTSAM_CMAKE_CONFIGURATION_TYPES) +set(CMAKE_CONFIGURATION_TYPES ${GTSAM_CMAKE_CONFIGURATION_TYPES} CACHE STRING "Build configurations" FORCE) + + # Default to Release mode if(NOT CMAKE_BUILD_TYPE AND NOT MSVC AND NOT XCODE_VERSION) set(GTSAM_CMAKE_BUILD_TYPE "Release" CACHE STRING @@ -13,39 +51,79 @@ endif() # Add option for using build type postfixes to allow installing multiple build modes option(GTSAM_BUILD_TYPE_POSTFIXES "Enable/Disable appending the build type to the name of compiled libraries" ON) -# Set custom compilation flags. -# NOTE: We set all the CACHE variables with a GTSAM prefix, and then set a normal local variable below -# so that we don't "pollute" the global variable namespace in the cmake cache. - # Set all CMAKE_BUILD_TYPE flags: - # (see https://cmake.org/Wiki/CMake_Useful_Variables#Compilers_and_Tools) +# Define all cache variables, to be populated below depending on the OS/compiler: +set(GTSAM_COMPILE_OPTIONS_PRIVATE "" CACHE STRING "(Do not edit) Private compiler flags for all build configurations." FORCE) +set(GTSAM_COMPILE_OPTIONS_PUBLIC "" CACHE STRING "(Do not edit) Public compiler flags (exported to user projects) for all build configurations." FORCE) +set(GTSAM_COMPILE_DEFINITIONS_PRIVATE "" CACHE STRING "(Do not edit) Private preprocessor macros for all build configurations." FORCE) +set(GTSAM_COMPILE_DEFINITIONS_PUBLIC "" CACHE STRING "(Do not edit) Public preprocessor macros for all build configurations." FORCE) +mark_as_advanced(GTSAM_COMPILE_OPTIONS_PRIVATE) +mark_as_advanced(GTSAM_COMPILE_OPTIONS_PUBLIC) +mark_as_advanced(GTSAM_COMPILE_DEFINITIONS_PRIVATE) +mark_as_advanced(GTSAM_COMPILE_DEFINITIONS_PUBLIC) + +foreach(build_type ${GTSAM_CMAKE_CONFIGURATION_TYPES}) + string(TOUPPER "${build_type}" build_type_toupper) + + # Define empty cache variables for "public". "private" are creaed below. + set(GTSAM_COMPILE_OPTIONS_PUBLIC_${build_type_toupper} "" CACHE STRING "(User editable) Public compiler flags (exported to user projects) for `${build_type_toupper}` configuration.") + set(GTSAM_COMPILE_DEFINITIONS_PUBLIC_${build_type_toupper} "" CACHE STRING "(User editable) Public preprocessor macros for `${build_type_toupper}` configuration.") +endforeach() + +# Common preprocessor macros for each configuration: +set(GTSAM_COMPILE_DEFINITIONS_PRIVATE_DEBUG "_DEBUG;EIGEN_INITIALIZE_MATRICES_BY_NAN" CACHE STRING "(User editable) Private preprocessor macros for Debug configuration.") +set(GTSAM_COMPILE_DEFINITIONS_PRIVATE_RELWITHDEBINFO "NDEBUG" CACHE STRING "(User editable) Private preprocessor macros for RelWithDebInfo configuration.") +set(GTSAM_COMPILE_DEFINITIONS_PRIVATE_RELEASE "NDEBUG" CACHE STRING "(User editable) Private preprocessor macros for Release configuration.") +set(GTSAM_COMPILE_DEFINITIONS_PRIVATE_PROFILING "NDEBUG" CACHE STRING "(User editable) Private preprocessor macros for Profiling configuration.") +set(GTSAM_COMPILE_DEFINITIONS_PRIVATE_TIMING "NDEBUG;ENABLE_TIMING" CACHE STRING "(User editable) Private preprocessor macros for Timing configuration.") if(MSVC) - set(GTSAM_CMAKE_C_FLAGS "/W3 /GR /EHsc /MP /DWINDOWS_LEAN_AND_MEAN" CACHE STRING "Flags used by the compiler for all builds.") - set(GTSAM_CMAKE_CXX_FLAGS "/W3 /GR /EHsc /MP /DWINDOWS_LEAN_AND_MEAN" CACHE STRING "Flags used by the compiler for all builds.") - set(GTSAM_CMAKE_C_FLAGS_DEBUG "/D_DEBUG /MDd /Zi /Ob0 /Od /RTC1 /DEIGEN_INITIALIZE_MATRICES_BY_NAN" CACHE STRING "Extra flags used by the compiler during debug builds.") - set(GTSAM_CMAKE_CXX_FLAGS_DEBUG "/D_DEBUG /MDd /Zi /Ob0 /Od /RTC1 /DEIGEN_INITIALIZE_MATRICES_BY_NAN" CACHE STRING "Extra flags used by the compiler during debug builds.") - set(GTSAM_CMAKE_C_FLAGS_RELWITHDEBINFO "/MD /O2 /DNDEBUG /Zi /d2Zi+" CACHE STRING "Extra flags used by the compiler during relwithdebinfo builds.") - set(GTSAM_CMAKE_CXX_FLAGS_RELWITHDEBINFO "/MD /O2 /DNDEBUG /Zi /d2Zi+" CACHE STRING "Extra flags used by the compiler during relwithdebinfo builds.") - set(GTSAM_CMAKE_C_FLAGS_RELEASE "/MD /O2 /DNDEBUG" CACHE STRING "Extra flags used by the compiler during release builds.") - set(GTSAM_CMAKE_CXX_FLAGS_RELEASE "/MD /O2 /DNDEBUG" CACHE STRING "Extra flags used by the compiler during release builds.") - set(GTSAM_CMAKE_C_FLAGS_PROFILING "${GTSAM_CMAKE_C_FLAGS_RELEASE} /Zi" CACHE STRING "Extra flags used by the compiler during profiling builds.") - set(GTSAM_CMAKE_CXX_FLAGS_PROFILING "${GTSAM_CMAKE_CXX_FLAGS_RELEASE} /Zi" CACHE STRING "Extra flags used by the compiler during profiling builds.") - set(GTSAM_CMAKE_C_FLAGS_TIMING "${GTSAM_CMAKE_C_FLAGS_RELEASE} /DENABLE_TIMING" CACHE STRING "Extra flags used by the compiler during timing builds.") - set(GTSAM_CMAKE_CXX_FLAGS_TIMING "${GTSAM_CMAKE_CXX_FLAGS_RELEASE} /DENABLE_TIMING" CACHE STRING "Extra flags used by the compiler during timing builds.") -else() - set(GTSAM_CMAKE_C_FLAGS "-std=c11 -Wall" CACHE STRING "Flags used by the compiler for all builds.") - set(GTSAM_CMAKE_CXX_FLAGS "-std=c++11 -Wall" CACHE STRING "Flags used by the compiler for all builds.") - set(GTSAM_CMAKE_C_FLAGS_DEBUG "-g -fno-inline -DEIGEN_INITIALIZE_MATRICES_BY_NAN" CACHE STRING "Extra flags used by the compiler during debug builds.") - set(GTSAM_CMAKE_CXX_FLAGS_DEBUG "-g -fno-inline -DEIGEN_INITIALIZE_MATRICES_BY_NAN" CACHE STRING "Extra flags used by the compiler during debug builds.") - set(GTSAM_CMAKE_C_FLAGS_RELWITHDEBINFO "-g -O3 -DNDEBUG" CACHE STRING "Extra flags used by the compiler during relwithdebinfo builds.") - set(GTSAM_CMAKE_CXX_FLAGS_RELWITHDEBINFO "-g -O3 -DNDEBUG" CACHE STRING "Extra flags used by the compiler during relwithdebinfo builds.") - set(GTSAM_CMAKE_C_FLAGS_RELEASE " -O3 -DNDEBUG" CACHE STRING "Extra flags used by the compiler during release builds.") - set(GTSAM_CMAKE_CXX_FLAGS_RELEASE " -O3 -DNDEBUG" CACHE STRING "Extra flags used by the compiler during release builds.") - set(GTSAM_CMAKE_C_FLAGS_PROFILING "${GTSAM_CMAKE_C_FLAGS_RELEASE}" CACHE STRING "Extra flags used by the compiler during profiling builds.") - set(GTSAM_CMAKE_CXX_FLAGS_PROFILING "${GTSAM_CMAKE_CXX_FLAGS_RELEASE}" CACHE STRING "Extra flags used by the compiler during profiling builds.") - set(GTSAM_CMAKE_C_FLAGS_TIMING "${GTSAM_CMAKE_C_FLAGS_RELEASE} -DENABLE_TIMING" CACHE STRING "Extra flags used by the compiler during timing builds.") - set(GTSAM_CMAKE_CXX_FLAGS_TIMING "${GTSAM_CMAKE_CXX_FLAGS_RELEASE} -DENABLE_TIMING" CACHE STRING "Extra flags used by the compiler during timing builds.") + # Common to all configurations: + list_append_cache(GTSAM_COMPILE_DEFINITIONS_PRIVATE + WINDOWS_LEAN_AND_MEAN + NOMINMAX + ) endif() +# Other (non-preprocessor macros) compiler flags: +if(MSVC) + # Common to all configurations, next for each configuration: + set(GTSAM_COMPILE_OPTIONS_PRIVATE_COMMON /W3 /GR /EHsc /MP CACHE STRING "(User editable) Private compiler flags for all configurations.") + set(GTSAM_COMPILE_OPTIONS_PRIVATE_DEBUG /MDd /Zi /Ob0 /Od /RTC1 CACHE STRING "(User editable) Private compiler flags for Debug configuration.") + set(GTSAM_COMPILE_OPTIONS_PRIVATE_RELWITHDEBINFO /MD /O2 /D /Zi /d2Zi+ CACHE STRING "(User editable) Private compiler flags for RelWithDebInfo configuration.") + set(GTSAM_COMPILE_OPTIONS_PRIVATE_RELEASE /MD /O2 CACHE STRING "(User editable) Private compiler flags for Release configuration.") + set(GTSAM_COMPILE_OPTIONS_PRIVATE_PROFILING /MD /O2 /Zi CACHE STRING "(User editable) Private compiler flags for Profiling configuration.") + set(GTSAM_COMPILE_OPTIONS_PRIVATE_TIMING /MD /O2 CACHE STRING "(User editable) Private compiler flags for Timing configuration.") +else() + # Common to all configurations, next for each configuration: + set(GTSAM_COMPILE_OPTIONS_PRIVATE_COMMON -Wall CACHE STRING "(User editable) Private compiler flags for all configurations.") + set(GTSAM_COMPILE_OPTIONS_PRIVATE_DEBUG -g -fno-inline CACHE STRING "(User editable) Private compiler flags for Debug configuration.") + set(GTSAM_COMPILE_OPTIONS_PRIVATE_RELWITHDEBINFO -g -O3 CACHE STRING "(User editable) Private compiler flags for RelWithDebInfo configuration.") + set(GTSAM_COMPILE_OPTIONS_PRIVATE_RELEASE -O3 CACHE STRING "(User editable) Private compiler flags for Release configuration.") + set(GTSAM_COMPILE_OPTIONS_PRIVATE_PROFILING -O3 CACHE STRING "(User editable) Private compiler flags for Profiling configuration.") + set(GTSAM_COMPILE_OPTIONS_PRIVATE_TIMING -g -O3 CACHE STRING "(User editable) Private compiler flags for Timing configuration.") +endif() + +# Enable C++11: +if (NOT CMAKE_VERSION VERSION_LESS 3.8) + set(GTSAM_COMPILE_FEATURES_PUBLIC "cxx_std_11" CACHE STRING "CMake compile features property for all gtsam targets.") + # See: https://cmake.org/cmake/help/latest/prop_tgt/CXX_EXTENSIONS.html + # This is to enable -std=c++11 instead of -std=g++11 + set(CMAKE_CXX_EXTENSIONS OFF) +else() + # Old cmake versions: + if (NOT MSVC) + list_append_cache(GTSAM_COMPILE_OPTIONS_PUBLIC $<$:-std=c++11>) + endif() +endif() + +# Merge all user-defined flags into the variables that are to be actually used by CMake: +foreach(build_type "common" ${GTSAM_CMAKE_CONFIGURATION_TYPES}) + append_config_if_not_empty(GTSAM_COMPILE_OPTIONS_PRIVATE ${build_type}) + append_config_if_not_empty(GTSAM_COMPILE_OPTIONS_PUBLIC ${build_type}) + append_config_if_not_empty(GTSAM_COMPILE_DEFINITIONS_PRIVATE ${build_type}) + append_config_if_not_empty(GTSAM_COMPILE_DEFINITIONS_PUBLIC ${build_type}) +endforeach() + +# Linker flags: set(GTSAM_CMAKE_SHARED_LINKER_FLAGS_TIMING "${CMAKE_SHARED_LINKER_FLAGS_RELEASE}" CACHE STRING "Linker flags during timing builds.") set(GTSAM_CMAKE_MODULE_LINKER_FLAGS_TIMING "${CMAKE_MODULE_LINKER_FLAGS_RELEASE}" CACHE STRING "Linker flags during timing builds.") set(GTSAM_CMAKE_EXE_LINKER_FLAGS_TIMING "${CMAKE_EXE_LINKER_FLAGS_RELEASE}" CACHE STRING "Linker flags during timing builds.") @@ -54,26 +132,11 @@ set(GTSAM_CMAKE_SHARED_LINKER_FLAGS_PROFILING "${CMAKE_SHARED_LINKER_FLAGS_RELEA set(GTSAM_CMAKE_MODULE_LINKER_FLAGS_PROFILING "${CMAKE_MODULE_LINKER_FLAGS_RELEASE}" CACHE STRING "Linker flags during profiling builds.") set(GTSAM_CMAKE_EXE_LINKER_FLAGS_PROFILING "${CMAKE_EXE_LINKER_FLAGS_RELEASE}" CACHE STRING "Linker flags during profiling builds.") -mark_as_advanced(GTSAM_CMAKE_C_FLAGS_TIMING GTSAM_CMAKE_CXX_FLAGS_TIMING GTSAM_CMAKE_EXE_LINKER_FLAGS_TIMING +mark_as_advanced(GTSAM_CMAKE_EXE_LINKER_FLAGS_TIMING GTSAM_CMAKE_SHARED_LINKER_FLAGS_TIMING GTSAM_CMAKE_MODULE_LINKER_FLAGS_TIMING - GTSAM_CMAKE_C_FLAGS_PROFILING GTSAM_CMAKE_CXX_FLAGS_PROFILING GTSAM_CMAKE_EXE_LINKER_FLAGS_PROFILING + GTSAM_CMAKE_C_FLAGS_PROFILING GTSAM_ GTSAM_CMAKE_EXE_LINKER_FLAGS_PROFILING GTSAM_CMAKE_SHARED_LINKER_FLAGS_PROFILING GTSAM_CMAKE_MODULE_LINKER_FLAGS_PROFILING) -# Apply the gtsam specific build flags as normal variables. This makes it so that they only -# apply to the gtsam part of the build if gtsam is built as a subproject -set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} ${GTSAM_CMAKE_C_FLAGS}") -set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${GTSAM_CMAKE_CXX_FLAGS}") -set(CMAKE_C_FLAGS_DEBUG "${CMAKE_C_FLAGS_DEBUG} ${GTSAM_CMAKE_C_FLAGS_DEBUG}") -set(CMAKE_CXX_FLAGS_DEBUG "${CMAKE_CXX_FLAGS_DEBUG} ${GTSAM_CMAKE_CXX_FLAGS_DEBUG}") -set(CMAKE_C_FLAGS_RELWITHDEBINFO "${CMAKE_C_FLAGS_RELWITHDEBINFO} ${GTSAM_CMAKE_C_FLAGS_RELWITHDEBINFO}") -set(CMAKE_CXX_FLAGS_RELWITHDEBINFO "${CMAKE_CXX_FLAGS_RELWITHDEBINFO} ${GTSAM_CMAKE_CXX_FLAGS_RELWITHDEBINFO}") -set(CMAKE_C_FLAGS_RELEASE "${CMAKE_C_FLAGS_RELEASE} ${GTSAM_CMAKE_C_FLAGS_RELEASE}") -set(CMAKE_CXX_FLAGS_RELEASE "${CMAKE_CXX_FLAGS_RELEASE} ${GTSAM_CMAKE_CXX_FLAGS_RELEASE}") -set(CMAKE_C_FLAGS_PROFILING "${CMAKE_C_FLAGS_PROFILING} ${GTSAM_CMAKE_C_FLAGS_PROFILING}") -set(CMAKE_CXX_FLAGS_PROFILING "${CMAKE_CXX_FLAGS_PROFILING} ${GTSAM_CMAKE_CXX_FLAGS_PROFILING}") -set(CMAKE_C_FLAGS_TIMING "${CMAKE_C_FLAGS_TIMING} ${GTSAM_CMAKE_C_FLAGS_TIMING}") -set(CMAKE_CXX_FLAGS_TIMING "${CMAKE_CXX_FLAGS_TIMING} ${GTSAM_CMAKE_CXX_FLAGS_TIMING}") - set(CMAKE_SHARED_LINKER_FLAGS_TIMING ${GTSAM_CMAKE_SHARED_LINKER_FLAGS_TIMING}) set(CMAKE_MODULE_LINKER_FLAGS_TIMING ${GTSAM_CMAKE_MODULE_LINKER_FLAGS_TIMING}) set(CMAKE_EXE_LINKER_FLAGS_TIMING ${GTSAM_CMAKE_EXE_LINKER_FLAGS_TIMING}) @@ -86,10 +149,19 @@ set(CMAKE_EXE_LINKER_FLAGS_PROFILING ${GTSAM_CMAKE_EXE_LINKER_FLAGS_PROFILING}) if(${CMAKE_CXX_COMPILER_ID} STREQUAL "Clang") # Apple Clang before 5.0 does not support -ftemplate-depth. if(NOT (APPLE AND "${CMAKE_CXX_COMPILER_VERSION}" VERSION_LESS "5.0")) - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -ftemplate-depth=1024") + list_append_cache(GTSAM_COMPILE_OPTIONS_PUBLIC "-ftemplate-depth=1024") endif() endif() +if (NOT MSVC) + option(GTSAM_BUILD_WITH_MARCH_NATIVE "Enable/Disable building with all instructions supported by native architecture (binary may not be portable!)" ON) + if(GTSAM_BUILD_WITH_MARCH_NATIVE) + # Add as public flag so all dependant projects also use it, as required + # by Eigen to avid crashes due to SIMD vectorization: + list_append_cache(GTSAM_COMPILE_OPTIONS_PUBLIC "-march=native") + endif() +endif() + # Set up build type library postfixes if(GTSAM_BUILD_TYPE_POSTFIXES) foreach(build_type Debug Timing Profiling RelWithDebInfo MinSizeRel) @@ -112,12 +184,6 @@ if(NOT "${CMAKE_BUILD_TYPE}" STREQUAL "") endif() endif() -# Set up build types for MSVC and XCode -set(GTSAM_CMAKE_CONFIGURATION_TYPES Debug Release Timing Profiling RelWithDebInfo MinSizeRel - CACHE STRING "Build types available to MSVC and XCode") -mark_as_advanced(FORCE GTSAM_CMAKE_CONFIGURATION_TYPES) -set(CMAKE_CONFIGURATION_TYPES ${GTSAM_CMAKE_CONFIGURATION_TYPES}) - # Check build types string(TOLOWER "${CMAKE_BUILD_TYPE}" cmake_build_type_tolower) if( NOT cmake_build_type_tolower STREQUAL "" @@ -153,3 +219,20 @@ function(gtsam_assign_all_source_folders) gtsam_assign_source_folders("${all_c_srcs};${all_cpp_srcs};${all_headers}") endfunction() +# Applies the per-config build flags to the given target (e.g. gtsam, wrap_lib) +function(gtsam_apply_build_flags target_name_) + # To enable C++11: the use of target_compile_features() is preferred since + # it will be not in conflict with a more modern C++ standard, if used in a + # client program. + if (NOT "${GTSAM_COMPILE_FEATURES_PUBLIC}" STREQUAL "") + target_compile_features(${target_name_} PUBLIC ${GTSAM_COMPILE_FEATURES_PUBLIC}) + endif() + + target_compile_definitions(${target_name_} PRIVATE ${GTSAM_COMPILE_DEFINITIONS_PRIVATE}) + target_compile_definitions(${target_name_} PUBLIC ${GTSAM_COMPILE_DEFINITIONS_PUBLIC}) + if (NOT "${GTSAM_COMPILE_OPTIONS_PUBLIC}" STREQUAL "") + target_compile_options(${target_name_} PUBLIC ${GTSAM_COMPILE_OPTIONS_PUBLIC}) + endif() + target_compile_options(${target_name_} PRIVATE ${GTSAM_COMPILE_OPTIONS_PRIVATE}) + +endfunction(gtsam_apply_build_flags) diff --git a/cmake/GtsamCythonWrap.cmake b/cmake/GtsamCythonWrap.cmake index 73e2b63e0..c3cad9d83 100644 --- a/cmake/GtsamCythonWrap.cmake +++ b/cmake/GtsamCythonWrap.cmake @@ -3,8 +3,23 @@ # in the current environment are different from the cached! unset(PYTHON_EXECUTABLE CACHE) unset(CYTHON_EXECUTABLE CACHE) +unset(PYTHON_INCLUDE_DIR CACHE) +unset(PYTHON_MAJOR_VERSION CACHE) + +if(GTSAM_PYTHON_VERSION STREQUAL "Default") + find_package(PythonInterp REQUIRED) + find_package(PythonLibs REQUIRED) +else() + find_package(PythonInterp ${GTSAM_PYTHON_VERSION} EXACT REQUIRED) + find_package(PythonLibs ${GTSAM_PYTHON_VERSION} EXACT REQUIRED) +endif() find_package(Cython 0.25.2 REQUIRED) +execute_process(COMMAND "${PYTHON_EXECUTABLE}" "-c" + "from __future__ import print_function;import sys;print(sys.version[0], end='')" + OUTPUT_VARIABLE PYTHON_MAJOR_VERSION +) + # User-friendly Cython wrapping and installing function. # Builds a Cython module from the provided interface_header. # For example, for the interface header gtsam.h, @@ -29,12 +44,12 @@ endfunction() function(set_up_required_cython_packages) # Set up building of cython module - find_package(PythonLibs 2.7 REQUIRED) include_directories(${PYTHON_INCLUDE_DIRS}) find_package(NumPy REQUIRED) include_directories(${NUMPY_INCLUDE_DIRS}) endfunction() + # Convert pyx to cpp by executing cython # This is the first step to compile cython from the command line # as described at: http://cython.readthedocs.io/en/latest/src/reference/compilation.html @@ -52,7 +67,7 @@ function(pyx_to_cpp target pyx_file generated_cpp include_dirs) add_custom_command( OUTPUT ${generated_cpp} COMMAND - ${CYTHON_EXECUTABLE} -X boundscheck=False -v --fast-fail --cplus ${includes_for_cython} ${pyx_file} -o ${generated_cpp} + ${CYTHON_EXECUTABLE} -X boundscheck=False -v --fast-fail --cplus -${PYTHON_MAJOR_VERSION} ${includes_for_cython} ${pyx_file} -o ${generated_cpp} VERBATIM) add_custom_target(${target} ALL DEPENDS ${generated_cpp}) endfunction() @@ -71,8 +86,13 @@ function(build_cythonized_cpp target cpp_file output_lib_we output_dir) if(APPLE) set(link_flags "-undefined dynamic_lookup") endif() - set_target_properties(${target} PROPERTIES COMPILE_FLAGS "-w" LINK_FLAGS "${link_flags}" - OUTPUT_NAME ${output_lib_we} PREFIX "" LIBRARY_OUTPUT_DIRECTORY ${output_dir}) + set_target_properties(${target} + PROPERTIES COMPILE_FLAGS "-w" + LINK_FLAGS "${link_flags}" + OUTPUT_NAME ${output_lib_we} + PREFIX "" + ${CMAKE_BUILD_TYPE_UPPER}_POSTFIX "" + LIBRARY_OUTPUT_DIRECTORY ${output_dir}) endfunction() # Cythonize a pyx from the command line as described at @@ -146,9 +166,13 @@ endfunction() function(install_cython_wrapped_library interface_header generated_files_path install_path) get_filename_component(module_name "${interface_header}" NAME_WE) - # NOTE: only installs .pxd and .pyx and binary files (not .cpp) - the trailing slash on the directory name + # NOTE: only installs .pxd and .pyx and binary files (not .cpp) - the trailing slash on the directory name # here prevents creating the top-level module name directory in the destination. - message(STATUS "Installing Cython Toolbox to ${install_path}") #${GTSAM_CYTHON_INSTALL_PATH}") + # Split up filename to strip trailing '/' in GTSAM_CYTHON_INSTALL_PATH/subdirectory if there is one + get_filename_component(location "${install_path}" PATH) + get_filename_component(name "${install_path}" NAME) + message(STATUS "Installing Cython Toolbox to ${location}${GTSAM_BUILD_TAG}/${name}") #${GTSAM_CYTHON_INSTALL_PATH}" + if(GTSAM_BUILD_TYPE_POSTFIXES) foreach(build_type ${CMAKE_CONFIGURATION_TYPES}) string(TOUPPER "${build_type}" build_type_upper) @@ -157,10 +181,8 @@ function(install_cython_wrapped_library interface_header generated_files_path in else() set(build_type_tag "${build_type}") endif() - # Split up filename to strip trailing '/' in GTSAM_CYTHON_INSTALL_PATH if there is one - get_filename_component(location "${install_path}" PATH) - get_filename_component(name "${install_path}" NAME) - install(DIRECTORY "${generated_files_path}/" DESTINATION "${location}/${name}${build_type_tag}" + + install(DIRECTORY "${generated_files_path}/" DESTINATION "${location}${build_type_tag}/${name}" CONFIGURATIONS "${build_type}" PATTERN "build" EXCLUDE PATTERN "CMakeFiles" EXCLUDE diff --git a/cmake/GtsamMatlabWrap.cmake b/cmake/GtsamMatlabWrap.cmake index bdd868665..5fc829bf2 100644 --- a/cmake/GtsamMatlabWrap.cmake +++ b/cmake/GtsamMatlabWrap.cmake @@ -35,7 +35,11 @@ mark_as_advanced(FORCE MEX_COMMAND) # Now that we have mex, trace back to find the Matlab installation root get_filename_component(MEX_COMMAND "${MEX_COMMAND}" REALPATH) get_filename_component(mex_path "${MEX_COMMAND}" PATH) -get_filename_component(MATLAB_ROOT "${mex_path}/.." ABSOLUTE) +if(mex_path MATCHES ".*/win64$") + get_filename_component(MATLAB_ROOT "${mex_path}/../.." ABSOLUTE) +else() + get_filename_component(MATLAB_ROOT "${mex_path}/.." ABSOLUTE) +endif() set(MATLAB_ROOT "${MATLAB_ROOT}" CACHE PATH "Path to MATLAB installation root (e.g. /usr/local/MATLAB/R2012a)") @@ -78,28 +82,29 @@ function(wrap_library_internal interfaceHeader linkLibraries extraIncludeDirs ex set(mexModuleExt mexw32) endif() endif() - + # Wrap codegen interface #usage: wrap interfacePath moduleName toolboxPath headerPath # interfacePath : *absolute* path to directory of module interface file # moduleName : the name of the module, interface file must be called moduleName.h # toolboxPath : the directory in which to generate the wrappers - # headerPath : path to matlab.h - + # headerPath : path to matlab.h + # Extract module name from interface header file name get_filename_component(interfaceHeader "${interfaceHeader}" ABSOLUTE) get_filename_component(modulePath "${interfaceHeader}" PATH) get_filename_component(moduleName "${interfaceHeader}" NAME_WE) - + # Paths for generated files set(generated_files_path "${PROJECT_BINARY_DIR}/wrap/${moduleName}") set(generated_cpp_file "${generated_files_path}/${moduleName}_wrapper.cpp") set(compiled_mex_modules_root "${PROJECT_BINARY_DIR}/wrap/${moduleName}_mex") - + message(STATUS "Building wrap module ${moduleName}") - + # Find matlab.h in GTSAM - if("${PROJECT_NAME}" STREQUAL "GTSAM") + if(("${PROJECT_NAME}" STREQUAL "gtsam") OR + ("${PROJECT_NAME}" STREQUAL "gtsam_unstable")) set(matlab_h_path "${PROJECT_SOURCE_DIR}") else() if(NOT GTSAM_INCLUDE_DIR) @@ -221,6 +226,7 @@ function(wrap_library_internal interfaceHeader linkLibraries extraIncludeDirs ex string(REPLACE ";" " " mexFlagsSpaced "${GTSAM_BUILD_MEX_BINARY_FLAGS}") add_library(${moduleName}_matlab_wrapper MODULE ${generated_cpp_file} ${interfaceHeader} ${otherSourcesAndObjects}) target_link_libraries(${moduleName}_matlab_wrapper ${correctedOtherLibraries}) + target_link_libraries(${moduleName}_matlab_wrapper ${moduleName}) set_target_properties(${moduleName}_matlab_wrapper PROPERTIES OUTPUT_NAME "${moduleName}_wrapper" PREFIX "" diff --git a/cmake/GtsamPrinting.cmake b/cmake/GtsamPrinting.cmake index 674fd4086..e53f9c54f 100644 --- a/cmake/GtsamPrinting.cmake +++ b/cmake/GtsamPrinting.cmake @@ -7,4 +7,45 @@ function(print_config_flag flag msg) else () message(STATUS " ${msg}: Disabled") endif () -endfunction(print_config_flag) +endfunction() + +# Based on https://github.com/jimbraun/XCDF/blob/master/cmake/CMakePadString.cmake +function(string_pad RESULT_NAME DESIRED_LENGTH VALUE) + string(LENGTH "${VALUE}" VALUE_LENGTH) + math(EXPR REQUIRED_PADS "${DESIRED_LENGTH} - ${VALUE_LENGTH}") + set(PAD ${VALUE}) + if(REQUIRED_PADS GREATER 0) + math(EXPR REQUIRED_MINUS_ONE "${REQUIRED_PADS} - 1") + foreach(FOO RANGE ${REQUIRED_MINUS_ONE}) + set(PAD "${PAD} ") + endforeach() + endif() + set(${RESULT_NAME} "${PAD}" PARENT_SCOPE) +endfunction() + +set(GTSAM_PRINT_SUMMARY_PADDING_LENGTH 50 CACHE STRING "Padding of cmake summary report lines after configuring.") +mark_as_advanced(GTSAM_PRINT_SUMMARY_PADDING_LENGTH) + +# Print " var: ${var}" padding with spaces as needed +function(print_padded variable_name) + string_pad(padded_prop ${GTSAM_PRINT_SUMMARY_PADDING_LENGTH} " ${variable_name}") + message(STATUS "${padded_prop}: ${${variable_name}}") +endfunction() + + +# Prints all the relevant CMake build options for a given target: +function(print_build_options_for_target target_name_) + print_padded(GTSAM_COMPILE_FEATURES_PUBLIC) + print_padded(GTSAM_COMPILE_OPTIONS_PRIVATE) + print_padded(GTSAM_COMPILE_OPTIONS_PUBLIC) + print_padded(GTSAM_COMPILE_DEFINITIONS_PRIVATE) + print_padded(GTSAM_COMPILE_DEFINITIONS_PUBLIC) + + foreach(build_type ${GTSAM_CMAKE_CONFIGURATION_TYPES}) + string(TOUPPER "${build_type}" build_type_toupper) + print_padded(GTSAM_COMPILE_OPTIONS_PRIVATE_${build_type_toupper}) + print_padded(GTSAM_COMPILE_OPTIONS_PUBLIC_${build_type_toupper}) + print_padded(GTSAM_COMPILE_DEFINITIONS_PRIVATE_${build_type_toupper}) + print_padded(GTSAM_COMPILE_DEFINITIONS_PUBLIC_${build_type_toupper}) + endforeach() +endfunction() diff --git a/cmake/GtsamTesting.cmake b/cmake/GtsamTesting.cmake index 15d4219e6..3b42ffa21 100644 --- a/cmake/GtsamTesting.cmake +++ b/cmake/GtsamTesting.cmake @@ -8,7 +8,7 @@ # Macro: # # gtsamAddTestsGlob(groupName globPatterns excludedFiles linkLibraries) -# +# # Add a group of unit tests. A list of unit test .cpp files or glob patterns specifies the # tests to create. Tests are assigned into a group name so they can easily by run # independently with a make target. Running 'make check' builds and runs all tests. @@ -35,7 +35,7 @@ endmacro() # Macro: # # gtsamAddExamplesGlob(globPatterns excludedFiles linkLibraries) -# +# # Add scripts that will serve as examples of how to use the library. A list of files or # glob patterns is specified, and one executable will be created for each matching .cpp # file. These executables will not be installed. They are built with 'make all' if @@ -60,7 +60,7 @@ endmacro() # Macro: # # gtsamAddTimingGlob(globPatterns excludedFiles linkLibraries) -# +# # Add scripts that time aspects of the library. A list of files or # glob patterns is specified, and one executable will be created for each matching .cpp # file. These executables will not be installed. They are not built with 'make all', @@ -88,29 +88,36 @@ enable_testing() option(GTSAM_BUILD_TESTS "Enable/Disable building of tests" ON) option(GTSAM_BUILD_EXAMPLES_ALWAYS "Build examples with 'make all' (build with 'make examples' if not)" ON) -option(GTSAM_BUILD_TIMING_ALWAYS "Build timing scripts with 'make all' (build with 'make timing' if not" OFF) + option(GTSAM_BUILD_TIMING_ALWAYS "Build timing scripts with 'make all' (build with 'make timing' if not" OFF) -# Add option for combining unit tests -if(MSVC OR XCODE_VERSION) - option(GTSAM_SINGLE_TEST_EXE "Combine unit tests into single executable (faster compile)" ON) -else() - option(GTSAM_SINGLE_TEST_EXE "Combine unit tests into single executable (faster compile)" OFF) -endif() -mark_as_advanced(GTSAM_SINGLE_TEST_EXE) + # Add option for combining unit tests + if(MSVC OR XCODE_VERSION) + option(GTSAM_SINGLE_TEST_EXE "Combine unit tests into single executable (faster compile)" ON) + else() + option(GTSAM_SINGLE_TEST_EXE "Combine unit tests into single executable (faster compile)" OFF) + endif() + mark_as_advanced(GTSAM_SINGLE_TEST_EXE) -# Enable make check (http://www.cmake.org/Wiki/CMakeEmulateMakeCheck) -if(GTSAM_BUILD_TESTS) - add_custom_target(check COMMAND ${CMAKE_CTEST_COMMAND} -C $ --output-on-failure) - - # Add target to build tests without running - add_custom_target(all.tests) -endif() + # Enable make check (http://www.cmake.org/Wiki/CMakeEmulateMakeCheck) + if(GTSAM_BUILD_TESTS) + add_custom_target(check COMMAND ${CMAKE_CTEST_COMMAND} -C $ --output-on-failure) + # Also add alternative checks using valgrind. + # We don't look for valgrind being installed in the system, since these + # targets are not invoked unless directly instructed by the user. + if (UNIX) + # Run all tests using valgrind: + add_custom_target(check_valgrind) + endif() -# Add examples target -add_custom_target(examples) + # Add target to build tests without running + add_custom_target(all.tests) + endif() -# Add timing target -add_custom_target(timing) + # Add examples target + add_custom_target(examples) + + # Add timing target + add_custom_target(timing) # Implementations of this file's macros: @@ -118,23 +125,24 @@ add_custom_target(timing) macro(gtsamAddTestsGlob_impl groupName globPatterns excludedFiles linkLibraries) if(GTSAM_BUILD_TESTS) # Add group target if it doesn't already exist - if(NOT TARGET check.${groupName}) + if(NOT TARGET check.${groupName}) add_custom_target(check.${groupName} COMMAND ${CMAKE_CTEST_COMMAND} -C $ --output-on-failure) + set_property(TARGET check.${groupName} PROPERTY FOLDER "Unit tests") endif() - - # Get all script files - file(GLOB script_files ${globPatterns}) - # Remove excluded scripts from the list - if(NOT "${excludedFiles}" STREQUAL "") + # Get all script files + file(GLOB script_files ${globPatterns}) + + # Remove excluded scripts from the list + if(NOT "${excludedFiles}" STREQUAL "") file(GLOB excludedFilePaths ${excludedFiles}) if("${excludedFilePaths}" STREQUAL "") message(WARNING "The pattern '${excludedFiles}' for excluding tests from group ${groupName} did not match any files") else() - list(REMOVE_ITEM script_files ${excludedFilePaths}) + list(REMOVE_ITEM script_files ${excludedFilePaths}) endif() - endif() - + endif() + # Separate into source files and headers (allows for adding headers to show up in # MSVC and Xcode projects). set(script_srcs "") @@ -147,7 +155,7 @@ macro(gtsamAddTestsGlob_impl groupName globPatterns excludedFiles linkLibraries) list(APPEND script_srcs ${script_file}) endif() endforeach() - + # Don't put test files in folders in MSVC and Xcode because they're already grouped source_group("" FILES ${script_srcs} ${script_headers}) @@ -156,26 +164,41 @@ macro(gtsamAddTestsGlob_impl groupName globPatterns excludedFiles linkLibraries) foreach(script_src IN ITEMS ${script_srcs}) # Get test base name get_filename_component(script_name ${script_src} NAME_WE) - + # Add executable add_executable(${script_name} ${script_src} ${script_headers}) target_link_libraries(${script_name} CppUnitLite ${linkLibraries}) - + + # Apply user build flags from CMake cache variables: + gtsam_apply_build_flags(${script_name}) + # Add target dependencies add_test(NAME ${script_name} COMMAND ${script_name}) add_dependencies(check.${groupName} ${script_name}) add_dependencies(check ${script_name}) - add_dependencies(all.tests ${script_name}) + add_dependencies(all.tests ${script_name}) if(NOT MSVC AND NOT XCODE_VERSION) - add_custom_target(${script_name}.run ${EXECUTABLE_OUTPUT_PATH}${script_name} DEPENDS ${script_name}) + # Regular test run: + add_custom_target(${script_name}.run + COMMAND ${EXECUTABLE_OUTPUT_PATH}${script_name} + DEPENDS ${script_name} + ) + + # Run with valgrind: + set(GENERATED_EXE "$") + add_custom_target(${script_name}.valgrind + COMMAND "valgrind" "--error-exitcode=1" ${GENERATED_EXE} + DEPENDS ${script_name} + ) + add_dependencies(check_valgrind ${script_name}.valgrind) endif() - + # Add TOPSRCDIR - set_property(SOURCE ${script_src} APPEND PROPERTY COMPILE_DEFINITIONS "TOPSRCDIR=\"${PROJECT_SOURCE_DIR}\"") - + set_property(SOURCE ${script_src} APPEND PROPERTY COMPILE_DEFINITIONS "TOPSRCDIR=\"${GTSAM_SOURCE_DIR}\"") + # Exclude from 'make all' and 'make install' set_target_properties(${script_name} PROPERTIES EXCLUDE_FROM_ALL ON) - + # Configure target folder (for MSVC and Xcode) set_property(TARGET ${script_name} PROPERTY FOLDER "Unit tests/${groupName}") endforeach() @@ -188,16 +211,21 @@ macro(gtsamAddTestsGlob_impl groupName globPatterns excludedFiles linkLibraries) # Default on MSVC and XCode - combine test group into a single exectuable set(target_name check_${groupName}_program) - + # Add executable add_executable(${target_name} "${script_srcs}" ${script_headers}) target_link_libraries(${target_name} CppUnitLite ${linkLibraries}) - + + # Apply user build flags from CMake cache variables: + gtsam_apply_build_flags(${target_name}) + + set_property(TARGET check_${groupName}_program PROPERTY FOLDER "Unit tests") + # Only have a main function in one script - use preprocessor set(rest_script_srcs ${script_srcs}) list(REMOVE_AT rest_script_srcs 0) set_property(SOURCE ${rest_script_srcs} APPEND PROPERTY COMPILE_DEFINITIONS "main=inline no_main") - + # Add target dependencies add_test(NAME ${target_name} COMMAND ${target_name}) add_dependencies(check.${groupName} ${target_name}) @@ -205,10 +233,10 @@ macro(gtsamAddTestsGlob_impl groupName globPatterns excludedFiles linkLibraries) if(NOT XCODE_VERSION) add_dependencies(all.tests ${target_name}) endif() - + # Add TOPSRCDIR - set_property(SOURCE ${script_srcs} APPEND PROPERTY COMPILE_DEFINITIONS "TOPSRCDIR=\"${PROJECT_SOURCE_DIR}\"") - + set_property(SOURCE ${script_srcs} APPEND PROPERTY COMPILE_DEFINITIONS "TOPSRCDIR=\"${GTSAM_SOURCE_DIR}\"") + # Exclude from 'make all' and 'make install' set_target_properties(${target_name} PROPERTIES EXCLUDE_FROM_ALL ON) @@ -220,18 +248,18 @@ endmacro() macro(gtsamAddExesGlob_impl globPatterns excludedFiles linkLibraries groupName buildWithAll) - # Get all script files - file(GLOB script_files ${globPatterns}) + # Get all script files + file(GLOB script_files ${globPatterns}) - # Remove excluded scripts from the list - if(NOT "${excludedFiles}" STREQUAL "") + # Remove excluded scripts from the list + if(NOT "${excludedFiles}" STREQUAL "") file(GLOB excludedFilePaths ${excludedFiles}) if("${excludedFilePaths}" STREQUAL "") message(WARNING "The script exclusion pattern '${excludedFiles}' did not match any files") else() - list(REMOVE_ITEM script_files ${excludedFilePaths}) + list(REMOVE_ITEM script_files ${excludedFilePaths}) endif() - endif() + endif() # Separate into source files and headers (allows for adding headers to show up in # MSVC and Xcode projects). @@ -257,18 +285,21 @@ macro(gtsamAddExesGlob_impl globPatterns excludedFiles linkLibraries groupName b # Add executable add_executable(${script_name} ${script_src} ${script_headers}) target_link_libraries(${script_name} ${linkLibraries}) - + + # Apply user build flags from CMake cache variables: + gtsam_apply_build_flags(${script_name}) + # Add target dependencies add_dependencies(${groupName} ${script_name}) if(NOT MSVC AND NOT XCODE_VERSION) - add_custom_target(${script_name}.run ${EXECUTABLE_OUTPUT_PATH}${script_name} DEPENDS ${script_name}) + add_custom_target(${script_name}.run ${EXECUTABLE_OUTPUT_PATH}${script_name} DEPENDS ${script_name}) endif() # Add TOPSRCDIR - set_property(SOURCE ${script_src} APPEND PROPERTY COMPILE_DEFINITIONS "TOPSRCDIR=\"${PROJECT_SOURCE_DIR}\"") + set_property(SOURCE ${script_src} APPEND PROPERTY COMPILE_DEFINITIONS "TOPSRCDIR=\"${GTSAM_SOURCE_DIR}\"") - # Exclude from all or not - note weird variable assignment because we're in a macro - set(buildWithAll_on ${buildWithAll}) + # Exclude from all or not - note weird variable assignment because we're in a macro + set(buildWithAll_on ${buildWithAll}) if(NOT buildWithAll_on) # Exclude from 'make all' and 'make install' set_target_properties("${script_name}" PROPERTIES EXCLUDE_FROM_ALL ON) diff --git a/cmake/README.md b/cmake/README.md index 34d1ffb52..7f38bbcf2 100644 --- a/cmake/README.md +++ b/cmake/README.md @@ -1,5 +1,4 @@ -GTSAMCMakeTools -=============== +# GTSAMCMakeTools This is the collection of GTSAM CMake tools that may be useful in external projects. The way to use this collection is by first making a find_package call: @@ -7,8 +6,7 @@ This is the collection of GTSAM CMake tools that may be useful in external proje which will add a directory containing the GTSAM CMake tools to the CMAKE_MODULE_PATH variable. After that, you may include the files you would like to use. These files and the functions they define are explained below. -GtsamBuildTypes ---------------- +## GtsamBuildTypes include(GtsamBuildTypes) @@ -17,8 +15,8 @@ Including this file immediately sets up the following build types and a drop-dow * `Debug` * `Release` * `RelWithDebInfo` -* `Profiling`: All optimizations enabled and minimal debug symbols -* `Timing`: Defines the symbol GTSAM_ENABLE_TIMING for using GTSAM timing instrumentation +* `Profiling`: All optimizations enabled and minimal debug symbols +* `Timing`: Defines the symbol GTSAM_ENABLE_TIMING for using GTSAM timing instrumentation It also configures several minor details, as follows: @@ -30,8 +28,7 @@ It defines the following functions: * `gtsam_assign_source_folders( [files] )` Organizes files in the IDE into folders to reflect the actual directory structure of those files. Folders will be determined relative to the current source folder when this function is called. * `gtsam_assign_all_source_folders()` Calls `gtsam_assign_source_folders` on all cpp, c, and h files recursively in the current source folder. -GtsamTesting ------------- +## GtsamTesting include(GtsamTesting) @@ -70,8 +67,7 @@ Defines two useful functions for creating CTest unit tests. Also immediately cr an empty string "" if nothing needs to be excluded. linkLibraries: The list of libraries to link to. -GtsamMatlabWrap ---------------- +## GtsamMatlabWrap include(GtsamMatlabWrap) @@ -97,8 +93,7 @@ Defines functions for generating MATLAB wrappers. Also immediately creates seve extraMexFlags: Any *additional* flags to pass to the compiler when building the wrap code. Normally, leave this empty. -GtsamMakeConfigFile -------------------- +## GtsamMakeConfigFile include(GtsamMakeConfigFile) diff --git a/cmake/cmake_uninstall.cmake.in b/cmake/cmake_uninstall.cmake.in new file mode 100644 index 000000000..aa20a69a6 --- /dev/null +++ b/cmake/cmake_uninstall.cmake.in @@ -0,0 +1,27 @@ +# ----------------------------------------------- +# File that provides "make uninstall" target +# We use the file 'install_manifest.txt' +# ----------------------------------------------- +if(NOT EXISTS "@CMAKE_CURRENT_BINARY_DIR@/install_manifest.txt") + message(FATAL_ERROR "Cannot find install manifest: \"@CMAKE_CURRENT_BINARY_DIR@/install_manifest.txt\"") +endif(NOT EXISTS "@CMAKE_CURRENT_BINARY_DIR@/install_manifest.txt") + +file(READ "@CMAKE_CURRENT_BINARY_DIR@/install_manifest.txt" files) +string(REGEX REPLACE "\n" ";" files "${files}") +foreach(file ${files}) + message(STATUS "Uninstalling \"$ENV{DESTDIR}${file}\"") + if(EXISTS "$ENV{DESTDIR}${file}") + exec_program( + "@CMAKE_COMMAND@" ARGS "-E remove \"$ENV{DESTDIR}${file}\"" + OUTPUT_VARIABLE rm_out + RETURN_VALUE rm_retval + ) + if(NOT "${rm_retval}" STREQUAL 0) + message(FATAL_ERROR "Problem when removing \"$ENV{DESTDIR}${file}\"") + endif(NOT "${rm_retval}" STREQUAL 0) + else(EXISTS "$ENV{DESTDIR}${file}") + message(STATUS "File \"$ENV{DESTDIR}${file}\" does not exist.") + endif(EXISTS "$ENV{DESTDIR}${file}") +endforeach(file) + + diff --git a/cmake/dllexport.h.in b/cmake/dllexport.h.in index 55683a496..9a0a344b7 100644 --- a/cmake/dllexport.h.in +++ b/cmake/dllexport.h.in @@ -31,10 +31,10 @@ // Whether GTSAM is compiled as static or DLL in windows. // This will be used to decide whether include __declspec(dllimport) or not in headers -#cmakedefine GTSAM_BUILD_STATIC_LIBRARY +#cmakedefine BUILD_SHARED_LIBS #ifdef _WIN32 -# ifdef @library_name@_BUILD_STATIC_LIBRARY +# ifndef BUILD_SHARED_LIBS # define @library_name@_EXPORT # define @library_name@_EXTERN_EXPORT extern # else @@ -50,3 +50,6 @@ # define @library_name@_EXPORT # define @library_name@_EXTERN_EXPORT extern #endif + +#undef BUILD_SHARED_LIBS + diff --git a/cmake/example_cmake_find_gtsam/CMakeLists.txt b/cmake/example_cmake_find_gtsam/CMakeLists.txt new file mode 100644 index 000000000..9a4be4d70 --- /dev/null +++ b/cmake/example_cmake_find_gtsam/CMakeLists.txt @@ -0,0 +1,17 @@ +# This file shows how to build and link a user project against GTSAM using CMake +################################################################################### +# To create your own project, replace "example" with the actual name of your project +cmake_minimum_required(VERSION 3.0) +project(example CXX) + +# Find GTSAM, either from a local build, or from a Debian/Ubuntu package. +find_package(GTSAM REQUIRED) + +add_executable(example + main.cpp +) + +# By using CMake exported targets, a simple "link" dependency introduces the +# include directories (-I) flags, links against Boost, and add any other +# required build flags (e.g. C++11, etc.) +target_link_libraries(example PRIVATE gtsam) diff --git a/cmake/example_cmake_find_gtsam/main.cpp b/cmake/example_cmake_find_gtsam/main.cpp new file mode 100644 index 000000000..4d93e1b19 --- /dev/null +++ b/cmake/example_cmake_find_gtsam/main.cpp @@ -0,0 +1,127 @@ +/* ---------------------------------------------------------------------------- + * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + * See LICENSE for the license information + * -------------------------------------------------------------------------- */ + +/** + * @file Pose2SLAMExample.cpp + * @brief A 2D Pose SLAM example + * @date Oct 21, 2010 + * @author Yong Dian Jian + */ + +/** + * A simple 2D pose slam example + * - The robot moves in a 2 meter square + * - The robot moves 2 meters each step, turning 90 degrees after each step + * - The robot initially faces along the X axis (horizontal, to the right in 2D) + * - We have full odometry between pose + * - We have a loop closure constraint when the robot returns to the first position + */ + +// In planar SLAM example we use Pose2 variables (x, y, theta) to represent the robot poses +#include + +// We will use simple integer Keys to refer to the robot poses. +#include + +// In GTSAM, measurement functions are represented as 'factors'. Several common factors +// have been provided with the library for solving robotics/SLAM/Bundle Adjustment problems. +// Here we will use Between factors for the relative motion described by odometry measurements. +// We will also use a Between Factor to encode the loop closure constraint +// Also, we will initialize the robot at the origin using a Prior factor. +#include +#include + +// When the factors are created, we will add them to a Factor Graph. As the factors we are using +// are nonlinear factors, we will need a Nonlinear Factor Graph. +#include + +// Finally, once all of the factors have been added to our factor graph, we will want to +// solve/optimize to graph to find the best (Maximum A Posteriori) set of variable values. +// GTSAM includes several nonlinear optimizers to perform this step. Here we will use the +// a Gauss-Newton solver +#include + +// Once the optimized values have been calculated, we can also calculate the marginal covariance +// of desired variables +#include + +// The nonlinear solvers within GTSAM are iterative solvers, meaning they linearize the +// nonlinear functions around an initial linearization point, then solve the linear system +// to update the linearization point. This happens repeatedly until the solver converges +// to a consistent set of variable values. This requires us to specify an initial guess +// for each variable, held in a Values container. +#include + + +using namespace std; +using namespace gtsam; + +int main(int argc, char** argv) { + + // 1. Create a factor graph container and add factors to it + NonlinearFactorGraph graph; + + // 2a. Add a prior on the first pose, setting it to the origin + // A prior factor consists of a mean and a noise model (covariance matrix) + noiseModel::Diagonal::shared_ptr priorNoise = noiseModel::Diagonal::Sigmas(Vector3(0.3, 0.3, 0.1)); + graph.emplace_shared >(1, Pose2(0, 0, 0), priorNoise); + + // For simplicity, we will use the same noise model for odometry and loop closures + noiseModel::Diagonal::shared_ptr model = noiseModel::Diagonal::Sigmas(Vector3(0.2, 0.2, 0.1)); + + // 2b. Add odometry factors + // Create odometry (Between) factors between consecutive poses + graph.emplace_shared >(1, 2, Pose2(2, 0, 0 ), model); + graph.emplace_shared >(2, 3, Pose2(2, 0, M_PI_2), model); + graph.emplace_shared >(3, 4, Pose2(2, 0, M_PI_2), model); + graph.emplace_shared >(4, 5, Pose2(2, 0, M_PI_2), model); + + // 2c. Add the loop closure constraint + // This factor encodes the fact that we have returned to the same pose. In real systems, + // these constraints may be identified in many ways, such as appearance-based techniques + // with camera images. We will use another Between Factor to enforce this constraint: + graph.emplace_shared >(5, 2, Pose2(2, 0, M_PI_2), model); + graph.print("\nFactor Graph:\n"); // print + + // 3. Create the data structure to hold the initialEstimate estimate to the solution + // For illustrative purposes, these have been deliberately set to incorrect values + Values initialEstimate; + initialEstimate.insert(1, Pose2(0.5, 0.0, 0.2 )); + initialEstimate.insert(2, Pose2(2.3, 0.1, -0.2 )); + initialEstimate.insert(3, Pose2(4.1, 0.1, M_PI_2)); + initialEstimate.insert(4, Pose2(4.0, 2.0, M_PI )); + initialEstimate.insert(5, Pose2(2.1, 2.1, -M_PI_2)); + initialEstimate.print("\nInitial Estimate:\n"); // print + + // 4. Optimize the initial values using a Gauss-Newton nonlinear optimizer + // The optimizer accepts an optional set of configuration parameters, + // controlling things like convergence criteria, the type of linear + // system solver to use, and the amount of information displayed during + // optimization. We will set a few parameters as a demonstration. + GaussNewtonParams parameters; + // Stop iterating once the change in error between steps is less than this value + parameters.relativeErrorTol = 1e-5; + // Do not perform more than N iteration steps + parameters.maxIterations = 100; + // Create the optimizer ... + GaussNewtonOptimizer optimizer(graph, initialEstimate, parameters); + // ... and optimize + Values result = optimizer.optimize(); + result.print("Final Result:\n"); + + // 5. Calculate and print marginal covariances for all variables + cout.precision(3); + Marginals marginals(graph, result); + cout << "x1 covariance:\n" << marginals.marginalCovariance(1) << endl; + cout << "x2 covariance:\n" << marginals.marginalCovariance(2) << endl; + cout << "x3 covariance:\n" << marginals.marginalCovariance(3) << endl; + cout << "x4 covariance:\n" << marginals.marginalCovariance(4) << endl; + cout << "x5 covariance:\n" << marginals.marginalCovariance(5) << endl; + + return 0; +} diff --git a/cmake/example_project/CMakeLists.txt b/cmake/example_project/CMakeLists.txt index 548d56acd..620ad4811 100644 --- a/cmake/example_project/CMakeLists.txt +++ b/cmake/example_project/CMakeLists.txt @@ -7,7 +7,7 @@ ################################################################################### # To create your own project, replace "example" with the actual name of your project -cmake_minimum_required(VERSION 2.6) +cmake_minimum_required(VERSION 3.0) project(example CXX C) # Include GTSAM CMake tools @@ -22,14 +22,20 @@ include_directories(BEFORE "${PROJECT_SOURCE_DIR}") ################################################################################### # Find GTSAM components find_package(GTSAM REQUIRED) # Uses installed package -include_directories(${GTSAM_INCLUDE_DIR}) +# Note: Since Jan-2019, GTSAMConfig.cmake defines exported CMake targets +# that automatically do include the include_directories() without the need +# to call include_directories(), just target_link_libraries(NAME gtsam) +#include_directories(${GTSAM_INCLUDE_DIR}) ################################################################################### # Build static library from common sources set(CONVENIENCE_LIB_NAME ${PROJECT_NAME}) -add_library(${CONVENIENCE_LIB_NAME} STATIC example/PrintExamples.h example/PrintExamples.cpp) +add_library(${CONVENIENCE_LIB_NAME} SHARED example/PrintExamples.h example/PrintExamples.cpp) target_link_libraries(${CONVENIENCE_LIB_NAME} gtsam) +# Install library +install(TARGETS ${CONVENIENCE_LIB_NAME} LIBRARY DESTINATION lib ARCHIVE DESTINATION lib RUNTIME DESTINATION bin) + ################################################################################### # Build tests (CMake tracks the dependecy to link with GTSAM through our project's static library) gtsamAddTestsGlob("example" "tests/test*.cpp" "" "${CONVENIENCE_LIB_NAME}") diff --git a/cmake/example_project/README.md b/cmake/example_project/README.md new file mode 100644 index 000000000..a1269cf19 --- /dev/null +++ b/cmake/example_project/README.md @@ -0,0 +1,32 @@ +# MATLAB Wrapper Example Project + +This project serves as a lightweight example for demonstrating how to wrap C++ code in MATLAB using GTSAM. + +## Compiling + +We follow the regular build procedure inside the `example_project` directory: + +```sh +mkdir build && cd build +cmake .. +make -j8 +sudo make install + +sudo ldconfig # ensures the shared object file generated is correctly loaded +``` + +## Usage + +Now you can open MATLAB and add the `gtsam_toolbox` to the MATLAB path + +```matlab +addpath('/usr/local/gtsam_toolbox') +``` + +At this point you are ready to run the example project. Starting from the `example_project` directory inside MATLAB, simply run code like regular MATLAB, e.g. + +```matlab +pe = example.PrintExamples(); +pe.sayHello(); +pe.sayGoodbye(); +``` \ No newline at end of file diff --git a/cmake/example_project/example.h b/cmake/example_project/example.h index 47b9a0aa2..b0d732e14 100644 --- a/cmake/example_project/example.h +++ b/cmake/example_project/example.h @@ -18,11 +18,14 @@ // This is an interface file for automatic MATLAB wrapper generation. See // gtsam.h for full documentation and more examples. +#include + namespace example { class PrintExamples { - void sayHello() const; - void sayGoodbye() const; + PrintExamples(); + void sayHello() const; + void sayGoodbye() const; }; } diff --git a/cmake/example_project/example/PrintExamples.h b/cmake/example_project/example/PrintExamples.h index b151dfbc7..25d4dd8cb 100644 --- a/cmake/example_project/example/PrintExamples.h +++ b/cmake/example_project/example/PrintExamples.h @@ -17,6 +17,7 @@ #pragma once +#include #include namespace example { diff --git a/cmake/obsolete/GtsamTestingObsolete.cmake b/cmake/obsolete/GtsamTestingObsolete.cmake index f56d138e6..c90abfa6c 100644 --- a/cmake/obsolete/GtsamTestingObsolete.cmake +++ b/cmake/obsolete/GtsamTestingObsolete.cmake @@ -1,22 +1,22 @@ -# Macro for adding categorized tests in a "tests" folder, with +# Macro for adding categorized tests in a "tests" folder, with # optional exclusion of tests and convenience library linking options -# +# # By default, all tests are linked with CppUnitLite and boost -# Arguments: +# Arguments: # - subdir The name of the category for this test # - local_libs A list of convenience libraries to use (if GTSAM_BUILD_CONVENIENCE_LIBRARIES is true) # - full_libs The main library to link against if not using convenience libraries -# - excluded_tests A list of test files that should not be compiled - use for debugging +# - excluded_tests A list of test files that should not be compiled - use for debugging function(gtsam_add_subdir_tests subdir local_libs full_libs excluded_tests) # Subdirectory target for tests add_custom_target(check.${subdir} COMMAND ${CMAKE_CTEST_COMMAND} -C $ --output-on-failure) set(is_test TRUE) # Put check target in Visual Studio solution folder - file(RELATIVE_PATH relative_path "${PROJECT_SOURCE_DIR}" "${CMAKE_CURRENT_SOURCE_DIR}") + file(RELATIVE_PATH relative_path "${GTSAM_SOURCE_DIR}" "${CMAKE_CURRENT_SOURCE_DIR}") set_property(TARGET check.${subdir} PROPERTY FOLDER "${relative_path}") - + # Link with CppUnitLite - pulled from gtsam installation list(APPEND local_libs CppUnitLite) list(APPEND full_libs CppUnitLite) @@ -29,15 +29,15 @@ function(gtsam_add_subdir_tests subdir local_libs full_libs excluded_tests) ${is_test}) # Set all as tests endfunction() -# Macro for adding categorized timing scripts in a "tests" folder, with +# Macro for adding categorized timing scripts in a "tests" folder, with # optional exclusion of tests and convenience library linking options -# +# # By default, all tests are linked with boost -# Arguments: +# Arguments: # - subdir The name of the category for this timing script # - local_libs A list of convenience libraries to use (if GTSAM_BUILD_CONVENIENCE_LIBRARIES is true) # - full_libs The main library to link against if not using convenience libraries -# - excluded_srcs A list of timing files that should not be compiled - use for debugging +# - excluded_srcs A list of timing files that should not be compiled - use for debugging macro(gtsam_add_subdir_timing subdir local_libs full_libs excluded_srcs) # Subdirectory target for timing - does not actually execute the scripts add_custom_target(timing.${subdir}) @@ -60,11 +60,11 @@ endmacro() # - excluded_srcs A list of timing files that should not be compiled - use for debugging function(gtsam_add_executables pattern local_libs full_libs excluded_srcs) set(is_test FALSE) - + if(NOT excluded_srcs) set(excluded_srcs "") endif() - + # Build executables gtsam_add_grouped_scripts("" "${pattern}" "" "Executable" "${local_libs}" "${full_libs}" "${excluded_srcs}" ${is_test}) endfunction() @@ -73,7 +73,7 @@ endfunction() macro(gtsam_add_grouped_scripts group pattern target_prefix pretty_prefix_name local_libs full_libs excluded_srcs is_test) # Print warning about using this obsolete function message(AUTHOR_WARNING "Warning: Please see GtsamTesting.cmake - obsolete cmake cmake macro for creating unit tests, examples, and scripts was called. This will be removed in the future. The new macros are much easier anyway!!") - + # Get all script files set(script_files "") foreach(one_pattern ${pattern}) @@ -102,20 +102,20 @@ macro(gtsam_add_grouped_scripts group pattern target_prefix pretty_prefix_name l list(APPEND script_srcs ${script_file}) endif() endforeach() - - + + # Add targets and dependencies for each script if(NOT "${group}" STREQUAL "") message(STATUS "Adding ${pretty_prefix_name}s in ${group}") endif() - + # Create exe's for each script, unless we're in SINGLE_TEST_EXE mode if(NOT is_test OR NOT GTSAM_SINGLE_TEST_EXE) foreach(script_src ${script_srcs}) get_filename_component(script_base ${script_src} NAME_WE) if (script_base) # Check for null filenames and headers set( script_bin ${script_base} ) - message(STATUS "Adding ${pretty_prefix_name} ${script_bin}") + message(STATUS "Adding ${pretty_prefix_name} ${script_bin}") add_executable(${script_bin} ${script_src} ${script_headers}) if(NOT "${target_prefix}" STREQUAL "") if(NOT "${group}" STREQUAL "") @@ -123,37 +123,37 @@ macro(gtsam_add_grouped_scripts group pattern target_prefix pretty_prefix_name l endif() add_dependencies(${target_prefix} ${script_bin}) endif() - + # Add TOPSRCDIR - set_property(SOURCE ${script_src} APPEND PROPERTY COMPILE_DEFINITIONS "TOPSRCDIR=\"${PROJECT_SOURCE_DIR}\"") + set_property(SOURCE ${script_src} APPEND PROPERTY COMPILE_DEFINITIONS "TOPSRCDIR=\"${GTSAM_SOURCE_DIR}\"") # Disable building during make all/install if (GTSAM_DISABLE_TESTS_ON_INSTALL) set_target_properties(${script_bin} PROPERTIES EXCLUDE_FROM_ALL ON) endif() - + if (is_test) add_test(NAME ${script_base} COMMAND ${script_bin}) endif() - + # Linking and dependendencies if (GTSAM_BUILD_CONVENIENCE_LIBRARIES) target_link_libraries(${script_bin} ${local_libs} ${GTSAM_BOOST_LIBRARIES}) else() target_link_libraries(${script_bin} ${full_libs} ${GTSAM_BOOST_LIBRARIES}) endif() - + # Add .run target if(NOT MSVC AND NOT XCODE_VERSION) add_custom_target(${script_bin}.run ${EXECUTABLE_OUTPUT_PATH}${script_bin} ${ARGN}) endif() - + # Set up Visual Studio folders - file(RELATIVE_PATH relative_path "${PROJECT_SOURCE_DIR}" "${CMAKE_CURRENT_SOURCE_DIR}") + file(RELATIVE_PATH relative_path "${GTSAM_SOURCE_DIR}" "${CMAKE_CURRENT_SOURCE_DIR}") set_property(TARGET ${script_bin} PROPERTY FOLDER "${relative_path}") endif() endforeach(script_src) - + if(MSVC) source_group("" FILES ${script_srcs} ${script_headers}) endif() @@ -166,28 +166,28 @@ macro(gtsam_add_grouped_scripts group pattern target_prefix pretty_prefix_name l else() target_link_libraries(${script_bin} ${Boost_LIBRARIES} ${full_libs}) endif() - + # Only have a main function in one script set(rest_script_srcs ${script_srcs}) list(REMOVE_AT rest_script_srcs 0) set_property(SOURCE ${rest_script_srcs} APPEND PROPERTY COMPILE_DEFINITIONS "main=static no_main") - + # Add TOPSRCDIR - set_property(SOURCE ${script_srcs} APPEND PROPERTY COMPILE_DEFINITIONS "TOPSRCDIR=\"${PROJECT_SOURCE_DIR}\"") - + set_property(SOURCE ${script_srcs} APPEND PROPERTY COMPILE_DEFINITIONS "TOPSRCDIR=\"${GTSAM_SOURCE_DIR}\"") + # Add test add_dependencies(${target_prefix}.${group} ${script_bin}) add_dependencies(${target_prefix} ${script_bin}) add_test(NAME ${target_prefix}.${group} COMMAND ${script_bin}) - + # Disable building during make all/install if (GTSAM_DISABLE_TESTS_ON_INSTALL) set_target_properties(${script_bin} PROPERTIES EXCLUDE_FROM_ALL ON) endif() - + # Set up Visual Studio folders if(MSVC) - file(RELATIVE_PATH relative_path "${PROJECT_SOURCE_DIR}" "${CMAKE_CURRENT_SOURCE_DIR}") + file(RELATIVE_PATH relative_path "${GTSAM_SOURCE_DIR}" "${CMAKE_CURRENT_SOURCE_DIR}") set_property(TARGET ${script_bin} PROPERTY FOLDER "${relative_path}") source_group("" FILES ${script_srcs} ${script_headers}) endif() diff --git a/cython/CMakeLists.txt b/cython/CMakeLists.txt index bc21b91d1..a351ec52b 100644 --- a/cython/CMakeLists.txt +++ b/cython/CMakeLists.txt @@ -19,22 +19,25 @@ if (GTSAM_INSTALL_CYTHON_TOOLBOX) # wrap gtsam_unstable if(GTSAM_BUILD_UNSTABLE) add_custom_target(gtsam_unstable_header DEPENDS "../gtsam_unstable/gtsam_unstable.h") - set(GTSAM_UNSTABLE_IMPORT "from gtsam_unstable import *") wrap_and_install_library_cython("../gtsam_unstable/gtsam_unstable.h" # interface_header "from gtsam.gtsam cimport *" # extra imports - "${GTSAM_CYTHON_INSTALL_PATH}/gtsam" # install path + "${GTSAM_CYTHON_INSTALL_PATH}/gtsam_unstable" # install path gtsam_unstable # library to link with "gtsam_unstable;gtsam_unstable_header;cythonize_gtsam" # dependencies to be built before wrapping ) - # for some reasons cython gtsam_unstable can't find gtsam/gtsam.pxd without doing this - file(WRITE ${PROJECT_BINARY_DIR}/cython/gtsam_unstable/__init__.py "") endif() + file(READ "${PROJECT_SOURCE_DIR}/cython/requirements.txt" CYTHON_INSTALL_REQUIREMENTS) + file(READ "${PROJECT_SOURCE_DIR}/README.md" README_CONTENTS) + # Install the custom-generated __init__.py # This is to make the build/cython/gtsam folder a python package, so gtsam can be found while wrapping gtsam_unstable - configure_file(${PROJECT_SOURCE_DIR}/cython/gtsam/__init__.py.in ${PROJECT_BINARY_DIR}/cython/gtsam/__init__.py) - install_cython_files("${PROJECT_BINARY_DIR}/cython/gtsam/__init__.py" "${GTSAM_CYTHON_INSTALL_PATH}/gtsam") + configure_file(${PROJECT_SOURCE_DIR}/cython/gtsam/__init__.py ${PROJECT_BINARY_DIR}/cython/gtsam/__init__.py COPYONLY) + configure_file(${PROJECT_SOURCE_DIR}/cython/gtsam_unstable/__init__.py ${PROJECT_BINARY_DIR}/cython/gtsam_unstable/__init__.py COPYONLY) + configure_file(${PROJECT_SOURCE_DIR}/cython/setup.py.in ${PROJECT_BINARY_DIR}/cython/setup.py) + install_cython_files("${PROJECT_BINARY_DIR}/cython/setup.py" "${GTSAM_CYTHON_INSTALL_PATH}") # install scripts and tests install_cython_scripts("${PROJECT_SOURCE_DIR}/cython/gtsam" "${GTSAM_CYTHON_INSTALL_PATH}" "*.py") + install_cython_scripts("${PROJECT_SOURCE_DIR}/cython/gtsam_unstable" "${GTSAM_CYTHON_INSTALL_PATH}" "*.py") endif () diff --git a/cython/README.md b/cython/README.md index 368d2a76d..6dcdd7c1c 100644 --- a/cython/README.md +++ b/cython/README.md @@ -1,27 +1,34 @@ This is the Cython/Python wrapper around the GTSAM C++ library. -INSTALL -======= +# INSTALL + +- if you want to build the gtsam python library for a specific python version (eg 2.7), use the `-DGTSAM_PYTHON_VERSION=2.7` option when running `cmake` otherwise the default interpreter will be used. + - If the interpreter is inside an environment (such as an anaconda environment or virtualenv environment) then the environment should be active while building gtsam. - This wrapper needs Cython(>=0.25.2), backports_abc>=0.5, and numpy. These can be installed as follows: ```bash pip install -r /cython/requirements.txt ``` -- For compatiblity with gtsam's Eigen version, it contains its own cloned version of [Eigency](https://github.com/wouterboomsma/eigency.git), +- For compatibility with gtsam's Eigen version, it contains its own cloned version of [Eigency](https://github.com/wouterboomsma/eigency.git), named **gtsam_eigency**, to interface between C++'s Eigen and Python's numpy. -- Build and install gtsam using cmake with GTSAM_INSTALL_CYTHON_TOOLBOX enabled. -The wrapped module will be installed to GTSAM_CYTHON_INSTALL_PATH, which is -by default: /cython +- Build and install gtsam using cmake with `GTSAM_INSTALL_CYTHON_TOOLBOX` enabled. +The wrapped module will be installed to `GTSAM_CYTHON_INSTALL_PATH`, which is +by default: `/cython` -- Modify your PYTHONPATH to include the GTSAM_CYTHON_INSTALL_PATH: +- To use the library without installing system-wide: modify your `PYTHONPATH` to include the `GTSAM_CYTHON_INSTALL_PATH`: ```bash export PYTHONPATH=$PYTHONPATH: ``` +- To install system-wide: run `make install` then navigate to `GTSAM_CYTHON_INSTALL_PATH` and run `python setup.py install` + - (the same command can be used to install into a virtual environment if it is active) + - note: if you don't want gtsam to install to a system directory such as `/usr/local`, pass `-DCMAKE_INSTALL_PREFIX="./install"` to cmake to install gtsam to a subdirectory of the build directory. + - if you run `setup.py` from the build directory rather than the installation directory, the script will warn you with the message: `setup.py is being run from an unexpected location`. + Before `make install` is run, not all the components of the package have been copied across, so running `setup.py` from the build directory would result in an incomplete package. + +# UNIT TESTS -UNIT TESTS -========== The Cython toolbox also has a small set of unit tests located in the test directory. To run them: @@ -30,8 +37,8 @@ test directory. To run them: python -m unittest discover ``` -WRITING YOUR OWN SCRIPTS -======================== +# WRITING YOUR OWN SCRIPTS + See the tests for examples. ## Some important notes: @@ -55,12 +62,12 @@ Examples: noiseModel_Gaussian, noiseModel_mEstimator_Tukey - Casting from a base class to a derive class must be done explicitly. Examples: ```Python - noiseBase = factor.get_noiseModel() + noiseBase = factor.noiseModel() noiseGaussian = dynamic_cast_noiseModel_Gaussian_noiseModel_Base(noiseBase) ``` -WRAPPING YOUR OWN PROJECT THAT USES GTSAM -========================================= +# WRAPPING YOUR OWN PROJECT THAT USES GTSAM + - Set PYTHONPATH to include ${GTSAM_CYTHON_INSTALL_PATH} + so that it can find gtsam Cython header: gtsam/gtsam.pxd @@ -92,63 +99,55 @@ KNOWN ISSUES - support these constructors by default and declare "delete" for special classes? -TODO -===== -☐ allow duplication of parent' functions in child classes. Not allowed for now due to conflicts in Cython. -☐ a common header for boost shared_ptr? (Or wait until everything is switched to std::shared_ptr in gtsam?) -☐ inner namespaces ==> inner packages? -☐ Wrap fixed-size Matrices/Vectors? +# TODO + +- [ ] allow duplication of parent' functions in child classes. Not allowed for now due to conflicts in Cython. +- [ ] a common header for boost shared_ptr? (Or wait until everything is switched to std::shared_ptr in gtsam?) +- [ ] inner namespaces ==> inner packages? +- [ ] Wrap fixed-size Matrices/Vectors? -Completed/Cancelled: -===== -✔ Fix Python tests: don't use " import * ": Bad style!!! @done (18-03-17 19:50) -✔ Unit tests for cython wrappers @done (18-03-17 18:45) -- simply compare generated files -✔ Wrap unstable @done (18-03-17 15:30) -✔ Unify cython/gtsam.h and the original gtsam.h @done (18-03-17 15:30) - ✔ 18-03-17: manage to unify the two versions by removing std container stubs from the matlab version,and keeping KeyList/KeyVector/KeySet as in the matlab version. Probably Cython 0.25 fixes the casting problem. - ✔ 06-03-17: manage to remove the requirements for default and copy constructors - ✘ 25-11-16: - Try to unify but failed. Main reasons are: Key/size_t, std containers, KeyVector/KeyList/KeySet. - Matlab doesn't need to know about Key, but I can't make Cython to ignore Key as it couldn't cast KeyVector, i.e. FastVector, to FastVector. -✘ Marginal and JointMarginal: revert changes @failed (17-03-17 11:00) -- Cython does need a default constructor! It produces cpp code like this: ```gtsam::JointMarginal __pyx_t_1;``` Users don't have to wrap this constructor, however. -✔ Convert input numpy Matrix/Vector to float dtype and storage order 'F' automatically, cannot crash! @done (15-03-17 13:00) -✔ Remove requirements.txt - Frank: don't bother with only 2 packages and a special case for eigency! @done (08-03-17 10:30) -✔ CMake install script @done (25-11-16 02:30) -✘ [REFACTOR] better name for uninstantiateClass: very vague!! @cancelled (25-11-16 02:30) -- lazy -✘ forward declaration? @cancelled (23-11-16 13:00) - nothing to do, seem to work? -✔ wrap VariableIndex: why is it in inference? If need to, shouldn't have constructors to specific FactorGraphs @done (23-11-16 13:00) -✔ Global functions @done (22-11-16 21:00) -✔ [REFACTOR] typesEqual --> isSameSignature @done (22-11-16 21:00) -✔ Proper overloads (constructors, static methods, methods) @done (20-11-16 21:00) -✔ Allow overloading methods. The current solution is annoying!!! @done (20-11-16 21:00) -✔ Casting from parent and grandparents @done (16-11-16 17:00) -✔ Allow overloading constructors. The current solution is annoying!!! @done (16-11-16 17:00) -✔ Support "print obj" @done (16-11-16 17:00) -✔ methods for FastVector: at, [], ... @done (16-11-16 17:00) -✔ Cython: Key and size_t: traits doesn't exist @done (16-09-12 18:34) -✔ KeyVector, KeyList, KeySet... @done (16-09-13 17:19) -✔ [Nice to have] parse typedef @done (16-09-13 17:19) -✔ ctypedef at correct places @done (16-09-12 18:34) -✔ expand template variable type in constructor/static methods? @done (16-09-12 18:34) -✔ NonlinearOptimizer: copy constructor deleted!!! @done (16-09-13 17:20) -✔ Value: no default constructor @done (16-09-13 17:20) -✔ ctypedef PriorFactor[Vector] PriorFactorVector @done (16-09-19 12:25) -✔ Delete duplicate methods in derived class @done (16-09-12 13:38) -✔ Fix return properly @done (16-09-11 17:14) - ✔ handle pair @done (16-09-11 17:14) -✔ Eigency: ambiguous call: A(const T&) A(const Vector& v) and Eigency A(Map[Vector]& v) @done (16-09-11 07:59) -✔ Eigency: Constructor: ambiguous construct from Vector/Matrix @done (16-09-11 07:59) -✔ Eigency: Fix method template of Vector/Matrix: template argument is [Vector] while arugment is Map[Vector] @done (16-09-11 08:22) -✔ Robust noise: copy assignment operator is deleted because of shared_ptr of the abstract Base class @done (16-09-10 09:05) -✘ Cython: Constructor: generate default constructor? (hack: if it's serializable?) @cancelled (16-09-13 17:20) -✘ Eigency: Map[] to Block @created(16-09-10 07:59) @cancelled (16-09-11 08:28) +# Completed/Cancelled: + +- [x] Fix Python tests: don't use " import * ": Bad style!!! (18-03-17 19:50) +- [x] Unit tests for cython wrappers @done (18-03-17 18:45) -- simply compare generated files +- [x] Wrap unstable @done (18-03-17 15:30) +- [x] Unify cython/gtsam.h and the original gtsam.h @done (18-03-17 15:30) +- [x] 18-03-17: manage to unify the two versions by removing std container stubs from the matlab version,and keeping KeyList/KeyVector/KeySet as in the matlab version. Probably Cython 0.25 fixes the casting problem. +- [x] 06-03-17: manage to remove the requirements for default and copy constructors +- [ ] 25-11-16: Try to unify but failed. Main reasons are: Key/size_t, std containers, KeyVector/KeyList/KeySet. Matlab doesn't need to know about Key, but I can't make Cython to ignore Key as it couldn't cast KeyVector, i.e. FastVector, to FastVector. +- [ ] Marginal and JointMarginal: revert changes @failed (17-03-17 11:00) -- Cython does need a default constructor! It produces cpp code like this: ```gtsam::JointMarginal __pyx_t_1;``` Users don't have to wrap this constructor, however. +- [x] Convert input numpy Matrix/Vector to float dtype and storage order 'F' automatically, cannot crash! @done (15-03-17 13:00) +- [x] Remove requirements.txt - Frank: don't bother with only 2 packages and a special case for eigency! @done (08-03-17 10:30) +- [x] CMake install script @done (25-11-16 02:30) +- [ ] [REFACTOR] better name for uninstantiateClass: very vague!! @cancelled (25-11-16 02:30) -- lazy +- [ ] forward declaration? @cancelled (23-11-16 13:00) - nothing to do, seem to work? +- [x] wrap VariableIndex: why is it in inference? If need to, shouldn't have constructors to specific FactorGraphs @done (23-11-16 13:00) +- [x] Global functions @done (22-11-16 21:00) +- [x] [REFACTOR] typesEqual --> isSameSignature @done (22-11-16 21:00) +- [x] Proper overloads (constructors, static methods, methods) @done (20-11-16 21:00) +- [x] Allow overloading methods. The current solution is annoying!!! @done (20-11-16 21:00) +- [x] Casting from parent and grandparents @done (16-11-16 17:00) +- [x] Allow overloading constructors. The current solution is annoying!!! @done (16-11-16 17:00) +- [x] Support "print obj" @done (16-11-16 17:00) +- [x] methods for FastVector: at, [], ... @done (16-11-16 17:00) +- [x] Cython: Key and size_t: traits doesn't exist @done (16-09-12 18:34) +- [x] KeyVector, KeyList, KeySet... @done (16-09-13 17:19) +- [x] [Nice to have] parse typedef @done (16-09-13 17:19) +- [x] ctypedef at correct places @done (16-09-12 18:34) +- [x] expand template variable type in constructor/static methods? @done (16-09-12 18:34) +- [x] NonlinearOptimizer: copy constructor deleted!!! @done (16-09-13 17:20) +- [x] Value: no default constructor @done (16-09-13 17:20) +- [x] ctypedef PriorFactor[Vector] PriorFactorVector @done (16-09-19 12:25) +- [x] Delete duplicate methods in derived class @done (16-09-12 13:38) +- [x] Fix return properly @done (16-09-11 17:14) +- [x] handle pair @done (16-09-11 17:14) +- [x] Eigency: ambiguous call: A(const T&) A(const Vector& v) and Eigency A(Map[Vector]& v) @done (16-09-11 07:59) +- [x] Eigency: Constructor: ambiguous construct from Vector/Matrix @done (16-09-11 07:59) +- [x] Eigency: Fix method template of Vector/Matrix: template argument is [Vector] while arugment is Map[Vector] @done (16-09-11 08:22) +- [x] Robust noise: copy assignment operator is deleted because of shared_ptr of the abstract Base class @done (16-09-10 09:05) +- [ ] Cython: Constructor: generate default constructor? (hack: if it's serializable?) @cancelled (16-09-13 17:20) +- [ ] Eigency: Map[] to Block @created(16-09-10 07:59) @cancelled (16-09-11 08:28) - inference before symbolic/linear - what's the purpose of "virtual" ?? - -Installation: - ☐ Prerequisite: - - Users create venv and pip install requirements before compiling - - Wrap cython script in gtsam/cython folder - ☐ Install built module into venv? diff --git a/cython/gtsam/__init__.py b/cython/gtsam/__init__.py new file mode 100644 index 000000000..d40ee4502 --- /dev/null +++ b/cython/gtsam/__init__.py @@ -0,0 +1,26 @@ +from .gtsam import * + +try: + import gtsam_unstable + + + def _deprecated_wrapper(item, name): + def wrapper(*args, **kwargs): + from warnings import warn + message = ('importing the unstable item "{}" directly from gtsam is deprecated. '.format(name) + + 'Please import it from gtsam_unstable.') + warn(message) + return item(*args, **kwargs) + return wrapper + + + for name in dir(gtsam_unstable): + if not name.startswith('__'): + item = getattr(gtsam_unstable, name) + if callable(item): + item = _deprecated_wrapper(item, name) + globals()[name] = item + +except ImportError: + pass + diff --git a/cython/gtsam/__init__.py.in b/cython/gtsam/__init__.py.in deleted file mode 100644 index 7d456023f..000000000 --- a/cython/gtsam/__init__.py.in +++ /dev/null @@ -1,2 +0,0 @@ -from gtsam import * -${GTSAM_UNSTABLE_IMPORT} diff --git a/cython/gtsam/examples/DogLegOptimizerExample.py b/cython/gtsam/examples/DogLegOptimizerExample.py new file mode 100644 index 000000000..776ceedc4 --- /dev/null +++ b/cython/gtsam/examples/DogLegOptimizerExample.py @@ -0,0 +1,118 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +Example comparing DoglegOptimizer with Levenberg-Marquardt. +Author: Frank Dellaert +""" +# pylint: disable=no-member, invalid-name + +import math +import argparse + +import gtsam +import matplotlib.pyplot as plt +import numpy as np + + +def run(args): + """Test Dogleg vs LM, inspired by issue #452.""" + + # print parameters + print("num samples = {}, deltaInitial = {}".format( + args.num_samples, args.delta)) + + # Ground truth solution + T11 = gtsam.Pose2(0, 0, 0) + T12 = gtsam.Pose2(1, 0, 0) + T21 = gtsam.Pose2(0, 1, 0) + T22 = gtsam.Pose2(1, 1, 0) + + # Factor graph + graph = gtsam.NonlinearFactorGraph() + + # Priors + prior = gtsam.noiseModel_Isotropic.Sigma(3, 1) + graph.add(gtsam.PriorFactorPose2(11, T11, prior)) + graph.add(gtsam.PriorFactorPose2(21, T21, prior)) + + # Odometry + model = gtsam.noiseModel_Diagonal.Sigmas(np.array([0.01, 0.01, 0.3])) + graph.add(gtsam.BetweenFactorPose2(11, 12, T11.between(T12), model)) + graph.add(gtsam.BetweenFactorPose2(21, 22, T21.between(T22), model)) + + # Range + model_rho = gtsam.noiseModel_Isotropic.Sigma(1, 0.01) + graph.add(gtsam.RangeFactorPose2(12, 22, 1.0, model_rho)) + + params = gtsam.DoglegParams() + params.setDeltaInitial(args.delta) # default is 10 + + # Add progressively more noise to ground truth + sigmas = [0.01, 0.1, 0.2, 0.5, 1, 2, 5, 10, 20] + n = len(sigmas) + p_dl, s_dl, p_lm, s_lm = [0]*n, [0]*n, [0]*n, [0]*n + for i, sigma in enumerate(sigmas): + dl_fails, lm_fails = 0, 0 + # Attempt num_samples optimizations for both DL and LM + for _attempt in range(args.num_samples): + initial = gtsam.Values() + initial.insert(11, T11.retract(np.random.normal(0, sigma, 3))) + initial.insert(12, T12.retract(np.random.normal(0, sigma, 3))) + initial.insert(21, T21.retract(np.random.normal(0, sigma, 3))) + initial.insert(22, T22.retract(np.random.normal(0, sigma, 3))) + + # Run dogleg optimizer + dl = gtsam.DoglegOptimizer(graph, initial, params) + result = dl.optimize() + dl_fails += graph.error(result) > 1e-9 + + # Run + lm = gtsam.LevenbergMarquardtOptimizer(graph, initial) + result = lm.optimize() + lm_fails += graph.error(result) > 1e-9 + + # Calculate Bayes estimate of success probability + # using a beta prior of alpha=0.5, beta=0.5 + alpha, beta = 0.5, 0.5 + v = args.num_samples+alpha+beta + p_dl[i] = (args.num_samples-dl_fails+alpha)/v + p_lm[i] = (args.num_samples-lm_fails+alpha)/v + + def stddev(p): + """Calculate standard deviation.""" + return math.sqrt(p*(1-p)/(1+v)) + + s_dl[i] = stddev(p_dl[i]) + s_lm[i] = stddev(p_lm[i]) + + fmt = "sigma= {}:\tDL success {:.2f}% +/- {:.2f}%, LM success {:.2f}% +/- {:.2f}%" + print(fmt.format(sigma, + 100*p_dl[i], 100*s_dl[i], + 100*p_lm[i], 100*s_lm[i])) + + if args.plot: + fig, ax = plt.subplots() + dl_plot = plt.errorbar(sigmas, p_dl, yerr=s_dl, label="Dogleg") + lm_plot = plt.errorbar(sigmas, p_lm, yerr=s_lm, label="LM") + plt.title("Dogleg emprical success vs. LM") + plt.legend(handles=[dl_plot, lm_plot]) + ax.set_xlim(0, sigmas[-1]+1) + ax.set_ylim(0, 1) + plt.show() + + +if __name__ == "__main__": + parser = argparse.ArgumentParser( + description="Compare Dogleg and LM success rates") + parser.add_argument("-n", "--num_samples", type=int, default=1000, + help="Number of samples for each sigma") + parser.add_argument("-d", "--delta", type=float, default=10.0, + help="Initial delta for dogleg") + parser.add_argument("-p", "--plot", action="store_true", + help="Flag to plot results") + args = parser.parse_args() + run(args) diff --git a/python/gtsam_examples/ImuFactorExample.py b/cython/gtsam/examples/ImuFactorExample.py similarity index 67% rename from python/gtsam_examples/ImuFactorExample.py rename to cython/gtsam/examples/ImuFactorExample.py index 781dae118..6cc8979f1 100644 --- a/python/gtsam_examples/ImuFactorExample.py +++ b/cython/gtsam/examples/ImuFactorExample.py @@ -1,58 +1,75 @@ """ +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + A script validating the ImuFactor inference. """ from __future__ import print_function + import math + import matplotlib.pyplot as plt import numpy as np - from mpl_toolkits.mplot3d import Axes3D import gtsam -from gtsam_utils import plotPose3 -from PreintegrationExample import PreintegrationExample, POSES_FIG +from gtsam.utils.plot import plot_pose3 +from PreintegrationExample import POSES_FIG, PreintegrationExample + +BIAS_KEY = int(gtsam.symbol(ord('b'), 0)) + + +def X(key): + """Create symbol for pose key.""" + return gtsam.symbol(ord('x'), key) + + +def V(key): + """Create symbol for velocity key.""" + return gtsam.symbol(ord('v'), key) -# shorthand symbols: -BIAS_KEY = int(gtsam.Symbol('b', 0)) -V = lambda j: int(gtsam.Symbol('v', j)) -X = lambda i: int(gtsam.Symbol('x', i)) np.set_printoptions(precision=3, suppress=True) + class ImuFactorExample(PreintegrationExample): def __init__(self): self.velocity = np.array([2, 0, 0]) - self.priorNoise = gtsam.noiseModel.Isotropic.Sigma(6, 0.1) - self.velNoise = gtsam.noiseModel.Isotropic.Sigma(3, 0.1) + self.priorNoise = gtsam.noiseModel_Isotropic.Sigma(6, 0.1) + self.velNoise = gtsam.noiseModel_Isotropic.Sigma(3, 0.1) - # Choose one of these twists to change scenario: + # Choose one of these twists to change scenario: zero_twist = (np.zeros(3), np.zeros(3)) forward_twist = (np.zeros(3), self.velocity) loop_twist = (np.array([0, -math.radians(30), 0]), self.velocity) - sick_twist = (np.array([math.radians(30), -math.radians(30), 0]), self.velocity) + sick_twist = ( + np.array([math.radians(30), -math.radians(30), 0]), self.velocity) accBias = np.array([-0.3, 0.1, 0.2]) gyroBias = np.array([0.1, 0.3, -0.1]) - bias = gtsam.ConstantBias(accBias, gyroBias) + bias = gtsam.imuBias_ConstantBias(accBias, gyroBias) dt = 1e-2 super(ImuFactorExample, self).__init__(sick_twist, bias, dt) def addPrior(self, i, graph): state = self.scenario.navState(i) - graph.push_back(gtsam.PriorFactorPose3(X(i), state.pose(), self.priorNoise)) - graph.push_back(gtsam.PriorFactorVector3(V(i), state.velocity(), self.velNoise)) - + graph.push_back(gtsam.PriorFactorPose3( + X(i), state.pose(), self.priorNoise)) + graph.push_back(gtsam.PriorFactorVector( + V(i), state.velocity(), self.velNoise)) + def run(self): graph = gtsam.NonlinearFactorGraph() - # initialize data structure for pre-integrated IMU measurements + # initialize data structure for pre-integrated IMU measurements pim = gtsam.PreintegratedImuMeasurements(self.params, self.actualBias) - - H9 = gtsam.OptionalJacobian9(); - + T = 12 num_poses = T + 1 # assumes 1 factor per second initial = gtsam.Values() @@ -61,32 +78,32 @@ class ImuFactorExample(PreintegrationExample): state_i = self.scenario.navState(float(i)) initial.insert(X(i), state_i.pose()) initial.insert(V(i), state_i.velocity()) - + # simulate the loop - i = 0 # state index + i = 0 # state index actual_state_i = self.scenario.navState(0) for k, t in enumerate(np.arange(0, T, self.dt)): # get measurements and add them to PIM measuredOmega = self.runner.measuredAngularVelocity(t) measuredAcc = self.runner.measuredSpecificForce(t) pim.integrateMeasurement(measuredAcc, measuredOmega, self.dt) - + # Plot IMU many times if k % 10 == 0: self.plotImu(t, measuredOmega, measuredAcc) - + # Plot every second if k % int(1 / self.dt) == 0: self.plotGroundTruthPose(t) - + # create IMU factor every second if (k + 1) % int(1 / self.dt) == 0: - factor = gtsam.ImuFactor(X(i), V(i), X(i + 1), V(i + 1), BIAS_KEY, pim) + factor = gtsam.ImuFactor(X(i), V(i), X( + i + 1), V(i + 1), BIAS_KEY, pim) graph.push_back(factor) if True: print(factor) - H2 = gtsam.OptionalJacobian96(); - print(pim.predict(actual_state_i, self.actualBias, H9, H2)) + print(pim.predict(actual_state_i, self.actualBias)) pim.resetIntegration() actual_state_i = self.scenario.navState(t + self.dt) i += 1 @@ -94,30 +111,33 @@ class ImuFactorExample(PreintegrationExample): # add priors on beginning and end self.addPrior(0, graph) self.addPrior(num_poses - 1, graph) - + # optimize using Levenberg-Marquardt optimization params = gtsam.LevenbergMarquardtParams() params.setVerbosityLM("SUMMARY") optimizer = gtsam.LevenbergMarquardtOptimizer(graph, initial, params) result = optimizer.optimize() - + # Calculate and print marginal covariances marginals = gtsam.Marginals(graph, result) print("Covariance on bias:\n", marginals.marginalCovariance(BIAS_KEY)) for i in range(num_poses): - print("Covariance on pose {}:\n{}\n".format(i, marginals.marginalCovariance(X(i)))) - print("Covariance on vel {}:\n{}\n".format(i, marginals.marginalCovariance(V(i)))) + print("Covariance on pose {}:\n{}\n".format( + i, marginals.marginalCovariance(X(i)))) + print("Covariance on vel {}:\n{}\n".format( + i, marginals.marginalCovariance(V(i)))) # Plot resulting poses i = 0 while result.exists(X(i)): pose_i = result.atPose3(X(i)) - plotPose3(POSES_FIG, pose_i, 0.1) + plot_pose3(POSES_FIG, pose_i, 0.1) i += 1 - print(result.atConstantBias(BIAS_KEY)) - + print(result.atimuBias_ConstantBias(BIAS_KEY)) + plt.ioff() plt.show() + if __name__ == '__main__': ImuFactorExample().run() diff --git a/cython/gtsam/examples/OdometryExample.py b/cython/gtsam/examples/OdometryExample.py index 5d2190d56..e778e3f85 100644 --- a/cython/gtsam/examples/OdometryExample.py +++ b/cython/gtsam/examples/OdometryExample.py @@ -17,6 +17,9 @@ import numpy as np import gtsam +import matplotlib.pyplot as plt +import gtsam.utils.plot as gtsam_plot + # Create noise models ODOMETRY_NOISE = gtsam.noiseModel_Diagonal.Sigmas(np.array([0.2, 0.2, 0.1])) PRIOR_NOISE = gtsam.noiseModel_Diagonal.Sigmas(np.array([0.3, 0.3, 0.1])) @@ -50,3 +53,17 @@ params = gtsam.LevenbergMarquardtParams() optimizer = gtsam.LevenbergMarquardtOptimizer(graph, initial, params) result = optimizer.optimize() print("\nFinal Result:\n{}".format(result)) + +# 5. Calculate and print marginal covariances for all variables +marginals = gtsam.Marginals(graph, result) +for i in range(1, 4): + print("X{} covariance:\n{}\n".format(i, marginals.marginalCovariance(i))) + +fig = plt.figure(0) +for i in range(1, 4): + gtsam_plot.plot_pose2(0, result.atPose2(i), 0.5, marginals.marginalCovariance(i)) +plt.axis('equal') +plt.show() + + + diff --git a/cython/gtsam/examples/PlanarManipulatorExample.py b/cython/gtsam/examples/PlanarManipulatorExample.py index af21e6ca5..e42ae09d7 100644 --- a/cython/gtsam/examples/PlanarManipulatorExample.py +++ b/cython/gtsam/examples/PlanarManipulatorExample.py @@ -24,6 +24,7 @@ from mpl_toolkits.mplot3d import Axes3D # pylint: disable=W0611 import gtsam import gtsam.utils.plot as gtsam_plot from gtsam import Pose2 +from gtsam.utils.test_case import GtsamTestCase def vector3(x, y, z): @@ -114,7 +115,7 @@ class ThreeLinkArm(object): l1Zl1 = expmap(0.0, 0.0, q[0]) l2Zl2 = expmap(0.0, self.L1, q[1]) - l3Zl3 = expmap(0.0, 7.0, q[2]) + l3Zl3 = expmap(0.0, self.L1+self.L2, q[2]) return compose(l1Zl1, l2Zl2, l3Zl3, self.sXt0) def ik(self, sTt_desired, e=1e-9): @@ -202,7 +203,7 @@ Q1 = np.radians(vector3(-30, -45, -90)) Q2 = np.radians(vector3(-90, 90, 0)) -class TestPose2SLAMExample(unittest.TestCase): +class TestPose2SLAMExample(GtsamTestCase): """Unit tests for functions used below.""" def setUp(self): @@ -296,12 +297,18 @@ def run_example(): """ Use trajectory interpolation and then trajectory tracking a la Murray to move a 3-link arm on a straight line. """ + # Create arm arm = ThreeLinkArm() + + # Get initial pose using forward kinematics q = np.radians(vector3(30, -30, 45)) sTt_initial = arm.fk(q) + + # Create interpolated trajectory in task space to desired goal pose sTt_goal = Pose2(2.4, 4.3, math.radians(0)) poses = trajectory(sTt_initial, sTt_goal, 50) + # Setup figure and plot initial pose fignum = 0 fig = plt.figure(fignum) axes = fig.gca() @@ -309,6 +316,8 @@ def run_example(): axes.set_ylim(0, 10) gtsam_plot.plot_pose2(fignum, arm.fk(q)) + # For all poses in interpolated trajectory, calculate dq to move to next pose. + # We do this by calculating the local Jacobian J and doing dq = inv(J)*delta(sTt, pose). for pose in poses: sTt = arm.fk(q) error = delta(sTt, pose) diff --git a/cython/gtsam/examples/Pose2SLAMExample.py b/cython/gtsam/examples/Pose2SLAMExample.py index b15b90864..680f2209f 100644 --- a/cython/gtsam/examples/Pose2SLAMExample.py +++ b/cython/gtsam/examples/Pose2SLAMExample.py @@ -19,6 +19,9 @@ import numpy as np import gtsam +import matplotlib.pyplot as plt +import gtsam.utils.plot as gtsam_plot + def vector3(x, y, z): """Create 3d double numpy array.""" @@ -85,3 +88,10 @@ print("Final Result:\n{}".format(result)) marginals = gtsam.Marginals(graph, result) for i in range(1, 6): print("X{} covariance:\n{}\n".format(i, marginals.marginalCovariance(i))) + +fig = plt.figure(0) +for i in range(1, 6): + gtsam_plot.plot_pose2(0, result.atPose2(i), 0.5, marginals.marginalCovariance(i)) + +plt.axis('equal') +plt.show() diff --git a/cython/gtsam/examples/Pose2SLAMExample_g2o.py b/cython/gtsam/examples/Pose2SLAMExample_g2o.py new file mode 100644 index 000000000..3aee7daff --- /dev/null +++ b/cython/gtsam/examples/Pose2SLAMExample_g2o.py @@ -0,0 +1,89 @@ +""" +GTSAM Copyright 2010-2018, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved +Authors: Frank Dellaert, et al. (see THANKS for the full author list) + +See LICENSE for the license information + +A 2D Pose SLAM example that reads input from g2o, converts it to a factor graph +and does the optimization. Output is written on a file, in g2o format +""" +# pylint: disable=invalid-name, E1101 + +from __future__ import print_function +import argparse +import math +import numpy as np +import matplotlib.pyplot as plt + +import gtsam +from gtsam.utils import plot + + +def vector3(x, y, z): + """Create 3d double numpy array.""" + return np.array([x, y, z], dtype=np.float) + + +parser = argparse.ArgumentParser( + description="A 2D Pose SLAM example that reads input from g2o, " + "converts it to a factor graph and does the optimization. " + "Output is written on a file, in g2o format") +parser.add_argument('-i', '--input', help='input file g2o format') +parser.add_argument('-o', '--output', + help="the path to the output file with optimized graph") +parser.add_argument('-m', '--maxiter', type=int, + help="maximum number of iterations for optimizer") +parser.add_argument('-k', '--kernel', choices=['none', 'huber', 'tukey'], + default="none", help="Type of kernel used") +parser.add_argument("-p", "--plot", action="store_true", + help="Flag to plot results") +args = parser.parse_args() + +g2oFile = gtsam.findExampleDataFile("noisyToyGraph.txt") if args.input is None\ + else args.input + +maxIterations = 100 if args.maxiter is None else args.maxiter + +is3D = False + +graph, initial = gtsam.readG2o(g2oFile, is3D) + +assert args.kernel == "none", "Supplied kernel type is not yet implemented" + +# Add prior on the pose having index (key) = 0 +graphWithPrior = graph +priorModel = gtsam.noiseModel_Diagonal.Variances(vector3(1e-6, 1e-6, 1e-8)) +graphWithPrior.add(gtsam.PriorFactorPose2(0, gtsam.Pose2(), priorModel)) + +params = gtsam.GaussNewtonParams() +params.setVerbosity("Termination") +params.setMaxIterations(maxIterations) +# parameters.setRelativeErrorTol(1e-5) +# Create the optimizer ... +optimizer = gtsam.GaussNewtonOptimizer(graphWithPrior, initial, params) +# ... and optimize +result = optimizer.optimize() + +print("Optimization complete") +print("initial error = ", graph.error(initial)) +print("final error = ", graph.error(result)) + + +if args.output is None: + print("\nFactor Graph:\n{}".format(graph)) + print("\nInitial Estimate:\n{}".format(initial)) + print("Final Result:\n{}".format(result)) +else: + outputFile = args.output + print("Writing results to file: ", outputFile) + graphNoKernel, _ = gtsam.readG2o(g2oFile, is3D) + gtsam.writeG2o(graphNoKernel, result, outputFile) + print ("Done!") + +if args.plot: + resultPoses = gtsam.extractPose2(result) + for i in range(resultPoses.shape[0]): + plot.plot_pose2(1, gtsam.Pose2(resultPoses[i, :])) + plt.show() diff --git a/cython/gtsam/examples/Pose3SLAMExample_g2o.py b/cython/gtsam/examples/Pose3SLAMExample_g2o.py new file mode 100644 index 000000000..38c5db275 --- /dev/null +++ b/cython/gtsam/examples/Pose3SLAMExample_g2o.py @@ -0,0 +1,72 @@ +""" + * @file Pose3SLAMExample_initializePose3.cpp + * @brief A 3D Pose SLAM example that reads input from g2o, and initializes the + * Pose3 using InitializePose3 + * @date Jan 17, 2019 + * @author Vikrant Shah based on CPP example by Luca Carlone +""" +# pylint: disable=invalid-name, E1101 + +from __future__ import print_function +import argparse +import numpy as np +import matplotlib.pyplot as plt +from mpl_toolkits.mplot3d import Axes3D + +import gtsam +from gtsam.utils import plot + + +def vector6(x, y, z, a, b, c): + """Create 6d double numpy array.""" + return np.array([x, y, z, a, b, c], dtype=np.float) + + +parser = argparse.ArgumentParser( + description="A 3D Pose SLAM example that reads input from g2o, and " + "initializes Pose3") +parser.add_argument('-i', '--input', help='input file g2o format') +parser.add_argument('-o', '--output', + help="the path to the output file with optimized graph") +parser.add_argument("-p", "--plot", action="store_true", + help="Flag to plot results") +args = parser.parse_args() + +g2oFile = gtsam.findExampleDataFile("pose3example.txt") if args.input is None \ + else args.input + +is3D = True +graph, initial = gtsam.readG2o(g2oFile, is3D) + +# Add Prior on the first key +priorModel = gtsam.noiseModel_Diagonal.Variances(vector6(1e-6, 1e-6, 1e-6, + 1e-4, 1e-4, 1e-4)) + +print("Adding prior to g2o file ") +graphWithPrior = graph +firstKey = initial.keys().at(0) +graphWithPrior.add(gtsam.PriorFactorPose3(firstKey, gtsam.Pose3(), priorModel)) + +params = gtsam.GaussNewtonParams() +params.setVerbosity("Termination") # this will show info about stopping conds +optimizer = gtsam.GaussNewtonOptimizer(graphWithPrior, initial, params) +result = optimizer.optimize() +print("Optimization complete") + +print("initial error = ", graphWithPrior.error(initial)) +print("final error = ", graphWithPrior.error(result)) + +if args.output is None: + print("Final Result:\n{}".format(result)) +else: + outputFile = args.output + print("Writing results to file: ", outputFile) + graphNoKernel, _ = gtsam.readG2o(g2oFile, is3D) + gtsam.writeG2o(graphNoKernel, result, outputFile) + print ("Done!") + +if args.plot: + resultPoses = gtsam.allPose3s(result) + for i in range(resultPoses.size()): + plot.plot_pose3(1, resultPoses.atPose3(i)) + plt.show() diff --git a/cython/gtsam/examples/Pose3SLAMExample_initializePose3Chordal.py b/cython/gtsam/examples/Pose3SLAMExample_initializePose3Chordal.py new file mode 100644 index 000000000..02c696905 --- /dev/null +++ b/cython/gtsam/examples/Pose3SLAMExample_initializePose3Chordal.py @@ -0,0 +1,35 @@ +""" +GTSAM Copyright 2010-2018, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved +Authors: Frank Dellaert, et al. (see THANKS for the full author list) + +See LICENSE for the license information + +Initialize PoseSLAM with Chordal init +Author: Luca Carlone, Frank Dellaert (python port) +""" +# pylint: disable=invalid-name, E1101 + +from __future__ import print_function + +import numpy as np + +import gtsam + +# Read graph from file +g2oFile = gtsam.findExampleDataFile("pose3example.txt") + +is3D = True +graph, initial = gtsam.readG2o(g2oFile, is3D) + +# Add prior on the first key. TODO: assumes first key ios z +priorModel = gtsam.noiseModel_Diagonal.Variances( + np.array([1e-6, 1e-6, 1e-6, 1e-4, 1e-4, 1e-4])) +firstKey = initial.keys().at(0) +graph.add(gtsam.PriorFactorPose3(0, gtsam.Pose3(), priorModel)) + +# Initializing Pose3 - chordal relaxation" +initialization = gtsam.InitializePose3.initialize(graph) + +print(initialization) diff --git a/python/gtsam_examples/PreintegrationExample.py b/cython/gtsam/examples/PreintegrationExample.py similarity index 81% rename from python/gtsam_examples/PreintegrationExample.py rename to cython/gtsam/examples/PreintegrationExample.py index b441ffecb..76520b355 100644 --- a/python/gtsam_examples/PreintegrationExample.py +++ b/cython/gtsam/examples/PreintegrationExample.py @@ -1,19 +1,26 @@ """ +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + A script validating the Preintegration of IMU measurements """ import math + import matplotlib.pyplot as plt import numpy as np - from mpl_toolkits.mplot3d import Axes3D import gtsam -from gtsam_utils import plotPose3 +from gtsam.utils.plot import plot_pose3 IMU_FIG = 1 POSES_FIG = 2 + class PreintegrationExample(object): @staticmethod @@ -22,18 +29,21 @@ class PreintegrationExample(object): params = gtsam.PreintegrationParams.MakeSharedU(g) kGyroSigma = math.radians(0.5) / 60 # 0.5 degree ARW kAccelSigma = 0.1 / 60 # 10 cm VRW - params.gyroscopeCovariance = kGyroSigma ** 2 * np.identity(3, np.float) - params.accelerometerCovariance = kAccelSigma ** 2 * np.identity(3, np.float) - params.integrationCovariance = 0.0000001 ** 2 * np.identity(3, np.float) + params.setGyroscopeCovariance( + kGyroSigma ** 2 * np.identity(3, np.float)) + params.setAccelerometerCovariance( + kAccelSigma ** 2 * np.identity(3, np.float)) + params.setIntegrationCovariance( + 0.0000001 ** 2 * np.identity(3, np.float)) return params def __init__(self, twist=None, bias=None, dt=1e-2): """Initialize with given twist, a pair(angularVelocityVector, velocityVector).""" - + # setup interactive plotting plt.ion() - # Setup loop as default scenario + # Setup loop as default scenario if twist is not None: (W, V) = twist else: @@ -52,21 +62,21 @@ class PreintegrationExample(object): # Create runner self.g = 10 # simple gravity constant self.params = self.defaultParams(self.g) - ptr = gtsam.ScenarioPointer(self.scenario) if bias is not None: self.actualBias = bias else: accBias = np.array([0, 0.1, 0]) gyroBias = np.array([0, 0, 0]) - self.actualBias = gtsam.ConstantBias(accBias, gyroBias) + self.actualBias = gtsam.imuBias_ConstantBias(accBias, gyroBias) - self.runner = gtsam.ScenarioRunner(ptr, self.params, self.dt, self.actualBias) + self.runner = gtsam.ScenarioRunner( + self.scenario, self.params, self.dt, self.actualBias) def plotImu(self, t, measuredOmega, measuredAcc): plt.figure(IMU_FIG) - # plot angular velocity + # plot angular velocity omega_b = self.scenario.omega_b(t) for i, (label, color) in enumerate(zip(self.labels, self.colors)): plt.subplot(4, 3, i + 1) @@ -99,9 +109,9 @@ class PreintegrationExample(object): def plotGroundTruthPose(self, t): # plot ground truth pose, as well as prediction from integrated IMU measurements actualPose = self.scenario.pose(t) - plotPose3(POSES_FIG, actualPose, 0.3) + plot_pose3(POSES_FIG, actualPose, 0.3) t = actualPose.translation() - self.maxDim = max([abs(t[0]), abs(t[1]), abs(t[2]), self.maxDim]) + self.maxDim = max([abs(t.x()), abs(t.y()), abs(t.z()), self.maxDim]) ax = plt.gca() ax.set_xlim3d(-self.maxDim, self.maxDim) ax.set_ylim3d(-self.maxDim, self.maxDim) @@ -120,10 +130,11 @@ class PreintegrationExample(object): self.plotGroundTruthPose(t) pim = self.runner.integrate(t, self.actualBias, True) predictedNavState = self.runner.predict(pim, self.actualBias) - plotPose3(POSES_FIG, predictedNavState.pose(), 0.1) + plot_pose3(POSES_FIG, predictedNavState.pose(), 0.1) plt.ioff() plt.show() + if __name__ == '__main__': PreintegrationExample().run() diff --git a/cython/gtsam/examples/README.md b/cython/gtsam/examples/README.md index 067929a20..35ec4f66d 100644 --- a/cython/gtsam/examples/README.md +++ b/cython/gtsam/examples/README.md @@ -1,4 +1,57 @@ These examples are almost identical to the old handwritten python wrapper examples. However, there are just some slight name changes, for example -noiseModel.Diagonal becomes noiseModel_Diagonal etc... -Also, annoyingly, instead of gtsam.Symbol('b',0) we now need to say gtsam.symbol(ord('b'), 0)) +`noiseModel.Diagonal` becomes `noiseModel_Diagonal` etc... +Also, annoyingly, instead of `gtsam.Symbol('b', 0)` we now need to say `gtsam.symbol(ord('b'), 0))` + +# Porting Progress + +| C++ Example Name | Ported | +|-------------------------------------------------------|--------| +| CameraResectioning | | +| CreateSFMExampleData | | +| DiscreteBayesNet_FG | none of the required discrete functionality is exposed through cython | +| easyPoint2KalmanFilter | ExtendedKalmanFilter not exposed through cython | +| elaboratePoint2KalmanFilter | GaussianSequentialSolver not exposed through cython | +| ImuFactorExample2 | X | +| ImuFactorsExample | | +| ISAM2Example_SmartFactor | | +| ISAM2_SmartFactorStereo_IMU | | +| LocalizationExample | impossible? | +| METISOrderingExample | | +| OdometryExample | X | +| PlanarSLAMExample | X | +| Pose2SLAMExample | X | +| Pose2SLAMExampleExpressions | | +| Pose2SLAMExample_g2o | X | +| Pose2SLAMExample_graph | | +| Pose2SLAMExample_graphviz | | +| Pose2SLAMExample_lago | lago not exposed through cython | +| Pose2SLAMStressTest | | +| Pose2SLAMwSPCG | | +| Pose3SLAMExample_changeKeys | | +| Pose3SLAMExampleExpressions_BearingRangeWithTransform | | +| Pose3SLAMExample_g2o | X | +| Pose3SLAMExample_initializePose3Chordal | | +| Pose3SLAMExample_initializePose3Gradient | | +| RangeISAMExample_plaza2 | | +| SelfCalibrationExample | | +| SFMExample_bal_COLAMD_METIS | | +| SFMExample_bal | | +| SFMExample | X | +| SFMExampleExpressions_bal | | +| SFMExampleExpressions | | +| SFMExample_SmartFactor | | +| SFMExample_SmartFactorPCG | | +| SimpleRotation | X | +| SolverComparer | | +| StereoVOExample | | +| StereoVOExample_large | | +| TimeTBB | | +| UGM_chain | discrete functionality not exposed | +| UGM_small | discrete functionality not exposed | +| VisualISAM2Example | X | +| VisualISAMExample | X | + +Extra Examples (with no C++ equivalent) +- PlanarManipulatorExample +- SFMData diff --git a/cython/gtsam/examples/SFMExample.py b/cython/gtsam/examples/SFMExample.py new file mode 100644 index 000000000..bf46f09d5 --- /dev/null +++ b/cython/gtsam/examples/SFMExample.py @@ -0,0 +1,118 @@ +""" +GTSAM Copyright 2010, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved +Authors: Frank Dellaert, et al. (see THANKS for the full author list) + +See LICENSE for the license information + +A structure-from-motion problem on a simulated dataset +""" +from __future__ import print_function + +import gtsam +import numpy as np +from gtsam.examples import SFMdata +from gtsam.gtsam import (Cal3_S2, DoglegOptimizer, + GenericProjectionFactorCal3_S2, NonlinearFactorGraph, + Point3, Pose3, PriorFactorPoint3, PriorFactorPose3, + Rot3, SimpleCamera, Values) + + +def symbol(name: str, index: int) -> int: + """ helper for creating a symbol without explicitly casting 'name' from str to int """ + return gtsam.symbol(ord(name), index) + + +def main(): + """ + Camera observations of landmarks (i.e. pixel coordinates) will be stored as Point2 (x, y). + + Each variable in the system (poses and landmarks) must be identified with a unique key. + We can either use simple integer keys (1, 2, 3, ...) or symbols (X1, X2, L1). + Here we will use Symbols + + In GTSAM, measurement functions are represented as 'factors'. Several common factors + have been provided with the library for solving robotics/SLAM/Bundle Adjustment problems. + Here we will use Projection factors to model the camera's landmark observations. + Also, we will initialize the robot at some location using a Prior factor. + + When the factors are created, we will add them to a Factor Graph. As the factors we are using + are nonlinear factors, we will need a Nonlinear Factor Graph. + + Finally, once all of the factors have been added to our factor graph, we will want to + solve/optimize to graph to find the best (Maximum A Posteriori) set of variable values. + GTSAM includes several nonlinear optimizers to perform this step. Here we will use a + trust-region method known as Powell's Degleg + + The nonlinear solvers within GTSAM are iterative solvers, meaning they linearize the + nonlinear functions around an initial linearization point, then solve the linear system + to update the linearization point. This happens repeatedly until the solver converges + to a consistent set of variable values. This requires us to specify an initial guess + for each variable, held in a Values container. + """ + + # Define the camera calibration parameters + K = Cal3_S2(50.0, 50.0, 0.0, 50.0, 50.0) + + # Define the camera observation noise model + measurement_noise = gtsam.noiseModel_Isotropic.Sigma(2, 1.0) # one pixel in u and v + + # Create the set of ground-truth landmarks + points = SFMdata.createPoints() + + # Create the set of ground-truth poses + poses = SFMdata.createPoses(K) + + # Create a factor graph + graph = NonlinearFactorGraph() + + # Add a prior on pose x1. This indirectly specifies where the origin is. + # 0.3 rad std on roll,pitch,yaw and 0.1m on x,y,z + pose_noise = gtsam.noiseModel_Diagonal.Sigmas(np.array([0.3, 0.3, 0.3, 0.1, 0.1, 0.1])) + factor = PriorFactorPose3(symbol('x', 0), poses[0], pose_noise) + graph.push_back(factor) + + # Simulated measurements from each camera pose, adding them to the factor graph + for i, pose in enumerate(poses): + camera = SimpleCamera(pose, K) + for j, point in enumerate(points): + measurement = camera.project(point) + factor = GenericProjectionFactorCal3_S2( + measurement, measurement_noise, symbol('x', i), symbol('l', j), K) + graph.push_back(factor) + + # Because the structure-from-motion problem has a scale ambiguity, the problem is still under-constrained + # Here we add a prior on the position of the first landmark. This fixes the scale by indicating the distance + # between the first camera and the first landmark. All other landmark positions are interpreted using this scale. + point_noise = gtsam.noiseModel_Isotropic.Sigma(3, 0.1) + factor = PriorFactorPoint3(symbol('l', 0), points[0], point_noise) + graph.push_back(factor) + graph.print_('Factor Graph:\n') + + # Create the data structure to hold the initial estimate to the solution + # Intentionally initialize the variables off from the ground truth + initial_estimate = Values() + for i, pose in enumerate(poses): + r = Rot3.Rodrigues(-0.1, 0.2, 0.25) + t = Point3(0.05, -0.10, 0.20) + transformed_pose = pose.compose(Pose3(r, t)) + initial_estimate.insert(symbol('x', i), transformed_pose) + for j, point in enumerate(points): + transformed_point = Point3(point.vector() + np.array([-0.25, 0.20, 0.15])) + initial_estimate.insert(symbol('l', j), transformed_point) + initial_estimate.print_('Initial Estimates:\n') + + # Optimize the graph and print results + params = gtsam.DoglegParams() + params.setVerbosity('TERMINATION') + optimizer = DoglegOptimizer(graph, initial_estimate, params) + print('Optimizing:') + result = optimizer.optimize() + result.print_('Final results:\n') + print('initial error = {}'.format(graph.error(initial_estimate))) + print('final error = {}'.format(graph.error(result))) + + +if __name__ == '__main__': + main() diff --git a/cython/gtsam/examples/SimpleRotation.py b/cython/gtsam/examples/SimpleRotation.py new file mode 100644 index 000000000..6e9b1320b --- /dev/null +++ b/cython/gtsam/examples/SimpleRotation.py @@ -0,0 +1,84 @@ +""" +GTSAM Copyright 2010, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved +Authors: Frank Dellaert, et al. (see THANKS for the full author list) + +See LICENSE for the license information + +This example will perform a relatively trivial optimization on +a single variable with a single factor. +""" + +import numpy as np +import gtsam + + +def main(): + """ + Step 1: Create a factor to express a unary constraint + + The "prior" in this case is the measurement from a sensor, + with a model of the noise on the measurement. + + The "Key" created here is a label used to associate parts of the + state (stored in "RotValues") with particular factors. They require + an index to allow for lookup, and should be unique. + + In general, creating a factor requires: + - A key or set of keys labeling the variables that are acted upon + - A measurement value + - A measurement model with the correct dimensionality for the factor + """ + prior = gtsam.Rot2.fromAngle(np.deg2rad(30)) + prior.print_('goal angle') + model = gtsam.noiseModel_Isotropic.Sigma(dim=1, sigma=np.deg2rad(1)) + key = gtsam.symbol(ord('x'), 1) + factor = gtsam.PriorFactorRot2(key, prior, model) + + """ + Step 2: Create a graph container and add the factor to it + + Before optimizing, all factors need to be added to a Graph container, + which provides the necessary top-level functionality for defining a + system of constraints. + + In this case, there is only one factor, but in a practical scenario, + many more factors would be added. + """ + graph = gtsam.NonlinearFactorGraph() + graph.push_back(factor) + graph.print_('full graph') + + """ + Step 3: Create an initial estimate + + An initial estimate of the solution for the system is necessary to + start optimization. This system state is the "Values" instance, + which is similar in structure to a dictionary, in that it maps + keys (the label created in step 1) to specific values. + + The initial estimate provided to optimization will be used as + a linearization point for optimization, so it is important that + all of the variables in the graph have a corresponding value in + this structure. + """ + initial = gtsam.Values() + initial.insert(key, gtsam.Rot2.fromAngle(np.deg2rad(20))) + initial.print_('initial estimate') + + """ + Step 4: Optimize + + After formulating the problem with a graph of constraints + and an initial estimate, executing optimization is as simple + as calling a general optimization function with the graph and + initial estimate. This will yield a new RotValues structure + with the final state of the optimization. + """ + result = gtsam.LevenbergMarquardtOptimizer(graph, initial).optimize() + result.print_('final result') + + +if __name__ == '__main__': + main() diff --git a/cython/gtsam/examples/VisualISAMExample.py b/cython/gtsam/examples/VisualISAMExample.py new file mode 100644 index 000000000..f4d81eaf7 --- /dev/null +++ b/cython/gtsam/examples/VisualISAMExample.py @@ -0,0 +1,106 @@ +""" +GTSAM Copyright 2010, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved +Authors: Frank Dellaert, et al. (see THANKS for the full author list) + +See LICENSE for the license information + +A visualSLAM example for the structure-from-motion problem on a simulated dataset +This version uses iSAM to solve the problem incrementally +""" + +from __future__ import print_function + +import numpy as np +import gtsam +from gtsam.examples import SFMdata +from gtsam.gtsam import (Cal3_S2, GenericProjectionFactorCal3_S2, + NonlinearFactorGraph, NonlinearISAM, Point3, Pose3, + PriorFactorPoint3, PriorFactorPose3, Rot3, + SimpleCamera, Values) + + +def symbol(name: str, index: int) -> int: + """ helper for creating a symbol without explicitly casting 'name' from str to int """ + return gtsam.symbol(ord(name), index) + + +def main(): + """ + A structure-from-motion example with landmarks + - The landmarks form a 10 meter cube + - The robot rotates around the landmarks, always facing towards the cube + """ + + # Define the camera calibration parameters + K = Cal3_S2(50.0, 50.0, 0.0, 50.0, 50.0) + + # Define the camera observation noise model + camera_noise = gtsam.noiseModel_Isotropic.Sigma(2, 1.0) # one pixel in u and v + + # Create the set of ground-truth landmarks + points = SFMdata.createPoints() + # Create the set of ground-truth poses + poses = SFMdata.createPoses(K) + + # Create a NonlinearISAM object which will relinearize and reorder the variables + # every "reorderInterval" updates + isam = NonlinearISAM(reorderInterval=3) + + # Create a Factor Graph and Values to hold the new data + graph = NonlinearFactorGraph() + initial_estimate = Values() + + # Loop over the different poses, adding the observations to iSAM incrementally + for i, pose in enumerate(poses): + camera = SimpleCamera(pose, K) + # Add factors for each landmark observation + for j, point in enumerate(points): + measurement = camera.project(point) + factor = GenericProjectionFactorCal3_S2(measurement, camera_noise, symbol('x', i), symbol('l', j), K) + graph.push_back(factor) + + # Intentionally initialize the variables off from the ground truth + noise = Pose3(r=Rot3.Rodrigues(-0.1, 0.2, 0.25), t=Point3(0.05, -0.10, 0.20)) + initial_xi = pose.compose(noise) + + # Add an initial guess for the current pose + initial_estimate.insert(symbol('x', i), initial_xi) + + # If this is the first iteration, add a prior on the first pose to set the coordinate frame + # and a prior on the first landmark to set the scale + # Also, as iSAM solves incrementally, we must wait until each is observed at least twice before + # adding it to iSAM. + if i == 0: + # Add a prior on pose x0, with 0.3 rad std on roll,pitch,yaw and 0.1m x,y,z + pose_noise = gtsam.noiseModel_Diagonal.Sigmas(np.array([0.3, 0.3, 0.3, 0.1, 0.1, 0.1])) + factor = PriorFactorPose3(symbol('x', 0), poses[0], pose_noise) + graph.push_back(factor) + + # Add a prior on landmark l0 + point_noise = gtsam.noiseModel_Isotropic.Sigma(3, 0.1) + factor = PriorFactorPoint3(symbol('l', 0), points[0], point_noise) + graph.push_back(factor) + + # Add initial guesses to all observed landmarks + noise = np.array([-0.25, 0.20, 0.15]) + for j, point in enumerate(points): + # Intentionally initialize the variables off from the ground truth + initial_lj = points[j].vector() + noise + initial_estimate.insert(symbol('l', j), Point3(initial_lj)) + else: + # Update iSAM with the new factors + isam.update(graph, initial_estimate) + current_estimate = isam.estimate() + print('*' * 50) + print('Frame {}:'.format(i)) + current_estimate.print_('Current estimate: ') + + # Clear the factor graph and values for the next iteration + graph.resize(0) + initial_estimate.clear() + + +if __name__ == '__main__': + main() diff --git a/cython/gtsam/tests/experiments.py b/cython/gtsam/tests/experiments.py deleted file mode 100644 index 425180173..000000000 --- a/cython/gtsam/tests/experiments.py +++ /dev/null @@ -1,112 +0,0 @@ -""" -This file is not a real python unittest. It contains small experiments -to test the wrapper with gtsam_test, a short version of gtsam.h. -Its name convention is different from other tests so it won't be discovered. -""" -import gtsam -import numpy as np - -r = gtsam.Rot3() -print(r) -print(r.pitch()) -r2 = gtsam.Rot3() -r3 = r.compose(r2) -print("r3 pitch:", r3.pitch()) - -v = np.array([1, 1, 1]) -print("v = ", v) -r4 = r3.retract(v) -print("r4 pitch:", r4.pitch()) -r4.print_(b'r4: ') -r3.print_(b"r3: ") - -v = r3.localCoordinates(r4) -print("localCoordinates:", v) - -Rmat = np.array([ - [0.990074, -0.0942928, 0.104218], - [0.104218, 0.990074, -0.0942928], - [-0.0942928, 0.104218, 0.990074] - ]) -r5 = gtsam.Rot3(Rmat) -r5.print_(b"r5: ") - -l = gtsam.Rot3.Logmap(r5) -print("l = ", l) - - -noise = gtsam.noiseModel_Gaussian.Covariance(Rmat) -noise.print_(b"noise:") - -D = np.array([1.,2.,3.]) -diag = gtsam.noiseModel_Diagonal.Variances(D) -print("diag:", diag) -diag.print_(b"diag:") -print("diag R:", diag.R()) - -p = gtsam.Point3() -p.print_("p:") -factor = gtsam.BetweenFactorPoint3(1,2,p, noise) -factor.print_(b"factor:") - -vv = gtsam.VectorValues() -vv.print_(b"vv:") -vv.insert(1, np.array([1.,2.,3.])) -vv.insert(2, np.array([3.,4.])) -vv.insert(3, np.array([5.,6.,7.,8.])) -vv.print_(b"vv:") - -vv2 = gtsam.VectorValues(vv) -vv2.insert(4, np.array([4.,2.,1])) -vv2.print_(b"vv2:") -vv.print_(b"vv:") - -vv.insert(4, np.array([1.,2.,4.])) -vv.print_(b"vv:") -vv3 = vv.add(vv2) - -vv3.print_(b"vv3:") - -values = gtsam.Values() -values.insert(1, gtsam.Point3()) -values.insert(2, gtsam.Rot3()) -values.print_(b"values:") - -factor = gtsam.PriorFactorVector(1, np.array([1.,2.,3.]), diag) -print "Prior factor vector: ", factor - - - -keys = gtsam.KeyVector() - -keys.push_back(1) -keys.push_back(2) -print 'size: ', keys.size() -print keys.at(0) -print keys.at(1) - -noise = gtsam.noiseModel_Isotropic.Precision(2, 3.0) -noise.print_('noise:') -print 'noise print:', noise -f = gtsam.JacobianFactor(7, np.ones([2,2]), model=noise, b=np.ones(2)) -print 'JacobianFactor(7):\n', f -print "A = ", f.getA() -print "b = ", f.getb() - -f = gtsam.JacobianFactor(np.ones(2)) -f.print_('jacoboian b_in:') - - -print "JacobianFactor initalized with b_in:", f - -diag = gtsam.noiseModel_Diagonal.Sigmas(np.array([1.,2.,3.])) -fv = gtsam.PriorFactorVector(1, np.array([4.,5.,6.]), diag) -print "priorfactorvector: ", fv - -print "base noise: ", fv.get_noiseModel() -print "casted to gaussian2: ", gtsam.dynamic_cast_noiseModel_Diagonal_noiseModel_Base(fv.get_noiseModel()) - -X = gtsam.symbol(65, 19) -print X -print gtsam.symbolChr(X) -print gtsam.symbolIndex(X) diff --git a/cython/gtsam/tests/gtsam_test.h b/cython/gtsam/tests/gtsam_test.h deleted file mode 100644 index 659a7cd0c..000000000 --- a/cython/gtsam/tests/gtsam_test.h +++ /dev/null @@ -1,772 +0,0 @@ -namespace gtsam { - -#include -typedef size_t Key; - -#include -template class FastVector { - FastVector(); - FastVector(const This& f); - void push_back(const T& e); - //T& operator[](int); - T at(int i); - size_t size() const; -}; - -typedef gtsam::FastVector KeyVector; - -//************************************************************************* -// geometry -//************************************************************************* - -#include -class Point2 { - // Standard Constructors - Point2(); - Point2(double x, double y); - Point2(Vector v); - //Point2(const gtsam::Point2& l); - - // Testable - void print(string s) const; - bool equals(const gtsam::Point2& pose, double tol) const; - - // Group - static gtsam::Point2 identity(); - - // Standard Interface - double x() const; - double y() const; - Vector vector() const; - double distance(const gtsam::Point2& p2) const; - double norm() const; - - // enabling serialization functionality - void serialize() const; -}; - -#include -class Point3 { - // Standard Constructors - Point3(); - Point3(double x, double y, double z); - Point3(Vector v); - //Point3(const gtsam::Point3& l); - - // Testable - void print(string s) const; - bool equals(const gtsam::Point3& p, double tol) const; - - // Group - static gtsam::Point3 identity(); - - // Standard Interface - Vector vector() const; - double x() const; - double y() const; - double z() const; - - // enabling serialization functionality - void serialize() const; -}; - -#include -class Rot2 { - // Standard Constructors and Named Constructors - Rot2(); - Rot2(double theta); - //Rot2(const gtsam::Rot2& l); - - static gtsam::Rot2 fromAngle(double theta); - static gtsam::Rot2 fromDegrees(double theta); - static gtsam::Rot2 fromCosSin(double c, double s); - - // Testable - void print(string s) const; - bool equals(const gtsam::Rot2& rot, double tol) const; - - // Group - static gtsam::Rot2 identity(); - gtsam::Rot2 inverse(); - gtsam::Rot2 compose(const gtsam::Rot2& p2) const; - gtsam::Rot2 between(const gtsam::Rot2& p2) const; - - // Manifold - gtsam::Rot2 retract(Vector v) const; - Vector localCoordinates(const gtsam::Rot2& p) const; - - // Lie Group - static gtsam::Rot2 Expmap(Vector v); - static Vector Logmap(const gtsam::Rot2& p); - - // Group Action on Point2 - gtsam::Point2 rotate(const gtsam::Point2& point) const; - gtsam::Point2 unrotate(const gtsam::Point2& point) const; - - // Standard Interface - static gtsam::Rot2 relativeBearing(const gtsam::Point2& d); // Ignoring derivative - static gtsam::Rot2 atan2(double y, double x); - double theta() const; - double degrees() const; - double c() const; - double s() const; - Matrix matrix() const; - - // enabling serialization functionality - void serialize() const; -}; - -#include -class Rot3 { - // Standard Constructors and Named Constructors - Rot3(); - Rot3(Matrix R); - //Rot3(const gtsam::Rot3& l); - - static gtsam::Rot3 Rx(double t); - static gtsam::Rot3 Ry(double t); - static gtsam::Rot3 Rz(double t); - static gtsam::Rot3 RzRyRx(double x, double y, double z); - static gtsam::Rot3 RzRyRx(Vector xyz); - static gtsam::Rot3 Yaw(double t); // positive yaw is to right (as in aircraft heading) - static gtsam::Rot3 Pitch(double t); // positive pitch is up (increasing aircraft altitude) - static gtsam::Rot3 Roll(double t); // positive roll is to right (increasing yaw in aircraft) - static gtsam::Rot3 Ypr(double y, double p, double r); - static gtsam::Rot3 Quaternion(double w, double x, double y, double z); - static gtsam::Rot3 Rodrigues(Vector v); - - // Testable - void print(string s) const; - bool equals(const gtsam::Rot3& rot, double tol) const; - - // Group - static gtsam::Rot3 identity(); - gtsam::Rot3 inverse() const; - gtsam::Rot3 compose(const gtsam::Rot3& p2) const; - gtsam::Rot3 between(const gtsam::Rot3& p2) const; - - // Manifold - //gtsam::Rot3 retractCayley(Vector v) const; // FIXME, does not exist in both Matrix and Quaternion options - gtsam::Rot3 retract(Vector v) const; - Vector localCoordinates(const gtsam::Rot3& p) const; - - // Group Action on Point3 - gtsam::Point3 rotate(const gtsam::Point3& p) const; - gtsam::Point3 unrotate(const gtsam::Point3& p) const; - - // Standard Interface - static gtsam::Rot3 Expmap(Vector v); - static Vector Logmap(const gtsam::Rot3& p); - Matrix matrix() const; - Matrix transpose() const; - gtsam::Point3 column(size_t index) const; - Vector xyz() const; - Vector ypr() const; - Vector rpy() const; - double roll() const; - double pitch() const; - double yaw() const; -// Vector toQuaternion() const; // FIXME: Can't cast to Vector properly - Vector quaternion() const; - - // enabling serialization functionality - void serialize() const; -}; - -#include -class Pose2 { - // Standard Constructor - Pose2(); - //Pose2(const gtsam::Pose2& pose); - Pose2(double x, double y, double theta); - Pose2(double theta, const gtsam::Point2& t); - Pose2(const gtsam::Rot2& r, const gtsam::Point2& t); - Pose2(Vector v); - - // Testable - void print(string s) const; - bool equals(const gtsam::Pose2& pose, double tol) const; - - // Group - static gtsam::Pose2 identity(); - gtsam::Pose2 inverse() const; - gtsam::Pose2 compose(const gtsam::Pose2& p2) const; - gtsam::Pose2 between(const gtsam::Pose2& p2) const; - - // Manifold - gtsam::Pose2 retract(Vector v) const; - Vector localCoordinates(const gtsam::Pose2& p) const; - - // Lie Group - static gtsam::Pose2 Expmap(Vector v); - static Vector Logmap(const gtsam::Pose2& p); - Matrix AdjointMap() const; - Vector Adjoint(const Vector& xi) const; - static Matrix wedge(double vx, double vy, double w); - - // Group Actions on Point2 - gtsam::Point2 transform_from(const gtsam::Point2& p) const; - gtsam::Point2 transform_to(const gtsam::Point2& p) const; - - // Standard Interface - double x() const; - double y() const; - double theta() const; - gtsam::Rot2 bearing(const gtsam::Point2& point) const; - double range(const gtsam::Point2& point) const; - gtsam::Point2 translation() const; - gtsam::Rot2 rotation() const; - Matrix matrix() const; - - // enabling serialization functionality - void serialize() const; -}; - - -#include -class Pose3 { - // Standard Constructors - Pose3(); - //Pose3(const gtsam::Pose3& pose); - Pose3(const gtsam::Rot3& r, const gtsam::Point3& t); - Pose3(const gtsam::Pose2& pose2); // FIXME: shadows Pose3(Pose3 pose) - Pose3(Matrix t); - - // Testable - void print(string s) const; - bool equals(const gtsam::Pose3& pose, double tol) const; - - // Group - static gtsam::Pose3 identity(); - gtsam::Pose3 inverse() const; - gtsam::Pose3 compose(const gtsam::Pose3& p2) const; - gtsam::Pose3 between(const gtsam::Pose3& p2) const; - - // Manifold - gtsam::Pose3 retract(Vector v) const; - Vector localCoordinates(const gtsam::Pose3& T2) const; - - // Lie Group - static gtsam::Pose3 Expmap(Vector v); - static Vector Logmap(const gtsam::Pose3& p); - Matrix AdjointMap() const; - Vector Adjoint(Vector xi) const; - static Matrix wedge(double wx, double wy, double wz, double vx, double vy, double vz); - - // Group Action on Point3 - gtsam::Point3 transform_from(const gtsam::Point3& p) const; - gtsam::Point3 transform_to(const gtsam::Point3& p) const; - - // Standard Interface - gtsam::Rot3 rotation() const; - gtsam::Point3 translation() const; - double x() const; - double y() const; - double z() const; - Matrix matrix() const; - gtsam::Pose3 transform_to(const gtsam::Pose3& pose) const; // FIXME: shadows other transform_to() - double range(const gtsam::Point3& point); - double range(const gtsam::Pose3& pose); - - // enabling serialization functionality - void serialize() const; -}; - -//************************************************************************* -// noise -//************************************************************************* - -namespace noiseModel { -#include -virtual class Base { -}; - -virtual class Gaussian : gtsam::noiseModel::Base { - static gtsam::noiseModel::Gaussian* SqrtInformation(Matrix R); - static gtsam::noiseModel::Gaussian* Covariance(Matrix R); - Matrix R() const; - bool equals(gtsam::noiseModel::Base& expected, double tol); - void print(string s) const; - - // enabling serialization functionality - void serializable() const; -}; - -virtual class Diagonal : gtsam::noiseModel::Gaussian { - static gtsam::noiseModel::Diagonal* Sigmas(Vector sigmas); - static gtsam::noiseModel::Diagonal* Variances(Vector variances); - static gtsam::noiseModel::Diagonal* Precisions(Vector precisions); - Matrix R() const; - void print(string s) const; - - // enabling serialization functionality - void serializable() const; -}; - -virtual class Constrained : gtsam::noiseModel::Diagonal { - static gtsam::noiseModel::Constrained* MixedSigmas(const Vector& mu, const Vector& sigmas); - static gtsam::noiseModel::Constrained* MixedSigmas(double m, const Vector& sigmas); - static gtsam::noiseModel::Constrained* MixedVariances(const Vector& mu, const Vector& variances); - static gtsam::noiseModel::Constrained* MixedVariances(const Vector& variances); - static gtsam::noiseModel::Constrained* MixedPrecisions(const Vector& mu, const Vector& precisions); - static gtsam::noiseModel::Constrained* MixedPrecisions(const Vector& precisions); - - static gtsam::noiseModel::Constrained* All(size_t dim); - static gtsam::noiseModel::Constrained* All(size_t dim, double mu); - - gtsam::noiseModel::Constrained* unit() const; - - // enabling serialization functionality - void serializable() const; -}; - -virtual class Isotropic : gtsam::noiseModel::Diagonal { - static gtsam::noiseModel::Isotropic* Sigma(size_t dim, double sigma); - static gtsam::noiseModel::Isotropic* Variance(size_t dim, double varianace); - static gtsam::noiseModel::Isotropic* Precision(size_t dim, double precision); - void print(string s) const; - - // enabling serialization functionality - void serializable() const; -}; - -virtual class Unit : gtsam::noiseModel::Isotropic { - static gtsam::noiseModel::Unit* Create(size_t dim); - void print(string s) const; - - // enabling serialization functionality - void serializable() const; -}; - -namespace mEstimator { -virtual class Base { -}; - -virtual class Null: gtsam::noiseModel::mEstimator::Base { - Null(); - //Null(const gtsam::noiseModel::mEstimator::Null& other); - void print(string s) const; - static gtsam::noiseModel::mEstimator::Null* Create(); - - // enabling serialization functionality - void serializable() const; -}; - -virtual class Fair: gtsam::noiseModel::mEstimator::Base { - Fair(double c); - //Fair(const gtsam::noiseModel::mEstimator::Fair& other); - void print(string s) const; - static gtsam::noiseModel::mEstimator::Fair* Create(double c); - - // enabling serialization functionality - void serializable() const; -}; - -virtual class Huber: gtsam::noiseModel::mEstimator::Base { - Huber(double k); - //Huber(const gtsam::noiseModel::mEstimator::Huber& other); - - void print(string s) const; - static gtsam::noiseModel::mEstimator::Huber* Create(double k); - - // enabling serialization functionality - void serializable() const; -}; - -virtual class Tukey: gtsam::noiseModel::mEstimator::Base { - Tukey(double k); - //Tukey(const gtsam::noiseModel::mEstimator::Tukey& other); - - void print(string s) const; - static gtsam::noiseModel::mEstimator::Tukey* Create(double k); - - // enabling serialization functionality - void serializable() const; -}; - -}///\namespace mEstimator - -virtual class Robust : gtsam::noiseModel::Base { - Robust(const gtsam::noiseModel::mEstimator::Base* robust, const gtsam::noiseModel::Base* noise); - //Robust(const gtsam::noiseModel::Robust& other); - - static gtsam::noiseModel::Robust* Create(const gtsam::noiseModel::mEstimator::Base* robust, const gtsam::noiseModel::Base* noise); - void print(string s) const; - - // enabling serialization functionality - void serializable() const; -}; - -}///\namespace noiseModel - -#include -class Sampler { - //Constructors - Sampler(gtsam::noiseModel::Diagonal* model, int seed); - Sampler(Vector sigmas, int seed); - Sampler(int seed); - //Sampler(const gtsam::Sampler& other); - - - //Standard Interface - size_t dim() const; - Vector sigmas() const; - gtsam::noiseModel::Diagonal* model() const; - Vector sample(); - Vector sampleNewModel(gtsam::noiseModel::Diagonal* model); -}; - -#include -class VectorValues { - //Constructors - VectorValues(); - VectorValues(const gtsam::VectorValues& other); - - //Named Constructors - static gtsam::VectorValues Zero(const gtsam::VectorValues& model); - - //Standard Interface - size_t size() const; - size_t dim(size_t j) const; - bool exists(size_t j) const; - void print(string s) const; - bool equals(const gtsam::VectorValues& expected, double tol) const; - void insert(size_t j, Vector value); - Vector vector() const; - Vector at(size_t j) const; - void update(const gtsam::VectorValues& values); - - //Advanced Interface - void setZero(); - - gtsam::VectorValues add(const gtsam::VectorValues& c) const; - void addInPlace(const gtsam::VectorValues& c); - gtsam::VectorValues subtract(const gtsam::VectorValues& c) const; - gtsam::VectorValues scale(double a) const; - void scaleInPlace(double a); - - bool hasSameStructure(const gtsam::VectorValues& other) const; - double dot(const gtsam::VectorValues& V) const; - double norm() const; - double squaredNorm() const; - - // enabling serialization functionality - void serialize() const; -}; - -#include -virtual class GaussianFactor { - gtsam::KeyVector keys() const; - void print(string s) const; - bool equals(const gtsam::GaussianFactor& lf, double tol) const; - double error(const gtsam::VectorValues& c) const; - gtsam::GaussianFactor* clone() const; - gtsam::GaussianFactor* negate() const; - Matrix augmentedInformation() const; - Matrix information() const; - Matrix augmentedJacobian() const; - pair jacobian() const; - size_t size() const; - bool empty() const; -}; - -#include -virtual class JacobianFactor : gtsam::GaussianFactor { - //Constructors - JacobianFactor(); - JacobianFactor(const gtsam::GaussianFactor& factor); - JacobianFactor(Vector b_in); - JacobianFactor(size_t i1, Matrix A1, Vector b, - const gtsam::noiseModel::Diagonal* model); - JacobianFactor(size_t i1, Matrix A1, size_t i2, Matrix A2, Vector b, - const gtsam::noiseModel::Diagonal* model); - JacobianFactor(size_t i1, Matrix A1, size_t i2, Matrix A2, size_t i3, Matrix A3, - Vector b, const gtsam::noiseModel::Diagonal* model); - //JacobianFactor(const gtsam::GaussianFactorGraph& graph); - //JacobianFactor(const gtsam::JacobianFactor& other); - - //Testable - void print(string s) const; - void printKeys(string s) const; - bool equals(const gtsam::GaussianFactor& lf, double tol) const; - size_t size() const; - Vector unweighted_error(const gtsam::VectorValues& c) const; - Vector error_vector(const gtsam::VectorValues& c) const; - double error(const gtsam::VectorValues& c) const; - - //Standard Interface - Matrix getA() const; - Vector getb() const; - size_t rows() const; - size_t cols() const; - bool isConstrained() const; - pair jacobianUnweighted() const; - Matrix augmentedJacobianUnweighted() const; - - void transposeMultiplyAdd(double alpha, const Vector& e, gtsam::VectorValues& x) const; - gtsam::JacobianFactor whiten() const; - - //pair eliminate(const gtsam::Ordering& keys) const; - - void setModel(bool anyConstrained, const Vector& sigmas); - - gtsam::noiseModel::Diagonal* get_model() const; - - // enabling serialization functionality - void serialize() const; -}; - -#include -virtual class HessianFactor : gtsam::GaussianFactor { - //Constructors - HessianFactor(); - HessianFactor(const gtsam::GaussianFactor& factor); - HessianFactor(size_t j, Matrix G, Vector g, double f); - HessianFactor(size_t j, Vector mu, Matrix Sigma); - HessianFactor(size_t j1, size_t j2, Matrix G11, Matrix G12, Vector g1, Matrix G22, - Vector g2, double f); - HessianFactor(size_t j1, size_t j2, size_t j3, Matrix G11, Matrix G12, Matrix G13, - Vector g1, Matrix G22, Matrix G23, Vector g2, Matrix G33, Vector g3, - double f); - //HessianFactor(const gtsam::GaussianFactorGraph& factors); - //HessianFactor(const gtsam::HessianFactor& other); - - //Testable - size_t size() const; - void print(string s) const; - void printKeys(string s) const; - bool equals(const gtsam::GaussianFactor& lf, double tol) const; - double error(const gtsam::VectorValues& c) const; - - //Standard Interface - size_t rows() const; - Matrix information() const; - double constantTerm() const; - Vector linearTerm() const; - - // enabling serialization functionality - void serialize() const; -}; - -#include -class Values { - Values(); - //Values(const gtsam::Values& other); - - size_t size() const; - bool empty() const; - void clear(); - size_t dim() const; - - void print(string s) const; - bool equals(const gtsam::Values& other, double tol) const; - - void insert(const gtsam::Values& values); - void update(const gtsam::Values& values); - void erase(size_t j); - void swap(gtsam::Values& values); - - bool exists(size_t j) const; - gtsam::KeyVector keys() const; - - gtsam::VectorValues zeroVectors() const; - - gtsam::Values retract(const gtsam::VectorValues& delta) const; - gtsam::VectorValues localCoordinates(const gtsam::Values& cp) const; - - // enabling serialization functionality - void serialize() const; - - // New in 4.0, we have to specialize every insert/update/at to generate wrappers - // Instead of the old: - // void insert(size_t j, const gtsam::Value& value); - // void update(size_t j, const gtsam::Value& val); - // gtsam::Value at(size_t j) const; - - // template - // void insert(size_t j, const T& t); - - // template - // void update(size_t j, const T& t); - void insert(size_t j, const gtsam::Point2& t); - void insert(size_t j, const gtsam::Point3& t); - void insert(size_t j, const gtsam::Rot2& t); - void insert(size_t j, const gtsam::Pose2& t); - void insert(size_t j, const gtsam::Rot3& t); - void insert(size_t j, const gtsam::Pose3& t); - void insert(size_t j, Vector t); - void insert(size_t j, Matrix t); - - void update(size_t j, const gtsam::Point2& t); - void update(size_t j, const gtsam::Point3& t); - void update(size_t j, const gtsam::Rot2& t); - void update(size_t j, const gtsam::Pose2& t); - void update(size_t j, const gtsam::Rot3& t); - void update(size_t j, const gtsam::Pose3& t); - void update(size_t j, Vector t); - void update(size_t j, Matrix t); - - template - T at(size_t j); - - /// version for double - void insertDouble(size_t j, double c); - double atDouble(size_t j) const; -}; - -#include -virtual class NonlinearFactor { - // Factor base class - size_t size() const; - gtsam::KeyVector keys() const; - void print(string s) const; - void printKeys(string s) const; - // NonlinearFactor - bool equals(const gtsam::NonlinearFactor& other, double tol) const; - - double error(const gtsam::Values& c) const; - size_t dim() const; - bool active(const gtsam::Values& c) const; - gtsam::GaussianFactor* linearize(const gtsam::Values& c) const; - gtsam::NonlinearFactor* clone() const; - // gtsam::NonlinearFactor* rekey(const gtsam::KeyVector& newKeys) const; //FIXME: Conversion from KeyVector to std::vector does not happen -}; - -#include -class NonlinearFactorGraph { - NonlinearFactorGraph(); - //NonlinearFactorGraph(const gtsam::NonlinearFactorGraph& graph); - - // FactorGraph - void print(string s) const; - bool equals(const gtsam::NonlinearFactorGraph& fg, double tol) const; - size_t size() const; - bool empty() const; - void remove(size_t i); - size_t nrFactors() const; - gtsam::NonlinearFactor* at(size_t idx) const; - void push_back(const gtsam::NonlinearFactorGraph& factors); - void push_back(gtsam::NonlinearFactor* factor); - void add(gtsam::NonlinearFactor* factor); - bool exists(size_t idx) const; - // gtsam::KeySet keys() const; - - // NonlinearFactorGraph - double error(const gtsam::Values& values) const; - double probPrime(const gtsam::Values& values) const; - //gtsam::Ordering orderingCOLAMD() const; - // Ordering* orderingCOLAMDConstrained(const gtsam::Values& c, const std::map& constraints) const; - //gtsam::GaussianFactorGraph* linearize(const gtsam::Values& values) const; - gtsam::NonlinearFactorGraph clone() const; - - // enabling serialization functionality - void serialize() const; -}; - -#include -virtual class NoiseModelFactor: gtsam::NonlinearFactor { - void equals(const gtsam::NoiseModelFactor& other, double tol) const; - gtsam::noiseModel::Base* get_noiseModel() const; // deprecated by below - gtsam::noiseModel::Base* noiseModel() const; - Vector unwhitenedError(const gtsam::Values& x) const; - Vector whitenedError(const gtsam::Values& x) const; -}; - -#include -template -virtual class PriorFactor : gtsam::NoiseModelFactor { - PriorFactor(size_t key, const T& prior, const gtsam::noiseModel::Base* noiseModel); - //PriorFactor(const This& other); - T prior() const; - - // enabling serialization functionality - void serialize() const; -}; - - -#include -template -virtual class BetweenFactor : gtsam::NoiseModelFactor { - BetweenFactor(size_t key1, size_t key2, const T& relativePose, const gtsam::noiseModel::Base* noiseModel); - //BetweenFactor(const This& other); - T measured() const; - - // enabling serialization functionality - void serialize() const; -}; - -#include -size_t symbol(char chr, size_t index); -char symbolChr(size_t key); -size_t symbolIndex(size_t key); - -#include -// Default keyformatter -void PrintKeyVector(const gtsam::KeyVector& keys); -void PrintKeyVector(const gtsam::KeyVector& keys, string s); - -#include -bool checkConvergence(double relativeErrorTreshold, - double absoluteErrorTreshold, double errorThreshold, - double currentError, double newError); - -#include -pair load2D(string filename, - gtsam::noiseModel::Diagonal* model, int maxID, bool addNoise, bool smart); -pair load2D(string filename, - gtsam::noiseModel::Diagonal* model, int maxID, bool addNoise); -pair load2D(string filename, - gtsam::noiseModel::Diagonal* model, int maxID); -pair load2D(string filename, - gtsam::noiseModel::Diagonal* model); -pair load2D(string filename); -pair load2D_robust(string filename, - gtsam::noiseModel::Base* model); -void save2D(const gtsam::NonlinearFactorGraph& graph, - const gtsam::Values& config, gtsam::noiseModel::Diagonal* model, - string filename); - -pair readG2o(string filename); -void writeG2o(const gtsam::NonlinearFactorGraph& graph, - const gtsam::Values& estimate, string filename); - -//************************************************************************* -// Utilities -//************************************************************************* - -namespace utilities { - - #include - // gtsam::KeyList createKeyList(Vector I); - // gtsam::KeyList createKeyList(string s, Vector I); - gtsam::KeyVector createKeyVector(Vector I); - gtsam::KeyVector createKeyVector(string s, Vector I); - // gtsam::KeySet createKeySet(Vector I); - // gtsam::KeySet createKeySet(string s, Vector I); - Matrix extractPoint2(const gtsam::Values& values); - Matrix extractPoint3(const gtsam::Values& values); - Matrix extractPose2(const gtsam::Values& values); - gtsam::Values allPose3s(gtsam::Values& values); - Matrix extractPose3(const gtsam::Values& values); - void perturbPoint2(gtsam::Values& values, double sigma, int seed); - void perturbPose2 (gtsam::Values& values, double sigmaT, double sigmaR, int seed); - void perturbPoint3(gtsam::Values& values, double sigma, int seed); - // void insertBackprojections(gtsam::Values& values, const gtsam::SimpleCamera& c, Vector J, Matrix Z, double depth); - // void insertProjectionFactors(gtsam::NonlinearFactorGraph& graph, size_t i, Vector J, Matrix Z, const gtsam::noiseModel::Base* model, const gtsam::Cal3_S2* K); - // void insertProjectionFactors(gtsam::NonlinearFactorGraph& graph, size_t i, Vector J, Matrix Z, const gtsam::noiseModel::Base* model, const gtsam::Cal3_S2* K, const gtsam::Pose3& body_P_sensor); - Matrix reprojectionErrors(const gtsam::NonlinearFactorGraph& graph, const gtsam::Values& values); - gtsam::Values localToWorld(const gtsam::Values& local, const gtsam::Pose2& base); - gtsam::Values localToWorld(const gtsam::Values& local, const gtsam::Pose2& base, const gtsam::KeyVector& keys); - -} //\namespace utilities - -#include -class RedirectCout { - RedirectCout(); - string str(); -}; - -} //\namespace gtsam diff --git a/cython/gtsam/tests/testScenarioRunner.py b/cython/gtsam/tests/testScenarioRunner.py new file mode 100644 index 000000000..97a97b0ec --- /dev/null +++ b/cython/gtsam/tests/testScenarioRunner.py @@ -0,0 +1,47 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +ScenarioRunner unit tests. +Author: Frank Dellaert & Duy Nguyen Ta (Python) +""" +import math +import unittest + +import numpy as np + +import gtsam +from gtsam.utils.test_case import GtsamTestCase + + +class TestScenarioRunner(GtsamTestCase): + def setUp(self): + self.g = 10 # simple gravity constant + + def test_loop_runner(self): + # Forward velocity 2m/s + # Pitch up with angular velocity 6 degree/sec (negative in FLU) + v = 2 + w = math.radians(6) + W = np.array([0, -w, 0]) + V = np.array([v, 0, 0]) + scenario = gtsam.ConstantTwistScenario(W, V) + + dt = 0.1 + params = gtsam.PreintegrationParams.MakeSharedU(self.g) + bias = gtsam.imuBias_ConstantBias() + runner = gtsam.ScenarioRunner( + scenario, params, dt, bias) + + # Test specific force at time 0: a is pointing up + t = 0.0 + a = w * v + np.testing.assert_almost_equal( + np.array([0, 0, a + self.g]), runner.actualSpecificForce(t)) + + +if __name__ == '__main__': + unittest.main() diff --git a/cython/gtsam/tests/test_Cal3Unified.py b/cython/gtsam/tests/test_Cal3Unified.py index 3225d2ff9..fbf5f3565 100644 --- a/cython/gtsam/tests/test_Cal3Unified.py +++ b/cython/gtsam/tests/test_Cal3Unified.py @@ -1,9 +1,22 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +Cal3Unified unit tests. +Author: Frank Dellaert & Duy Nguyen Ta (Python) +""" import unittest -import gtsam + import numpy as np +import gtsam +from gtsam.utils.test_case import GtsamTestCase -class TestCal3Unified(unittest.TestCase): + +class TestCal3Unified(GtsamTestCase): def test_Cal3Unified(self): K = gtsam.Cal3Unified() @@ -11,12 +24,15 @@ class TestCal3Unified(unittest.TestCase): self.assertEqual(K.fx(), 1.) def test_retract(self): - expected = gtsam.Cal3Unified(100 + 2, 105 + 3, 0.0 + 4, 320 + 5, 240 + 6, 1e-3 + 7, 2.0*1e-3 + 8, 3.0*1e-3 + 9, 4.0*1e-3 + 10, 0.1 + 1) - K = gtsam.Cal3Unified(100, 105, 0.0, 320, 240, 1e-3, 2.0*1e-3, 3.0*1e-3, 4.0*1e-3, 0.1) + expected = gtsam.Cal3Unified(100 + 2, 105 + 3, 0.0 + 4, 320 + 5, 240 + 6, + 1e-3 + 7, 2.0*1e-3 + 8, 3.0*1e-3 + 9, 4.0*1e-3 + 10, 0.1 + 1) + K = gtsam.Cal3Unified(100, 105, 0.0, 320, 240, + 1e-3, 2.0*1e-3, 3.0*1e-3, 4.0*1e-3, 0.1) d = np.array([2, 3, 4, 5, 6, 7, 8, 9, 10, 1], order='F') actual = K.retract(d) - self.assertTrue(actual.equals(expected, 1e-9)) + self.gtsamAssertEquals(actual, expected) np.testing.assert_allclose(d, K.localCoordinates(actual)) + if __name__ == "__main__": unittest.main() diff --git a/cython/gtsam/tests/test_JacobianFactor.py b/cython/gtsam/tests/test_JacobianFactor.py index bf63c839b..04433492b 100644 --- a/cython/gtsam/tests/test_JacobianFactor.py +++ b/cython/gtsam/tests/test_JacobianFactor.py @@ -1,8 +1,22 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +JacobianFactor unit tests. +Author: Frank Dellaert & Duy Nguyen Ta (Python) +""" import unittest -import gtsam + import numpy as np -class TestJacobianFactor(unittest.TestCase): +import gtsam +from gtsam.utils.test_case import GtsamTestCase + + +class TestJacobianFactor(GtsamTestCase): def test_eliminate(self): # Recommended way to specify a matrix (see cython/README) @@ -54,7 +68,7 @@ class TestJacobianFactor(unittest.TestCase): expectedCG = gtsam.GaussianConditional( x2, d, R11, l1, S12, x1, S13, gtsam.noiseModel_Unit.Create(2)) # check if the result matches - self.assertTrue(actualCG.equals(expectedCG, 1e-4)) + self.gtsamAssertEquals(actualCG, expectedCG, 1e-4) # the expected linear factor Bl1 = np.array([[4.47214, 0.00], @@ -72,7 +86,7 @@ class TestJacobianFactor(unittest.TestCase): expectedLF = gtsam.JacobianFactor(l1, Bl1, x1, Bx1, b1, model2) # check if the result matches the combined (reduced) factor - self.assertTrue(lf.equals(expectedLF, 1e-4)) + self.gtsamAssertEquals(lf, expectedLF, 1e-4) if __name__ == "__main__": unittest.main() diff --git a/cython/gtsam/tests/test_KalmanFilter.py b/cython/gtsam/tests/test_KalmanFilter.py index 56f9e2573..94c41df72 100644 --- a/cython/gtsam/tests/test_KalmanFilter.py +++ b/cython/gtsam/tests/test_KalmanFilter.py @@ -1,8 +1,22 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +KalmanFilter unit tests. +Author: Frank Dellaert & Duy Nguyen Ta (Python) +""" import unittest -import gtsam + import numpy as np -class TestKalmanFilter(unittest.TestCase): +import gtsam +from gtsam.utils.test_case import GtsamTestCase + + +class TestKalmanFilter(GtsamTestCase): def test_KalmanFilter(self): F = np.eye(2) diff --git a/cython/gtsam/tests/test_LocalizationExample.py b/cython/gtsam/tests/test_LocalizationExample.py index c373f162c..6ce65f087 100644 --- a/cython/gtsam/tests/test_LocalizationExample.py +++ b/cython/gtsam/tests/test_LocalizationExample.py @@ -1,8 +1,22 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +Localization unit tests. +Author: Frank Dellaert & Duy Nguyen Ta (Python) +""" import unittest -import gtsam + import numpy as np -class TestLocalizationExample(unittest.TestCase): +import gtsam +from gtsam.utils.test_case import GtsamTestCase + + +class TestLocalizationExample(GtsamTestCase): def test_LocalizationExample(self): # Create the graph (defined in pose2SLAM.h, derived from @@ -43,7 +57,7 @@ class TestLocalizationExample(unittest.TestCase): P = [None] * result.size() for i in range(0, result.size()): pose_i = result.atPose2(i) - self.assertTrue(pose_i.equals(groundTruth.atPose2(i), 1e-4)) + self.gtsamAssertEquals(pose_i, groundTruth.atPose2(i), 1e-4) P[i] = marginals.marginalCovariance(i) if __name__ == "__main__": diff --git a/cython/gtsam/tests/test_NonlinearOptimizer.py b/cython/gtsam/tests/test_NonlinearOptimizer.py new file mode 100644 index 000000000..efefb218a --- /dev/null +++ b/cython/gtsam/tests/test_NonlinearOptimizer.py @@ -0,0 +1,72 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +Unit tests for IMU testing scenarios. +Author: Frank Dellaert & Duy Nguyen Ta (Python) +""" +# pylint: disable=invalid-name, no-name-in-module + +from __future__ import print_function + +import unittest + +import gtsam +from gtsam import (DoglegOptimizer, DoglegParams, GaussNewtonOptimizer, + GaussNewtonParams, LevenbergMarquardtOptimizer, + LevenbergMarquardtParams, NonlinearFactorGraph, Ordering, + Point2, PriorFactorPoint2, Values) +from gtsam.utils.test_case import GtsamTestCase + +KEY1 = 1 +KEY2 = 2 + + +class TestScenario(GtsamTestCase): + def test_optimize(self): + """Do trivial test with three optimizer variants.""" + fg = NonlinearFactorGraph() + model = gtsam.noiseModel_Unit.Create(2) + fg.add(PriorFactorPoint2(KEY1, Point2(0, 0), model)) + + # test error at minimum + xstar = Point2(0, 0) + optimal_values = Values() + optimal_values.insert(KEY1, xstar) + self.assertEqual(0.0, fg.error(optimal_values), 0.0) + + # test error at initial = [(1-cos(3))^2 + (sin(3))^2]*50 = + x0 = Point2(3, 3) + initial_values = Values() + initial_values.insert(KEY1, x0) + self.assertEqual(9.0, fg.error(initial_values), 1e-3) + + # optimize parameters + ordering = Ordering() + ordering.push_back(KEY1) + + # Gauss-Newton + gnParams = GaussNewtonParams() + gnParams.setOrdering(ordering) + actual1 = GaussNewtonOptimizer(fg, initial_values, gnParams).optimize() + self.assertAlmostEqual(0, fg.error(actual1)) + + # Levenberg-Marquardt + lmParams = LevenbergMarquardtParams.CeresDefaults() + lmParams.setOrdering(ordering) + actual2 = LevenbergMarquardtOptimizer( + fg, initial_values, lmParams).optimize() + self.assertAlmostEqual(0, fg.error(actual2)) + + # Dogleg + dlParams = DoglegParams() + dlParams.setOrdering(ordering) + actual3 = DoglegOptimizer(fg, initial_values, dlParams).optimize() + self.assertAlmostEqual(0, fg.error(actual3)) + + +if __name__ == "__main__": + unittest.main() diff --git a/cython/gtsam/tests/test_OdometryExample.py b/cython/gtsam/tests/test_OdometryExample.py index 1100e8334..c8ea95588 100644 --- a/cython/gtsam/tests/test_OdometryExample.py +++ b/cython/gtsam/tests/test_OdometryExample.py @@ -1,8 +1,22 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +Odometry unit tests. +Author: Frank Dellaert & Duy Nguyen Ta (Python) +""" import unittest -import gtsam + import numpy as np -class TestOdometryExample(unittest.TestCase): +import gtsam +from gtsam.utils.test_case import GtsamTestCase + + +class TestOdometryExample(GtsamTestCase): def test_OdometryExample(self): # Create the graph (defined in pose2SLAM.h, derived from @@ -39,7 +53,7 @@ class TestOdometryExample(unittest.TestCase): # Check first pose equality pose_1 = result.atPose2(1) - self.assertTrue(pose_1.equals(gtsam.Pose2(), 1e-4)) + self.gtsamAssertEquals(pose_1, gtsam.Pose2(), 1e-4) if __name__ == "__main__": unittest.main() diff --git a/cython/gtsam/tests/test_PlanarSLAMExample.py b/cython/gtsam/tests/test_PlanarSLAMExample.py index 046a93f35..ae813d35c 100644 --- a/cython/gtsam/tests/test_PlanarSLAMExample.py +++ b/cython/gtsam/tests/test_PlanarSLAMExample.py @@ -1,11 +1,25 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +PlanarSLAM unit tests. +Author: Frank Dellaert & Duy Nguyen Ta (Python) +""" import unittest -import gtsam from math import pi + import numpy as np -class TestPose2SLAMExample(unittest.TestCase): +import gtsam +from gtsam.utils.test_case import GtsamTestCase - def test_Pose2SLAMExample(self): + +class TestPlanarSLAM(GtsamTestCase): + + def test_PlanarSLAM(self): # Assumptions # - All values are axis aligned # - Robot poses are facing along the X axis (horizontal, to the right in images) @@ -56,7 +70,7 @@ class TestPose2SLAMExample(unittest.TestCase): P = marginals.marginalCovariance(1) pose_1 = result.atPose2(1) - self.assertTrue(pose_1.equals(gtsam.Pose2(), 1e-4)) + self.gtsamAssertEquals(pose_1, gtsam.Pose2(), 1e-4) diff --git a/cython/gtsam/tests/test_Pose2.py b/cython/gtsam/tests/test_Pose2.py new file mode 100644 index 000000000..9652b594a --- /dev/null +++ b/cython/gtsam/tests/test_Pose2.py @@ -0,0 +1,32 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +Pose2 unit tests. +Author: Frank Dellaert & Duy Nguyen Ta (Python) +""" +import unittest + +import numpy as np + +import gtsam +from gtsam import Pose2 +from gtsam.utils.test_case import GtsamTestCase + + +class TestPose2(GtsamTestCase): + """Test selected Pose2 methods.""" + + def test_adjoint(self): + """Test adjoint method.""" + xi = np.array([1, 2, 3]) + expected = np.dot(Pose2.adjointMap_(xi), xi) + actual = Pose2.adjoint_(xi, xi) + np.testing.assert_array_equal(actual, expected) + + +if __name__ == "__main__": + unittest.main() diff --git a/cython/gtsam/tests/test_Pose2SLAMExample.py b/cython/gtsam/tests/test_Pose2SLAMExample.py index bcaa7be4f..a79b6b18c 100644 --- a/cython/gtsam/tests/test_Pose2SLAMExample.py +++ b/cython/gtsam/tests/test_Pose2SLAMExample.py @@ -1,9 +1,23 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +Pose2SLAM unit tests. +Author: Frank Dellaert & Duy Nguyen Ta (Python) +""" import unittest -import gtsam from math import pi + import numpy as np -class TestPose2SLAMExample(unittest.TestCase): +import gtsam +from gtsam.utils.test_case import GtsamTestCase + + +class TestPose2SLAMExample(GtsamTestCase): def test_Pose2SLAMExample(self): # Assumptions @@ -56,7 +70,7 @@ class TestPose2SLAMExample(unittest.TestCase): P = marginals.marginalCovariance(1) pose_1 = result.atPose2(1) - self.assertTrue(pose_1.equals(gtsam.Pose2(), 1e-4)) + self.gtsamAssertEquals(pose_1, gtsam.Pose2(), 1e-4) if __name__ == "__main__": unittest.main() diff --git a/cython/gtsam/tests/test_Pose3.py b/cython/gtsam/tests/test_Pose3.py index 4752a4b02..577a13304 100644 --- a/cython/gtsam/tests/test_Pose3.py +++ b/cython/gtsam/tests/test_Pose3.py @@ -1,13 +1,24 @@ -"""Pose3 unit tests.""" +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +Pose3 unit tests. +Author: Frank Dellaert & Duy Nguyen Ta (Python) +""" import math import unittest import numpy as np +import gtsam from gtsam import Point3, Pose3, Rot3 +from gtsam.utils.test_case import GtsamTestCase -class TestPose3(unittest.TestCase): +class TestPose3(GtsamTestCase): """Test selected Pose3 methods.""" def test_between(self): @@ -16,14 +27,14 @@ class TestPose3(unittest.TestCase): T3 = Pose3(Rot3.Rodrigues(-90, 0, 0), Point3(1, 2, 3)) expected = T2.inverse().compose(T3) actual = T2.between(T3) - self.assertTrue(actual.equals(expected, 1e-6)) + self.gtsamAssertEquals(actual, expected, 1e-6) def test_transform_to(self): - """Test transform_to method.""" + """Test transformTo method.""" transform = Pose3(Rot3.Rodrigues(0, 0, -1.570796), Point3(2, 4, 0)) - actual = transform.transform_to(Point3(3, 2, 10)) + actual = transform.transformTo(Point3(3, 2, 10)) expected = Point3(2, 1, 10) - self.assertTrue(actual.equals(expected, 1e-6)) + self.gtsamAssertEquals(actual, expected, 1e-6) def test_range(self): """Test range method.""" @@ -49,8 +60,8 @@ class TestPose3(unittest.TestCase): def test_adjoint(self): """Test adjoint method.""" xi = np.array([1, 2, 3, 4, 5, 6]) - expected = np.dot(Pose3.adjointMap(xi), xi) - actual = Pose3.adjoint(xi, xi) + expected = np.dot(Pose3.adjointMap_(xi), xi) + actual = Pose3.adjoint_(xi, xi) np.testing.assert_array_equal(actual, expected) diff --git a/cython/gtsam/tests/test_Pose3SLAMExample.py b/cython/gtsam/tests/test_Pose3SLAMExample.py index e33db2145..1e9eaac67 100644 --- a/cython/gtsam/tests/test_Pose3SLAMExample.py +++ b/cython/gtsam/tests/test_Pose3SLAMExample.py @@ -1,10 +1,24 @@ -import unittest -import numpy as np -import gtsam -from math import pi -from gtsam.utils.circlePose3 import * +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved -class TestPose3SLAMExample(unittest.TestCase): +See LICENSE for the license information + +PoseSLAM unit tests. +Author: Frank Dellaert & Duy Nguyen Ta (Python) +""" +import unittest +from math import pi + +import numpy as np + +import gtsam +from gtsam.utils.test_case import GtsamTestCase +from gtsam.utils.circlePose3 import * + + +class TestPose3SLAMExample(GtsamTestCase): def test_Pose3SLAMExample(self): # Create a hexagon of poses @@ -40,7 +54,7 @@ class TestPose3SLAMExample(unittest.TestCase): result = optimizer.optimizeSafely() pose_1 = result.atPose3(1) - self.assertTrue(pose_1.equals(p1, 1e-4)) + self.gtsamAssertEquals(pose_1, p1, 1e-4) if __name__ == "__main__": unittest.main() diff --git a/cython/gtsam/tests/test_PriorFactor.py b/cython/gtsam/tests/test_PriorFactor.py index 95ec2ae94..0acf50c2c 100644 --- a/cython/gtsam/tests/test_PriorFactor.py +++ b/cython/gtsam/tests/test_PriorFactor.py @@ -1,8 +1,22 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +PriorFactor unit tests. +Author: Frank Dellaert & Duy Nguyen Ta (Python) +""" import unittest -import gtsam + import numpy as np -class TestPriorFactor(unittest.TestCase): +import gtsam +from gtsam.utils.test_case import GtsamTestCase + + +class TestPriorFactor(GtsamTestCase): def test_PriorFactor(self): values = gtsam.Values() diff --git a/cython/gtsam/tests/test_SFMExample.py b/cython/gtsam/tests/test_SFMExample.py index 606b26a43..e8fa46186 100644 --- a/cython/gtsam/tests/test_SFMExample.py +++ b/cython/gtsam/tests/test_SFMExample.py @@ -1,11 +1,24 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +SFM unit tests. +Author: Frank Dellaert & Duy Nguyen Ta (Python) +""" import unittest -import gtsam -from gtsam import symbol + import numpy as np + +import gtsam import gtsam.utils.visual_data_generator as generator +from gtsam import symbol +from gtsam.utils.test_case import GtsamTestCase -class TestSFMExample(unittest.TestCase): +class TestSFMExample(GtsamTestCase): def test_SFMExample(self): options = generator.Options() @@ -59,11 +72,11 @@ class TestSFMExample(unittest.TestCase): # Check optimized results, should be equal to ground truth for i in range(len(truth.cameras)): pose_i = result.atPose3(symbol(ord('x'), i)) - self.assertTrue(pose_i.equals(truth.cameras[i].pose(), 1e-5)) + self.gtsamAssertEquals(pose_i, truth.cameras[i].pose(), 1e-5) for j in range(len(truth.points)): point_j = result.atPoint3(symbol(ord('p'), j)) - self.assertTrue(point_j.equals(truth.points[j], 1e-5)) + self.gtsamAssertEquals(point_j, truth.points[j], 1e-5) if __name__ == "__main__": unittest.main() diff --git a/cython/gtsam/tests/test_Scenario.py b/cython/gtsam/tests/test_Scenario.py index 4cca1400b..09601fba5 100644 --- a/cython/gtsam/tests/test_Scenario.py +++ b/cython/gtsam/tests/test_Scenario.py @@ -1,11 +1,27 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +Scenario unit tests. +Author: Frank Dellaert & Duy Nguyen Ta (Python) +""" +from __future__ import print_function + import math import unittest + import numpy as np import gtsam +from gtsam.utils.test_case import GtsamTestCase + +# pylint: disable=invalid-name, E1101 -class TestScenario(unittest.TestCase): +class TestScenario(GtsamTestCase): def setUp(self): pass @@ -29,7 +45,8 @@ class TestScenario(unittest.TestCase): T30 = scenario.pose(T) np.testing.assert_almost_equal( np.array([math.pi, 0, math.pi]), T30.rotation().xyz()) - self.assert_(gtsam.Point3(0, 0, 2 * R).equals(T30.translation(), 1e-9)) + self.gtsamAssertEquals(gtsam.Point3( + 0, 0, 2.0 * R), T30.translation(), 1e-9) if __name__ == '__main__': diff --git a/cython/gtsam/tests/test_SimpleCamera.py b/cython/gtsam/tests/test_SimpleCamera.py index 7924a9b1c..efdfec561 100644 --- a/cython/gtsam/tests/test_SimpleCamera.py +++ b/cython/gtsam/tests/test_SimpleCamera.py @@ -1,18 +1,31 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +SimpleCamera unit tests. +Author: Frank Dellaert & Duy Nguyen Ta (Python) +""" import math -import numpy as np import unittest -from gtsam import Pose2, Point3, Rot3, Pose3, Cal3_S2, SimpleCamera +import numpy as np + +import gtsam +from gtsam import Cal3_S2, Point3, Pose2, Pose3, Rot3, SimpleCamera +from gtsam.utils.test_case import GtsamTestCase K = Cal3_S2(625, 625, 0, 0, 0) -class TestSimpleCamera(unittest.TestCase): +class TestSimpleCamera(GtsamTestCase): def test_constructor(self): pose1 = Pose3(Rot3(np.diag([1, -1, -1])), Point3(0, 0, 0.5)) camera = SimpleCamera(pose1, K) - self.assertTrue(camera.calibration().equals(K, 1e-9)) - self.assertTrue(camera.pose().equals(pose1, 1e-9)) + self.gtsamAssertEquals(camera.calibration(), K, 1e-9) + self.gtsamAssertEquals(camera.pose(), pose1, 1e-9) def test_level2(self): # Create a level camera, looking in Y-direction @@ -25,7 +38,7 @@ class TestSimpleCamera(unittest.TestCase): z = Point3(0,1,0) wRc = Rot3(x,y,z) expected = Pose3(wRc,Point3(0.4,0.3,0.1)) - self.assertTrue(camera.pose().equals(expected, 1e-9)) + self.gtsamAssertEquals(camera.pose(), expected, 1e-9) if __name__ == "__main__": diff --git a/cython/gtsam/tests/test_StereoVOExample.py b/cython/gtsam/tests/test_StereoVOExample.py index dacd4a116..3f5f57522 100644 --- a/cython/gtsam/tests/test_StereoVOExample.py +++ b/cython/gtsam/tests/test_StereoVOExample.py @@ -1,10 +1,23 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +Stereo VO unit tests. +Author: Frank Dellaert & Duy Nguyen Ta (Python) +""" import unittest -import gtsam -from gtsam import symbol + import numpy as np +import gtsam +from gtsam import symbol +from gtsam.utils.test_case import GtsamTestCase -class TestStereoVOExample(unittest.TestCase): + +class TestStereoVOExample(GtsamTestCase): def test_StereoVOExample(self): ## Assumptions @@ -60,10 +73,10 @@ class TestStereoVOExample(unittest.TestCase): ## check equality for the first pose and point pose_x1 = result.atPose3(x1) - self.assertTrue(pose_x1.equals(first_pose,1e-4)) + self.gtsamAssertEquals(pose_x1, first_pose,1e-4) point_l1 = result.atPoint3(l1) - self.assertTrue(point_l1.equals(expected_l1,1e-4)) + self.gtsamAssertEquals(point_l1, expected_l1,1e-4) if __name__ == "__main__": unittest.main() diff --git a/cython/gtsam/tests/test_Values.py b/cython/gtsam/tests/test_Values.py index 08e133840..20634a21c 100644 --- a/cython/gtsam/tests/test_Values.py +++ b/cython/gtsam/tests/test_Values.py @@ -1,19 +1,34 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +Values unit tests. +Author: Frank Dellaert & Duy Nguyen Ta (Python) +""" +# pylint: disable=invalid-name, E1101, E0611 import unittest + import numpy as np -from gtsam import Point2, Point3, Unit3, Rot2, Pose2, Rot3, Pose3 -from gtsam import Values, Cal3_S2, Cal3DS2, Cal3Bundler, EssentialMatrix, imuBias_ConstantBias +import gtsam +from gtsam import (Cal3_S2, Cal3Bundler, Cal3DS2, EssentialMatrix, Point2, + Point3, Pose2, Pose3, Rot2, Rot3, Unit3, Values, + imuBias_ConstantBias) +from gtsam.utils.test_case import GtsamTestCase -class TestValues(unittest.TestCase): +class TestValues(GtsamTestCase): def test_values(self): values = Values() E = EssentialMatrix(Rot3(), Unit3()) tol = 1e-9 - values.insert(0, Point2(0,0)) - values.insert(1, Point3(0,0,0)) + values.insert(0, Point2(0, 0)) + values.insert(1, Point3(0, 0, 0)) values.insert(2, Rot2()) values.insert(3, Pose2()) values.insert(4, Rot3()) @@ -34,36 +49,38 @@ class TestValues(unittest.TestCase): # The wrapper will automatically fix the type and storage order for you, # but for performance reasons, it's recommended to specify the correct # type and storage order. - vec = np.array([1., 2., 3.]) # for vectors, the order is not important, but dtype still is + # for vectors, the order is not important, but dtype still is + vec = np.array([1., 2., 3.]) values.insert(11, vec) mat = np.array([[1., 2.], [3., 4.]], order='F') values.insert(12, mat) # Test with dtype int and the default order='C' # This still works as the wrapper converts to the correct type and order for you # but is nornally not recommended! - mat2 = np.array([[1,2,],[3,5]]) + mat2 = np.array([[1, 2, ], [3, 5]]) values.insert(13, mat2) - self.assertTrue(values.atPoint2(0).equals(Point2(), tol)) - self.assertTrue(values.atPoint3(1).equals(Point3(), tol)) - self.assertTrue(values.atRot2(2).equals(Rot2(), tol)) - self.assertTrue(values.atPose2(3).equals(Pose2(), tol)) - self.assertTrue(values.atRot3(4).equals(Rot3(), tol)) - self.assertTrue(values.atPose3(5).equals(Pose3(), tol)) - self.assertTrue(values.atCal3_S2(6).equals(Cal3_S2(), tol)) - self.assertTrue(values.atCal3DS2(7).equals(Cal3DS2(), tol)) - self.assertTrue(values.atCal3Bundler(8).equals(Cal3Bundler(), tol)) - self.assertTrue(values.atEssentialMatrix(9).equals(E, tol)) - self.assertTrue(values.atimuBias_ConstantBias( - 10).equals(imuBias_ConstantBias(), tol)) + self.gtsamAssertEquals(values.atPoint2(0), Point2(0,0), tol) + self.gtsamAssertEquals(values.atPoint3(1), Point3(0,0,0), tol) + self.gtsamAssertEquals(values.atRot2(2), Rot2(), tol) + self.gtsamAssertEquals(values.atPose2(3), Pose2(), tol) + self.gtsamAssertEquals(values.atRot3(4), Rot3(), tol) + self.gtsamAssertEquals(values.atPose3(5), Pose3(), tol) + self.gtsamAssertEquals(values.atCal3_S2(6), Cal3_S2(), tol) + self.gtsamAssertEquals(values.atCal3DS2(7), Cal3DS2(), tol) + self.gtsamAssertEquals(values.atCal3Bundler(8), Cal3Bundler(), tol) + self.gtsamAssertEquals(values.atEssentialMatrix(9), E, tol) + self.gtsamAssertEquals(values.atimuBias_ConstantBias( + 10), imuBias_ConstantBias(), tol) # special cases for Vector and Matrix: actualVector = values.atVector(11) - self.assertTrue(np.allclose(vec, actualVector, tol)) + np.testing.assert_allclose(vec, actualVector, tol) actualMatrix = values.atMatrix(12) - self.assertTrue(np.allclose(mat, actualMatrix, tol)) + np.testing.assert_allclose(mat, actualMatrix, tol) actualMatrix2 = values.atMatrix(13) - self.assertTrue(np.allclose(mat2, actualMatrix2, tol)) + np.testing.assert_allclose(mat2, actualMatrix2, tol) + if __name__ == "__main__": unittest.main() diff --git a/cython/gtsam/tests/test_VisualISAMExample.py b/cython/gtsam/tests/test_VisualISAMExample.py index 39bfa6eb4..99d7e6160 100644 --- a/cython/gtsam/tests/test_VisualISAMExample.py +++ b/cython/gtsam/tests/test_VisualISAMExample.py @@ -1,10 +1,25 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +visual_isam unit tests. +Author: Frank Dellaert & Duy Nguyen Ta (Python) +""" import unittest + import numpy as np -from gtsam import symbol + +import gtsam import gtsam.utils.visual_data_generator as generator import gtsam.utils.visual_isam as visual_isam +from gtsam import symbol +from gtsam.utils.test_case import GtsamTestCase -class TestVisualISAMExample(unittest.TestCase): + +class TestVisualISAMExample(GtsamTestCase): def test_VisualISAMExample(self): # Data Options @@ -32,11 +47,11 @@ class TestVisualISAMExample(unittest.TestCase): for i in range(len(truth.cameras)): pose_i = result.atPose3(symbol(ord('x'), i)) - self.assertTrue(pose_i.equals(truth.cameras[i].pose(), 1e-5)) + self.gtsamAssertEquals(pose_i, truth.cameras[i].pose(), 1e-5) for j in range(len(truth.points)): point_j = result.atPoint3(symbol(ord('l'), j)) - self.assertTrue(point_j.equals(truth.points[j], 1e-5)) + self.gtsamAssertEquals(point_j, truth.points[j], 1e-5) if __name__ == "__main__": unittest.main() diff --git a/cython/gtsam/tests/test_dataset.py b/cython/gtsam/tests/test_dataset.py new file mode 100644 index 000000000..60fb9450d --- /dev/null +++ b/cython/gtsam/tests/test_dataset.py @@ -0,0 +1,45 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +Unit tests for testing dataset access. +Author: Frank Dellaert & Duy Nguyen Ta (Python) +""" +# pylint: disable=invalid-name, no-name-in-module, no-member + +from __future__ import print_function + +import unittest + +import gtsam +from gtsam import BetweenFactorPose3, BetweenFactorPose3s +from gtsam.utils.test_case import GtsamTestCase + + +class TestDataset(GtsamTestCase): + """Tests for datasets.h wrapper.""" + + def setUp(self): + """Get some common paths.""" + self.pose3_example_g2o_file = gtsam.findExampleDataFile( + "pose3example.txt") + + def test_readG2o3D(self): + """Test reading directly into factor graph.""" + is3D = True + graph, initial = gtsam.readG2o(self.pose3_example_g2o_file, is3D) + self.assertEqual(graph.size(), 6) + self.assertEqual(initial.size(), 5) + + def test_parse3Dfactors(self): + """Test parsing into data structure.""" + factors = gtsam.parse3DFactors(self.pose3_example_g2o_file) + self.assertEqual(factors.size(), 6) + self.assertIsInstance(factors.at(0), BetweenFactorPose3) + + +if __name__ == '__main__': + unittest.main() diff --git a/cython/gtsam/tests/test_dsf_map.py b/cython/gtsam/tests/test_dsf_map.py new file mode 100644 index 000000000..6eb551034 --- /dev/null +++ b/cython/gtsam/tests/test_dsf_map.py @@ -0,0 +1,38 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +Unit tests for Disjoint Set Forest. +Author: Frank Dellaert & Varun Agrawal +""" +# pylint: disable=invalid-name, no-name-in-module, no-member + +from __future__ import print_function + +import unittest + +import gtsam +from gtsam.utils.test_case import GtsamTestCase + + +class TestDSFMap(GtsamTestCase): + """Tests for DSFMap.""" + + def test_all(self): + """Test everything in DFSMap.""" + def key(index_pair): + return index_pair.i(), index_pair.j() + + dsf = gtsam.DSFMapIndexPair() + pair1 = gtsam.IndexPair(1, 18) + self.assertEqual(key(dsf.find(pair1)), key(pair1)) + pair2 = gtsam.IndexPair(2, 2) + dsf.merge(pair1, pair2) + self.assertTrue(dsf.find(pair1), dsf.find(pair1)) + + +if __name__ == '__main__': + unittest.main() diff --git a/cython/gtsam/tests/test_initialize_pose3.py b/cython/gtsam/tests/test_initialize_pose3.py new file mode 100644 index 000000000..3aa7e3470 --- /dev/null +++ b/cython/gtsam/tests/test_initialize_pose3.py @@ -0,0 +1,89 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +Unit tests for 3D SLAM initialization, using rotation relaxation. +Author: Luca Carlone and Frank Dellaert (Python) +""" +# pylint: disable=invalid-name, E1101, E0611 +import unittest + +import numpy as np + +import gtsam +from gtsam import NonlinearFactorGraph, Point3, Pose3, Rot3, Values +from gtsam.utils.test_case import GtsamTestCase + +x0, x1, x2, x3 = 0, 1, 2, 3 + + +class TestValues(GtsamTestCase): + + def setUp(self): + + model = gtsam.noiseModel_Isotropic.Sigma(6, 0.1) + + # We consider a small graph: + # symbolic FG + # x2 0 1 + # / | \ 1 2 + # / | \ 2 3 + # x3 | x1 2 0 + # \ | / 0 3 + # \ | / + # x0 + # + p0 = Point3(0, 0, 0) + self.R0 = Rot3.Expmap(np.array([0.0, 0.0, 0.0])) + p1 = Point3(1, 2, 0) + self.R1 = Rot3.Expmap(np.array([0.0, 0.0, 1.570796])) + p2 = Point3(0, 2, 0) + self.R2 = Rot3.Expmap(np.array([0.0, 0.0, 3.141593])) + p3 = Point3(-1, 1, 0) + self.R3 = Rot3.Expmap(np.array([0.0, 0.0, 4.712389])) + + pose0 = Pose3(self.R0, p0) + pose1 = Pose3(self.R1, p1) + pose2 = Pose3(self.R2, p2) + pose3 = Pose3(self.R3, p3) + + g = NonlinearFactorGraph() + g.add(gtsam.BetweenFactorPose3(x0, x1, pose0.between(pose1), model)) + g.add(gtsam.BetweenFactorPose3(x1, x2, pose1.between(pose2), model)) + g.add(gtsam.BetweenFactorPose3(x2, x3, pose2.between(pose3), model)) + g.add(gtsam.BetweenFactorPose3(x2, x0, pose2.between(pose0), model)) + g.add(gtsam.BetweenFactorPose3(x0, x3, pose0.between(pose3), model)) + g.add(gtsam.PriorFactorPose3(x0, pose0, model)) + self.graph = g + + def test_buildPose3graph(self): + pose3graph = gtsam.InitializePose3.buildPose3graph(self.graph) + + def test_orientations(self): + pose3Graph = gtsam.InitializePose3.buildPose3graph(self.graph) + + initial = gtsam.InitializePose3.computeOrientationsChordal(pose3Graph) + + # comparison is up to M_PI, that's why we add some multiples of 2*M_PI + self.gtsamAssertEquals(initial.atRot3(x0), self.R0, 1e-6) + self.gtsamAssertEquals(initial.atRot3(x1), self.R1, 1e-6) + self.gtsamAssertEquals(initial.atRot3(x2), self.R2, 1e-6) + self.gtsamAssertEquals(initial.atRot3(x3), self.R3, 1e-6) + + def test_initializePoses(self): + g2oFile = gtsam.findExampleDataFile("pose3example-grid") + is3D = True + inputGraph, expectedValues = gtsam.readG2o(g2oFile, is3D) + priorModel = gtsam.noiseModel_Unit.Create(6) + inputGraph.add(gtsam.PriorFactorPose3(0, Pose3(), priorModel)) + + initial = gtsam.InitializePose3.initialize(inputGraph) + # TODO(frank): very loose !! + self.gtsamAssertEquals(initial, expectedValues, 0.1) + + +if __name__ == "__main__": + unittest.main() diff --git a/cython/gtsam/utils/plot.py b/cython/gtsam/utils/plot.py index 19402a080..3871fa18c 100644 --- a/cython/gtsam/utils/plot.py +++ b/cython/gtsam/utils/plot.py @@ -2,9 +2,10 @@ import numpy as np import matplotlib.pyplot as plt +from matplotlib import patches -def plot_pose2_on_axes(axes, pose, axis_length=0.1): +def plot_pose2_on_axes(axes, pose, axis_length=0.1, covariance=None): """Plot a 2D pose on given axis 'axes' with given 'axis_length'.""" # get rotation and translation (center) gRp = pose.rotation().matrix() # rotation from pose to global @@ -20,13 +21,26 @@ def plot_pose2_on_axes(axes, pose, axis_length=0.1): line = np.append(origin[np.newaxis], y_axis[np.newaxis], axis=0) axes.plot(line[:, 0], line[:, 1], 'g-') + if covariance is not None: + pPp = covariance[0:2, 0:2] + gPp = np.matmul(np.matmul(gRp, pPp), gRp.T) -def plot_pose2(fignum, pose, axis_length=0.1): + w, v = np.linalg.eig(gPp) + + # k = 2.296 + k = 5.0 + + angle = np.arctan2(v[1, 0], v[0, 0]) + e1 = patches.Ellipse(origin, np.sqrt(w[0]*k), np.sqrt(w[1]*k), + np.rad2deg(angle), fill=False) + axes.add_patch(e1) + +def plot_pose2(fignum, pose, axis_length=0.1, covariance=None): """Plot a 2D pose on given figure with given 'axis_length'.""" # get figure object fig = plt.figure(fignum) axes = fig.gca() - plot_pose2_on_axes(axes, pose, axis_length) + plot_pose2_on_axes(axes, pose, axis_length, covariance) def plot_point3_on_axes(axes, point, linespec): diff --git a/cython/gtsam/utils/test_case.py b/cython/gtsam/utils/test_case.py new file mode 100644 index 000000000..7df1e6ee9 --- /dev/null +++ b/cython/gtsam/utils/test_case.py @@ -0,0 +1,27 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +TestCase class with GTSAM assert utils. +Author: Frank Dellaert +""" +import unittest + + +class GtsamTestCase(unittest.TestCase): + """TestCase class with GTSAM assert utils.""" + + def gtsamAssertEquals(self, actual, expected, tol=1e-9): + """ AssertEqual function that prints out actual and expected if not equal. + Usage: + self.gtsamAssertEqual(actual,expected) + Keyword Arguments: + tol {float} -- tolerance passed to 'equals', default 1e-9 + """ + equal = actual.equals(expected, tol) + if not equal: + raise self.failureException( + "Values are not equal:\n{}!={}".format(actual, expected)) diff --git a/cython/gtsam_eigency/CMakeLists.txt b/cython/gtsam_eigency/CMakeLists.txt index 54b7de9aa..77bead834 100644 --- a/cython/gtsam_eigency/CMakeLists.txt +++ b/cython/gtsam_eigency/CMakeLists.txt @@ -22,17 +22,28 @@ cythonize(cythonize_eigency_conversions "../gtsam_eigency/conversions.pyx" "conv "${OUTPUT_DIR}" "${EIGENCY_INCLUDE_DIR}" "" "" "") cythonize(cythonize_eigency_core "../gtsam_eigency/core.pyx" "core" ${OUTPUT_DIR} "${EIGENCY_INCLUDE_DIR}" "" "" "") + +# Include Eigen headers: +target_include_directories(cythonize_eigency_conversions PUBLIC + $ + $ +) +target_include_directories(cythonize_eigency_core PUBLIC + $ + $ +) + add_dependencies(cythonize_eigency_core cythonize_eigency_conversions) add_custom_target(cythonize_eigency) add_dependencies(cythonize_eigency cythonize_eigency_conversions cythonize_eigency_core) # install install(DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR} - DESTINATION ${GTSAM_CYTHON_INSTALL_PATH} + DESTINATION "${GTSAM_CYTHON_INSTALL_PATH}${GTSAM_BUILD_TAG}" PATTERN "CMakeLists.txt" EXCLUDE PATTERN "__init__.py.in" EXCLUDE) install(TARGETS cythonize_eigency_core cythonize_eigency_conversions - DESTINATION "${GTSAM_CYTHON_INSTALL_PATH}/gtsam_eigency") -install(FILES ${OUTPUT_DIR}/conversions_api.h DESTINATION ${GTSAM_CYTHON_INSTALL_PATH}/gtsam_eigency) + DESTINATION "${GTSAM_CYTHON_INSTALL_PATH}${GTSAM_BUILD_TAG}/gtsam_eigency") +install(FILES ${OUTPUT_DIR}/conversions_api.h DESTINATION ${GTSAM_CYTHON_INSTALL_PATH}${GTSAM_BUILD_TAG}/gtsam_eigency) configure_file(__init__.py.in ${OUTPUT_DIR}/__init__.py) -install(FILES ${OUTPUT_DIR}/__init__.py DESTINATION ${GTSAM_CYTHON_INSTALL_PATH}/gtsam_eigency) +install(FILES ${OUTPUT_DIR}/__init__.py DESTINATION ${GTSAM_CYTHON_INSTALL_PATH}${GTSAM_BUILD_TAG}/gtsam_eigency) diff --git a/cython/gtsam_eigency/__init__.py.in b/cython/gtsam_eigency/__init__.py.in index dd278d128..a59d51eab 100644 --- a/cython/gtsam_eigency/__init__.py.in +++ b/cython/gtsam_eigency/__init__.py.in @@ -1,7 +1,7 @@ import os import numpy as np -__eigen_dir__ = "${GTSAM_EIGEN_INCLUDE_PREFIX}" +__eigen_dir__ = "${GTSAM_EIGEN_INCLUDE_FOR_INSTALL}" def get_includes(include_eigen=True): root = os.path.dirname(__file__) diff --git a/cython/gtsam_eigency/eigency_cpp.h b/cython/gtsam_eigency/eigency_cpp.h index 923ca7c94..ce303182e 100644 --- a/cython/gtsam_eigency/eigency_cpp.h +++ b/cython/gtsam_eigency/eigency_cpp.h @@ -35,7 +35,7 @@ inline PyArrayObject *_ndarray_view(double *data, long rows, long cols, return ndarray_double_C(data, rows, cols, outer_stride>0?outer_stride:cols, inner_stride>0?inner_stride:1); } else { // Eigen column-major mode: row_stride=outer_stride, and col_stride=inner_stride - // If no stride is given, the cow_stride is set to the number of rows. + // If no stride is given, the cow_stride is set to the number of rows. return ndarray_double_F(data, rows, cols, inner_stride>0?inner_stride:1, outer_stride>0?outer_stride:rows); } } @@ -355,7 +355,7 @@ public: FlattenedMap() : Base(NULL, 0, 0), object_(NULL) {} - + FlattenedMap(Scalar *data, long rows, long cols, long outer_stride=0, long inner_stride=0) : Base(data, rows, cols, Eigen::Stride<_StrideOuter, _StrideInner>(outer_stride, inner_stride)), @@ -363,7 +363,7 @@ public: } FlattenedMap(PyArrayObject *object) - : Base((Scalar *)((PyArrayObject*)object)->data, + : Base((Scalar *)((PyArrayObject*)object)->data, // : Base(_from_numpy((PyArrayObject*)object), (((PyArrayObject*)object)->nd == 2) ? ((PyArrayObject*)object)->dimensions[0] : 1, (((PyArrayObject*)object)->nd == 2) ? ((PyArrayObject*)object)->dimensions[1] : ((PyArrayObject*)object)->dimensions[0], @@ -390,7 +390,7 @@ public: return *this; } - + operator Base() const { return static_cast(*this); } @@ -429,7 +429,7 @@ public: (ColsAtCompileTime == Eigen::Dynamic) ? 0 : ColsAtCompileTime), object_(NULL) { } - + Map(Scalar *data, long rows, long cols) : Base(data, rows, cols), object_(NULL) {} @@ -456,7 +456,7 @@ public: throw std::invalid_argument("Numpy array must be a in one contiguous segment to be able to be transferred to a Eigen Map."); Py_XINCREF(object_); } - + Map &operator=(const Map &other) { if (other.object_) { new (this) Map(other.object_); @@ -474,7 +474,7 @@ public: MapBase::operator=(other); return *this; } - + operator Base() const { return static_cast(*this); } diff --git a/cython/gtsam_unstable/__init__.py b/cython/gtsam_unstable/__init__.py new file mode 100644 index 000000000..3195e6da4 --- /dev/null +++ b/cython/gtsam_unstable/__init__.py @@ -0,0 +1 @@ +from .gtsam_unstable import * diff --git a/cython/gtsam_unstable/examples/FixedLagSmootherExample.py b/cython/gtsam_unstable/examples/FixedLagSmootherExample.py new file mode 100644 index 000000000..786701e0f --- /dev/null +++ b/cython/gtsam_unstable/examples/FixedLagSmootherExample.py @@ -0,0 +1,102 @@ +""" +GTSAM Copyright 2010-2018, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved +Authors: Frank Dellaert, et al. (see THANKS for the full author list) + +See LICENSE for the license information + +Demonstration of the fixed-lag smoothers using a planar robot example +and multiple odometry-like sensors +Author: Frank Dellaert (C++), Jeremy Aguilon (Python) +""" + +import numpy as np + +import gtsam +import gtsam_unstable + + +def _timestamp_key_value(key, value): + """ + + """ + return gtsam_unstable.FixedLagSmootherKeyTimestampMapValue( + key, value + ) + + +def BatchFixedLagSmootherExample(): + """ + Runs a batch fixed smoother on an agent with two odometry + sensors that is simply moving to the + """ + + # Define a batch fixed lag smoother, which uses + # Levenberg-Marquardt to perform the nonlinear optimization + lag = 2.0 + smoother_batch = gtsam_unstable.BatchFixedLagSmoother(lag) + + # Create containers to store the factors and linearization points + # that will be sent to the smoothers + new_factors = gtsam.NonlinearFactorGraph() + new_values = gtsam.Values() + new_timestamps = gtsam_unstable.FixedLagSmootherKeyTimestampMap() + + # Create a prior on the first pose, placing it at the origin + prior_mean = gtsam.Pose2(0, 0, 0) + prior_noise = gtsam.noiseModel_Diagonal.Sigmas(np.array([0.3, 0.3, 0.1])) + X1 = 0 + new_factors.push_back(gtsam.PriorFactorPose2(X1, prior_mean, prior_noise)) + new_values.insert(X1, prior_mean) + new_timestamps.insert(_timestamp_key_value(X1, 0.0)) + + delta_time = 0.25 + time = 0.25 + + while time <= 3.0: + previous_key = 1000 * (time - delta_time) + current_key = 1000 * time + + # assign current key to the current timestamp + new_timestamps.insert(_timestamp_key_value(current_key, time)) + + # Add a guess for this pose to the new values + # Assume that the robot moves at 2 m/s. Position is time[s] * 2[m/s] + current_pose = gtsam.Pose2(time * 2, 0, 0) + new_values.insert(current_key, current_pose) + + # Add odometry factors from two different sources with different error + # stats + odometry_measurement_1 = gtsam.Pose2(0.61, -0.08, 0.02) + odometry_noise_1 = gtsam.noiseModel_Diagonal.Sigmas( + np.array([0.1, 0.1, 0.05])) + new_factors.push_back(gtsam.BetweenFactorPose2( + previous_key, current_key, odometry_measurement_1, odometry_noise_1 + )) + + odometry_measurement_2 = gtsam.Pose2(0.47, 0.03, 0.01) + odometry_noise_2 = gtsam.noiseModel_Diagonal.Sigmas( + np.array([0.05, 0.05, 0.05])) + new_factors.push_back(gtsam.BetweenFactorPose2( + previous_key, current_key, odometry_measurement_2, odometry_noise_2 + )) + + # Update the smoothers with the new factors. In this case, + # one iteration must pass for Levenberg-Marquardt to accurately + # estimate + if time >= 0.50: + smoother_batch.update(new_factors, new_values, new_timestamps) + print("Timestamp = " + str(time) + ", Key = " + str(current_key)) + print(smoother_batch.calculateEstimatePose2(current_key)) + + new_timestamps.clear() + new_values.clear() + new_factors.resize(0) + + time += delta_time + + +if __name__ == '__main__': + BatchFixedLagSmootherExample() + print("Example complete") diff --git a/cython/gtsam_unstable/examples/__init__.py b/cython/gtsam_unstable/examples/__init__.py new file mode 100644 index 000000000..e69de29bb diff --git a/cython/gtsam_unstable/tests/__init__.py b/cython/gtsam_unstable/tests/__init__.py new file mode 100644 index 000000000..e69de29bb diff --git a/cython/gtsam_unstable/tests/test_FixedLagSmootherExample.py b/cython/gtsam_unstable/tests/test_FixedLagSmootherExample.py new file mode 100644 index 000000000..8d3af311f --- /dev/null +++ b/cython/gtsam_unstable/tests/test_FixedLagSmootherExample.py @@ -0,0 +1,135 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +Cal3Unified unit tests. +Author: Frank Dellaert & Duy Nguyen Ta (Python) +""" +import unittest + +import numpy as np + +import gtsam +import gtsam_unstable +from gtsam.utils.test_case import GtsamTestCase + + +def _timestamp_key_value(key, value): + return gtsam_unstable.FixedLagSmootherKeyTimestampMapValue( + key, value + ) + + +class TestFixedLagSmootherExample(GtsamTestCase): + ''' + Tests the fixed lag smoother wrapper + ''' + + def test_FixedLagSmootherExample(self): + ''' + Simple test that checks for equality between C++ example + file and the Python implementation. See + gtsam_unstable/examples/FixedLagSmootherExample.cpp + ''' + # Define a batch fixed lag smoother, which uses + # Levenberg-Marquardt to perform the nonlinear optimization + lag = 2.0 + smoother_batch = gtsam_unstable.BatchFixedLagSmoother(lag) + + # Create containers to store the factors and linearization points + # that will be sent to the smoothers + new_factors = gtsam.NonlinearFactorGraph() + new_values = gtsam.Values() + new_timestamps = gtsam_unstable.FixedLagSmootherKeyTimestampMap() + + # Create a prior on the first pose, placing it at the origin + prior_mean = gtsam.Pose2(0, 0, 0) + prior_noise = gtsam.noiseModel_Diagonal.Sigmas( + np.array([0.3, 0.3, 0.1])) + X1 = 0 + new_factors.push_back( + gtsam.PriorFactorPose2( + X1, prior_mean, prior_noise)) + new_values.insert(X1, prior_mean) + new_timestamps.insert(_timestamp_key_value(X1, 0.0)) + + delta_time = 0.25 + time = 0.25 + + i = 0 + + ground_truth = [ + gtsam.Pose2(0.995821, 0.0231012, 0.0300001), + gtsam.Pose2(1.49284, 0.0457247, 0.045), + gtsam.Pose2(1.98981, 0.0758879, 0.06), + gtsam.Pose2(2.48627, 0.113502, 0.075), + gtsam.Pose2(2.98211, 0.158558, 0.09), + gtsam.Pose2(3.47722, 0.211047, 0.105), + gtsam.Pose2(3.97149, 0.270956, 0.12), + gtsam.Pose2(4.4648, 0.338272, 0.135), + gtsam.Pose2(4.95705, 0.41298, 0.15), + gtsam.Pose2(5.44812, 0.495063, 0.165), + gtsam.Pose2(5.9379, 0.584503, 0.18), + ] + + # Iterates from 0.25s to 3.0s, adding 0.25s each loop + # In each iteration, the agent moves at a constant speed + # and its two odometers measure the change. The smoothed + # result is then compared to the ground truth + while time <= 3.0: + previous_key = 1000 * (time - delta_time) + current_key = 1000 * time + + # assign current key to the current timestamp + new_timestamps.insert(_timestamp_key_value(current_key, time)) + + # Add a guess for this pose to the new values + # Assume that the robot moves at 2 m/s. Position is time[s] * + # 2[m/s] + current_pose = gtsam.Pose2(time * 2, 0, 0) + new_values.insert(current_key, current_pose) + + # Add odometry factors from two different sources with different + # error stats + odometry_measurement_1 = gtsam.Pose2(0.61, -0.08, 0.02) + odometry_noise_1 = gtsam.noiseModel_Diagonal.Sigmas( + np.array([0.1, 0.1, 0.05])) + new_factors.push_back( + gtsam.BetweenFactorPose2( + previous_key, + current_key, + odometry_measurement_1, + odometry_noise_1)) + + odometry_measurement_2 = gtsam.Pose2(0.47, 0.03, 0.01) + odometry_noise_2 = gtsam.noiseModel_Diagonal.Sigmas( + np.array([0.05, 0.05, 0.05])) + new_factors.push_back( + gtsam.BetweenFactorPose2( + previous_key, + current_key, + odometry_measurement_2, + odometry_noise_2)) + + # Update the smoothers with the new factors. In this case, + # one iteration must pass for Levenberg-Marquardt to accurately + # estimate + if time >= 0.50: + smoother_batch.update(new_factors, new_values, new_timestamps) + + estimate = smoother_batch.calculateEstimatePose2(current_key) + self.assertTrue(estimate.equals(ground_truth[i], 1e-4)) + i += 1 + + new_timestamps.clear() + new_values.clear() + new_factors.resize(0) + + time += delta_time + + +if __name__ == "__main__": + unittest.main() diff --git a/cython/setup.py.in b/cython/setup.py.in new file mode 100644 index 000000000..c35e54079 --- /dev/null +++ b/cython/setup.py.in @@ -0,0 +1,51 @@ +import os +import sys +try: + from setuptools import setup, find_packages +except ImportError: + from distutils.core import setup, find_packages + +if 'SETUP_PY_NO_CHECK' not in os.environ: + script_path = os.path.abspath(os.path.realpath(__file__)) + install_path = os.path.abspath(os.path.realpath(os.path.join('${GTSAM_CYTHON_INSTALL_PATH}${GTSAM_BUILD_TAG}', 'setup.py'))) + if script_path != install_path: + print('setup.py is being run from an unexpected location: "{}"'.format(script_path)) + print('please run `make install` and run the script from there') + sys.exit(1) + + +packages = find_packages() + +setup( + name='gtsam', + description='Georgia Tech Smoothing And Mapping library', + url='https://gtsam.org/', + version='${GTSAM_VERSION_STRING}', # https://www.python.org/dev/peps/pep-0440/ + author='Frank Dellaert et. al.', + author_email='frank.dellaert@gtsam.org', + license='Simplified BSD license', + keywords='slam sam robotics localization mapping optimization', + long_description='''${README_CONTENTS}''', + # https://pypi.org/pypi?%3Aaction=list_classifiers + classifiers=[ + 'Development Status :: 5 - Production/Stable', + 'Intended Audience :: Education', + 'Intended Audience :: Developers', + 'Intended Audience :: Science/Research', + 'Operating System :: MacOS', + 'Operating System :: Microsoft :: Windows', + 'Operating System :: POSIX', + 'License :: OSI Approved :: BSD License', + 'Programming Language :: Python :: 2', + 'Programming Language :: Python :: 3', + ], + + packages=packages, + package_data={package: + [f for f in os.listdir(package.replace('.', os.path.sep)) if os.path.splitext(f)[1] in ('.so', '.dll')] + for package in packages + }, + install_requires=[line.strip() for line in ''' +${CYTHON_INSTALL_REQUIREMENTS} +'''.splitlines() if len(line.strip()) > 0 and not line.strip().startswith('#')] +) diff --git a/debian/README.md b/debian/README.md new file mode 100644 index 000000000..74eb351cd --- /dev/null +++ b/debian/README.md @@ -0,0 +1,12 @@ +# How to build a GTSAM debian package + +To use the ``debuild`` command, install the ``devscripts`` package + + sudo apt install devscripts + +Change into the gtsam directory, then run: + + debuild -us -uc -j4 + +Adjust the ``-j4`` depending on how many CPUs you want to build on in +parallel. diff --git a/debian/changelog b/debian/changelog new file mode 100644 index 000000000..ef5d5ab97 --- /dev/null +++ b/debian/changelog @@ -0,0 +1,5 @@ +gtsam (4.0.0-1berndpfrommer) bionic; urgency=medium + + * initial release + + -- Bernd Pfrommer Wed, 18 Jul 2018 20:36:44 -0400 diff --git a/debian/compat b/debian/compat new file mode 100644 index 000000000..ec635144f --- /dev/null +++ b/debian/compat @@ -0,0 +1 @@ +9 diff --git a/debian/control b/debian/control new file mode 100644 index 000000000..9a37e4377 --- /dev/null +++ b/debian/control @@ -0,0 +1,15 @@ +Source: gtsam +Section: libs +Priority: optional +Maintainer: Frank Dellaert +Uploaders: Jose Luis Blanco Claraco , Bernd Pfrommer +Build-Depends: cmake, libboost-all-dev (>= 1.58), libeigen3-dev, libtbb-dev, debhelper (>=9) +Standards-Version: 3.9.7 +Homepage: https://github.com/borglab/gtsam +Vcs-Browser: https://github.com/borglab/gtsam + +Package: libgtsam-dev +Architecture: any +Depends: ${shlibs:Depends}, ${misc:Depends} +Description: Georgia Tech Smoothing and Mapping Library + gtsam: Georgia Tech Smoothing and Mapping library for SLAM type applications diff --git a/debian/copyright b/debian/copyright new file mode 100644 index 000000000..c2f41d83d --- /dev/null +++ b/debian/copyright @@ -0,0 +1,15 @@ +Format: https://www.debian.org/doc/packaging-manuals/copyright-format/1.0/ +Upstream-Name: gtsam +Source: https://bitbucket.org/gtborg/gtsam.git + +Files: * +Copyright: 2017, Frank Dellaert +License: BSD + +Files: gtsam/3rdparty/CCOLAMD/* +Copyright: 2005-2011, Univ. of Florida. Authors: Timothy A. Davis, Sivasankaran Rajamanickam, and Stefan Larimore. Closely based on COLAMD by Davis, Stefan Larimore, in collaboration with Esmond Ng, and John Gilbert. http://www.cise.ufl.edu/research/sparse +License: GNU LESSER GENERAL PUBLIC LICENSE + +Files: gtsam/3rdparty/Eigen/* +Copyright: 2017, Multiple Authors +License: MPL2 diff --git a/debian/gtsam-docs.docs b/debian/gtsam-docs.docs new file mode 100644 index 000000000..e69de29bb diff --git a/debian/rules b/debian/rules new file mode 100755 index 000000000..6a8d21c00 --- /dev/null +++ b/debian/rules @@ -0,0 +1,25 @@ +#!/usr/bin/make -f +# See debhelper(7) (uncomment to enable) +# output every command that modifies files on the build system. +export DH_VERBOSE = 1 + + +# see FEATURE AREAS in dpkg-buildflags(1) +#export DEB_BUILD_MAINT_OPTIONS = hardening=+all + +# see ENVIRONMENT in dpkg-buildflags(1) +# package maintainers to append CFLAGS +#export DEB_CFLAGS_MAINT_APPEND = -Wall -pedantic +# package maintainers to append LDFLAGS +#export DEB_LDFLAGS_MAINT_APPEND = -Wl,--as-needed + + +%: + dh $@ --parallel + + +# dh_make generated override targets +# This is example for Cmake (See https://bugs.debian.org/641051 ) +override_dh_auto_configure: + dh_auto_configure -- -DCMAKE_BUILD_TYPE=RelWithDebInfo -DCMAKE_INSTALL_PREFIX=/usr -DGTSAM_BUILD_EXAMPLES_ALWAYS=OFF -DGTSAM_BUILD_TESTS=OFF -DGTSAM_BUILD_WRAP=OFF -DGTSAM_BUILD_DOCS=OFF -DGTSAM_INSTALL_CPPUNITLITE=OFF -DGTSAM_INSTALL_GEOGRAPHICLIB=OFF -DGTSAM_BUILD_TYPE_POSTFIXES=OFF + diff --git a/debian/source/format b/debian/source/format new file mode 100644 index 000000000..163aaf8d8 --- /dev/null +++ b/debian/source/format @@ -0,0 +1 @@ +3.0 (quilt) diff --git a/doc/Code/LocalizationExample2.cpp b/doc/Code/LocalizationExample2.cpp index 7fce69566..d22180314 100644 --- a/doc/Code/LocalizationExample2.cpp +++ b/doc/Code/LocalizationExample2.cpp @@ -1,5 +1,5 @@ // add unary measurement factors, like GPS, on all three poses -noiseModel::Diagonal::shared_ptr unaryNoise = +noiseModel::Diagonal::shared_ptr unaryNoise = noiseModel::Diagonal::Sigmas(Vector2(0.1, 0.1)); // 10cm std on x,y graph.add(boost::make_shared(1, 0.0, 0.0, unaryNoise)); graph.add(boost::make_shared(2, 2.0, 0.0, unaryNoise)); diff --git a/doc/Code/LocalizationFactor.cpp b/doc/Code/LocalizationFactor.cpp index 8b80f2b2a..79a54903e 100644 --- a/doc/Code/LocalizationFactor.cpp +++ b/doc/Code/LocalizationFactor.cpp @@ -5,7 +5,7 @@ public: UnaryFactor(Key j, double x, double y, const SharedNoiseModel& model): NoiseModelFactor1(model, j), mx_(x), my_(y) {} - Vector evaluateError(const Pose2& q, + Vector evaluateError(const Pose2& q, boost::optional H = boost::none) const { if (H) (*H) = (Matrix(2,3)<< 1.0,0.0,0.0, 0.0,1.0,0.0).finished(); diff --git a/doc/Code/OdometryExample.cpp b/doc/Code/OdometryExample.cpp index ef880384c..6e736e2d7 100644 --- a/doc/Code/OdometryExample.cpp +++ b/doc/Code/OdometryExample.cpp @@ -3,13 +3,13 @@ NonlinearFactorGraph graph; // Add a Gaussian prior on pose x_1 Pose2 priorMean(0.0, 0.0, 0.0); -noiseModel::Diagonal::shared_ptr priorNoise = +noiseModel::Diagonal::shared_ptr priorNoise = noiseModel::Diagonal::Sigmas(Vector3(0.3, 0.3, 0.1)); graph.add(PriorFactor(1, priorMean, priorNoise)); // Add two odometry factors Pose2 odometry(2.0, 0.0, 0.0); -noiseModel::Diagonal::shared_ptr odometryNoise = +noiseModel::Diagonal::shared_ptr odometryNoise = noiseModel::Diagonal::Sigmas(Vector3(0.2, 0.2, 0.1)); graph.add(BetweenFactor(1, 2, odometry, odometryNoise)); graph.add(BetweenFactor(2, 3, odometry, odometryNoise)); diff --git a/doc/Code/Pose2SLAMExample.cpp b/doc/Code/Pose2SLAMExample.cpp index 2e2b41704..1738aabc5 100644 --- a/doc/Code/Pose2SLAMExample.cpp +++ b/doc/Code/Pose2SLAMExample.cpp @@ -1,10 +1,10 @@ NonlinearFactorGraph graph; -noiseModel::Diagonal::shared_ptr priorNoise = +noiseModel::Diagonal::shared_ptr priorNoise = noiseModel::Diagonal::Sigmas(Vector3(0.3, 0.3, 0.1)); graph.add(PriorFactor(1, Pose2(0, 0, 0), priorNoise)); // Add odometry factors -noiseModel::Diagonal::shared_ptr model = +noiseModel::Diagonal::shared_ptr model = noiseModel::Diagonal::Sigmas(Vector3(0.2, 0.2, 0.1)); graph.add(BetweenFactor(1, 2, Pose2(2, 0, 0 ), model)); graph.add(BetweenFactor(2, 3, Pose2(2, 0, M_PI_2), model)); diff --git a/doc/trustregion.bib b/doc/trustregion.bib index 7fcd509f4..7c87eef9b 100644 --- a/doc/trustregion.bib +++ b/doc/trustregion.bib @@ -8,7 +8,6 @@ %% Saved with string encoding Unicode (UTF-8) - @webpage{Hauser06lecture, Author = {Raphael Hauser}, Date-Added = {2011-10-10 15:21:22 +0000}, @@ -16,11 +15,5 @@ Title = {Lecture Notes on Unconstrained Optimization}, Url = {http://www.numerical.rl.ac.uk/nimg/oupartc/lectures/raphael/}, Year = {2006}, - Bdsk-Url-1 = {http://www.numerical.rl.ac.uk/nimg/oupartc/lectures/raphael/}, - Bdsk-File-1 = {YnBsaXN0MDDUAQIDBAUIJidUJHRvcFgkb2JqZWN0c1gkdmVyc2lvblkkYXJjaGl2ZXLRBgdUcm9vdIABqAkKFRYXGyIjVSRudWxs0wsMDQ4RFFpOUy5vYmplY3RzV05TLmtleXNWJGNsYXNzog8QgASABqISE4ACgAOAB1lhbGlhc0RhdGFccmVsYXRpdmVQYXRo0hgNGRpXTlMuZGF0YU8RAYwAAAAAAYwAAgAADE1hY2ludG9zaCBIRAAAAAAAAAAAAAAAAAAAAMpAsaxIKwAAAD/T8xBIYXVzZXIwNmxlY3R1cmUxAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAQn+Sv+qSlgAAAAAAAAAAAAMAAgAACSAAAAAAAAAAAAAAAAAAAAAKTGl0ZXJhdHVyZQAQAAgAAMpA6ewAAAARAAgAAL/q2OYAAAABAAwAP9PzAAUCJwAAvuwAAgA5TWFjaW50b3NoIEhEOlVzZXJzOgByaWNoYXJkOgBMaXRlcmF0dXJlOgBIYXVzZXIwNmxlY3R1cmUxAAAOACIAEABIAGEAdQBzAGUAcgAwADYAbABlAGMAdAB1AHIAZQAxAA8AGgAMAE0AYQBjAGkAbgB0AG8AcwBoACAASABEABIAKVVzZXJzL3JpY2hhcmQvTGl0ZXJhdHVyZS9IYXVzZXIwNmxlY3R1cmUxAAATAAEvAAAVAAIADv//AACABdIcHR4fWCRjbGFzc2VzWiRjbGFzc25hbWWjHyAhXU5TTXV0YWJsZURhdGFWTlNEYXRhWE5TT2JqZWN0XxAkLi4vLi4vLi4vTGl0ZXJhdHVyZS9IYXVzZXIwNmxlY3R1cmUx0hwdJCWiJSFcTlNEaWN0aW9uYXJ5EgABhqBfEA9OU0tleWVkQXJjaGl2ZXIACAARABYAHwAoADIANQA6ADwARQBLAFIAXQBlAGwAbwBxAHMAdgB4AHoAfACGAJMAmACgAjACMgI3AkACSwJPAl0CZAJtApQCmQKcAqkCrgAAAAAAAAIBAAAAAAAAACgAAAAAAAAAAAAAAAAAAALA}, - Bdsk-File-2 = {YnBsaXN0MDDUAQIDBAUIJidUJHRvcFgkb2JqZWN0c1gkdmVyc2lvblkkYXJjaGl2ZXLRBgdUcm9vdIABqAkKFRYXGyIjVSRudWxs0wsMDQ4RFFpOUy5vYmplY3RzV05TLmtleXNWJGNsYXNzog8QgASABqISE4ACgAOAB1lhbGlhc0RhdGFccmVsYXRpdmVQYXRo0hgNGRpXTlMuZGF0YU8RAYwAAAAAAYwAAgAADE1hY2ludG9zaCBIRAAAAAAAAAAAAAAAAAAAAMpAsaxIKwAAAD/T8xBIYXVzZXIwNmxlY3R1cmUyAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAQn+Xv+qSowAAAAAAAAAAAAMAAgAACSAAAAAAAAAAAAAAAAAAAAAKTGl0ZXJhdHVyZQAQAAgAAMpA6ewAAAARAAgAAL/q2PMAAAABAAwAP9PzAAUCJwAAvuwAAgA5TWFjaW50b3NoIEhEOlVzZXJzOgByaWNoYXJkOgBMaXRlcmF0dXJlOgBIYXVzZXIwNmxlY3R1cmUyAAAOACIAEABIAGEAdQBzAGUAcgAwADYAbABlAGMAdAB1AHIAZQAyAA8AGgAMAE0AYQBjAGkAbgB0AG8AcwBoACAASABEABIAKVVzZXJzL3JpY2hhcmQvTGl0ZXJhdHVyZS9IYXVzZXIwNmxlY3R1cmUyAAATAAEvAAAVAAIADv//AACABdIcHR4fWCRjbGFzc2VzWiRjbGFzc25hbWWjHyAhXU5TTXV0YWJsZURhdGFWTlNEYXRhWE5TT2JqZWN0XxAkLi4vLi4vLi4vTGl0ZXJhdHVyZS9IYXVzZXIwNmxlY3R1cmUy0hwdJCWiJSFcTlNEaWN0aW9uYXJ5EgABhqBfEA9OU0tleWVkQXJjaGl2ZXIACAARABYAHwAoADIANQA6ADwARQBLAFIAXQBlAGwAbwBxAHMAdgB4AHoAfACGAJMAmACgAjACMgI3AkACSwJPAl0CZAJtApQCmQKcAqkCrgAAAAAAAAIBAAAAAAAAACgAAAAAAAAAAAAAAAAAAALA}, - Bdsk-File-3 = {YnBsaXN0MDDUAQIDBAUIJidUJHRvcFgkb2JqZWN0c1gkdmVyc2lvblkkYXJjaGl2ZXLRBgdUcm9vdIABqAkKFRYXGyIjVSRudWxs0wsMDQ4RFFpOUy5vYmplY3RzV05TLmtleXNWJGNsYXNzog8QgASABqISE4ACgAOAB1lhbGlhc0RhdGFccmVsYXRpdmVQYXRo0hgNGRpXTlMuZGF0YU8RAYwAAAAAAYwAAgAADE1hY2ludG9zaCBIRAAAAAAAAAAAAAAAAAAAAMpAsaxIKwAAAD/T8xBIYXVzZXIwNmxlY3R1cmUzAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAQn+mv+qSpQAAAAAAAAAAAAMAAgAACSAAAAAAAAAAAAAAAAAAAAAKTGl0ZXJhdHVyZQAQAAgAAMpA6ewAAAARAAgAAL/q2PUAAAABAAwAP9PzAAUCJwAAvuwAAgA5TWFjaW50b3NoIEhEOlVzZXJzOgByaWNoYXJkOgBMaXRlcmF0dXJlOgBIYXVzZXIwNmxlY3R1cmUzAAAOACIAEABIAGEAdQBzAGUAcgAwADYAbABlAGMAdAB1AHIAZQAzAA8AGgAMAE0AYQBjAGkAbgB0AG8AcwBoACAASABEABIAKVVzZXJzL3JpY2hhcmQvTGl0ZXJhdHVyZS9IYXVzZXIwNmxlY3R1cmUzAAATAAEvAAAVAAIADv//AACABdIcHR4fWCRjbGFzc2VzWiRjbGFzc25hbWWjHyAhXU5TTXV0YWJsZURhdGFWTlNEYXRhWE5TT2JqZWN0XxAkLi4vLi4vLi4vTGl0ZXJhdHVyZS9IYXVzZXIwNmxlY3R1cmUz0hwdJCWiJSFcTlNEaWN0aW9uYXJ5EgABhqBfEA9OU0tleWVkQXJjaGl2ZXIACAARABYAHwAoADIANQA6ADwARQBLAFIAXQBlAGwAbwBxAHMAdgB4AHoAfACGAJMAmACgAjACMgI3AkACSwJPAl0CZAJtApQCmQKcAqkCrgAAAAAAAAIBAAAAAAAAACgAAAAAAAAAAAAAAAAAAALA}, - Bdsk-File-4 = {YnBsaXN0MDDUAQIDBAUIJidUJHRvcFgkb2JqZWN0c1gkdmVyc2lvblkkYXJjaGl2ZXLRBgdUcm9vdIABqAkKFRYXGyIjVSRudWxs0wsMDQ4RFFpOUy5vYmplY3RzV05TLmtleXNWJGNsYXNzog8QgASABqISE4ACgAOAB1lhbGlhc0RhdGFccmVsYXRpdmVQYXRo0hgNGRpXTlMuZGF0YU8RAYwAAAAAAYwAAgAADE1hY2ludG9zaCBIRAAAAAAAAAAAAAAAAAAAAMpAsaxIKwAAAD/T8xBIYXVzZXIwNmxlY3R1cmU0AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAQn+vv+qSpwAAAAAAAAAAAAMAAgAACSAAAAAAAAAAAAAAAAAAAAAKTGl0ZXJhdHVyZQAQAAgAAMpA6ewAAAARAAgAAL/q2PcAAAABAAwAP9PzAAUCJwAAvuwAAgA5TWFjaW50b3NoIEhEOlVzZXJzOgByaWNoYXJkOgBMaXRlcmF0dXJlOgBIYXVzZXIwNmxlY3R1cmU0AAAOACIAEABIAGEAdQBzAGUAcgAwADYAbABlAGMAdAB1AHIAZQA0AA8AGgAMAE0AYQBjAGkAbgB0AG8AcwBoACAASABEABIAKVVzZXJzL3JpY2hhcmQvTGl0ZXJhdHVyZS9IYXVzZXIwNmxlY3R1cmU0AAATAAEvAAAVAAIADv//AACABdIcHR4fWCRjbGFzc2VzWiRjbGFzc25hbWWjHyAhXU5TTXV0YWJsZURhdGFWTlNEYXRhWE5TT2JqZWN0XxAkLi4vLi4vLi4vTGl0ZXJhdHVyZS9IYXVzZXIwNmxlY3R1cmU00hwdJCWiJSFcTlNEaWN0aW9uYXJ5EgABhqBfEA9OU0tleWVkQXJjaGl2ZXIACAARABYAHwAoADIANQA6ADwARQBLAFIAXQBlAGwAbwBxAHMAdgB4AHoAfACGAJMAmACgAjACMgI3AkACSwJPAl0CZAJtApQCmQKcAqkCrgAAAAAAAAIBAAAAAAAAACgAAAAAAAAAAAAAAAAAAALA}, - Bdsk-File-5 = {YnBsaXN0MDDUAQIDBAUIJidUJHRvcFgkb2JqZWN0c1gkdmVyc2lvblkkYXJjaGl2ZXLRBgdUcm9vdIABqAkKFRYXGyIjVSRudWxs0wsMDQ4RFFpOUy5vYmplY3RzV05TLmtleXNWJGNsYXNzog8QgASABqISE4ACgAOAB1lhbGlhc0RhdGFccmVsYXRpdmVQYXRo0hgNGRpXTlMuZGF0YU8RAYwAAAAAAYwAAgAADE1hY2ludG9zaCBIRAAAAAAAAAAAAAAAAAAAAMpAsaxIKwAAAD/T8xBIYXVzZXIwNmxlY3R1cmU1AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAQn+5v+qSqAAAAAAAAAAAAAMAAgAACSAAAAAAAAAAAAAAAAAAAAAKTGl0ZXJhdHVyZQAQAAgAAMpA6ewAAAARAAgAAL/q2PgAAAABAAwAP9PzAAUCJwAAvuwAAgA5TWFjaW50b3NoIEhEOlVzZXJzOgByaWNoYXJkOgBMaXRlcmF0dXJlOgBIYXVzZXIwNmxlY3R1cmU1AAAOACIAEABIAGEAdQBzAGUAcgAwADYAbABlAGMAdAB1AHIAZQA1AA8AGgAMAE0AYQBjAGkAbgB0AG8AcwBoACAASABEABIAKVVzZXJzL3JpY2hhcmQvTGl0ZXJhdHVyZS9IYXVzZXIwNmxlY3R1cmU1AAATAAEvAAAVAAIADv//AACABdIcHR4fWCRjbGFzc2VzWiRjbGFzc25hbWWjHyAhXU5TTXV0YWJsZURhdGFWTlNEYXRhWE5TT2JqZWN0XxAkLi4vLi4vLi4vTGl0ZXJhdHVyZS9IYXVzZXIwNmxlY3R1cmU10hwdJCWiJSFcTlNEaWN0aW9uYXJ5EgABhqBfEA9OU0tleWVkQXJjaGl2ZXIACAARABYAHwAoADIANQA6ADwARQBLAFIAXQBlAGwAbwBxAHMAdgB4AHoAfACGAJMAmACgAjACMgI3AkACSwJPAl0CZAJtApQCmQKcAqkCrgAAAAAAAAIBAAAAAAAAACgAAAAAAAAAAAAAAAAAAALA}, - Bdsk-File-6 = {YnBsaXN0MDDUAQIDBAUIJidUJHRvcFgkb2JqZWN0c1gkdmVyc2lvblkkYXJjaGl2ZXLRBgdUcm9vdIABqAkKFRYXGyIjVSRudWxs0wsMDQ4RFFpOUy5vYmplY3RzV05TLmtleXNWJGNsYXNzog8QgASABqISE4ACgAOAB1lhbGlhc0RhdGFccmVsYXRpdmVQYXRo0hgNGRpXTlMuZGF0YU8RAYwAAAAAAYwAAgAADE1hY2ludG9zaCBIRAAAAAAAAAAAAAAAAAAAAMpAsaxIKwAAAD/T8xBIYXVzZXIwNmxlY3R1cmU2AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAQn/Fv+qSqgAAAAAAAAAAAAMAAgAACSAAAAAAAAAAAAAAAAAAAAAKTGl0ZXJhdHVyZQAQAAgAAMpA6ewAAAARAAgAAL/q2PoAAAABAAwAP9PzAAUCJwAAvuwAAgA5TWFjaW50b3NoIEhEOlVzZXJzOgByaWNoYXJkOgBMaXRlcmF0dXJlOgBIYXVzZXIwNmxlY3R1cmU2AAAOACIAEABIAGEAdQBzAGUAcgAwADYAbABlAGMAdAB1AHIAZQA2AA8AGgAMAE0AYQBjAGkAbgB0AG8AcwBoACAASABEABIAKVVzZXJzL3JpY2hhcmQvTGl0ZXJhdHVyZS9IYXVzZXIwNmxlY3R1cmU2AAATAAEvAAAVAAIADv//AACABdIcHR4fWCRjbGFzc2VzWiRjbGFzc25hbWWjHyAhXU5TTXV0YWJsZURhdGFWTlNEYXRhWE5TT2JqZWN0XxAkLi4vLi4vLi4vTGl0ZXJhdHVyZS9IYXVzZXIwNmxlY3R1cmU20hwdJCWiJSFcTlNEaWN0aW9uYXJ5EgABhqBfEA9OU0tleWVkQXJjaGl2ZXIACAARABYAHwAoADIANQA6ADwARQBLAFIAXQBlAGwAbwBxAHMAdgB4AHoAfACGAJMAmACgAjACMgI3AkACSwJPAl0CZAJtApQCmQKcAqkCrgAAAAAAAAIBAAAAAAAAACgAAAAAAAAAAAAAAAAAAALA}, - Bdsk-File-7 = {YnBsaXN0MDDUAQIDBAUIJidUJHRvcFgkb2JqZWN0c1gkdmVyc2lvblkkYXJjaGl2ZXLRBgdUcm9vdIABqAkKFRYXGyIjVSRudWxs0wsMDQ4RFFpOUy5vYmplY3RzV05TLmtleXNWJGNsYXNzog8QgASABqISE4ACgAOAB1lhbGlhc0RhdGFccmVsYXRpdmVQYXRo0hgNGRpXTlMuZGF0YU8RAYwAAAAAAYwAAgAADE1hY2ludG9zaCBIRAAAAAAAAAAAAAAAAAAAAMpAsaxIKwAAAD/T8xBIYXVzZXIwNmxlY3R1cmU3AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAQn/Pv+qSrAAAAAAAAAAAAAMAAgAACSAAAAAAAAAAAAAAAAAAAAAKTGl0ZXJhdHVyZQAQAAgAAMpA6ewAAAARAAgAAL/q2PwAAAABAAwAP9PzAAUCJwAAvuwAAgA5TWFjaW50b3NoIEhEOlVzZXJzOgByaWNoYXJkOgBMaXRlcmF0dXJlOgBIYXVzZXIwNmxlY3R1cmU3AAAOACIAEABIAGEAdQBzAGUAcgAwADYAbABlAGMAdAB1AHIAZQA3AA8AGgAMAE0AYQBjAGkAbgB0AG8AcwBoACAASABEABIAKVVzZXJzL3JpY2hhcmQvTGl0ZXJhdHVyZS9IYXVzZXIwNmxlY3R1cmU3AAATAAEvAAAVAAIADv//AACABdIcHR4fWCRjbGFzc2VzWiRjbGFzc25hbWWjHyAhXU5TTXV0YWJsZURhdGFWTlNEYXRhWE5TT2JqZWN0XxAkLi4vLi4vLi4vTGl0ZXJhdHVyZS9IYXVzZXIwNmxlY3R1cmU30hwdJCWiJSFcTlNEaWN0aW9uYXJ5EgABhqBfEA9OU0tleWVkQXJjaGl2ZXIACAARABYAHwAoADIANQA6ADwARQBLAFIAXQBlAGwAbwBxAHMAdgB4AHoAfACGAJMAmACgAjACMgI3AkACSwJPAl0CZAJtApQCmQKcAqkCrgAAAAAAAAIBAAAAAAAAACgAAAAAAAAAAAAAAAAAAALA}} + howpublished = {\href{http://www.numerical.rl.ac.uk/nimg/oupartc/lectures/raphael/}{link}}, +} diff --git a/doc/trustregion.lyx b/doc/trustregion.lyx index bc4393fdf..97bc6ec74 100644 --- a/doc/trustregion.lyx +++ b/doc/trustregion.lyx @@ -1,10 +1,11 @@ -#LyX 2.0 created this file. For more info see http://www.lyx.org/ -\lyxformat 413 +#LyX 2.1 created this file. For more info see http://www.lyx.org/ +\lyxformat 474 \begin_document \begin_header \textclass article \begin_preamble -\usepackage{amssymb} +\usepackage{url} +\usepackage{hyperref} \end_preamble \use_default_options true \maintain_unincluded_children false @@ -15,13 +16,13 @@ \font_roman default \font_sans default \font_typewriter default +\font_math auto \font_default_family default \use_non_tex_fonts false \font_sc false \font_osf false \font_sf_scale 100 \font_tt_scale 100 - \graphics default \default_output_format default \output_sync 0 @@ -32,15 +33,24 @@ \use_hyperref false \papersize default \use_geometry false -\use_amsmath 1 -\use_esint 1 -\use_mhchem 1 -\use_mathdots 1 +\use_package amsmath 1 +\use_package amssymb 2 +\use_package cancel 1 +\use_package esint 1 +\use_package mathdots 1 +\use_package mathtools 1 +\use_package mhchem 1 +\use_package stackrel 0 +\use_package stmaryrd 1 +\use_package undertilde 1 \cite_engine basic +\cite_engine_type default +\biblio_style plain \use_bibtopic false \use_indices false \paperorientation portrait \suppress_date false +\justification true \use_refstyle 1 \index Index \shortcut idx @@ -231,7 +241,7 @@ key "Hauser06lecture" \end_inset - (in our /net/hp223/borg/Literature folder). +. \end_layout \begin_layout Standard @@ -465,22 +475,39 @@ where \end_inset . - A typical update rule [ -\color blue -see where this came from in paper -\color inherit -] is + A typical update rule, as per Lec. + 7-1.2 of +\begin_inset CommandInset citation +LatexCommand cite +key "Hauser06lecture" + +\end_inset + + is: \begin_inset Formula \[ -\Delta\leftarrow\begin{cases} -\max\left(\Delta,3\norm{\delta x_{d}}\right)\text{,} & \rho>0.75\\ -\Delta & 0.75>\rho>0.25\\ -\Delta/2 & 0.25>\rho +\Delta_{k+1}\leftarrow\begin{cases} +\Delta_{k}/4 & \rho<0.25\\ +\min\left(2\Delta_{k},\Delta_{max}\right)\text{,} & \rho>0.75\\ +\Delta_{k} & 0.75>\rho>0.25 \end{cases} \] \end_inset +where +\begin_inset Formula $\Delta_{k}\triangleq\norm{\delta x_{d}}$ +\end_inset + +. + Note that the rule is designed to ensure that +\begin_inset Formula $\Delta_{k}$ +\end_inset + +never exceeds the maximum trust region size +\begin_inset Formula $\Delta_{max}.$ +\end_inset + \end_layout @@ -593,9 +620,9 @@ To find the intersection of the line between \begin{align*} \Delta & =\norm{\left(1-\tau\right)\delta x_{u}+\tau\delta x_{n}}\\ \Delta^{2} & =\left(1-\tau\right)^{2}\delta x_{u}^{\t}\delta x_{u}+2\tau\left(1-\tau\right)\delta x_{u}^{\t}\delta x_{n}+\tau^{2}\delta x_{n}^{\t}\delta x_{n}\\ -0 & =uu-2\tau uu+\tau^{2}uu+2\tau un-2\tau^{2}un+\tau^{2}nn-\Delta^{2}\\ -0 & =\left(uu-2un+nn\right)\tau^{2}+\left(2un-2uu\right)\tau-\Delta^{2}+uu\\ -\tau & =\frac{-\left(2un-2uu\right)\pm\sqrt{\left(2un-2uu\right)^{2}-4\left(uu-2un+nn\right)\left(uu-\Delta^{2}\right)}}{2\left(uu-un+nn\right)} +0 & =\delta x_{u}^{\t}\delta x_{u}-2\tau\delta x_{u}^{\t}\delta x_{u}+\tau^{2}\delta x_{u}^{\t}\delta x_{u}+2\tau\delta x_{u}^{\t}\delta x_{n}-2\tau^{2}\delta x_{u}^{\t}\delta x_{n}+\tau^{2}\delta x_{n}^{\t}\delta x_{n}-\Delta^{2}\\ +0 & =\left(\delta x_{u}^{\t}\delta x_{u}-2\delta x_{u}^{\t}\delta x_{n}+\delta x_{n}^{\t}\delta x_{n}\right)\tau^{2}+\left(2\delta x_{u}^{\t}\delta x_{n}-2\delta x_{u}^{\t}\delta x_{u}\right)\tau-\Delta^{2}+\delta x_{u}^{\t}\delta x_{u}\\ +\tau & =\frac{-\left(2\delta x_{u}^{\t}\delta x_{n}-2\delta x_{u}^{\t}\delta x_{u}\right)\pm\sqrt{\left(2\delta x_{u}^{\t}\delta x_{n}-2\delta x_{u}^{\t}\delta x_{u}\right)^{2}-4\left(\delta x_{u}^{\t}\delta x_{u}-2\delta x_{u}^{\t}\delta x_{n}+\delta x_{n}^{\t}\delta x_{n}\right)\left(\delta x_{u}^{\t}\delta x_{u}-\Delta^{2}\right)}}{2\left(\delta x_{u}^{\t}\delta x_{u}-\delta x_{u}^{\t}\delta x_{n}+\delta x_{n}^{\t}\delta x_{n}\right)} \end{align*} \end_inset @@ -641,7 +668,7 @@ Thus, mathematically, we can write the dogleg update \begin_inset Formula \[ \delta x_{d}^{\left(k\right)}=\begin{cases} --\frac{\Delta}{\norm{g^{\left(k\right)}}}g^{\left(k\right)}\text{,} & \Delta<\norm{\delta x_{u}^{\left(k\right)}}\\ +-\frac{\Delta}{\norm{\delta x_{u}^{\left(k\right)}}}\delta x_{u}^{\left(k\right)}\text{,} & \Delta<\norm{\delta x_{u}^{\left(k\right)}}\\ \left(1-\tau^{\left(k\right)}\right)\delta x_{u}^{\left(k\right)}+\tau^{\left(k\right)}\delta x_{n}^{\left(k\right)}\text{,} & \norm{\delta x_{u}^{\left(k\right)}}<\Delta<\norm{\delta x_{n}^{\left(k\right)}}\\ \delta x_{n}^{\left(k\right)}\text{,} & \norm{\delta x_{n}^{\left(k\right)}}<\Delta \end{cases} diff --git a/doc/trustregion.pdf b/doc/trustregion.pdf index 31ca0c5b1..22dcac035 100644 Binary files a/doc/trustregion.pdf and b/doc/trustregion.pdf differ diff --git a/examples/CameraResectioning.cpp b/examples/CameraResectioning.cpp index 204af1fea..e3408b67b 100644 --- a/examples/CameraResectioning.cpp +++ b/examples/CameraResectioning.cpp @@ -1,6 +1,6 @@ /* ---------------------------------------------------------------------------- - * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * GTSAM Copyright 2010, Georgia Tech Research Corporation, * Atlanta, Georgia 30332-0415 * All Rights Reserved * Authors: Frank Dellaert, et al. (see THANKS for the full author list) diff --git a/examples/Data/HS21.QPS b/examples/Data/HS21.QPS new file mode 100644 index 000000000..c71305c6e --- /dev/null +++ b/examples/Data/HS21.QPS @@ -0,0 +1,20 @@ +NAME HS21 +ROWS + N OBJ.FUNC + G R------1 +COLUMNS + C------1 R------1 0.100000e+02 + C------2 R------1 -.100000e+01 +RHS + RHS OBJ.FUNC 0.100000e+03 + RHS R------1 0.100000e+02 +RANGES +BOUNDS + LO BOUNDS C------1 0.200000e+01 + UP BOUNDS C------1 0.500000e+02 + LO BOUNDS C------2 -.500000e+02 + UP BOUNDS C------2 0.500000e+02 +QUADOBJ + C------1 C------1 0.200000e-01 + C------2 C------2 0.200000e+01 +ENDATA diff --git a/examples/Data/HS268.QPS b/examples/Data/HS268.QPS new file mode 100644 index 000000000..53de89421 --- /dev/null +++ b/examples/Data/HS268.QPS @@ -0,0 +1,55 @@ +NAME HS268 +ROWS + N OBJ.FUNC + G R------1 + G R------2 + G R------3 + G R------4 + G R------5 +COLUMNS + C------1 OBJ.FUNC 0.183400e+05 R------1 -.100000e+01 + C------1 R------2 0.100000e+02 R------3 -.800000e+01 + C------1 R------4 0.800000e+01 R------5 -.400000e+01 + C------2 OBJ.FUNC -.341980e+05 R------1 -.100000e+01 + C------2 R------2 0.100000e+02 R------3 0.100000e+01 + C------2 R------4 -.100000e+01 R------5 -.200000e+01 + C------3 OBJ.FUNC 0.454200e+04 R------1 -.100000e+01 + C------3 R------2 -.300000e+01 R------3 -.200000e+01 + C------3 R------4 0.200000e+01 R------5 0.300000e+01 + C------4 OBJ.FUNC 0.867200e+04 R------1 -.100000e+01 + C------4 R------2 0.500000e+01 R------3 -.500000e+01 + C------4 R------4 0.500000e+01 R------5 -.500000e+01 + C------5 OBJ.FUNC 0.860000e+02 R------1 -.100000e+01 + C------5 R------2 0.400000e+01 R------3 0.300000e+01 + C------5 R------4 -.300000e+01 R------5 0.100000e+01 +RHS + RHS OBJ.FUNC -.144630e+05 + RHS R------1 -.500000e+01 + RHS R------2 0.200000e+02 + RHS R------3 -.400000e+02 + RHS R------4 0.110000e+02 + RHS R------5 -.300000e+02 +RANGES +BOUNDS + FR BOUNDS C------1 + FR BOUNDS C------2 + FR BOUNDS C------3 + FR BOUNDS C------4 + FR BOUNDS C------5 +QUADOBJ + C------1 C------1 0.203940e+05 + C------1 C------2 -.249080e+05 + C------1 C------3 -.202600e+04 + C------1 C------4 0.389600e+04 + C------1 C------5 0.658000e+03 + C------2 C------2 0.418180e+05 + C------2 C------3 -.346600e+04 + C------2 C------4 -.982800e+04 + C------2 C------5 -.372000e+03 + C------3 C------3 0.351000e+04 + C------3 C------4 0.217800e+04 + C------3 C------5 -.348000e+03 + C------4 C------4 0.303000e+04 + C------4 C------5 -.440000e+02 + C------5 C------5 0.540000e+02 +ENDATA diff --git a/examples/Data/HS35.QPS b/examples/Data/HS35.QPS new file mode 100644 index 000000000..1ee230e39 --- /dev/null +++ b/examples/Data/HS35.QPS @@ -0,0 +1,20 @@ +NAME HS35 +ROWS + N OBJ.FUNC + G R------1 +COLUMNS + C------1 OBJ.FUNC -.800000e+01 R------1 -.100000e+01 + C------2 OBJ.FUNC -.600000e+01 R------1 -.100000e+01 + C------3 OBJ.FUNC -.400000e+01 R------1 -.200000e+01 +RHS + RHS OBJ.FUNC -.900000e+01 + RHS R------1 -.300000e+01 +RANGES +BOUNDS +QUADOBJ + C------1 C------1 0.400000e+01 + C------1 C------2 0.200000e+01 + C------1 C------3 0.200000e+01 + C------2 C------2 0.400000e+01 + C------3 C------3 0.200000e+01 +ENDATA diff --git a/examples/Data/HS35MOD.QPS b/examples/Data/HS35MOD.QPS new file mode 100644 index 000000000..2fe75ef96 --- /dev/null +++ b/examples/Data/HS35MOD.QPS @@ -0,0 +1,21 @@ +NAME HS35MOD +ROWS + N OBJ.FUNC + G R------1 +COLUMNS + C------1 OBJ.FUNC -.800000e+01 R------1 -.100000e+01 + C------2 OBJ.FUNC -.600000e+01 R------1 -.100000e+01 + C------3 OBJ.FUNC -.400000e+01 R------1 -.200000e+01 +RHS + RHS OBJ.FUNC -.900000e+01 + RHS R------1 -.300000e+01 +RANGES +BOUNDS + FX BOUNDS C------2 0.500000e+00 +QUADOBJ + C------1 C------1 0.400000e+01 + C------1 C------2 0.200000e+01 + C------1 C------3 0.200000e+01 + C------2 C------2 0.400000e+01 + C------3 C------3 0.200000e+01 +ENDATA diff --git a/examples/Data/HS51.QPS b/examples/Data/HS51.QPS new file mode 100644 index 000000000..46416af03 --- /dev/null +++ b/examples/Data/HS51.QPS @@ -0,0 +1,33 @@ +NAME HS51 +ROWS + N OBJ.FUNC + E R------1 + E R------2 + E R------3 +COLUMNS + C------1 R------1 0.100000e+01 + C------2 OBJ.FUNC -.400000e+01 R------1 0.300000e+01 + C------2 R------3 0.100000e+01 + C------3 OBJ.FUNC -.400000e+01 R------2 0.100000e+01 + C------4 OBJ.FUNC -.200000e+01 R------2 0.100000e+01 + C------5 OBJ.FUNC -.200000e+01 R------2 -.200000e+01 + C------5 R------3 -.100000e+01 +RHS + RHS OBJ.FUNC -.600000e+01 + RHS R------1 0.400000e+01 +RANGES +BOUNDS + FR BOUNDS C------1 + FR BOUNDS C------2 + FR BOUNDS C------3 + FR BOUNDS C------4 + FR BOUNDS C------5 +QUADOBJ + C------1 C------1 0.200000e+01 + C------1 C------2 -.200000e+01 + C------2 C------2 0.400000e+01 + C------2 C------3 0.200000e+01 + C------3 C------3 0.200000e+01 + C------4 C------4 0.200000e+01 + C------5 C------5 0.200000e+01 +ENDATA diff --git a/examples/Data/HS52.QPS b/examples/Data/HS52.QPS new file mode 100644 index 000000000..06add5ac3 --- /dev/null +++ b/examples/Data/HS52.QPS @@ -0,0 +1,32 @@ +NAME HS52 +ROWS + N OBJ.FUNC + E R------1 + E R------2 + E R------3 +COLUMNS + C------1 R------1 0.100000e+01 + C------2 OBJ.FUNC -.400000e+01 R------1 0.300000e+01 + C------2 R------3 0.100000e+01 + C------3 OBJ.FUNC -.400000e+01 R------2 0.100000e+01 + C------4 OBJ.FUNC -.200000e+01 R------2 0.100000e+01 + C------5 OBJ.FUNC -.200000e+01 R------2 -.200000e+01 + C------5 R------3 -.100000e+01 +RHS + RHS OBJ.FUNC -.600000e+01 +RANGES +BOUNDS + FR BOUNDS C------1 + FR BOUNDS C------2 + FR BOUNDS C------3 + FR BOUNDS C------4 + FR BOUNDS C------5 +QUADOBJ + C------1 C------1 0.320000e+02 + C------1 C------2 -.800000e+01 + C------2 C------2 0.400000e+01 + C------2 C------3 0.200000e+01 + C------3 C------3 0.200000e+01 + C------4 C------4 0.200000e+01 + C------5 C------5 0.200000e+01 +ENDATA diff --git a/examples/Data/QPTEST.QPS b/examples/Data/QPTEST.QPS new file mode 100644 index 000000000..8f4f17f05 --- /dev/null +++ b/examples/Data/QPTEST.QPS @@ -0,0 +1,19 @@ +NAME QP example +ROWS + N obj + G r1 + L r2 +COLUMNS + c1 r1 2.0 r2 -1.0 + c1 obj 1.5 + c2 r1 1.0 r2 2.0 + c2 obj -2.0 +RHS + rhs1 r1 2.0 r2 6.0 +BOUNDS + UP bnd1 c1 20.0 +QUADOBJ + c1 c1 8.0 + c1 c2 2.0 + c2 c2 10.0 +ENDATA diff --git a/examples/Data/randomGrid3D.xml b/examples/Data/randomGrid3D.xml new file mode 100644 index 000000000..6a82ce31c --- /dev/null +++ b/examples/Data/randomGrid3D.xml @@ -0,0 +1,3414 @@ + + + + + + + 32 + 1 + + + + + + 2 + 0 + 0 + 1 + + + + + + 9 + 7 + + 3.20776022311033415e+01 + -3.21030367555546334e+01 + -4.10921918858809718e+01 + -2.97297166857905353e+01 + 5.12273135695288744e+01 + 5.32024088136580744e+01 + 7.91786461660617107e+01 + 6.02804880595302208e+01 + -3.20503372222358784e+00 + -4.49785699465720157e+00 + 9.06604158034029126e+01 + 5.65784169718906416e+00 + 3.12765298180226239e+01 + 2.69796747523965372e+01 + 6.45574939874757661e+01 + -3.41086208590283135e+01 + 3.16243899688174857e+01 + -6.07548743284260979e+01 + 5.22759578856884062e+01 + 2.73875651690404389e+01 + -6.70630095670253041e+01 + 8.09592862312814248e+01 + -2.90562646005293850e+01 + 1.97217242898365228e+01 + 1.92063557124931243e+01 + -3.42017680808024593e+01 + 5.18983240742203904e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + -0.00000000000000000e+00 + -8.81008786560076906e+00 + 9.93170954106413291e+01 + 7.64832733308121160e+00 + 9.74088247837876793e+01 + 6.98423466470551624e+00 + 2.15114230210294117e+01 + 8.81008786560076906e+00 + -9.93170954106413291e+01 + -7.64832733308121160e+00 + -0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 2.08303433971152465e+01 + 9.34532104006540187e+00 + -9.73589326595991906e+01 + -9.74088247837876793e+01 + -6.98423466470551624e+00 + -2.15114230210294117e+01 + -2.08303433971152465e+01 + -9.34532104006540187e+00 + 9.73589326595991906e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + -9.96847734946016431e+01 + -9.41956956915240795e+00 + 3.58611803229205250e+01 + 1.37202268725982691e+02 + 8.31655615217660085e+01 + -2.96050013164699770e+01 + 5.56978428429618404e+01 + -1.64096733189184050e+02 + -6.76911341847846018e+01 + + + + 4 + 0 + 0 + 3 + 6 + 7 + + 0 + 9 + 0 + + + + + + + + + + + + 2 + 0 + 1 + 2 + + + + + + 9 + 7 + + -5.23677913323444741e+01 + 2.23054746283748031e+01 + -9.06323879014932388e+00 + 5.52805622243718773e+01 + 7.94539068269289146e+01 + 1.94541508392102571e+01 + -6.13821741431047201e+01 + 5.56974973159738553e+01 + -7.78665862090978944e+00 + -3.50785425178010168e+00 + -8.59643527732278869e+01 + 4.37949256925254957e+01 + 1.46448346762102268e+01 + -9.84525875940883211e+00 + -6.31187688571179351e+01 + -1.68743787040301001e+01 + 4.96429783126596220e+01 + 6.02933235638437850e+01 + -8.50324227920073668e+01 + -8.14408668091479448e+00 + 7.80614049299559465e+00 + -3.12168328896096590e+01 + -8.16862254520412101e+00 + 7.01147846710003364e+01 + 4.14413157080187986e+01 + -1.74987783157454646e+00 + 7.04591203724149580e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + -0.00000000000000000e+00 + -2.60374020501451531e+00 + -5.42127786775135831e+01 + 8.39892562474970532e+01 + -9.97226081614345645e+01 + 7.26909685044996312e+00 + 1.60051631037066500e+00 + 2.60374020501451531e+00 + 5.42127786775135831e+01 + -8.39892562474970532e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + -6.97294474564191535e+00 + -8.37146036187337330e+01 + -5.42516652512392241e+01 + 9.97226081614345645e+01 + -7.26909685044996312e+00 + -1.60051631037066500e+00 + 6.97294474564191535e+00 + 8.37146036187337330e+01 + 5.42516652512392241e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.08200476037924709e+01 + 1.28950357649989712e+02 + 1.43352339174516089e+02 + -2.38602247867744630e+01 + -5.20893463997723600e+01 + 2.84608516229487805e+01 + 6.76429765595175212e+01 + 1.20773294728176111e+02 + -1.20589752280510609e+02 + + + + 4 + 0 + 0 + 3 + 6 + 7 + + 0 + 9 + 0 + + + + + + + + + + + + 2 + 0 + 2 + 3 + + + + + + 9 + 7 + + -1.96993691143317093e+01 + -2.72709220997507202e+01 + 4.46131383257576886e+01 + 9.30649268771392428e+01 + 3.22308546546604946e+00 + -1.69350730671129561e+01 + -3.00372292195983448e+01 + 4.73051200126789553e+01 + -6.91348627543176519e+01 + 8.77985890195871921e-01 + 2.95766095687473936e+01 + -7.96244285285575017e+01 + 7.31430977105361357e+00 + 9.52212779955403192e+01 + 2.32608409272044945e+01 + -1.06369613385613393e+00 + -2.30114188850419632e+00 + -5.58240668503478901e+01 + 8.63825257313862096e+01 + 3.81456041339674954e+01 + 2.72998827723357493e+01 + 3.09037953339841458e+01 + -1.77447464898715950e+01 + -1.04957062263738177e+01 + 3.97018822008379715e+01 + -7.27393475106917862e+01 + -4.57204758371371796e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + -4.59114589009974594e+01 + 8.09444187944725400e+01 + 3.66079090854293696e+01 + -7.62990082722604797e+01 + -1.48208463505055157e+01 + -6.29190261377608593e+01 + 4.59114589009974594e+01 + -8.09444187944725400e+01 + -3.66079090854293696e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + -4.55038380606685564e+01 + -5.68185144075392898e+01 + 6.85642555729200751e+01 + 7.62990082722604797e+01 + 1.48208463505055157e+01 + 6.29190261377608593e+01 + 4.55038380606685564e+01 + 5.68185144075392898e+01 + -6.85642555729200751e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + -8.55922050845758786e-01 + 1.40043738778271234e+02 + -3.81613152068798769e+01 + -5.81227180496655009e+01 + -3.94713178138164338e+01 + 3.22753989340650662e+01 + 1.32631681079235051e+02 + -3.12863815406522541e+01 + -4.03072840384836510e+01 + + + + 4 + 0 + 0 + 3 + 6 + 7 + + 0 + 9 + 0 + + + + + + + + + + + + 2 + 0 + 3 + 4 + + + + + + 9 + 7 + + 8.66048172555662319e+01 + -1.52328612569721304e+01 + 4.48534445123967629e+01 + 2.02981055828854124e+01 + -4.93746572823205057e+01 + -2.74451016941264996e+01 + 4.12224960002507945e+00 + -6.40449795031895519e+01 + -5.03376341440287618e+01 + 4.92248012617162161e+01 + 3.93527186553859920e+01 + -6.89623533878909143e+01 + -4.08605085624496382e+01 + 5.95700970246627293e+01 + 3.55176671176527492e+01 + 9.26276585311693879e+00 + -6.84332455006064038e+01 + 4.88721436512163976e+00 + -4.03054194818879719e+00 + -1.78980733327891492e+01 + 3.45198923956961394e+01 + -8.80228615455582002e+01 + -4.55655125601066899e+01 + -9.64228954249413128e+00 + 1.13078887631363152e+01 + -3.24259783798813004e+01 + 8.58793556515557270e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + -0.00000000000000000e+00 + -8.08548316492842929e+01 + 5.81668844249688917e+01 + 8.89436648998715995e+00 + 4.55868302729299728e+01 + 5.23625800953892124e+01 + 7.19722245829668879e+01 + 8.08548316492842929e+01 + -5.81668844249688917e+01 + -8.89436648998715995e+00 + -0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 3.72066809139564114e+01 + 6.22476807764455131e+01 + -6.88541148612105047e+01 + -4.55868302729299728e+01 + -5.23625800953892124e+01 + -7.19722245829668879e+01 + -3.72066809139564114e+01 + -6.22476807764455131e+01 + 6.88541148612105047e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + -4.49706199136485765e+01 + 2.66285359051983370e+01 + 1.14028652024075640e+02 + 5.86398529753103119e+01 + 8.34746189227890056e+00 + 1.60810773504427289e+02 + 1.79694799386287997e+02 + -4.53728709677613509e+01 + -1.70780906392258842e+01 + + + + 4 + 0 + 0 + 3 + 6 + 7 + + 0 + 9 + 0 + + + + + + + + + + + + 2 + 0 + 4 + 5 + + + + + + 9 + 7 + + 6.43003424386522084e+01 + 1.19796180071396279e+01 + 4.55761542738693137e+01 + -6.52039759607597773e+01 + 5.89636417155482349e+01 + 1.80719252805888360e+01 + -1.51516354244859457e+01 + -5.00500232613797280e+01 + -5.34352949392747476e+01 + 7.42583468150113362e+01 + 7.45315542640838657e+00 + -5.24573072801267415e+01 + 4.09274245687232323e+01 + -1.68412174720425938e+01 + -1.36705786744805522e+01 + 2.70644906205976383e+01 + -8.31804320954470597e+01 + 4.33744783589924054e+01 + -1.22788002717957223e+01 + -6.11064170046755617e+00 + -7.16592171005377452e+01 + -5.30800076837930419e+01 + -7.82610172559931669e+01 + 2.92797087670289500e+01 + -2.22315273959740871e+01 + -2.13187310855278938e+01 + -6.26781275987031279e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 6.86610695050494400e+01 + 1.26119199040840346e+01 + 7.16002584545316836e+01 + -7.26277336162735736e+01 + 1.63646703530006263e+01 + 6.67638365734117087e+01 + -6.86610695050494400e+01 + -1.26119199040840346e+01 + -7.16002584545316836e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + -3.29694467444833483e+00 + -9.78424092128285139e+01 + 2.03959092771819215e+01 + 7.26277336162735736e+01 + -1.63646703530006263e+01 + -6.67638365734117087e+01 + 3.29694467444833483e+00 + 9.78424092128285139e+01 + -2.03959092771819215e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.74531092467603024e+01 + -9.68528064078233442e-01 + -1.43955992851650620e+01 + -3.71890171910416072e+01 + 2.70827825121624883e+01 + 1.59657441575989878e+02 + -1.61093211332558155e+02 + -2.36356649401689936e+01 + -3.50656643781457547e+01 + + + + 4 + 0 + 0 + 3 + 6 + 7 + + 0 + 9 + 0 + + + + + + + + + + + + 2 + 0 + 5 + 6 + + + + + + 9 + 7 + + -6.40637543398504619e+01 + -1.35919926214779476e+01 + -7.55586787939104454e+01 + 7.49591051894634859e+01 + -1.51203828101076443e+01 + -6.04179319959996945e+01 + 1.63126149967003826e+01 + -3.67352169146467711e+00 + -1.49855747686980401e+01 + -7.64033153697704415e-01 + 5.83204655642280656e+00 + -2.26064773215979020e+00 + -1.21801830224353154e+01 + 9.23282518419687364e+01 + -3.58808093806811215e+01 + 6.76481543691339766e+01 + 3.42590164955414807e+01 + 6.51923982648987277e+01 + -2.26801968652302843e+00 + -9.78783400225560598e+01 + 1.94155506146273105e+01 + 1.64832141235940597e+01 + 2.49817026599325320e+00 + -1.62466150125265507e+01 + -7.07730069025061255e+01 + 1.59540577889256383e+01 + 6.50575730811547004e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + -0.00000000000000000e+00 + -2.60428350122129437e+01 + -6.97694761102178944e+01 + 6.67382270354284231e+01 + -9.26426416957655618e+01 + 3.75218214997053465e+01 + 3.07471152699694139e+00 + 2.60428350122129437e+01 + 6.97694761102178944e+01 + -6.67382270354284231e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + -2.71866085445878198e+01 + -6.10273144964611944e+01 + -7.44080318325472234e+01 + 9.26426416957655618e+01 + -3.75218214997053465e+01 + -3.07471152699694139e+00 + 2.71866085445878198e+01 + 6.10273144964611944e+01 + 7.44080318325472234e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.03933661487596595e+02 + 4.68471191704998802e+01 + 1.18875204735324314e+01 + -2.97055153316788463e+01 + 7.27443939906840598e+01 + 7.23444094058463492e+01 + 3.82415703375670404e+01 + -2.27415768204949451e+01 + -3.07813391103898937e+01 + + + + 4 + 0 + 0 + 3 + 6 + 7 + + 0 + 9 + 0 + + + + + + + + + + + + 2 + 0 + 6 + 7 + + + + + + 9 + 7 + + 1.85630374271583953e+01 + -5.29313735130414926e+01 + 3.66303674355102942e+01 + 1.04645716047590440e+01 + 5.73485858047936077e+01 + -5.08591115829850366e+01 + 9.38445241664948213e+01 + -1.36042785531324792e+01 + -2.31303222840427054e+01 + -9.56612084104992455e+00 + -2.98701442261074703e+01 + 7.62840716168778670e+01 + -1.92910486636706899e+01 + -5.04699434611332478e+01 + 3.46538201809487560e+01 + 3.08818026153629788e+01 + 7.17821170583860777e+01 + 5.45013702935509130e+01 + -5.34080385938858839e+01 + 6.23631140795577465e+01 + 4.43545654716690905e+01 + -7.95485560661077074e+01 + -2.30201810552558968e+01 + -5.51074857191607634e+01 + 1.18903119380668851e+01 + -2.67045605220385767e+01 + -2.32776001751549053e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.79872266803328138e+01 + 8.64209977399809475e+01 + -4.69879859748907549e+01 + 9.82455450157955568e+01 + -1.33902787243874393e+01 + 1.29812680517931049e+01 + -1.79872266803328138e+01 + -8.64209977399809475e+01 + 4.69879859748907549e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 4.92671908064704667e+00 + -4.84985730234346519e+01 + -8.73133200250165942e+01 + -9.82455450157955568e+01 + 1.33902787243874393e+01 + -1.29812680517931049e+01 + -4.92671908064704667e+00 + 4.84985730234346519e+01 + 8.73133200250165942e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + -8.68503697620646733e+01 + -6.63265206223623283e-01 + 5.77899517416623070e+01 + 1.54728954524297080e+02 + -7.36729123490597857e+01 + -4.33714485898333280e+01 + -8.08065933920789270e+00 + -1.49263004123200204e+02 + 1.24142002075972883e+02 + + + + 4 + 0 + 0 + 3 + 6 + 7 + + 0 + 9 + 0 + + + + + + + + + + + + 2 + 0 + 7 + 8 + + + + + + 9 + 7 + + 4.74062871911341759e+01 + 5.71222009314007693e+01 + -2.90538462259461063e+01 + 4.09276699085499303e+01 + 3.99974137866047528e+01 + -1.99073676332006535e+01 + -7.78029399881401531e+01 + 5.27745236895511312e+01 + -3.37039333639074385e+01 + -9.12848490867447815e+00 + -6.92290536396862421e+01 + -2.32360574632871630e+00 + 1.58993825041621264e+01 + 5.31010116114126660e+01 + -6.55564733827918502e+01 + -3.41955054720470475e+00 + 4.69927897084473187e+01 + 7.43534572740371971e+01 + -6.28440645552295862e+01 + 4.27829075558255525e+01 + 5.46299457034644860e+01 + 7.56316908352858093e+01 + 1.42185369226067397e+01 + 5.51031175481571864e+01 + 2.63284733063378651e+00 + 2.23353419791525312e+01 + 4.20873574259948739e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.80585028832817862e+01 + -9.52829540657210430e+01 + -2.43936290478516966e+01 + -9.74947022342857252e+01 + -2.06160114466111395e+01 + 8.35243127964282905e+00 + -1.80585028832817862e+01 + 9.52829540657210430e+01 + 2.43936290478516966e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + -1.29874366163019737e+01 + 2.22741719608807998e+01 + -9.66187753679099757e+01 + 9.74947022342857252e+01 + 2.06160114466111395e+01 + -8.35243127964282905e+00 + 1.29874366163019737e+01 + -2.22741719608807998e+01 + 9.66187753679099757e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 7.39787443001634273e+01 + -3.29520218737291373e+01 + 1.75142945360573606e+02 + -4.89974435425370416e+01 + -9.39530685963477481e+01 + -3.92888663032043226e+01 + 4.46158732311312889e+01 + 1.62422063134678211e+02 + -1.51571321993876627e+01 + + + + 4 + 0 + 0 + 3 + 6 + 7 + + 0 + 9 + 0 + + + + + + + + + + + + 2 + 0 + 8 + 9 + + + + + + 9 + 7 + + 9.41130157063151671e+01 + 1.30096002577236085e+01 + -9.65142385029295902e+00 + -2.97023439769390656e+01 + 3.10157410489098062e-01 + 4.06407354840771795e+00 + -9.58311576289570155e+00 + 9.66152903465384156e+01 + 2.35615250878309794e+01 + 1.77277266667175297e+01 + -4.94856229862016690e+01 + 8.47852845508831336e+01 + 1.34310978254269742e+01 + -8.43883523083151488e+01 + -5.15167787166412623e+01 + 3.41073399110957187e-01 + 2.18139939555895035e+00 + 9.36548913434189423e+00 + -2.80240621096084510e+01 + -7.66577929709818839e+00 + 9.19688865464188510e+00 + -9.38736839860108603e+01 + -1.81862826844923511e+01 + 1.54239226370280336e+00 + -8.73344590429244683e+00 + 2.30576115914954443e+01 + -9.65297250180462356e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + -9.99929178544290664e+01 + 6.62091181731783163e-01 + -9.88946016968861308e-01 + -6.23564336177379053e-01 + 4.16306145486879302e+01 + 9.09203118110426516e+01 + 9.99929178544290664e+01 + -6.62091181731783163e-01 + 9.88946016968861308e-01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.01367967132287018e+00 + 9.09200394168724984e+01 + -4.16235376434812636e+01 + 6.23564336177379053e-01 + -4.16306145486879302e+01 + -9.09203118110426516e+01 + -1.01367967132287018e+00 + -9.09200394168724984e+01 + 4.16235376434812636e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 5.55282235936336566e+00 + -1.76495493086246057e+02 + -9.69626169859593645e+00 + -1.18086675146736617e+01 + 9.21060305839002780e+01 + 5.32168712759193419e+00 + 1.99148216329777483e+02 + 1.06989143861811957e+01 + -5.26829527913709494e+00 + + + + 4 + 0 + 0 + 3 + 6 + 7 + + 0 + 9 + 0 + + + + + + + + + + + + 2 + 0 + 9 + 10 + + + + + + 9 + 7 + + -8.63087793249897430e+01 + -1.92823330270961684e+01 + -4.42211315553459627e+01 + 2.21505354932965801e+01 + -2.63320996942306031e+01 + -5.69788664986630025e+01 + -4.53775288609686314e+01 + 2.58526272351369890e+01 + 5.53658756361871127e+01 + -1.54315640909267664e+01 + -4.32654755327350813e+01 + 1.97045712499729326e+01 + 7.39853470327932428e+01 + -5.76879953686396973e+01 + 2.69216116215563304e+01 + 6.54801163688819514e+01 + 5.53812651216026666e+01 + -2.49089008945160231e+01 + -9.71189061792836705e-01 + -7.25245368327360609e+01 + 4.96429238183381116e+01 + 6.85930292060070612e-01 + -1.12841816293779988e+01 + -7.69094846357958062e+01 + -5.16757922033419734e-02 + -6.79147932987382035e+01 + -4.02434226181160639e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 7.83449748282976799e+01 + 6.13201754047114846e+01 + 1.00946028891096997e+01 + -1.98027611608243852e+01 + 9.23644092983748521e+00 + 9.75834966034573341e+01 + -7.83449748282976799e+01 + -6.13201754047114846e+01 + -1.00946028891096997e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 5.89059892503364324e+01 + -7.84507759508154265e+01 + 1.93793752003053505e+01 + 1.98027611608243852e+01 + -9.23644092983748521e+00 + -9.75834966034573341e+01 + -5.89059892503364324e+01 + 7.84507759508154265e+01 + -1.93793752003053505e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + -1.06986312175636783e+02 + 1.28415573927117009e+02 + 5.26747761738054123e+01 + -8.33248123208498015e+01 + -6.72578872464476092e+01 + 1.08240234163658471e+02 + -1.79030185090507175e+01 + -1.01966657528716965e+02 + 5.84227812301104876e+01 + + + + 4 + 0 + 0 + 3 + 6 + 7 + + 0 + 9 + 0 + + + + + + + + + + + + 2 + 0 + 10 + 11 + + + + + + 9 + 7 + + 1.17302291731448682e+00 + 2.23736436785092039e+01 + 8.70065012231049764e+01 + 7.67707833816357947e+01 + 5.73162887867323292e+01 + -1.32881532104113664e+00 + -2.51982778355239070e+01 + -7.72901736529863381e+00 + 4.53049731782644329e+01 + 8.54937155952362531e+01 + -4.11223504877864485e+01 + 2.12416634370425328e+01 + -2.90259802009985357e+01 + -8.76138896821732693e+00 + -5.06100435935214055e+00 + -3.81597643193563130e+01 + -9.02600433698408864e+01 + 7.99447271884073940e-01 + -2.24916749275050378e+01 + 2.24299023473424732e+01 + 3.83080111263447165e+01 + -5.03856743318980023e+01 + 7.20086537445330919e+01 + -4.63731853719149143e+01 + 2.85914723565250490e+01 + -2.34837711903294171e+01 + -7.92472197577816644e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + -2.63903093070078647e+01 + -2.67183596992454575e+01 + 9.26805310173727577e+01 + -8.93547271763020774e+01 + 4.29554589851731663e+01 + -1.30599109729635039e+01 + 2.63903093070078647e+01 + 2.67183596992454575e+01 + -9.26805310173727577e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + -3.63219534982506076e+01 + -8.62609865371063478e+01 + -3.52101959056759028e+01 + 8.93547271763020774e+01 + -4.29554589851731663e+01 + 1.30599109729635039e+01 + 3.63219534982506076e+01 + 8.62609865371063478e+01 + 3.52101959056759028e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + -1.04067559180773088e+01 + 7.90108728350369383e-01 + 5.78189525430708571e+01 + -1.16280923178694167e+02 + 8.10714898076704600e+01 + 7.53829806570444134e+01 + -5.78201683295110769e+01 + 6.19589188064910701e+01 + -1.33505720595716895e+02 + + + + 4 + 0 + 0 + 3 + 6 + 7 + + 0 + 9 + 0 + + + + + + + + + + + + 2 + 0 + 11 + 12 + + + + + + 9 + 7 + + 3.68344254692879192e+00 + 4.86691203808377892e+00 + -1.57231292941544805e+01 + 3.72290369400325147e+01 + 2.06331817836064921e+01 + -8.89534944072540839e+01 + -8.53296212948073389e+01 + 4.59306709423131920e+01 + -2.45010409318042690e+01 + 2.57025147685637876e+01 + 2.56000347344376031e+01 + -9.16529948262070491e+01 + 2.63288801817711970e-01 + 6.59382843634221683e+00 + 1.98864164108950128e+01 + -3.68109153857383404e+01 + -8.63480489179755466e+01 + -3.21511205713796500e+01 + 8.19562719339757138e+01 + -5.68704775649636858e+01 + 6.94175446640136773e+00 + -5.03482257069523769e+01 + -7.72158009035328661e+01 + -3.65965187643956114e+01 + -7.19547325119217618e+00 + -9.46558534641098959e+00 + -4.77765582369805042e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + -7.29991262018860425e+01 + 6.43134564832916169e+01 + -2.31280541536218962e+01 + -5.24720785637083011e+01 + -7.44213220616246360e+01 + -4.13297446617319864e+01 + 7.29991262018860425e+01 + -6.43134564832916169e+01 + 2.31280541536218962e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + -4.37927910159324512e+01 + -1.80345817187895037e+01 + 8.80735222258265793e+01 + 5.24720785637083011e+01 + 7.44213220616246360e+01 + 4.13297446617319864e+01 + 4.37927910159324512e+01 + 1.80345817187895037e+01 + -8.80735222258265793e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 9.48709591330575535e+01 + 9.60518679589807789e+01 + -5.19581436253384297e+01 + 2.54957713470891250e+01 + -1.34158356561916207e+02 + -2.25547332522903439e+01 + 1.09221138500000791e+02 + -4.57450052559468858e+01 + -6.82129290695598485e+01 + + + + 4 + 0 + 0 + 3 + 6 + 7 + + 0 + 9 + 0 + + + + + + + + + + + + 2 + 0 + 12 + 13 + + + + + + 9 + 7 + + 1.93941690967042213e+01 + -3.90998618366849584e+01 + 1.63698620253740224e+00 + 1.66123034210985914e+01 + 8.85555525420248557e+01 + 2.63934202043697148e+01 + -8.61979615512473032e+01 + 1.74318161103396001e+01 + -3.92907393347052789e+01 + -7.36585675537442341e+01 + 5.45643959900256945e+01 + -4.73596788713465688e+00 + 1.23230795012408407e+01 + 3.75671217770436385e+01 + -8.32914041112130690e+01 + -4.08563087068878872e+01 + 8.53843323058891990e+00 + 3.64960868565984242e+01 + -6.45808132649689668e+01 + -7.41043072657268738e+01 + -2.22937919750649804e+00 + -1.10797951271104100e+00 + -1.86389067743133623e+01 + -4.83331185591061043e+01 + 2.23431972515867372e+01 + -4.99220528272985842e+00 + -8.44039814228390526e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + -0.00000000000000000e+00 + 5.32207681440972067e+01 + -3.06680603945050478e+01 + 7.89114688102511224e+01 + -5.56684880542022569e+01 + -8.29014582098623265e+01 + 5.32613034365356164e+00 + -5.32207681440972067e+01 + 3.06680603945050478e+01 + -7.89114688102511224e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 6.37853374680371630e+01 + -4.67634290692784660e+01 + -6.11932383991170568e+01 + 5.56684880542022569e+01 + 8.29014582098623265e+01 + -5.32613034365356164e+00 + -6.37853374680371630e+01 + 4.67634290692784660e+01 + 6.11932383991170568e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + -6.90389218165145877e+01 + 4.83379444724982577e+01 + 1.61042728694415416e+02 + -1.53499694264126390e+02 + -6.29210660700233788e+01 + -1.36328982272427429e-01 + -7.32570951739669738e+01 + -6.73028752573054874e+01 + -7.84207879822722163e+01 + + + + 4 + 0 + 0 + 3 + 6 + 7 + + 0 + 9 + 0 + + + + + + + + + + + + 2 + 0 + 13 + 14 + + + + + + 9 + 7 + + 6.06804300720567937e+01 + 6.78223389316968621e+01 + 1.14214673416742691e+01 + 2.85045083366314387e+01 + 2.67345752695483867e+01 + 9.28156907783291274e+00 + -3.79052729172203868e+01 + 4.99857449838935750e+01 + -7.77096553357260120e+01 + -7.82277784247720263e+01 + 5.40246939742984793e+01 + 2.32633737948870305e+01 + 2.47956201341556586e+01 + -1.05317240685613065e+01 + 9.52360095902563302e+01 + -1.29078256939381077e+01 + 9.88755369559818398e+00 + 1.89881719971782701e+01 + 9.09983932556493968e+00 + 4.26215664457260388e+01 + 1.04271324229186870e+01 + -6.00988012459201499e+01 + -6.92347566083080466e+01 + 1.36255057217382767e+01 + 5.89311254734215737e+01 + -4.94916274785966195e+01 + -5.89796648826666967e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + -2.89030917873941853e+01 + 8.70749520313458305e+01 + -3.97814531392241904e+01 + -9.56630827209552450e+01 + -2.78467078053438328e+01 + 8.55192777842975183e+00 + 2.89030917873941853e+01 + -8.70749520313458305e+01 + 3.97814531392241904e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + -3.63123800557649812e+00 + 4.05279359595652906e+01 + 9.13471429077244466e+01 + 9.56630827209552450e+01 + 2.78467078053438328e+01 + -8.55192777842975183e+00 + 3.63123800557649812e+00 + -4.05279359595652906e+01 + -9.13471429077244466e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.43780450624784670e+01 + -6.63129258801445189e+01 + 4.67182022743824987e+00 + -2.52301003257763057e+01 + -9.40350333946463337e+01 + -1.71054540098886392e+01 + 9.90721820600476235e+01 + -1.66885836907954435e+01 + 5.08294565998758543e+01 + + + + 4 + 0 + 0 + 3 + 6 + 7 + + 0 + 9 + 0 + + + + + + + + + + + + 2 + 0 + 14 + 15 + + + + + + 9 + 7 + + -2.76355843137293995e+01 + -7.18186699571359952e+01 + 3.07651775764515065e+01 + -6.40640399324160086e+01 + -2.68919032866484322e+01 + 9.38443754617159698e+00 + -7.15464009647350991e+01 + 4.97633461308791567e+01 + -2.49225935590679519e+01 + 1.43932895637872207e+01 + -2.88438285303894943e+01 + 6.70843814351506182e+01 + -2.31361564910724091e+01 + 9.02877315480068603e+01 + 3.51897296575981642e+01 + 1.03017517985169054e+01 + -1.55151545070516619e+01 + 6.47165615401468699e+01 + 5.11107200952757168e+01 + 4.26513944039867638e+01 + 5.62224381230135037e+01 + -6.85270728206629229e+01 + -1.63576632701424352e+01 + 1.39839419419296167e+01 + 4.30853333607984084e+01 + -1.81999495152501289e+01 + -7.11401633803200042e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + -8.15059339771809164e+01 + -5.54598536753216109e+01 + -1.67626774955357369e+01 + -1.04808841952049807e+01 + 4.25686446848321935e+01 + -8.98780371179923492e+01 + 8.15059339771809164e+01 + 5.54598536753216109e+01 + 1.67626774955357369e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 5.69818724946287603e+01 + -7.14990567770542356e+01 + -4.05086544703406517e+01 + 1.04808841952049807e+01 + -4.25686446848321935e+01 + 8.98780371179923492e+01 + -5.69818724946287603e+01 + 7.14990567770542356e+01 + 4.05086544703406517e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + -0.00000000000000000e+00 + 2.31230716791378725e+01 + 2.46912491883496621e+01 + 3.19609408881894597e+00 + 1.52981265769411010e+01 + 1.32876273309615431e+01 + 2.19836964146123970e+00 + 2.74814898754146313e+01 + -2.79167095337952915e+01 + 5.37372498127196874e+00 + + + + 4 + 0 + 0 + 3 + 6 + 7 + + 0 + 9 + 0 + + + + + + + + + + + + 2 + 0 + 15 + 16 + + + + + + 9 + 7 + + -5.10421334268497020e+01 + -3.97471595810313332e+01 + -1.64389363316277826e+00 + 2.54089618298921245e+01 + -3.15327493370988705e+01 + 9.13980507822707153e+01 + -5.91789668556331776e+01 + -4.81012757100621684e+01 + 1.65563384387473489e+00 + -6.78890977332195860e+01 + -3.50650650222022904e+01 + -8.69105008709039062e+00 + -5.80472933502369273e+01 + 6.88255140605843536e+01 + 3.93666342323419940e+01 + 4.37233513120340049e+01 + 4.71317258377345070e+01 + 1.72241668652535651e+01 + -4.44141172746378885e+01 + 7.81566561420669927e+01 + -4.26269969902096406e+01 + 1.02994128500864690e+01 + -1.21754201166700025e+01 + -9.79654030213998794e+00 + -3.57503904294827279e+01 + 2.58360247551576450e+01 + 8.83514468333149239e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + -8.11187605223852870e+01 + -5.83599337897738124e+01 + 3.72354929672284474e+00 + 4.13366904132922599e+01 + -5.27200270517053724e+01 + 7.42420148793328991e+01 + 8.11187605223852870e+01 + 5.83599337897738124e+01 + -3.72354929672284474e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + -4.13645345312568224e+01 + 6.17633943021323262e+01 + 6.68898976474907556e+01 + -4.13366904132922599e+01 + 5.27200270517053724e+01 + -7.42420148793328991e+01 + 4.13645345312568224e+01 + -6.17633943021323262e+01 + -6.68898976474907556e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 6.98804353612945732e+01 + -9.46593060564561881e+01 + -1.56916014852066439e+02 + -3.53367495425767473e+01 + -1.16911080827186709e+02 + 7.34112761651981316e+01 + 2.36033204137547230e+01 + 1.27622949564988858e+02 + -4.72506285651327431e+01 + + + + 4 + 0 + 0 + 3 + 6 + 7 + + 0 + 9 + 0 + + + + + + + + + + + + 2 + 0 + 16 + 17 + + + + + + 9 + 7 + + -5.85435867217505290e+01 + 2.33746012476837990e+01 + -5.77863483723881544e+01 + -5.63329646716383934e+01 + -7.47638541726440593e+01 + 3.41977282497739097e+01 + -4.10879444630993547e+01 + 7.01966859196727366e+00 + -3.18903501380708931e+01 + 7.49027535040175820e+01 + -1.88037812404022127e+01 + -5.50573390958028739e+01 + -1.05105126900153234e+01 + 3.04370847103721403e+01 + 2.74657650627104459e+01 + -5.06989372188159564e+01 + -7.70752893724180126e+01 + -2.65036593071036783e+01 + -8.31624785461406368e+00 + 7.75118867469858053e+00 + -5.96862946091213260e+01 + 3.40815941189988152e+01 + -5.16283223754141716e+01 + -6.67021661737265248e+01 + 4.67870803895238083e+01 + -6.21976850537821235e+01 + 4.44353424269327562e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + -9.98522291990096846e+01 + -2.17344032867269910e+00 + 4.98081129196222250e+00 + -1.69510675143138556e+00 + -7.46243396331473150e+01 + -6.65457327513788073e+01 + 9.98522291990096846e+01 + 2.17344032867269910e+00 + -4.98081129196222250e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 5.16322932762926534e+00 + -6.65318276575533361e+01 + 7.44772245149880234e+01 + 1.69510675143138556e+00 + 7.46243396331473150e+01 + 6.65457327513788073e+01 + -5.16322932762926534e+00 + 6.65318276575533361e+01 + -7.44772245149880234e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + -3.50474015754750923e+01 + -2.85468905697825797e+01 + -8.26608268609589487e+01 + 7.28338697761986396e+01 + -1.03233140690458100e+02 + -6.32144076335772187e+00 + 4.02504937228882511e+01 + 1.40718088483059116e+01 + 7.44299004116042227e+01 + + + + 4 + 0 + 0 + 3 + 6 + 7 + + 0 + 9 + 0 + + + + + + + + + + + + 2 + 0 + 17 + 18 + + + + + + 9 + 7 + + -8.82393493416751795e+01 + -6.12481728289156635e+00 + 6.45898243198292366e-01 + 3.86841248560220095e+01 + -4.52281770219861770e+01 + -4.30849606407744687e+01 + -2.62811256127213326e+01 + -5.90797411700203270e+01 + -5.09550094510600857e+01 + 4.68685179819303457e+01 + -2.73625956906887646e+00 + 1.87456681275038339e+00 + 7.09242852066529537e+01 + -3.96201491012311280e+01 + 4.26233675831482230e+01 + -5.26328438238840803e+01 + -5.34225198350244597e+01 + 6.12486839444391720e+01 + -3.76709521788862034e+00 + 9.35400534400023815e+01 + -3.47030072986988287e+01 + 3.20432748703922687e+00 + 2.41487264929615755e+01 + 7.47759826419143678e+01 + -2.25246616168526836e+00 + -2.57366654666450962e+01 + -5.63865719112063317e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 9.03046090553630876e+01 + 2.33581936525576914e+01 + -3.60481951371722431e+01 + 1.31196185024049097e+01 + -9.49105504326207523e+01 + -2.86332503730943557e+01 + -9.03046090553630876e+01 + -2.33581936525576914e+01 + 3.60481951371722431e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + -4.09017504968844747e+01 + 2.11277591302666750e+01 + -8.87731074167399186e+01 + -1.31196185024049097e+01 + 9.49105504326207523e+01 + 2.86332503730943557e+01 + 4.09017504968844747e+01 + -2.11277591302666750e+01 + 8.87731074167399186e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + -0.00000000000000000e+00 + 4.26251548517658989e+01 + -5.58446106332349572e+01 + -4.99134201995332649e+00 + 7.19670254876823492e+01 + -1.87430011171921045e+01 + -5.57531304221817550e+01 + -9.47135556308831283e+00 + -7.80687492596315167e+01 + 5.77908380638228465e+01 + + + + 4 + 0 + 0 + 3 + 6 + 7 + + 0 + 9 + 0 + + + + + + + + + + + + 2 + 0 + 18 + 19 + + + + + + 9 + 7 + + 6.21423423624779545e+01 + 1.02374321697767794e+01 + -2.61952819865811541e+01 + 1.64810134236028816e+01 + -9.33026901138422886e+01 + -2.97993293115291316e+01 + 6.47591857034336442e+01 + 2.72657426895055011e+01 + -2.33482872492159856e+01 + -6.84639855508772825e+01 + -1.58264297171629540e+01 + 2.10899487969025330e+01 + -3.01026938649666285e+01 + 2.36828763275138563e+01 + -9.22944706954510821e+01 + 6.50721593326321113e+01 + 1.34399733570446998e+01 + -1.47336875153178202e+01 + 1.81996160352434408e+01 + 5.50471142576061965e+01 + 8.12609439867173649e+01 + 3.09138639218085887e+00 + -1.18364488818499112e+01 + 7.45772273447166401e-02 + 3.87852402909780736e+01 + -7.92723675773540748e+01 + 4.57949875755143552e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + -7.14353163221378225e+01 + -6.97621833385175307e+01 + 5.49848686450887225e+00 + 4.54649938592219129e+01 + -4.02948505639650421e+01 + 7.94308463470498509e+01 + 7.14353163221378225e+01 + 6.97621833385175307e+01 + -5.49848686450887225e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + -5.31970855906319784e+01 + 5.92415630606653920e+01 + 6.05021263328172836e+01 + -4.54649938592219129e+01 + 4.02948505639650421e+01 + -7.94308463470498509e+01 + 5.31970855906319784e+01 + -5.92415630606653920e+01 + -6.05021263328172836e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 8.66602846584249278e+01 + -1.40571348898168708e+02 + -1.29029667681538402e+01 + -4.84107069228954998e+01 + -6.46593270163667029e+01 + 1.03797317950936275e+02 + 6.32154043923236131e+01 + 1.69243370521808174e+01 + -9.00005277714220426e+01 + + + + 4 + 0 + 0 + 3 + 6 + 7 + + 0 + 9 + 0 + + + + + + + + + + + + 2 + 0 + 19 + 20 + + + + + + 9 + 7 + + 5.40325063921370585e+01 + 5.12983919091620777e+00 + 4.24856501928409855e+01 + -6.01366381168498805e+01 + -6.66348312341534665e+01 + 1.23707663998909716e+01 + 2.51821654645419386e+01 + -4.49879933093015580e+01 + 6.61923323512717872e+01 + -8.16765559697753787e+01 + -1.72226454079742588e+01 + 3.80134460532522880e+01 + -3.51922609512735107e+01 + -2.39876166901732191e+01 + 7.97471671594631992e+00 + -4.83518374187914013e+00 + 8.66273522162050824e+01 + 4.67131848907273408e+01 + 1.17456223558336159e+01 + -5.59162876565777989e+00 + 8.16530126090797523e+01 + 6.71811935630704937e+01 + -7.04411581080473894e+01 + -2.09183319463410733e+01 + -1.56755267575532145e+01 + 1.18327312907135145e+01 + -5.35254607305620027e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + -0.00000000000000000e+00 + 1.72947781738215802e+01 + -7.37458142645349284e+01 + 6.52874071041194242e+01 + -9.78660995310737718e+01 + -5.39934004805816503e+00 + 1.98260860892763304e+01 + -1.72947781738215802e+01 + 7.37458142645349284e+01 + -6.52874071041194242e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + -1.10958195052130399e+01 + -6.73231164274660614e+01 + -7.31059558722925402e+01 + 9.78660995310737718e+01 + 5.39934004805816503e+00 + -1.98260860892763304e+01 + 1.10958195052130399e+01 + 6.73231164274660614e+01 + 7.31059558722925402e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + -5.38048032045895752e+00 + 1.65536142881929180e+02 + 8.22017033006773943e+01 + -7.27309788858385105e+01 + -1.01358249880792499e+01 + 1.16499706864703938e+02 + 7.80821322304104655e+01 + 9.19602704161340796e+01 + -8.91929751904364565e+01 + + + + 4 + 0 + 0 + 3 + 6 + 7 + + 0 + 9 + 0 + + + + + + + + + + + + 2 + 0 + 20 + 21 + + + + + + 9 + 7 + + 6.79396504738739537e+01 + 4.82037868237773779e+01 + -5.47024548652807283e+01 + -7.00832895591236564e+01 + 5.14309272143008727e+01 + -3.67255818969308834e+01 + 1.86928047352814559e+01 + -2.23350198922307115e+01 + 1.77311293144151279e+01 + 7.44105813075135192e+00 + 5.99087969415584212e+01 + 5.30460372996668283e+01 + -1.22158131494639797e+01 + -1.50072994727732638e+01 + -6.43870652455934760e+01 + -1.47523300546991756e+01 + 7.84637907473050689e+01 + -5.14524303561770466e+01 + 1.48130048314395335e+00 + -3.96193494527523526e+01 + -4.51446929817367320e+01 + 2.41623483145540554e+01 + -4.80504534286710054e+01 + -6.06763607845337773e+01 + 9.54718801387472098e+01 + 2.61345793187026096e+01 + 4.22977195343479639e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + -4.31638784413171734e+01 + 8.58566719453584426e+01 + 2.76678781327787284e+01 + -6.66070179567136051e+01 + -9.65155343163612223e+00 + -7.39618325575448523e+01 + 4.31638784413171734e+01 + -8.58566719453584426e+01 + -2.76678781327787284e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + -6.08307879023215037e+01 + -5.03535440542508113e+01 + 6.13525536906117850e+01 + 6.66070179567136051e+01 + 9.65155343163612223e+00 + 7.39618325575448523e+01 + 6.08307879023215037e+01 + 5.03535440542508113e+01 + -6.13525536906117850e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.33814642652391399e+02 + 1.77445244940366287e-01 + -1.49228346303260491e+01 + -6.12411970511728132e-01 + 5.97803936488639280e+01 + -1.02665793382055853e+02 + 2.53293581625552058e+01 + -3.42663008134674527e+01 + 5.61197444293587395e+01 + + + + 4 + 0 + 0 + 3 + 6 + 7 + + 0 + 9 + 0 + + + + + + + + + + + + 2 + 0 + 21 + 22 + + + + + + 9 + 7 + + -6.74405298173737435e+01 + 7.32759993494661614e+01 + -6.72758148030300518e+00 + 2.84952832715093294e+01 + 3.71106482095568992e+01 + 5.87105666468560798e+01 + 3.06497832963929113e+01 + 2.67945705145493136e+01 + 5.23800862467740629e+01 + -2.34193589858697777e+01 + -2.67958038635302600e+01 + 2.45872057837964846e+01 + 1.16252649553510334e+01 + 8.99424898505579051e+01 + -2.22061693363508326e+01 + 6.98562239082597500e+01 + -3.31539117547968303e+01 + -5.85832970823880999e+01 + 5.89049685210982901e+01 + 4.59874265404548481e+01 + -5.08083954437895216e+01 + -2.22191873368612889e+01 + 1.16539331220696187e+01 + -7.08270509506904347e+01 + 6.46018011815524602e+01 + 1.94415681363770645e+01 + 4.04539860386468320e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 9.78145711723120286e+01 + 1.76232674770143696e+01 + -1.10331368980137903e+01 + -1.40616464377447681e+01 + 1.69815554662718142e+01 + -9.75392068524539155e+01 + -9.78145711723120286e+01 + -1.76232674770143696e+01 + 1.10331368980137903e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + -1.53159970565603700e+01 + 9.69589976091932186e+01 + 1.90885572211179095e+01 + 1.40616464377447681e+01 + -1.69815554662718142e+01 + 9.75392068524539155e+01 + 1.53159970565603700e+01 + -9.69589976091932186e+01 + -1.90885572211179095e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + -2.25457773322750015e+01 + -1.39359117049240723e+02 + -1.01360767749937452e+02 + -1.06577486560693373e+02 + 3.69148207609075527e+01 + -6.52361857149522422e+01 + -9.51115531141346224e+01 + 7.07220482565039248e+01 + -3.57407782543718326e+01 + + + + 4 + 0 + 0 + 3 + 6 + 7 + + 0 + 9 + 0 + + + + + + + + + + + + 2 + 0 + 22 + 23 + + + + + + 9 + 7 + + 9.41929589378244003e+01 + 8.94097901372627391e+00 + 3.01620867599012286e+01 + 2.46922319059140740e+01 + 1.35465056881596215e+01 + -4.89963411381141611e+01 + -1.68344538935716344e+01 + -1.83167626535859007e+01 + 7.95313381974681306e+01 + -5.18828216803281350e+00 + -4.19655627938833504e+01 + -6.55823195034947481e+00 + 7.35562337314085681e+01 + 5.97403143502788865e+01 + -2.03387857576245445e-01 + 6.60668686562018337e+01 + -6.61937508072900442e+01 + -2.10487850516630495e+01 + 1.54947760148805180e+01 + -8.96286058833042887e+01 + -5.79472767879112993e+00 + -6.70795355915261116e+00 + -1.69646265262306706e+01 + -8.65671984840189168e+01 + -1.21336256996353509e+01 + 3.69909891189522924e+01 + -4.84851501469951671e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + -0.00000000000000000e+00 + 8.51395966446430350e+01 + -5.19584580090174413e+01 + 7.18106708732509347e+00 + -5.24346283807042397e+01 + -8.39535649250525182e+01 + 1.42270405549584336e+01 + -8.51395966446430350e+01 + 5.19584580090174413e+01 + -7.18106708732509347e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + -1.36338907320492919e+00 + -1.58782107839693651e+01 + -9.87219509153607788e+01 + 5.24346283807042397e+01 + 8.39535649250525182e+01 + -1.42270405549584336e+01 + 1.36338907320492919e+00 + 1.58782107839693651e+01 + 9.87219509153607788e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 3.07007154914777551e+01 + 2.70881185233511914e+01 + 3.78166527462940882e+00 + -1.15162420127751133e+02 + -6.75390943713141123e+00 + 3.95885323960980529e+00 + -1.29970649317129876e+01 + 1.14524822858325365e+02 + 2.24989739182521227e+01 + + + + 4 + 0 + 0 + 3 + 6 + 7 + + 0 + 9 + 0 + + + + + + + + + + + + 2 + 0 + 23 + 24 + + + + + + 9 + 7 + + -1.83421298069983294e+01 + -8.40178887379047552e+01 + 1.37665553988889080e+01 + 3.46271545199608042e+01 + 4.05922653756383482e+01 + -7.00698095538007770e+00 + 9.19927590625682683e+01 + -3.22667773518094236e+01 + 3.91925773350330608e+00 + 4.07207141973007651e+01 + -3.85719388369921674e+01 + -7.75337815930943464e+01 + 7.24865255322073381e+01 + -3.53413936296266158e+01 + 5.86044610642822335e+01 + -1.83884977004002117e+01 + 1.46625501311897892e+01 + 1.87515674799128185e+01 + -2.53722481762123628e+01 + -3.66484706705800178e+01 + 3.56472023092901580e+01 + -4.40875208799477321e+01 + -6.95087704456724254e+01 + 1.97777311636326232e+01 + 1.27979930474377834e+01 + 3.35520358632383733e+01 + 9.10304934695741821e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + -2.81762066375282245e+01 + 9.59328037613137070e+01 + -1.73162987170684679e+00 + -8.31278175295505264e+01 + -2.53085961788951153e+01 + -4.94898061445724977e+01 + 2.81762066375282245e+01 + -9.59328037613137070e+01 + 1.73162987170684679e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + -4.79152098220707003e+01 + -1.25048839237672293e+01 + 8.68778484181097070e+01 + 8.31278175295505264e+01 + 2.53085961788951153e+01 + 4.94898061445724977e+01 + 4.79152098220707003e+01 + 1.25048839237672293e+01 + -8.68778484181097070e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + -3.78847831737257366e+01 + 2.29972416224487830e+01 + -1.37159770597291157e+02 + -4.30909041970757869e+01 + -7.29718405033518991e+01 + -1.27753851859623239e+02 + -4.00153271264082644e+00 + -1.83214678716897197e+02 + 3.84258732608477231e+01 + + + + 4 + 0 + 0 + 3 + 6 + 7 + + 0 + 9 + 0 + + + + + + + + + + + + 2 + 0 + 24 + 25 + + + + + + 9 + 7 + + -1.42022591781322873e+01 + -3.56662961537267762e+01 + -1.29665633112741379e+01 + -4.42547548664715933e+01 + 8.53484085500931968e+01 + -1.21228131477824768e+01 + 7.44576769541145751e+01 + 3.58775048496875613e+01 + 4.62292669635554603e+01 + 1.27026107710752729e+01 + -9.11117710856913021e+01 + 2.52571349253896464e+01 + -3.19164772916096373e+00 + -2.63470878340458832e+01 + 1.88346366483448016e+01 + 5.40205809637968812e+01 + -1.90775864349462978e+01 + -8.09820522299282857e+01 + 6.16280452912953720e+01 + 1.93876135715390099e+01 + 7.12990641830701719e+01 + 6.58414093447228908e+01 + 1.80759831933341069e+01 + -6.99233759491107918e+01 + 3.27566373625739402e+01 + 9.70961890249048842e+00 + 4.91628253265810322e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 9.34197183252336458e+01 + 2.76233972145661149e+01 + 2.25766284985226449e+01 + -2.39170403241009595e+01 + 1.53702168542746431e+00 + 9.70855949483436831e+01 + -9.34197183252336458e+01 + -2.76233972145661149e+01 + -2.25766284985226449e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 2.64713318548450189e+01 + -9.60967506769340645e+01 + 8.04258037981846208e+00 + 2.39170403241009595e+01 + -1.53702168542746431e+00 + -9.70855949483436831e+01 + -2.64713318548450189e+01 + 9.60967506769340645e+01 + -8.04258037981846208e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 4.99415394471549448e+01 + 8.89774612805008616e+01 + -7.21549206200566857e+01 + -8.47137695131298614e+01 + -3.96302269514171712e+01 + 2.91958404364136328e+01 + -1.14979727399682560e+02 + 6.32312875848932592e+01 + -5.83619937525406982e+01 + + + + 4 + 0 + 0 + 3 + 6 + 7 + + 0 + 9 + 0 + + + + + + + + + + + + 2 + 0 + 25 + 26 + + + + + + 9 + 7 + + 4.75279810851286726e+01 + 1.27698906927141866e+01 + -3.85248964418578721e+00 + 8.38265009034030300e+01 + 2.34263445942633055e+01 + 4.00325151654156208e+00 + -3.67133537961906153e+00 + 7.31784749045807636e+00 + 9.95211070535517166e+01 + 7.72966987607180016e+01 + 3.83523138848579492e+01 + 1.84348658933893006e+01 + -5.00282378767150675e+01 + 1.62934700342947103e+00 + -1.23502536597363957e+01 + 3.08280910111897235e+01 + -9.23259671614170685e+01 + 9.05617058795025009e+00 + -3.32567607414421573e+01 + 4.65581163028938505e+01 + 8.06472888898161528e+01 + -1.09449242551094059e+01 + 8.15866317932763252e+01 + -5.45355209481987444e+01 + -6.85221032691171050e+00 + 2.03202505385987919e+01 + 3.49109728776780415e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + -0.00000000000000000e+00 + 5.75486223700384372e+01 + -3.56976774925786202e+01 + 7.35787461495951334e+01 + -7.77278254550152923e+01 + 4.09823526552186745e+00 + 6.27820803871861983e+01 + -5.75486223700384372e+01 + 3.56976774925786202e+01 + -7.35787461495951334e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + -2.54271747023806824e+01 + -9.33213817372218273e+01 + -2.53885505161348775e+01 + 7.77278254550152923e+01 + -4.09823526552186745e+00 + -6.27820803871861983e+01 + 2.54271747023806824e+01 + 9.33213817372218273e+01 + 2.53885505161348775e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 5.11234651369603128e+01 + 1.45916426283882128e+01 + 8.14361101436695947e+01 + -9.64495575814352151e+01 + 5.69392664765279974e+01 + 1.45591038998347216e+02 + -1.52360008121073719e+02 + 3.92577375478538881e+00 + -7.47401324352360774e+01 + + + + 4 + 0 + 0 + 3 + 6 + 7 + + 0 + 9 + 0 + + + + + + + + + + + + 2 + 0 + 7 + 10 + + + + + + 9 + 7 + + -5.40766118135344485e+01 + -6.55945677789347137e+00 + 5.92166444746720977e-01 + 8.33981325801565987e+01 + -1.15536936327200639e+01 + 1.11233523720273890e+01 + -9.80808079024424018e+00 + -8.64371084278765380e+01 + 4.74584491239462309e+01 + 1.25135196935038806e+01 + 9.77748374151099995e+01 + 6.14999725352584115e+00 + 1.36807989121553284e+01 + 4.43989849701706429e+00 + -9.89599830977766572e+01 + -2.01505456436379626e+00 + -1.55263904030224698e+01 + -7.65145679760131925e-01 + 8.31600037168701789e+01 + -1.88305696684158264e+01 + -2.79941305069657931e+00 + 5.18811705043763141e+01 + -7.17174238817171439e+00 + 6.66998670151083850e+00 + -8.31970807941664781e+00 + -4.61019176373218968e+01 + -8.79761519740697651e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 7.83449748282976799e+01 + 6.13201754047114846e+01 + 1.00946028891096997e+01 + -1.98027611608243852e+01 + 9.23644092983748521e+00 + 9.75834966034573341e+01 + -7.83449748282976799e+01 + -6.13201754047114846e+01 + -1.00946028891096997e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 5.89059892503364324e+01 + -7.84507759508154265e+01 + 1.93793752003053505e+01 + 1.98027611608243852e+01 + -9.23644092983748521e+00 + -9.75834966034573341e+01 + -5.89059892503364324e+01 + 7.84507759508154265e+01 + -1.93793752003053505e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + -6.07889604414481113e+01 + 8.49672366649234476e+01 + -1.19149060367207383e+02 + -3.26841768394553398e+01 + -8.97350957633814517e+01 + 9.13622785379021281e+01 + -1.77493968880864855e+02 + -4.85855715361152676e+01 + -7.39158595946127228e+00 + + + + 4 + 0 + 0 + 3 + 6 + 7 + + 0 + 9 + 0 + + + + + + + + + + + + 2 + 0 + 9 + 14 + + + + + + 9 + 7 + + 4.43615564152903019e+01 + -3.09502672537490433e+01 + -6.65256070847414378e+01 + 4.96695435786911474e+01 + 2.78172662190901541e+01 + 6.19720498005987466e+01 + -7.45919697090238145e+01 + 1.35179597700267684e+00 + 1.13620760877569249e+00 + 5.07131897166802617e+01 + -6.73003419642306540e+01 + 3.11633063652204427e+01 + 5.47056695452382584e+01 + 6.11187671649742512e+01 + -2.76098847773204135e+01 + 6.65963623398869657e+01 + 1.43297991149407444e+00 + -1.99391285797603790e-01 + 7.65967691022320984e-01 + 1.84943157433388130e+01 + -6.50656556956834748e+01 + 8.44674932355512387e-01 + 2.30555803308049860e+01 + -6.99700625824593629e+01 + -3.40876610014427706e-01 + -9.55299072188111609e+01 + -2.94902469873441930e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + -2.89030917873941853e+01 + 8.70749520313458305e+01 + -3.97814531392241904e+01 + -9.56630827209552450e+01 + -2.78467078053438328e+01 + 8.55192777842975183e+00 + 2.89030917873941853e+01 + -8.70749520313458305e+01 + 3.97814531392241904e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + -3.63123800557649812e+00 + 4.05279359595652906e+01 + 9.13471429077244466e+01 + 9.56630827209552450e+01 + 2.78467078053438328e+01 + -8.55192777842975183e+00 + 3.63123800557649812e+00 + -4.05279359595652906e+01 + -9.13471429077244466e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + -7.02581401004128878e+01 + -1.05108950320020767e+02 + -1.10573546354685661e+02 + -2.82871715200345584e+01 + -9.82678476821147342e+01 + -1.38389269150812240e+01 + 2.98238876860104902e+01 + -1.16573384649075678e+02 + 1.35327233223631623e+02 + + + + 4 + 0 + 0 + 3 + 6 + 7 + + 0 + 9 + 0 + + + + + + + + + + + + 2 + 0 + 10 + 25 + + + + + + 9 + 7 + + 3.95766223652825175e+01 + 2.36448299245490254e+01 + -2.45799893899839930e+01 + -7.00228044208398188e+01 + -4.93985238797199173e+01 + 1.28698697829822883e+01 + 7.78345939301136092e+00 + 2.90892349948341078e+01 + 9.40990441114148695e+01 + -8.42616415682074660e+01 + -2.90334966132265606e+01 + -1.43512687624874875e+01 + -2.62231810185785967e+01 + -4.77560189769582593e+01 + -8.01321381020614343e-01 + 4.26634609899314583e+01 + -8.24081707666526171e+01 + 1.64578293010562966e+01 + -8.45857606147821528e+00 + 2.58771125144124774e+01 + -9.15441805767733570e+01 + 5.92769857321209486e+01 + -7.03919737513036381e+01 + -3.24535577243972782e+01 + -1.66359962010244793e+01 + 2.48028458121687763e+01 + -2.15529183777999371e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 9.34197183252336458e+01 + 2.76233972145661149e+01 + 2.25766284985226449e+01 + -2.39170403241009595e+01 + 1.53702168542746431e+00 + 9.70855949483436831e+01 + -9.34197183252336458e+01 + -2.76233972145661149e+01 + -2.25766284985226449e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 2.64713318548450189e+01 + -9.60967506769340645e+01 + 8.04258037981846208e+00 + 2.39170403241009595e+01 + -1.53702168542746431e+00 + -9.70855949483436831e+01 + -2.64713318548450189e+01 + 9.60967506769340645e+01 + -8.04258037981846208e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + -6.19976450903283478e+01 + 1.85138049290959714e+02 + 2.04096238885501400e+01 + -5.38401179783636792e+01 + 1.95403129638118465e+01 + 3.38132128740523674e+00 + -1.81977553628765463e+02 + -6.94268461743989320e+01 + -2.32863678513998718e+00 + + + + 4 + 0 + 0 + 3 + 6 + 7 + + 0 + 9 + 0 + + + + + + + + + + + + 2 + 0 + 13 + 22 + + + + + + 9 + 7 + + 1.61359876726555882e+01 + 1.08711432986265653e+01 + 8.51184696478907732e+00 + 6.31122752697449414e+01 + -1.20771880436756209e+01 + 7.50149628126125521e+01 + -4.10840851091186110e+01 + -8.68858010361213076e+01 + 2.35731234098279678e+01 + 4.08177879353251924e+01 + -2.17654374458011439e+01 + 8.78457730201184290e+01 + -2.17842465512247614e+01 + 1.46672234096332783e+01 + 6.07972286227193015e-01 + 6.89954693463132855e+01 + -4.93810369540159471e+01 + -4.74803457645439977e+01 + -6.20341282977744939e+01 + -7.54126088063309794e+01 + 1.25298075512294904e+01 + -5.28542109714301915e+01 + 5.80638264069757923e+01 + 5.82126617561848008e+01 + -2.29292298928228675e+01 + -1.00045379878072604e+00 + 1.50754924253946800e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 9.78145711723120286e+01 + 1.76232674770143696e+01 + -1.10331368980137903e+01 + -1.40616464377447681e+01 + 1.69815554662718142e+01 + -9.75392068524539155e+01 + -9.78145711723120286e+01 + -1.76232674770143696e+01 + 1.10331368980137903e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + -1.53159970565603700e+01 + 9.69589976091932186e+01 + 1.90885572211179095e+01 + 1.40616464377447681e+01 + -1.69815554662718142e+01 + 9.75392068524539155e+01 + 1.53159970565603700e+01 + -9.69589976091932186e+01 + -1.90885572211179095e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 8.03183434009733901e+01 + -1.57959181406014523e+02 + -6.44060214101481705e+01 + -6.64898917378079801e+01 + -6.21866664385735888e+01 + -6.61756460634393022e+01 + -1.52823432141161049e+02 + -1.42511660560011357e+01 + -7.24093903591090111e+01 + + + + 4 + 0 + 0 + 3 + 6 + 7 + + 0 + 9 + 0 + + + + + + + + + + + + 2 + 0 + 20 + 15 + + + + + + 9 + 7 + + 4.71343070271561331e+01 + -6.72091990499062604e+01 + 5.47388912655424136e+01 + 8.35500845890857278e+01 + 2.23841738875626213e+01 + -3.32945376880477681e+01 + -2.59734415135038539e+01 + -2.12006909898996589e+01 + 2.34658474313030787e+01 + 6.32652845860905977e+00 + 9.30238234940692976e+00 + 3.37625583972403689e+01 + 3.44554933454442613e+00 + 8.79955033997688929e+01 + 4.09722885299349642e+01 + -1.92439510927881194e+01 + 4.62720459594682580e+01 + -8.23910435376807584e+01 + -5.55999617765192156e+00 + 6.20368695338309522e+01 + 7.15470037167418553e+01 + 3.41059120969163914e+01 + -1.39920442875337869e+01 + -2.48395357584865195e+01 + 9.22321060162172301e+01 + 2.27421056426905714e+01 + 1.25600461547882558e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + -8.15059339771809164e+01 + -5.54598536753216109e+01 + -1.67626774955357369e+01 + -1.04808841952049807e+01 + 4.25686446848321935e+01 + -8.98780371179923492e+01 + 8.15059339771809164e+01 + 5.54598536753216109e+01 + 1.67626774955357369e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 5.69818724946287603e+01 + -7.14990567770542356e+01 + -4.05086544703406517e+01 + 1.04808841952049807e+01 + -4.25686446848321935e+01 + 8.98780371179923492e+01 + -5.69818724946287603e+01 + 7.14990567770542356e+01 + 4.05086544703406517e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + -0.00000000000000000e+00 + -1.44773765128431023e+02 + 3.21567907629271019e+01 + 6.77990836285083986e+01 + 3.24643872643349098e+01 + 3.07230481384375675e+00 + -8.66387073171390654e+00 + 6.03331707496851593e+01 + 1.38479259212844596e+02 + 6.83329111783498746e+01 + + + + 4 + 0 + 0 + 3 + 6 + 7 + + 0 + 9 + 0 + + + + + + + + + + + + 27 + 0 + 0 + 1 + 2 + 3 + 4 + 5 + 6 + 7 + 8 + 9 + 10 + 11 + 12 + 13 + 14 + 15 + 16 + 17 + 18 + 19 + 20 + 21 + 22 + 23 + 24 + 25 + 26 + + + + + + 3 + 82 + + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.00000000000000000e+00 + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.00000000000000000e+00 + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.00000000000000000e+00 + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.00000000000000000e+00 + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.00000000000000000e+00 + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.00000000000000000e+00 + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.00000000000000000e+00 + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.00000000000000000e+00 + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.00000000000000000e+00 + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.00000000000000000e+00 + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.00000000000000000e+00 + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.00000000000000000e+00 + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.00000000000000000e+00 + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.00000000000000000e+00 + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.00000000000000000e+00 + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.00000000000000000e+00 + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.00000000000000000e+00 + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.00000000000000000e+00 + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.00000000000000000e+00 + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.00000000000000000e+00 + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.00000000000000000e+00 + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.00000000000000000e+00 + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.00000000000000000e+00 + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.00000000000000000e+00 + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.00000000000000000e+00 + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.00000000000000000e+00 + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + + + + 29 + 0 + 0 + 3 + 6 + 9 + 12 + 15 + 18 + 21 + 24 + 27 + 30 + 33 + 36 + 39 + 42 + 45 + 48 + 51 + 54 + 57 + 60 + 63 + 66 + 69 + 72 + 75 + 78 + 81 + 82 + + 0 + 3 + 0 + + + + + + + + + + + diff --git a/examples/Data/toy3D.xml b/examples/Data/toy3D.xml new file mode 100644 index 000000000..13dbcbe6c --- /dev/null +++ b/examples/Data/toy3D.xml @@ -0,0 +1,169 @@ + + + + + + + 2 + 1 + + + + + + 2 + 0 + 0 + 1 + + + + + + 9 + 7 + + 1.22427709071730959e+01 + 1.51514613104920048e+01 + 3.60934366857813060e+00 + -1.18407259026383116e+01 + 7.84826117220921216e+00 + 1.23509165494819051e+01 + -6.09875015991639735e+00 + 6.16547190708139126e-01 + 3.94972084922329048e+00 + -4.89208482920378174e+00 + 3.02091647632478866e+00 + -8.95328692238917512e+00 + 7.89831607220345955e+00 + -2.36793602009719084e+00 + 1.48517612051941725e+01 + -3.97284286249233731e-01 + -1.95744531643153863e+01 + -3.85954855417462017e+00 + 4.79268277145419042e+00 + -9.01707953629520453e+00 + 1.37848069005841385e+01 + 1.04829326688375950e+01 + -5.00630568442241675e+00 + 4.70463561852773182e+00 + -1.59179134598689274e+01 + -2.04767784956723942e+00 + 9.54135497908261954e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + -0.00000000000000000e+00 + -1.76201757312015372e+00 + 1.98634190821282672e+01 + 1.52966546661624236e+00 + 1.94817649567575373e+01 + 1.39684693294110307e+00 + 4.30228460420588288e+00 + 1.76201757312015372e+00 + -1.98634190821282672e+01 + -1.52966546661624236e+00 + -0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 4.16606867942304948e+00 + 1.86906420801308037e+00 + -1.94717865319198360e+01 + -1.94817649567575373e+01 + -1.39684693294110307e+00 + -4.30228460420588288e+00 + -4.16606867942304948e+00 + -1.86906420801308037e+00 + 1.94717865319198360e+01 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.00891462904330531e+01 + -1.08132497987816869e+01 + 8.66487736568128497e+00 + 2.88370015604634311e+01 + 1.89391698948574643e+01 + 2.12398960190661290e+00 + 1.22150946112124039e+01 + -2.33658532501596561e+01 + 1.51576204760307363e+01 + + + + 4 + 0 + 0 + 3 + 6 + 7 + + 0 + 9 + 0 + + + + + + + + + + + + 2 + 0 + 0 + 1 + + + + + + 3 + 7 + + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.00000000000000000e+00 + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 1.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + 0.00000000000000000e+00 + + + + 4 + 0 + 0 + 3 + 6 + 7 + + 0 + 3 + 0 + + + + + + + + + + + diff --git a/examples/DiscreteBayesNet_FG.cpp b/examples/DiscreteBayesNet_FG.cpp index 64c17c3db..6eb08c12e 100644 --- a/examples/DiscreteBayesNet_FG.cpp +++ b/examples/DiscreteBayesNet_FG.cpp @@ -1,6 +1,6 @@ /* ---------------------------------------------------------------------------- - * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * GTSAM Copyright 2010, Georgia Tech Research Corporation, * Atlanta, Georgia 30332-0415 * All Rights Reserved * Authors: Frank Dellaert, et al. (see THANKS for the full author list) diff --git a/examples/ImuFactorsExample.cpp b/examples/ImuFactorsExample.cpp index a8e50e1f1..f04b73f6b 100644 --- a/examples/ImuFactorsExample.cpp +++ b/examples/ImuFactorsExample.cpp @@ -91,7 +91,7 @@ int main(int argc, char* argv[]) cout << "initial state:\n" << initial_state.transpose() << "\n\n"; // Assemble initial quaternion through gtsam constructor ::quaternion(w,x,y,z); - Rot3 prior_rotation = Rot3::Quaternion(initial_state(6), initial_state(3), + Rot3 prior_rotation = Rot3::Quaternion(initial_state(6), initial_state(3), initial_state(4), initial_state(5)); Point3 prior_point(initial_state.head<3>()); Pose3 prior_pose(prior_rotation, prior_point); @@ -102,7 +102,7 @@ int main(int argc, char* argv[]) int correction_count = 0; initial_values.insert(X(correction_count), prior_pose); initial_values.insert(V(correction_count), prior_velocity); - initial_values.insert(B(correction_count), prior_imu_bias); + initial_values.insert(B(correction_count), prior_imu_bias); // Assemble prior noise model and add it the graph. noiseModel::Diagonal::shared_ptr pose_noise_model = noiseModel::Diagonal::Sigmas((Vector(6) << 0.01, 0.01, 0.01, 0.5, 0.5, 0.5).finished()); // rad,rad,rad,m, m, m @@ -138,7 +138,7 @@ int main(int argc, char* argv[]) p->biasAccCovariance = bias_acc_cov; // acc bias in continuous p->biasOmegaCovariance = bias_omega_cov; // gyro bias in continuous p->biasAccOmegaInt = bias_acc_omega_int; - + #ifdef USE_COMBINED imu_preintegrated_ = new PreintegratedCombinedMeasurements(p, prior_imu_bias); #else @@ -154,7 +154,7 @@ int main(int argc, char* argv[]) double current_position_error = 0.0, current_orientation_error = 0.0; double output_time = 0.0; - double dt = 0.005; // The real system has noise, but here, results are nearly + double dt = 0.005; // The real system has noise, but here, results are nearly // exactly the same, so keeping this for simplicity. // All priors have been set up, now iterate through the data file. @@ -203,8 +203,8 @@ int main(int argc, char* argv[]) *preint_imu); graph->add(imu_factor); imuBias::ConstantBias zero_bias(Vector3(0, 0, 0), Vector3(0, 0, 0)); - graph->add(BetweenFactor(B(correction_count-1), - B(correction_count ), + graph->add(BetweenFactor(B(correction_count-1), + B(correction_count ), zero_bias, bias_noise_model)); #endif @@ -215,7 +215,7 @@ int main(int argc, char* argv[]) gps(2)), // D, correction_noise); graph->add(gps_factor); - + // Now optimize and compare results. prop_state = imu_preintegrated_->predict(prev_state, prev_bias); initial_values.insert(X(correction_count), prop_state.pose()); @@ -250,10 +250,10 @@ int main(int argc, char* argv[]) // display statistics cout << "Position error:" << current_position_error << "\t " << "Angular error:" << current_orientation_error << "\n"; - fprintf(fp_out, "%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f\n", + fprintf(fp_out, "%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f\n", output_time, gtsam_position(0), gtsam_position(1), gtsam_position(2), gtsam_quat.x(), gtsam_quat.y(), gtsam_quat.z(), gtsam_quat.w(), - gps(0), gps(1), gps(2), + gps(0), gps(1), gps(2), gps_quat.x(), gps_quat.y(), gps_quat.z(), gps_quat.w()); output_time += 1.0; diff --git a/examples/InverseKinematicsExampleExpressions.cpp b/examples/InverseKinematicsExampleExpressions.cpp new file mode 100644 index 000000000..9e86886e7 --- /dev/null +++ b/examples/InverseKinematicsExampleExpressions.cpp @@ -0,0 +1,92 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file InverseKinematicsExampleExpressions.cpp + * @brief Implement inverse kinematics on a three-link arm using expressions. + * @date April 15, 2019 + * @author Frank Dellaert + */ + +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +using namespace std; +using namespace gtsam; + +// Scalar multiplication of a vector, with derivatives. +inline Vector3 scalarMultiply(const double& s, const Vector3& v, + OptionalJacobian<3, 1> Hs, + OptionalJacobian<3, 3> Hv) { + if (Hs) *Hs = v; + if (Hv) *Hv = s * I_3x3; + return s * v; +} + +// Expression version of scalar product, using above function. +inline Vector3_ operator*(const Double_& s, const Vector3_& v) { + return Vector3_(&scalarMultiply, s, v); +} + +// Expression version of Pose2::Expmap +inline Pose2_ Expmap(const Vector3_& xi) { return Pose2_(&Pose2::Expmap, xi); } + +// Main function +int main(int argc, char** argv) { + // Three-link planar manipulator specification. + const double L1 = 3.5, L2 = 3.5, L3 = 2.5; // link lengths + const Pose2 sXt0(0, L1 + L2 + L3, M_PI / 2); // end-effector pose at rest + const Vector3 xi1(0, 0, 1), xi2(L1, 0, 1), + xi3(L1 + L2, 0, 1); // screw axes at rest + + // Create Expressions for unknowns + using symbol_shorthand::Q; + Double_ q1(Q(1)), q2(Q(2)), q3(Q(3)); + + // Forward kinematics expression as product of exponentials + Pose2_ l1Zl1 = Expmap(q1 * Vector3_(xi1)); + Pose2_ l2Zl2 = Expmap(q2 * Vector3_(xi2)); + Pose2_ l3Zl3 = Expmap(q3 * Vector3_(xi3)); + Pose2_ forward = compose(compose(l1Zl1, l2Zl2), compose(l3Zl3, Pose2_(sXt0))); + + // Create a factor graph with a a single expression factor. + ExpressionFactorGraph graph; + Pose2 desiredEndEffectorPose(3, 2, 0); + auto model = noiseModel::Diagonal::Sigmas(Vector3(0.2, 0.2, 0.1)); + graph.addExpressionFactor(forward, desiredEndEffectorPose, model); + + // Create initial estimate + Values initial; + initial.insert(Q(1), 0.1); + initial.insert(Q(2), 0.2); + initial.insert(Q(3), 0.3); + initial.print("\nInitial Estimate:\n"); // print + GTSAM_PRINT(forward.value(initial)); + + // Optimize the initial values using a Levenberg-Marquardt nonlinear optimizer + LevenbergMarquardtParams params; + params.setlambdaInitial(1e6); + LevenbergMarquardtOptimizer optimizer(graph, initial, params); + Values result = optimizer.optimize(); + result.print("Final Result:\n"); + + GTSAM_PRINT(forward.value(result)); + + return 0; +} diff --git a/examples/LocalizationExample.cpp b/examples/LocalizationExample.cpp index 17f921fd1..3c07fd4e3 100644 --- a/examples/LocalizationExample.cpp +++ b/examples/LocalizationExample.cpp @@ -1,6 +1,6 @@ /* ---------------------------------------------------------------------------- - * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * GTSAM Copyright 2010, Georgia Tech Research Corporation, * Atlanta, Georgia 30332-0415 * All Rights Reserved * Authors: Frank Dellaert, et al. (see THANKS for the full author list) diff --git a/examples/METISOrderingExample.cpp b/examples/METISOrderingExample.cpp index 3416eb6b7..76b5098f6 100644 --- a/examples/METISOrderingExample.cpp +++ b/examples/METISOrderingExample.cpp @@ -1,6 +1,6 @@ /* ---------------------------------------------------------------------------- - * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * GTSAM Copyright 2010, Georgia Tech Research Corporation, * Atlanta, Georgia 30332-0415 * All Rights Reserved * Authors: Frank Dellaert, et al. (see THANKS for the full author list) diff --git a/examples/OdometryExample.cpp b/examples/OdometryExample.cpp index 3b547e70c..6dc0d9a93 100644 --- a/examples/OdometryExample.cpp +++ b/examples/OdometryExample.cpp @@ -1,6 +1,6 @@ /* ---------------------------------------------------------------------------- - * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * GTSAM Copyright 2010, Georgia Tech Research Corporation, * Atlanta, Georgia 30332-0415 * All Rights Reserved * Authors: Frank Dellaert, et al. (see THANKS for the full author list) diff --git a/examples/PlanarSLAMExample.cpp b/examples/PlanarSLAMExample.cpp index 7c43c22e2..52638fdca 100644 --- a/examples/PlanarSLAMExample.cpp +++ b/examples/PlanarSLAMExample.cpp @@ -1,6 +1,6 @@ /* ---------------------------------------------------------------------------- - * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * GTSAM Copyright 2010, Georgia Tech Research Corporation, * Atlanta, Georgia 30332-0415 * All Rights Reserved * Authors: Frank Dellaert, et al. (see THANKS for the full author list) diff --git a/examples/Pose3SLAMExampleExpressions_BearingRangeWithTransform.cpp b/examples/Pose3SLAMExampleExpressions_BearingRangeWithTransform.cpp new file mode 100644 index 000000000..551814a6b --- /dev/null +++ b/examples/Pose3SLAMExampleExpressions_BearingRangeWithTransform.cpp @@ -0,0 +1,102 @@ +/** + * @file Pose3SLAMExampleExpressions_BearingRangeWithTransform.cpp + * @brief A simultaneous optimization of trajectory, landmarks and sensor-pose with respect to body-pose using bearing-range measurements done with Expressions + * @author Thomas Horstink + * @date January 4th, 2019 + */ + +#include +#include +#include +#include +#include +#include +#include + +using namespace gtsam; + +typedef BearingRange BearingRange3D; + +/* ************************************************************************* */ +int main(int argc, char* argv[]) { + + // Move around so the whole state (including the sensor tf) is observable + Pose3 init_pose = Pose3(); + Pose3 delta_pose1 = Pose3(Rot3().Yaw(2*M_PI/8).Pitch(M_PI/8), Point3(1, 0, 0)); + Pose3 delta_pose2 = Pose3(Rot3().Pitch(-M_PI/8), Point3(1, 0, 0)); + Pose3 delta_pose3 = Pose3(Rot3().Yaw(-2*M_PI/8), Point3(1, 0, 0)); + + int steps = 4; + auto poses = createPoses(init_pose, delta_pose1, steps); + auto poses2 = createPoses(init_pose, delta_pose2, steps); + auto poses3 = createPoses(init_pose, delta_pose3, steps); + + // Concatenate poses to create trajectory + poses.insert( poses.end(), poses2.begin(), poses2.end() ); + poses.insert( poses.end(), poses3.begin(), poses3.end() ); // std::vector of Pose3 + auto points = createPoints(); // std::vector of Point3 + + // (ground-truth) sensor pose in body frame, further an unknown variable + Pose3 body_T_sensor_gt(Rot3::RzRyRx(-M_PI_2, 0.0, -M_PI_2), Point3(0.25, -0.10, 1.0)); + + // The graph + ExpressionFactorGraph graph; + + // Specify uncertainty on first pose prior and also for between factor (simplicity reasons) + auto poseNoise = noiseModel::Diagonal::Sigmas((Vector(6)<<0.3,0.3,0.3,0.1,0.1,0.1).finished()); + + // Uncertainty bearing range measurement; + auto bearingRangeNoise = noiseModel::Diagonal::Sigmas((Vector(3)<<0.01,0.03,0.05).finished()); + + // Expressions for body-frame at key 0 and sensor-tf + Pose3_ x_('x', 0); + Pose3_ body_T_sensor_('T', 0); + + // Add a prior on the body-pose + graph.addExpressionFactor(x_, poses[0], poseNoise); + + // Simulated measurements from pose + for (size_t i = 0; i < poses.size(); ++i) { + auto world_T_sensor = poses[i].compose(body_T_sensor_gt); + for (size_t j = 0; j < points.size(); ++j) { + + // This expression is the key feature of this example: it creates a differentiable expression of the measurement after being displaced by sensor transform. + auto prediction_ = Expression( BearingRange3D::Measure, Pose3_('x',i)*body_T_sensor_, Point3_('l',j)); + + // Create a *perfect* measurement + auto measurement = BearingRange3D(world_T_sensor.bearing(points[j]), world_T_sensor.range(points[j])); + + // Add factor + graph.addExpressionFactor(prediction_, measurement, bearingRangeNoise); + } + + // and add a between factor to the graph + if (i > 0) + { + // And also we have a *perfect* measurement for the between factor. + graph.addExpressionFactor(between(Pose3_('x', i-1),Pose3_('x', i)), poses[i-1].between(poses[i]), poseNoise); + } + } + + // Create perturbed initial + Values initial; + Pose3 delta(Rot3::Rodrigues(-0.1, 0.2, 0.25), Point3(0.05, -0.10, 0.20)); + for (size_t i = 0; i < poses.size(); ++i) + initial.insert(Symbol('x', i), poses[i].compose(delta)); + for (size_t j = 0; j < points.size(); ++j) + initial.insert(Symbol('l', j), points[j] + Point3(-0.25, 0.20, 0.15)); + + // Initialize body_T_sensor wrongly (because we do not know!) + initial.insert(Symbol('T',0), Pose3()); + + std::cout << "initial error: " << graph.error(initial) << std::endl; + Values result = LevenbergMarquardtOptimizer(graph, initial).optimize(); + std::cout << "final error: " << graph.error(result) << std::endl; + + initial.at(Symbol('T',0)).print("\nInitial estimate body_T_sensor\n"); /* initial sensor_P_body estimate */ + result.at(Symbol('T',0)).print("\nFinal estimate body_T_sensor\n"); /* optimized sensor_P_body estimate */ + body_T_sensor_gt.print("\nGround truth body_T_sensor\n"); /* sensor_P_body ground truth */ + + return 0; +} +/* ************************************************************************* */ \ No newline at end of file diff --git a/examples/Pose3SLAMExample_changeKeys.cpp b/examples/Pose3SLAMExample_changeKeys.cpp index 9cab73822..cceaac4ee 100644 --- a/examples/Pose3SLAMExample_changeKeys.cpp +++ b/examples/Pose3SLAMExample_changeKeys.cpp @@ -79,7 +79,7 @@ int main(const int argc, const char *argv[]) { key2 = pose3Between->key2() - firstKey; } NonlinearFactor::shared_ptr simpleFactor( - new BetweenFactor(key1, key2, pose3Between->measured(), pose3Between->get_noiseModel())); + new BetweenFactor(key1, key2, pose3Between->measured(), pose3Between->noiseModel())); simpleGraph.add(simpleFactor); } } diff --git a/examples/RangeISAMExample_plaza2.cpp b/examples/RangeISAMExample_plaza2.cpp index 032d61a4a..7b1667e12 100644 --- a/examples/RangeISAMExample_plaza2.cpp +++ b/examples/RangeISAMExample_plaza2.cpp @@ -108,7 +108,7 @@ int main (int argc, char** argv) { // Set Noise parameters Vector priorSigmas = Vector3(1,1,M_PI); - Vector odoSigmas = Vector3(0.05, 0.01, 0.2); + Vector odoSigmas = Vector3(0.05, 0.01, 0.1); double sigmaR = 100; // range standard deviation const NM::Base::shared_ptr // all same type priorNoise = NM::Diagonal::Sigmas(priorSigmas), //prior @@ -157,7 +157,7 @@ int main (int argc, char** argv) { boost::tie(t, odometry) = timedOdometry; // add odometry factor - newFactors.push_back(BetweenFactor(i-1, i, odometry,NM::Diagonal::Sigmas(odoSigmas))); + newFactors.push_back(BetweenFactor(i-1, i, odometry, odoNoise)); // predict pose and add as initial estimate Pose2 predictedPose = lastPose.compose(odometry); diff --git a/examples/SFMExampleExpressions.cpp b/examples/SFMExampleExpressions.cpp index 30db9144d..191664ef6 100644 --- a/examples/SFMExampleExpressions.cpp +++ b/examples/SFMExampleExpressions.cpp @@ -72,7 +72,7 @@ int main(int argc, char* argv[]) { Point2 measurement = camera.project(points[j]); // Below an expression for the prediction of the measurement: Point3_ p('l', j); - Point2_ prediction = uncalibrate(cK, project(transform_to(x, p))); + Point2_ prediction = uncalibrate(cK, project(transformTo(x, p))); // Again, here we use an ExpressionFactor graph.addExpressionFactor(prediction, measurement, measurementNoise); } diff --git a/examples/SFMdata.h b/examples/SFMdata.h index 25442d527..5462868c9 100644 --- a/examples/SFMdata.h +++ b/examples/SFMdata.h @@ -16,9 +16,10 @@ */ /** - * A structure-from-motion example with landmarks + * A structure-from-motion example with landmarks, default function arguments give * - The landmarks form a 10 meter cube * - The robot rotates around the landmarks, always facing towards the cube + * Passing function argument allows to specificy an initial position, a pose increment and step count. */ // As this is a full 3D problem, we will use Pose3 variables to represent the camera @@ -49,20 +50,19 @@ std::vector createPoints() { } /* ************************************************************************* */ -std::vector createPoses() { +std::vector createPoses( + const gtsam::Pose3& init = gtsam::Pose3(gtsam::Rot3::Ypr(M_PI/2,0,-M_PI/2), gtsam::Point3(30, 0, 0)), + const gtsam::Pose3& delta = gtsam::Pose3(gtsam::Rot3::Ypr(0,-M_PI/4,0), gtsam::Point3(sin(M_PI/4)*30, 0, 30*(1-sin(M_PI/4)))), + int steps = 8) { // Create the set of ground-truth poses + // Default values give a circular trajectory, radius 30 at pi/4 intervals, always facing the circle center std::vector poses; - double radius = 30.0; - int i = 0; - double theta = 0.0; - gtsam::Point3 up(0,0,1); - gtsam::Point3 target(0,0,0); - for(; i < 8; ++i, theta += 2*M_PI/8) { - gtsam::Point3 position = gtsam::Point3(radius*cos(theta), radius*sin(theta), 0.0); - gtsam::SimpleCamera camera = gtsam::SimpleCamera::Lookat(position, target, up); - poses.push_back(camera.pose()); + int i = 1; + poses.push_back(init); + for(; i < steps; ++i) { + poses.push_back(poses[i-1].compose(delta)); } + return poses; -} -/* ************************************************************************* */ +} \ No newline at end of file diff --git a/examples/SimpleRotation.cpp b/examples/SimpleRotation.cpp index 1f40d8c60..f70a44eec 100644 --- a/examples/SimpleRotation.cpp +++ b/examples/SimpleRotation.cpp @@ -1,6 +1,6 @@ /* ---------------------------------------------------------------------------- - * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * GTSAM Copyright 2010, Georgia Tech Research Corporation, * Atlanta, Georgia 30332-0415 * All Rights Reserved * Authors: Frank Dellaert, et al. (see THANKS for the full author list) diff --git a/examples/SolverComparer.cpp b/examples/SolverComparer.cpp index f3915ce22..80ac08e03 100644 --- a/examples/SolverComparer.cpp +++ b/examples/SolverComparer.cpp @@ -361,8 +361,8 @@ void runIncremental() const auto& measured = factor->measured(); Rot2 measuredBearing = measured.bearing(); double measuredRange = measured.range(); - newVariables.insert(lmKey, - pose.transform_from(measuredBearing.rotate(Point2(measuredRange, 0.0)))); + newVariables.insert(lmKey, + pose.transformFrom(measuredBearing.rotate(Point2(measuredRange, 0.0)))); } } else diff --git a/examples/StereoVOExample.cpp b/examples/StereoVOExample.cpp index 27c10deb3..65ab5422d 100644 --- a/examples/StereoVOExample.cpp +++ b/examples/StereoVOExample.cpp @@ -22,7 +22,7 @@ * -moves forward 1 meter * -takes stereo readings on three landmarks */ - + #include #include #include @@ -40,7 +40,7 @@ int main(int argc, char** argv){ NonlinearFactorGraph graph; Pose3 first_pose; graph.emplace_shared >(1, Pose3()); - + //create factor noise model with 3 sigmas of value 1 const noiseModel::Isotropic::shared_ptr model = noiseModel::Isotropic::Sigma(3,1); //create stereo camera calibration object with .2m between cameras diff --git a/examples/StereoVOExample_large.cpp b/examples/StereoVOExample_large.cpp index 80831bd21..5eeb6ac3c 100644 --- a/examples/StereoVOExample_large.cpp +++ b/examples/StereoVOExample_large.cpp @@ -50,7 +50,7 @@ int main(int argc, char** argv){ string calibration_loc = findExampleDataFile("VO_calibration.txt"); string pose_loc = findExampleDataFile("VO_camera_poses_large.txt"); string factor_loc = findExampleDataFile("VO_stereo_factors_large.txt"); - + //read camera calibration info from file // focal lengths fx, fy, skew s, principal point u0, v0, baseline b double fx, fy, s, u0, v0, b; @@ -60,7 +60,7 @@ int main(int argc, char** argv){ //create stereo camera calibration object const Cal3_S2Stereo::shared_ptr K(new Cal3_S2Stereo(fx,fy,s,u0,v0,b)); - + ifstream pose_file(pose_loc.c_str()); cout << "Reading camera poses" << endl; int pose_id; @@ -72,7 +72,7 @@ int main(int argc, char** argv){ } initial_estimate.insert(Symbol('x', pose_id), Pose3(m)); } - + // camera and landmark keys size_t x, l; @@ -89,8 +89,8 @@ int main(int argc, char** argv){ //if the landmark variable included in this factor has not yet been added to the initial variable value estimate, add it if (!initial_estimate.exists(Symbol('l', l))) { Pose3 camPose = initial_estimate.at(Symbol('x', x)); - //transform_from() transforms the input Point3 from the camera pose space, camPose, to the global space - Point3 worldPoint = camPose.transform_from(Point3(X, Y, Z)); + //transformFrom() transforms the input Point3 from the camera pose space, camPose, to the global space + Point3 worldPoint = camPose.transformFrom(Point3(X, Y, Z)); initial_estimate.insert(Symbol('l', l), worldPoint); } } diff --git a/examples/UGM_chain.cpp b/examples/UGM_chain.cpp index 0461c1869..4ce4e7af4 100644 --- a/examples/UGM_chain.cpp +++ b/examples/UGM_chain.cpp @@ -36,7 +36,7 @@ int main(int argc, char** argv) { // Each node takes 1 of 7 possible states denoted by 0-6 in following order: // ["VideoGames" "Industry" "GradSchool" "VideoGames(with PhD)" - // "Industry(with PhD)" "Academia" "Deceased"] + // "Industry(with PhD)" "Academia" "Deceased"] const size_t nrStates = 7; // define variables diff --git a/examples/UGM_small.cpp b/examples/UGM_small.cpp index 43cd9b34c..f5338bc67 100644 --- a/examples/UGM_small.cpp +++ b/examples/UGM_small.cpp @@ -1,6 +1,6 @@ /* ---------------------------------------------------------------------------- - * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * GTSAM Copyright 2010, Georgia Tech Research Corporation, * Atlanta, Georgia 30332-0415 * All Rights Reserved * Authors: Frank Dellaert, et al. (see THANKS for the full author list) diff --git a/examples/easyPoint2KalmanFilter.cpp b/examples/easyPoint2KalmanFilter.cpp index d68cedb74..49b99a5b6 100644 --- a/examples/easyPoint2KalmanFilter.cpp +++ b/examples/easyPoint2KalmanFilter.cpp @@ -1,6 +1,6 @@ /* ---------------------------------------------------------------------------- - * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * GTSAM Copyright 2010, Georgia Tech Research Corporation, * Atlanta, Georgia 30332-0415 * All Rights Reserved * Authors: Frank Dellaert, et al. (see THANKS for the full author list) diff --git a/examples/elaboratePoint2KalmanFilter.cpp b/examples/elaboratePoint2KalmanFilter.cpp index a0300adf9..1dde7efb5 100644 --- a/examples/elaboratePoint2KalmanFilter.cpp +++ b/examples/elaboratePoint2KalmanFilter.cpp @@ -1,6 +1,6 @@ /* ---------------------------------------------------------------------------- - * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * GTSAM Copyright 2010, Georgia Tech Research Corporation, * Atlanta, Georgia 30332-0415 * All Rights Reserved * Authors: Frank Dellaert, et al. (see THANKS for the full author list) @@ -140,7 +140,7 @@ int main() { const GaussianConditional::shared_ptr& cg0 = linearBayesNet->back(); assert(cg0->nrFrontals() == 1); assert(cg0->nrParents() == 0); - linearFactorGraph->add(0, cg0->get_R(), cg0->get_d() - cg0->get_R()*result[ordering->at(x1)], noiseModel::Diagonal::Sigmas(cg0->get_sigmas(), true)); + linearFactorGraph->add(0, cg0->R(), cg0->d() - cg0->R()*result[ordering->at(x1)], noiseModel::Diagonal::Sigmas(cg0->get_sigmas(), true)); // Create the desired ordering ordering = Ordering::shared_ptr(new Ordering); diff --git a/gtsam.h b/gtsam.h index 8097cc6c9..826f8472e 100644 --- a/gtsam.h +++ b/gtsam.h @@ -209,11 +209,63 @@ class KeyGroupMap { bool insert2(size_t key, int val); }; +// Actually a FastSet +class FactorIndexSet { + FactorIndexSet(); + FactorIndexSet(const gtsam::FactorIndexSet& set); + + // common STL methods + size_t size() const; + bool empty() const; + void clear(); + + // structure specific methods + void insert(size_t factorIndex); + bool erase(size_t factorIndex); // returns true if value was removed + bool count(size_t factorIndex) const; // returns true if value exists +}; + +// Actually a vector +class FactorIndices { + FactorIndices(); + FactorIndices(const gtsam::FactorIndices& other); + + // common STL methods + size_t size() const; + bool empty() const; + void clear(); + + // structure specific methods + size_t at(size_t i) const; + size_t front() const; + size_t back() const; + void push_back(size_t factorIndex) const; +}; + //************************************************************************* // base //************************************************************************* /** gtsam namespace functions */ + +#include +bool isDebugVersion(); + +#include +class IndexPair { + IndexPair(); + IndexPair(size_t i, size_t j); + size_t i() const; + size_t j() const; +}; + +template +class DSFMap { + DSFMap(); + KEY find(const KEY& key) const; + void merge(const KEY& x, const KEY& y); +}; + #include bool linear_independent(Matrix A, Matrix B, double tol); @@ -577,14 +629,14 @@ class Pose2 { static Matrix LogmapDerivative(const gtsam::Pose2& v); Matrix AdjointMap() const; Vector Adjoint(Vector xi) const; - static Matrix adjointMap(Vector v); - Vector adjoint(Vector xi, Vector y); - Vector adjointTranspose(Vector xi, Vector y); + static Matrix adjointMap_(Vector v); + static Vector adjoint_(Vector xi, Vector y); + static Vector adjointTranspose(Vector xi, Vector y); static Matrix wedge(double vx, double vy, double w); // Group Actions on Point2 - gtsam::Point2 transform_from(const gtsam::Point2& p) const; - gtsam::Point2 transform_to(const gtsam::Point2& p) const; + gtsam::Point2 transformFrom(const gtsam::Point2& p) const; + gtsam::Point2 transformTo(const gtsam::Point2& p) const; // Standard Interface double x() const; @@ -628,16 +680,16 @@ class Pose3 { static Vector Logmap(const gtsam::Pose3& pose); Matrix AdjointMap() const; Vector Adjoint(Vector xi) const; - static Matrix adjointMap(Vector xi); - static Vector adjoint(Vector xi, Vector y); + static Matrix adjointMap_(Vector xi); + static Vector adjoint_(Vector xi, Vector y); static Vector adjointTranspose(Vector xi, Vector y); static Matrix ExpmapDerivative(Vector xi); static Matrix LogmapDerivative(const gtsam::Pose3& xi); static Matrix wedge(double wx, double wy, double wz, double vx, double vy, double vz); // Group Action on Point3 - gtsam::Point3 transform_from(const gtsam::Point3& point) const; - gtsam::Point3 transform_to(const gtsam::Point3& point) const; + gtsam::Point3 transformFrom(const gtsam::Point3& point) const; + gtsam::Point3 transformTo(const gtsam::Point3& point) const; // Standard Interface gtsam::Rot3 rotation() const; @@ -646,7 +698,8 @@ class Pose3 { double y() const; double z() const; Matrix matrix() const; - gtsam::Pose3 transform_to(const gtsam::Pose3& pose) const; // FIXME: shadows other transform_to() + gtsam::Pose3 transformPoseFrom(const gtsam::Pose3& pose) const; + gtsam::Pose3 transformPoseTo(const gtsam::Pose3& pose) const; double range(const gtsam::Point3& point); double range(const gtsam::Pose3& pose); @@ -1218,14 +1271,30 @@ class VariableIndex { namespace noiseModel { #include virtual class Base { + void print(string s) const; + // Methods below are available for all noise models. However, can't add them + // because wrap (incorrectly) thinks robust classes derive from this Base as well. + // bool isConstrained() const; + // bool isUnit() const; + // size_t dim() const; + // Vector sigmas() const; }; virtual class Gaussian : gtsam::noiseModel::Base { static gtsam::noiseModel::Gaussian* SqrtInformation(Matrix R); static gtsam::noiseModel::Gaussian* Covariance(Matrix R); - Matrix R() const; + bool equals(gtsam::noiseModel::Base& expected, double tol); - void print(string s) const; + + // access to noise model + Matrix R() const; + Matrix information() const; + Matrix covariance() const; + + // Whitening operations + Vector whiten(Vector v) const; + Vector unwhiten(Vector v) const; + Matrix Whiten(Matrix H) const; // enabling serialization functionality void serializable() const; @@ -1236,7 +1305,11 @@ virtual class Diagonal : gtsam::noiseModel::Gaussian { static gtsam::noiseModel::Diagonal* Variances(Vector variances); static gtsam::noiseModel::Diagonal* Precisions(Vector precisions); Matrix R() const; - void print(string s) const; + + // access to noise model + Vector sigmas() const; + Vector invsigmas() const; + Vector precisions() const; // enabling serialization functionality void serializable() const; @@ -1263,7 +1336,9 @@ virtual class Isotropic : gtsam::noiseModel::Diagonal { static gtsam::noiseModel::Isotropic* Sigma(size_t dim, double sigma); static gtsam::noiseModel::Isotropic* Variance(size_t dim, double varianace); static gtsam::noiseModel::Isotropic* Precision(size_t dim, double precision); - void print(string s) const; + + // access to noise model + double sigma() const; // enabling serialization functionality void serializable() const; @@ -1271,7 +1346,6 @@ virtual class Isotropic : gtsam::noiseModel::Diagonal { virtual class Unit : gtsam::noiseModel::Isotropic { static gtsam::noiseModel::Unit* Create(size_t dim); - void print(string s) const; // enabling serialization functionality void serializable() const; @@ -1279,11 +1353,11 @@ virtual class Unit : gtsam::noiseModel::Isotropic { namespace mEstimator { virtual class Base { + void print(string s) const; }; virtual class Null: gtsam::noiseModel::mEstimator::Base { Null(); - void print(string s) const; static gtsam::noiseModel::mEstimator::Null* Create(); // enabling serialization functionality @@ -1292,7 +1366,6 @@ virtual class Null: gtsam::noiseModel::mEstimator::Base { virtual class Fair: gtsam::noiseModel::mEstimator::Base { Fair(double c); - void print(string s) const; static gtsam::noiseModel::mEstimator::Fair* Create(double c); // enabling serialization functionality @@ -1301,7 +1374,6 @@ virtual class Fair: gtsam::noiseModel::mEstimator::Base { virtual class Huber: gtsam::noiseModel::mEstimator::Base { Huber(double k); - void print(string s) const; static gtsam::noiseModel::mEstimator::Huber* Create(double k); // enabling serialization functionality @@ -1310,7 +1382,6 @@ virtual class Huber: gtsam::noiseModel::mEstimator::Base { virtual class Tukey: gtsam::noiseModel::mEstimator::Base { Tukey(double k); - void print(string s) const; static gtsam::noiseModel::mEstimator::Tukey* Create(double k); // enabling serialization functionality @@ -1322,7 +1393,6 @@ virtual class Tukey: gtsam::noiseModel::mEstimator::Base { virtual class Robust : gtsam::noiseModel::Base { Robust(const gtsam::noiseModel::mEstimator::Base* robust, const gtsam::noiseModel::Base* noise); static gtsam::noiseModel::Robust* Create(const gtsam::noiseModel::mEstimator::Base* robust, const gtsam::noiseModel::Base* noise); - void print(string s) const; // enabling serialization functionality void serializable() const; @@ -1713,7 +1783,7 @@ virtual class SubgraphSolverParameters : gtsam::ConjugateGradientParameters { virtual class SubgraphSolver { SubgraphSolver(const gtsam::GaussianFactorGraph &A, const gtsam::SubgraphSolverParameters ¶meters, const gtsam::Ordering& ordering); - SubgraphSolver(const gtsam::GaussianFactorGraph &Ab1, const gtsam::GaussianFactorGraph &Ab2, const gtsam::SubgraphSolverParameters ¶meters, const gtsam::Ordering& ordering); + SubgraphSolver(const gtsam::GaussianFactorGraph &Ab1, const gtsam::GaussianFactorGraph* Ab2, const gtsam::SubgraphSolverParameters ¶meters, const gtsam::Ordering& ordering); gtsam::VectorValues optimize() const; }; @@ -1819,6 +1889,7 @@ class NonlinearFactorGraph { gtsam::KeyVector keyVector() const; // NonlinearFactorGraph + void printErrors(const gtsam::Values& values) const; double error(const gtsam::Values& values) const; double probPrime(const gtsam::Values& values) const; gtsam::Ordering orderingCOLAMD() const; @@ -1850,7 +1921,6 @@ virtual class NonlinearFactor { #include virtual class NoiseModelFactor: gtsam::NonlinearFactor { bool equals(const gtsam::NoiseModelFactor& other, double tol) const; - gtsam::noiseModel::Base* get_noiseModel() const; // deprecated by below gtsam::noiseModel::Base* noiseModel() const; Vector unwhitenedError(const gtsam::Values& x) const; Vector whitenedError(const gtsam::Values& x) const; @@ -2002,10 +2072,12 @@ virtual class NonlinearOptimizerParams { void setVerbosity(string s); string getLinearSolverType() const; - void setLinearSolverType(string solver); - void setOrdering(const gtsam::Ordering& ordering); + void setIterativeParams(gtsam::IterativeOptimizationParameters* params); + void setOrdering(const gtsam::Ordering& ordering); + string getOrderingType() const; + void setOrderingType(string ordering); bool isMultifrontal() const; bool isSequential() const; @@ -2026,15 +2098,32 @@ virtual class GaussNewtonParams : gtsam::NonlinearOptimizerParams { virtual class LevenbergMarquardtParams : gtsam::NonlinearOptimizerParams { LevenbergMarquardtParams(); - double getlambdaInitial() const; + bool getDiagonalDamping() const; double getlambdaFactor() const; + double getlambdaInitial() const; + double getlambdaLowerBound() const; double getlambdaUpperBound() const; + bool getUseFixedLambdaFactor(); + string getLogFile() const; string getVerbosityLM() const; - void setlambdaInitial(double value); + void setDiagonalDamping(bool flag); void setlambdaFactor(double value); + void setlambdaInitial(double value); + void setlambdaLowerBound(double value); void setlambdaUpperBound(double value); + void setUseFixedLambdaFactor(bool flag); + void setLogFile(string s); void setVerbosityLM(string s); + + static gtsam::LevenbergMarquardtParams LegacyDefaults(); + static gtsam::LevenbergMarquardtParams CeresDefaults(); + + static gtsam::LevenbergMarquardtParams EnsureHasOrdering( + gtsam::LevenbergMarquardtParams params, + const gtsam::NonlinearFactorGraph& graph); + static gtsam::LevenbergMarquardtParams ReplaceOrdering( + gtsam::LevenbergMarquardtParams params, const gtsam::Ordering& ordering); }; #include @@ -2055,7 +2144,7 @@ virtual class NonlinearOptimizer { double error() const; int iterations() const; gtsam::Values values() const; - void iterate() const; + gtsam::GaussianFactorGraph* iterate() const; }; #include @@ -2173,8 +2262,6 @@ class ISAM2Result { size_t getCliques() const; }; -class FactorIndices {}; - class ISAM2 { ISAM2(); ISAM2(const gtsam::ISAM2Params& params); @@ -2316,6 +2403,21 @@ virtual class BearingFactor : gtsam::NoiseModelFactor { typedef gtsam::BearingFactor BearingFactor2D; typedef gtsam::BearingFactor BearingFactorPose2; +#include +template +class BearingRange { + BearingRange(const BEARING& b, const RANGE& r); + BEARING bearing() const; + RANGE range() const; + // TODO(frank): can't class instance itself? + // static gtsam::BearingRange Measure(const POSE& pose, const POINT& point); + static BEARING MeasureBearing(const POSE& pose, const POINT& point); + static RANGE MeasureRange(const POSE& pose, const POINT& point); + void print(string s) const; +}; + +typedef gtsam::BearingRange BearingRange2D; + #include template virtual class BearingRangeFactor : gtsam::NoiseModelFactor { @@ -2449,6 +2551,7 @@ virtual class EssentialMatrixFactor : gtsam::NoiseModelFactor { }; #include +string findExampleDataFile(string name); pair load2D(string filename, gtsam::noiseModel::Diagonal* model, int maxID, bool addNoise, bool smart); pair load2D(string filename, @@ -2464,7 +2567,38 @@ void save2D(const gtsam::NonlinearFactorGraph& graph, const gtsam::Values& config, gtsam::noiseModel::Diagonal* model, string filename); +// std::vector::shared_ptr> +class BetweenFactorPose3s +{ + size_t size() const; + gtsam::BetweenFactorPose3* at(size_t i) const; +}; + +#include +class InitializePose3 { + static gtsam::Values computeOrientationsChordal( + const gtsam::NonlinearFactorGraph& pose3Graph); + static gtsam::Values computeOrientationsGradient( + const gtsam::NonlinearFactorGraph& pose3Graph, + const gtsam::Values& givenGuess, size_t maxIter, const bool setRefFrame); + static gtsam::Values computeOrientationsGradient( + const gtsam::NonlinearFactorGraph& pose3Graph, + const gtsam::Values& givenGuess); + static gtsam::NonlinearFactorGraph buildPose3graph( + const gtsam::NonlinearFactorGraph& graph); + static gtsam::Values initializeOrientations( + const gtsam::NonlinearFactorGraph& graph); + static gtsam::Values initialize(const gtsam::NonlinearFactorGraph& graph, + const gtsam::Values& givenGuess, + bool useGradient); + static gtsam::Values initialize(const gtsam::NonlinearFactorGraph& graph); +}; + +gtsam::BetweenFactorPose3s parse3DFactors(string filename); +pair load3D(string filename); + pair readG2o(string filename); +pair readG2o(string filename, bool is3D); void writeG2o(const gtsam::NonlinearFactorGraph& graph, const gtsam::Values& estimate, string filename); @@ -2726,6 +2860,30 @@ virtual class AcceleratingScenario : gtsam::Scenario { Vector omega_b); }; +#include +class ScenarioRunner { + ScenarioRunner(const gtsam::Scenario& scenario, + const gtsam::PreintegrationParams* p, + double imuSampleTime, + const gtsam::imuBias::ConstantBias& bias); + Vector gravity_n() const; + Vector actualAngularVelocity(double t) const; + Vector actualSpecificForce(double t) const; + Vector measuredAngularVelocity(double t) const; + Vector measuredSpecificForce(double t) const; + double imuSampleTime() const; + gtsam::PreintegratedImuMeasurements integrate( + double T, const gtsam::imuBias::ConstantBias& estimatedBias, + bool corrupted) const; + gtsam::NavState predict( + const gtsam::PreintegratedImuMeasurements& pim, + const gtsam::imuBias::ConstantBias& estimatedBias) const; + Matrix estimateCovariance( + double T, size_t N, + const gtsam::imuBias::ConstantBias& estimatedBias) const; + Matrix estimateNoiseCovariance(size_t N) const; +}; + //************************************************************************* // Utilities //************************************************************************* diff --git a/gtsam/3rdparty/CMakeLists.txt b/gtsam/3rdparty/CMakeLists.txt index 6ca7514ac..9a99bdba8 100644 --- a/gtsam/3rdparty/CMakeLists.txt +++ b/gtsam/3rdparty/CMakeLists.txt @@ -41,6 +41,10 @@ add_subdirectory(ceres) # add_subdirectory (tools) # Find GeographicLib using the find script distributed with it +unset(GEOGRAPHICLIB_FOUND CACHE) +unset(GeographicLib_INCLUDE_DIRS CACHE) +unset(GeographicLib_LIBRARIES CACHE) +unset(GeographicLib_LIBRARY_DIRS CACHE) include(GeographicLib/cmake/FindGeographicLib.cmake) # Set up the option to install GeographicLib diff --git a/gtsam/3rdparty/GeographicLib/00README.txt b/gtsam/3rdparty/GeographicLib/00README.txt index 47ef4b8fb..8a16e66ea 100644 --- a/gtsam/3rdparty/GeographicLib/00README.txt +++ b/gtsam/3rdparty/GeographicLib/00README.txt @@ -3,7 +3,7 @@ A library for geographic projections. Written by Charles Karney and licensed under the MIT/X11 License. For more information, see - http://geographiclib.sourceforge.net/ + https://geographiclib.sourceforge.io/ Files @@ -13,131 +13,57 @@ Files INSTALL -- brief installation instructions NEWS -- a history of changes - include/GeographicLib/ and src/ - Config.h.in, Config.h -- system dependent configuration - Constants.hpp -- WGS84 constants - Math.hpp -- math routines - Utility.hpp -- I/O and date routines - Accumulator.[ch]pp -- quad precision adder - PolarStereographic.[ch]pp -- polar stereographic projection - TransverseMercator.[ch]pp -- transverse Mercator projection - UTMUPS.[ch]pp -- UTM and UPS - MGRS.[ch]pp -- MGRS - TransverseMercatorExact.[ch]pp -- exact TM projection - EllipticFunction.[ch]pp -- elliptic functions - GeoCoords.[ch]pp -- hold geographic location - DMS.[ch]pp -- handle degrees minutes seconds - Geocentric.[ch]pp -- geocentric coordinates - LocalCartesian.[ch]pp -- local cartesian coordinates - Geodesic.[ch]pp -- geodesic calculations - GeodesicLine.[ch]pp -- calculations on a single geodesic - PolygonArea.[ch]pp -- polygon area - AzimuthalEquidistant.[ch]pp -- azimuthal equidistant projection - Gnomonic.[ch]pp -- gnomonic projection - CassiniSoldner.[ch]pp -- Cassini-Soldner equidistant projection - Geoid.[ch]pp -- geoid heights - Gravity{Model,Circle}.[ch]pp -- gravity models - Magnetic{Model,Circle}.[ch]pp -- geomagentic models - {Spherical,Circular}Engine.[ch]pp -- spherical harmonic sums - SphericalHarmonic{,1,2}.hpp -- frontend for spherical harmonics - LambertConformalConic.[ch]pp -- Lambert conformal conic projection - AlbersEqualArea.[ch]pp -- Albers equal area projection - Gnomonic.[ch]pp -- Ellipsoidal gnomonic projection - OSGB.[ch]pp -- Ordnance Survey grid system - Geohash.[ch]pp -- conversions for geohashes - Ellipsoid.[ch]pp -- ellipsoid properties + include/GeographicLib/*.hpp + headers for the library + src/*.cpp + implementation for the library examples/ - example-*.cpp -- simple usage examples for all the classes - GeoidToGTX.cpp -- a parallelization example + examples for each class tools/ - GeoConvert.cpp -- geographic conversion utility - TransverseMercatorTest.cpp -- TM tester - GeodSolve.cpp -- geodesic utility - CartConvert.cpp -- convert to geocentric and local cartesian - EquidistantTest.cpp -- exercise AzimuthalEquidistant and CassiniSoldner - GeoidEval.cpp -- evaluate geoid heights - Gravity.cpp -- evaluate gravity - MagneticField.cpp -- evaluate magnetic field - Planimeter.cpp -- computer polygon areas - geographiclib-get-geoids -- download geoid datasets - geographiclib-get-magnetic -- download geomagnetic models - - windows/ - GeographicLib-vc9.sln -- MS Studio 2008 solution - Geographic-vc9.vcproj -- project for library - GeoConvert-vc9.vcproj -- project for GeoConvert - TransverseMercatorTest-vc9.vcproj -- project for TransverseMercatorTest - Geod-vc9.vcproj -- project for Geod - Planimeter-vc9.vcproj -- project for Planimeter - CartConvert-vc9.vcproj -- project for CartConvert - EquidistantTest-vc9.vcproj -- project for EquidistantTest - GeoidEval-vc9.vcproj -- project for GeoidEval - Gravity-vc9.vcproj -- project for Gravity - MagneticField-vc9.vcproj -- project for MagneticField - also files for MS Studio 2005 (with vc8) - also files for MS Studio 2010 (with vc10) - NETGeographic-vc10.vcxproj -- project for .NET wrapper - - maxima/ - tm.mac -- Maxima code for high precision TM - ellint.mac -- Maxima code for elliptic functions needed by tm.mac - tmseries.mac -- Maxima code for series approximations for TM - geod.mac -- Maxima code for series approximations for Geodesic - geodesic.mac -- Maxima code for geodesic problems - - matlab/ - geographiclibinterface.m -- Matlab code to compile Matlab interfaces - utmupsforward.{cpp,m} -- Matlab code to convert geographic to UTM/UPS - utmupsreverse.{cpp,m} -- Matlab code to convert UTM/UPS to geographic - mgrsforward.{cpp,m} -- Matlab code to convert UTM/UPS to MGRS - mgrsreverse.{cpp,m} -- Matlab code to convert MGRS to UTM/UPS - geodesicdirect.{cpp,m} -- Matlab code for the direct geodesic problem - geodesicinverse.{cpp,m} -- Matlab code for the inverse geodesic problem - geodesicline.{cpp,m} -- Matlab code for geodesic lines - geoidheight.{cpp,m} -- Matlab code to look up geoid heights - polygonarea.{cpp,m} -- Matlab code for polygon areas - geoddoc.m -- documentation for native Matlab geodesic routines - geodreckon.m -- native Matlab implementation of direct geodesic problem - geoddistance.m -- native Matlab implementation of inverse geodesic problem - geodarea.m -- native Matlab implementation of polygon area - defaultellipsoid.m, ecc2flat.m, flat2ecc.m -- auxiliary functions - geodproj.m -- documentation for geodesic projections - *_{fwd,inv}.m -- native Matlab implementation of geodesic projections - private/*.m -- internal functions for geodesic routines - - doc/ - doxyfile.in -- Doxygen config file - Geographic.dox -- main page of Doxygen documentation - geodseries30.html -- geodesic series to 30th order - tmseries30.html -- transverse Mercator series to 30th order - html/* -- directory with built documentation - scripts/*.html -- demonstrations of the JavaScript interface - scripts/GeographicLib/*.js -- JavaScript implementation of geodesics - - man/ - *.pod -- plain old documentation - *.1 -- man pages in nroff format - *.1.html -- man pages in html format - *.usage -- documentation for incorporation into executables - - python/GeographicLib/*.py -- Python implementation of geodesic routines - - java/.../*.java -- Java implementation of geodesic routines - - dotnet/NETGeographicLib/*.{cpp,h} -- .NET wrapper for GeographicLib - dotnet/examples/CS/*.cs -- simple C# examples for each class - dotnet/examples/ManagedCPP/*.cpp -- Managed C++ examples for each class - dotnet/examples/VB/*.vb -- simple Visual Basic examples for each class - dotnet/Projection/* -- a more complex C# application - - legacy/C/* -- C implementation of geodesic routines - legacy/Fortran/* -- Fortran implementation of geodesic routines + command-line utilities Makefile.mk -- Unix/Linux makefiles configure -- autoconf configuration script CMakeLists.txt -- cmake configuration files cmake/ - FindGeographicLib.cmake -- cmake find script - *.cmake.in -- cmake config templates + support files for building with CMake + + windows/ + project files for building under Windows (but CMake is preferred) + + maxima/ + Maxima code for generating series expansions, etc. + + matlab/ + geographiclib/ + *.m, private/*.m -- Matlab implementation of some classes + geographiclib-legacy/ + *.{m,cpp} -- legacy Matlab routines + + doc/ + files for generating documentation with Doxygen + + man/ + man pages for the utilities + + python/GeographicLib/*.py -- Python implementation of geodesic routines + + java/.../*.java -- Java implementation of geodesic routines + + js/ + src/*.js -- JavaScript implementation of geodesic routines + samples/*.html -- demonstrations of the JavaScript interface + + legacy/ + C/ -- C implementation of geodesic routines + Fortran/ -- Fortran implementation of geodesic routines + + dotnet/ + NETGeographicLib/*.{cpp,h} -- .NET wrapper for GeographicLib + examples/ + CS/*.cs -- simple C# examples for each class + ManagedCPP/*.cpp -- Managed C++ examples for each class + VB/*.vb -- simple Visual Basic examples for each class + Projection/ -- a more complex C# application diff --git a/gtsam/3rdparty/GeographicLib/AUTHORS b/gtsam/3rdparty/GeographicLib/AUTHORS index 01c69972b..8a9c048c1 100644 --- a/gtsam/3rdparty/GeographicLib/AUTHORS +++ b/gtsam/3rdparty/GeographicLib/AUTHORS @@ -2,5 +2,10 @@ Charles Karney Francesco Paolo Lovergine (autoconfiscation) Mathieu Peyréga (help with gravity models) Andrew MacIntyre (python/setup.py) -Skip Breidbach (maven support for Java) +Skip Breidbach (maven support for Java) Scott Heiman (.NET wrappers + C# examples) +Chris Bennight (deploying Java library) +Sebastian Mattheis (gnomonic projection in Java) +Yurij Mikhalevich <0@39.yt> (node.js port) +Phil Miller (putting tests into python/setup.py) +Jonathan Takahashi (boost-python sample) diff --git a/gtsam/3rdparty/GeographicLib/CMakeLists.txt b/gtsam/3rdparty/GeographicLib/CMakeLists.txt index e698f622a..a0d54a5db 100644 --- a/gtsam/3rdparty/GeographicLib/CMakeLists.txt +++ b/gtsam/3rdparty/GeographicLib/CMakeLists.txt @@ -2,7 +2,7 @@ project (GeographicLib) # Version information set (PROJECT_VERSION_MAJOR 1) -set (PROJECT_VERSION_MINOR 35) +set (PROJECT_VERSION_MINOR 49) set (PROJECT_VERSION_PATCH 0) set (PROJECT_VERSION "${PROJECT_VERSION_MAJOR}.${PROJECT_VERSION_MINOR}") if (PROJECT_VERSION_PATCH GREATER 0) @@ -12,23 +12,23 @@ endif () if (DEFINED CPACK_PACKAGE_VERSION_COUNT) # majic (version 0.1.9 and later) invokes cmake defining, e.g., - # -D CPACK_PACKAGE_VERSION=1.35-SNAPSHOT + # -D CPACK_PACKAGE_VERSION=1.37-001-SNAPSHOT # -D CPACK_PACKAGE_VERSION_COUNT=2 # -D CPACK_PACKAGE_VERSION_MAJOR=1 - # -D CPACK_PACKAGE_VERSION_MINOR=35 - # -D CPACK_PACKAGE_VERSION_SUFFIX=-SNAPSHOT - # Check that the first two version numbers are consistent. + # -D CPACK_PACKAGE_VERSION_MINOR=36 + # -D CPACK_PACKAGE_VERSION_SUFFIX=-001-SNAPSHOT + # Check that the version numbers are consistent. if (CPACK_PACKAGE_VERSION_COUNT EQUAL 2) - set (CPACK_PACKAGE_VERSION_PATCH ${PROJECT_VERSION_PATCH}) + set (CPACK_PACKAGE_VERSION_PATCH 0) elseif (CPACK_PACKAGE_VERSION_COUNT LESS 2) message (FATAL_ERROR "CPACK_PACKAGE_VERSION_COUNT must be 2 or more") endif () if (NOT ( CPACK_PACKAGE_VERSION_MAJOR EQUAL PROJECT_VERSION_MAJOR AND - CPACK_PACKAGE_VERSION_MINOR EQUAL PROJECT_VERSION_MINOR)) + CPACK_PACKAGE_VERSION_MINOR EQUAL PROJECT_VERSION_MINOR AND + CPACK_PACKAGE_VERSION_PATCH EQUAL PROJECT_VERSION_PATCH)) message (FATAL_ERROR "Inconsistency in CPACK and PROJECT version numbers") endif () - set (PROJECT_VERSION_PATCH ${CPACK_PACKAGE_VERSION_PATCH}) set (PROJECT_VERSION ${CPACK_PACKAGE_VERSION}) else () @@ -42,8 +42,8 @@ endif () # The library version tracks the numbering given by libtool in the # autoconf set up. -set (LIBVERSION 10) -set (LIBVERSIONFULL 10.1.2) +set (LIBVERSION_API 17) +set (LIBVERSION_BUILD 17.1.2) string (TOLOWER ${PROJECT_NAME} PROJECT_NAME_LOWER) string (TOUPPER ${PROJECT_NAME} PROJECT_NAME_UPPER) @@ -61,63 +61,22 @@ cmake_minimum_required (VERSION 2.8.4) # This version was released 2011-02-16 # CMAKE_INSTALL_PREFIX being used when it's ON. if (WIN32) - option (COMMON_INSTALL_PATH "Use a common installation path for packages" OFF) + option (COMMON_INSTALL_PATH "Use a common installation path for packages" + OFF) else () option (COMMON_INSTALL_PATH "Use a common installation path for packages" ON) endif () -# The use of PACKAGE_PATH and INSTALL_PATH is now DEPRECATED. -# (2) PACKAGE_PATH and INSTALL_PATH govern the find_package search -# path and the installation directory. (find_package is not used by -# GeographicLib since it doesn't depend on other packages. However -# PACKAGE_PATH is used here for uniformity with other packages which -# adopt the same conventions.) -# -# If PACKAGE_PATH is defined, it is prepended to CMAKE_PREFIX_PATH. -# -# If INSTALL_PATH is not specified but PACKAGE_PATH is, then -# INSTALL_PATH is set to -# ${PACKAGE_PATH}, if COMMON_INSTALL_PATH is ON; -# ${PACKAGE_PATH}/${PROJECT_NAME}-${PROJECT_VERSION}, otherwise. -# -# If INSTALL_PATH is now defined, then set CMAKE_INSTALL_PREFIX to -# INSTALL_PATH. -# -# Typically, only PACKAGE_PATH needs to be specified, e.g., -# cmake -D PACKAGE_PATH=/opt .. (on Linux) -# => CMAKE_PREFIX_PATH=/opt CMAKE_INSTALL_PREFIX=/opt -# cmake -D PACKAGE_PATH=C:/pkg .. (on Windows) -# => CMAKE_PREFIX_PATH=C:/pkg CMAKE_INSTALL_PREFIX=C:/pkg/GeographicLib-1.22 - -if (PACKAGE_PATH) - set (CMAKE_PREFIX_PATH ${PACKAGE_PATH} ${CMAKE_PREFIX_PATH}) - message (STATUS "CMAKE_PREFIX_PATH set to ${CMAKE_PREFIX_PATH}") -endif () - -if (NOT INSTALL_PATH AND PACKAGE_PATH) - if (COMMON_INSTALL_PATH) - set (INSTALL_PATH ${PACKAGE_PATH} CACHE PATH "Installation directory" FORCE) - else () - set (INSTALL_PATH ${PACKAGE_PATH}/${PROJECT_NAME}-${PROJECT_VERSION} - CACHE PATH "Installation directory" FORCE) - endif () -endif () -if (INSTALL_PATH) - file (TO_CMAKE_PATH ${INSTALL_PATH} CMAKE_INSTALL_PREFIX) - message (STATUS "CMAKE_INSTALL_PREFIX set to ${CMAKE_INSTALL_PREFIX}") -endif () +# (2) PACKAGE_PATH and INSTALL_PATH have now been removed # (3) Where to look for data files. Various classes look in the geoids, # gravity, magnetic, subdirectories of ${GEOGRAPHICLIB_DATA}. if (WIN32) # The binary installers for the data files for Windows are created - # with Inno Setup which uses {commonappdata}. On most Windows - # systems this is - # "C:/Documents and Settings/All Users/Application Data", while on - # newer systems (Windows 7), it is C:/ProgramData. However the - # longer name "works" on all Windows systems. + # with Inno Setup which uses {commonappdata} which (since Windows + # Vista) is C:/ProgramData. set (GEOGRAPHICLIB_DATA - "C:/Documents and Settings/All Users/Application Data/GeographicLib" + "C:/ProgramData/GeographicLib" CACHE PATH "Location for data for GeographicLib") else () set (GEOGRAPHICLIB_DATA @@ -136,15 +95,15 @@ endif () set_property (CACHE GEOGRAPHICLIB_LIB_TYPE PROPERTY STRINGS "SHARED" "STATIC" "BOTH") -if ("${GEOGRAPHICLIB_LIB_TYPE}" STREQUAL "BOTH") +if (GEOGRAPHICLIB_LIB_TYPE STREQUAL "BOTH") set (GEOGRAPHICLIB_SHARED_LIB ON) set (GEOGRAPHICLIB_STATIC_LIB ON) set (GEOGRAPHICLIB_LIB_TYPE_VAL 2) -elseif ("${GEOGRAPHICLIB_LIB_TYPE}" STREQUAL "SHARED") +elseif (GEOGRAPHICLIB_LIB_TYPE STREQUAL "SHARED") set (GEOGRAPHICLIB_SHARED_LIB ON) set (GEOGRAPHICLIB_STATIC_LIB OFF) set (GEOGRAPHICLIB_LIB_TYPE_VAL 1) -elseif ("${GEOGRAPHICLIB_LIB_TYPE}" STREQUAL "STATIC") +elseif (GEOGRAPHICLIB_LIB_TYPE STREQUAL "STATIC") set (GEOGRAPHICLIB_SHARED_LIB OFF) set (GEOGRAPHICLIB_STATIC_LIB ON) set (GEOGRAPHICLIB_LIB_TYPE_VAL 0) @@ -174,29 +133,24 @@ else () set (PROJECT_DEFINITIONS ${PROJECT_STATIC_DEFINITIONS}) endif () -# (5) Compile the Matlab interfaces? Skip Matlab compilation if OFF -set (MATLAB_COMPILER OFF CACHE STRING - "Compiler for matlab/octave interface: mex or mkoctfile or OFF") -set_property (CACHE MATLAB_COMPILER PROPERTY STRINGS "mex" "mkoctfile" OFF) - -# (6) Create the documentation? This depends on whether doxygen can be +# (5) Create the documentation? This depends on whether doxygen can be # found. If this is OFF, then links will be provided to the online # documentation on Sourceforge. option (GEOGRAPHICLIB_DOCUMENTATION "Use doxygen to create the documentation" OFF) -# (7) Build .NET wrapper library NETGeographicLib. This only applies to +# (6) Build .NET wrapper library NETGeographicLib. This only applies to # Windows. Default is OFF, because, currently, most people don't use # this interface. option (BUILD_NETGEOGRAPHICLIB "Build NETGeographicLib library" OFF) -# (8) Set the default "real" precision. This should probably be left +# (7) Set the default "real" precision. This should probably be left # at 2 (double). set (GEOGRAPHICLIB_PRECISION 2 CACHE STRING - "Default real precision: 1 = float, 2 = double, 3 = long double") -set_property (CACHE GEOGRAPHICLIB_PRECISION PROPERTY STRINGS 1 2 3) + "Precision: 1 = float, 2 = double, 3 = extended, 4 = quadruple, 5 = variable") +set_property (CACHE GEOGRAPHICLIB_PRECISION PROPERTY STRINGS 1 2 3 4 5) -# (9) When making a binary package, should we include the debug version +# (8) When making a binary package, should we include the debug version # of the library? This applies to MSVC only, because that's the # platform where debug and release compilations do not inter-operate. # It requires building as follows: @@ -206,6 +160,23 @@ set_property (CACHE GEOGRAPHICLIB_PRECISION PROPERTY STRINGS 1 2 3) option (PACKAGE_DEBUG_LIBS "Include debug versions of library in binary package" OFF) +# (9) Try to link against boost when building the examples. The +# NearestNeighbor example optionally uses the Boost library. Set to ON, +# if you want to exercise this functionality. Default is OFF, so that +# cmake configuration isn't slowed down looking for Boost. +option (USE_BOOST_FOR_EXAMPLES + "Look for Boost library when compiling examples" OFF) + +# (10) On Mac OS X, build multiple architectures? Set to ON to build +# i386 and x86_64. Default is OFF, meaning build for default +# architecture. +option (APPLE_MULTIPLE_ARCHITECTURES + "Build multiple architectures for Apple systems" OFF) + +# (11) Convert warnings into errors? Default is OFF. If the tests +# directory is present you get this behavior regardless. +option (CONVERT_WARNINGS_TO_ERRORS "Convert warnings into errors?" OFF) + set (LIBNAME Geographic) if (MSVC OR CMAKE_CONFIGURATION_TYPES) # For multi-config systems and for Visual Studio, the debug version of @@ -213,48 +184,262 @@ if (MSVC OR CMAKE_CONFIGURATION_TYPES) set (CMAKE_DEBUG_POSTFIX _d) endif () +if (EXISTS ${PROJECT_SOURCE_DIR}/tests/CMakeLists.txt) + set (DEVELOPER ON) +else () + set (DEVELOPER OFF) +endif () + if (NOT MSVC) # Set the run time path for shared libraries for non-Windows machines. # (1) include link path for external packages (not needed with - # GeographicLib because there are no external packages). - set (CMAKE_INSTALL_RPATH_USE_LINK_PATH TRUE) + # GeographicLib because there are no external packages). This only + # makes sense for native builds. + if (NOT CMAKE_CROSSCOMPILING) + set (CMAKE_INSTALL_RPATH_USE_LINK_PATH TRUE) + endif () # (2) include installed path for GeographicLib. if (NOT APPLE) # Use relative path so that package is relocatable set (CMAKE_INSTALL_RPATH "\$ORIGIN/../lib${LIB_SUFFIX}") else () - # Need absolute path with MacOSx - set (CMAKE_INSTALL_NAME_DIR "${CMAKE_INSTALL_PREFIX}/lib${LIB_SUFFIX}") + if (CMAKE_VERSION VERSION_LESS 2.8.12) + # Use absolute path with MacOSx + set (CMAKE_INSTALL_NAME_DIR "${CMAKE_INSTALL_PREFIX}/lib${LIB_SUFFIX}") + else () + # cmake 2.8.12 introduced a way to make the package relocatable. + # See also INSTALL_RPATH property on the tools. + set (CMAKE_MACOSX_RPATH ON) + endif () endif () endif () -if (NOT (CYGWIN OR ANDROID)) - # cygwin and android have a long double but the support for ::cbrtl, - # etc., is missing - include (CheckTypeSize) - check_type_size ("long double" LONG_DOUBLE BUILTIN_TYPES_ONLY) -endif () +include (CheckTypeSize) +check_type_size ("long double" LONG_DOUBLE BUILTIN_TYPES_ONLY) +set (GEOGRAPHICLIB_HAVE_LONG_DOUBLE ${HAVE_LONG_DOUBLE}) include (TestBigEndian) -test_big_endian (WORDS_BIGENDIAN) +test_big_endian (GEOGRAPHICLIB_WORDS_BIGENDIAN) + +# Make the compiler more picky. +include (CheckCXXCompilerFlag) +if (MSVC) + string (REGEX REPLACE "/W[0-4]" "" CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS}") + # Turn on parallel builds for Visual Studio + set (CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} /W4 /MP") +else () + set (FLOAT_CONVERSION_FLAG "-Wfloat-conversion") + check_cxx_compiler_flag (${FLOAT_CONVERSION_FLAG} FLOAT_CONVERSION) + if (NOT FLOAT_CONVERSION) + set (FLOAT_CONVERSION_FLAG) + endif () + set (CMAKE_CXX_FLAGS + "${CMAKE_CXX_FLAGS} -Wall -Wextra ${FLOAT_CONVERSION_FLAG}") + # g++ 6.0 defaults to -std=gnu++14 + if (NOT (CMAKE_CXX_COMPILER_ID STREQUAL GNU AND + NOT CMAKE_CXX_COMPILER_VERSION VERSION_LESS 6.0) OR + # but Boost 1.60 quadmath needs c++14 and not gnu++14 + GEOGRAPHICLIB_PRECISION EQUAL 4) + # check for C++11 support. This flag is *not* propagated to clients + # that use GeographicLib. However, this is of no consequence. When + # the client code is being compiled (and the GeographicLib headers + # being included), work-alike substitutions are used. + # The only "deprecated" flag included here is "0x" to activate C++11 + # with old versions of g++. We'll add "17" when it's available. + # Note: C++11 (actually gnu++14) support is turned on by default in + # g++ 6.1 and later. + foreach (_F 14 11 0x) + set (CXX11_FLAG "-std=c++${_F}") + set (_T CXX11TEST${_F}) + check_cxx_compiler_flag (${CXX11_FLAG} ${_T}) + if (${_T}) + break () + endif () + unset (CXX11_FLAG) + endforeach () + if (CXX11_FLAG) + set (CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${CXX11_FLAG}") + endif () + endif () +endif () +if (DEVELOPER OR CONVERT_WARNINGS_TO_ERRORS) + if (MSVC) + set (CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} /WX") + set (CMAKE_STATIC_LINKER_FLAGS "${CMAKE_STATIC_LINKER_FLAGS} /WX") + set (CMAKE_SHARED_LINKER_FLAGS "${CMAKE_SHARED_LINKER_FLAGS} /WX") + set (CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} /WX") + else () + set (CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Werror") + endif () +endif () + +include (CheckCXXSourceCompiles) +if (MSVC) + set (CMAKE_REQUIRED_FLAGS "${CMAKE_CXX_FLAGS} /WX") +else () + set (CMAKE_REQUIRED_FLAGS "${CMAKE_CXX_FLAGS} -Werror") +endif () +# Check whether the C++11 math function: std::expm1, std::atanh, +# etc. are available. This flag is *not* propagated to clients that use +# GeographicLib. However, this is of no consequence. When the client +# code is being compiled (and the GeographicLib headers being included), +# work-alike substitutions are used. +check_cxx_source_compiles ( + "#include +int main() { + int q; + return int(std::hypot(3.0, 4.0) + std::expm1(0.5) + + std::log1p(2.0) + std::asinh(10.0) + + std::atanh(0.8) + std::cbrt(8.0) + + std::fma(1.0, 2.0, 3.0) + std::remquo(100.0, 90.0, &q) + + std::remainder(100.0, 90.0) + std::copysign(1.0, -0.0)) + + std::isfinite(4.0) + std::isnan(0.0); +}\n" CXX11_MATH) +if (CXX11_MATH) + add_definitions (-DGEOGRAPHICLIB_CXX11_MATH=1) +else () + add_definitions (-DGEOGRAPHICLIB_CXX11_MATH=0) +endif () + +# Check whether the C++11 static_assert macro is available. This flag +# is *not* propagated to clients that use GeographicLib. However, this +# is of no consequence. When the client code is being compiled (and the +# GeographicLib headers being included), a work-alike substitution is +# used. +check_cxx_source_compiles ( + "#include +int main() { + static_assert(true, \"static assert test\"); + return 0; +}\n" CXX11_STATIC_ASSERT) +if (CXX11_STATIC_ASSERT) + add_definitions (-DGEOGRAPHICLIB_HAS_STATIC_ASSERT=1) +else () + add_definitions (-DGEOGRAPHICLIB_HAS_STATIC_ASSERT=0) +endif () + +# Set the include directories. Look in ${PROJECT_BINARY_DIR}/include +# first because that's where Config.h will be +include_directories ("${PROJECT_BINARY_DIR}/include" include) + +#if (USE_BOOST_FOR_EXAMPLES) +# # quad precision numbers appeared in Boost 1.54. +# find_package (Boost 1.54 COMPONENTS serialization) +#elseif (GEOGRAPHICLIB_PRECISION EQUAL 4) +# if (CMAKE_CXX_COMPILER_ID STREQUAL GNU AND CXX11_MATH) +# find_package (Boost 1.54) +# endif () +#endif () + +set (HIGHPREC_LIBRARIES) +if (GEOGRAPHICLIB_PRECISION EQUAL 1) + message (WARNING "Compiling with floats which results in poor accuracy") +elseif (GEOGRAPHICLIB_PRECISION EQUAL 2) + # This is the default +elseif (GEOGRAPHICLIB_PRECISION EQUAL 3) + if (WIN32) + message (WARNING + "Cannot support long double on Windows, switching to double") + set (GEOGRAPHICLIB_PRECISION 2) + endif () +elseif (GEOGRAPHICLIB_PRECISION EQUAL 4) + if (CMAKE_CXX_COMPILER_ID STREQUAL GNU AND CXX11_MATH) + if (Boost_FOUND) + include_directories ("${Boost_INCLUDE_DIRS}") + set (HIGHPREC_LIBRARIES quadmath) + if (NOT CMAKE_CXX_COMPILER_VERSION VERSION_LESS 4.8) + # Enable Q suffix for quad precision in g++ 4.8 and later + set (CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -fext-numeric-literals") + endif () + # Boost uses std::auto_ptr which is deprecated in C++11. Suppress + # ensuing warnings. See also + # https://svn.boost.org/trac/boost/ticket/11411 + set (CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wno-deprecated-declarations") + # Suppress the warnings that boost can spew out, e.g., + # "typedef 'boost_concept_check905' locally defined but not used" + set (CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wno-unused-local-typedefs") + endif () + endif () + if (NOT HIGHPREC_LIBRARIES) + message (WARNING "Cannot support quad precision, switching to double") + set (GEOGRAPHICLIB_PRECISION 2) + endif () +elseif (GEOGRAPHICLIB_PRECISION EQUAL 5) + if (CXX11_MATH) + # Install MPFR C++ version 3.6.5 (2016-12-19) or later from + # http://www.holoborodko.com/pavel/mpfr and install mpreal.h in the + # include directory. NOTE: MPFR C++ is covered by the GPL; be sure + # to abide by the terms of this license. + # + # For Linux, use system versions of mpfr and gmp. For Apple, use + # brew install mpfr. Recent versions of mpfr (3.0 or later) work + # fine. For Windows, download MPFR-MPIR-x86-x64-MSVC2010.zip from + # the MPFR C++ site and unpack in the top-level directory. The + # Windows build only works with GEOGRAPHICLIB_LIB_TYPE=STATIC. + # NOTE: mpfr, gmp, and mpir are covered by the LGPL; be sure to + # abide by the terms of this license. + # + # Need Visual Studio 12 2013 or later, g++ 4.5 or later; not sure + # about clang. + if (WIN32) + if (MSVC AND NOT MSVC_VERSION LESS 1800) + if (CMAKE_SIZEOF_VOID_P EQUAL 8) + set (_ARCH x64) + else () + set (_ARCH Win32) + endif () + include_directories (mpfr_mpir_x86_x64_msvc2010/mpfr + mpfr_mpir_x86_x64_msvc2010/mpir/dll/${_ARCH}/Release) + # These are C libraries so it's OK to use release versions for + # debug builds. Also these work for later versions of Visual + # Studio (specifically version 12). + link_directories (mpfr_mpir_x86_x64_msvc2010/mpfr/dll/${_ARCH}/Release + mpfr_mpir_x86_x64_msvc2010/mpir/dll/${_ARCH}/Release) + set (HIGHPREC_LIBRARIES mpfr mpir) + # Suppress the myriad of "conditional expression is constant" + # warnings + set (CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} /wd4127") + endif () + else () + if (APPLE) + include_directories (/usr/local/include) + link_directories (/usr/local/lib) + endif () + # g++ before 4.5 doesn't work (no explicit cast operator) + if (NOT (CMAKE_CXX_COMPILER_ID STREQUAL GNU AND + CMAKE_CXX_COMPILER_VERSION VERSION_LESS 4.5)) + set (HIGHPREC_LIBRARIES mpfr gmp) + endif () + endif () + endif () + if (NOT HIGHPREC_LIBRARIES) + message (WARNING "Cannot support mpfr, switching to double") + set (GEOGRAPHICLIB_PRECISION 2) + endif () +endif () + +if (APPLE AND APPLE_MULTIPLE_ARCHITECTURES) + if (CMAKE_SYSTEM_PROCESSOR MATCHES "i.86" OR + CMAKE_SYSTEM_PROCESSOR MATCHES "amd64" OR + CMAKE_SYSTEM_PROCESSOR MATCHES "x86") + set (CMAKE_OSX_ARCHITECTURES "i386;x86_64") + endif () +endif () # Create a Config.h to expose system information to the compiler configure_file ( include/GeographicLib/Config.h.in - include/GeographicLib/Config.h ) + include/GeographicLib/Config.h + @ONLY) -# The documentation depends on doxygen. Need version 1.8.1.2 or later -# for support of greek letters and math symbols. +# The documentation depends on doxygen. if (GEOGRAPHICLIB_DOCUMENTATION) set (DOXYGEN_SKIP_DOT ON) - find_package (Doxygen 1.8.1.2) - if (DOXYGEN_FOUND) - execute_process (COMMAND ${DOXYGEN_EXECUTABLE} --version - OUTPUT_VARIABLE DOXYGEN_VERSION OUTPUT_STRIP_TRAILING_WHITESPACE) - if (DOXYGEN_VERSION VERSION_LESS 1.4.0) - set (DOXYGEN_FOUND FALSE) - message (STATUS "Doxygen version found, ${DOXYGEN_VERSION}, is too old") - endif () - endif () + # Version 1.8.7 or later needed for … + find_package (Doxygen 1.8.7) + # For JavaScript documentation + find_program (JSDOC jsdoc) + # For Python documentation + find_program (SPHINX sphinx-build) endif () # The man pages are written as pod files and converted to nroff format, @@ -262,7 +447,9 @@ endif () # available on an end-user's system, the creation of the final # documentation is therefore only done in "MAINTAINER" mode. The # maintainer runs "make distrib-all" which installs the transformed -# documentation files into the source tree. +# documentation files into the source tree. Skip Apple here because +# man/makeusage.sh uses "head --lines -4" to drop the last 4 lines of a +# file and there's no simple equivalent for MacOSX if (NOT WIN32 AND NOT APPLE) find_program (HAVE_POD2MAN pod2man) find_program (HAVE_POD2HTML pod2html) @@ -278,116 +465,54 @@ if (MAINTAINER) add_dependencies (distrib-all distrib-man) endif () -# Look for the tool to compile the Matlab interfaces. -if (MATLAB_COMPILER) - if (WIN32) - set (MATLAB_COMPILER_EXT ".bat") - else () - set (MATLAB_COMPILER_EXT "") - endif () - find_program (MEX "${MATLAB_COMPILER}${MATLAB_COMPILER_EXT}") - if (MATLAB_COMPILER MATCHES "mex") - get_filename_component (MATLABDIR "${MEX}" REALPATH) - get_filename_component (MATLABDIR "${MATLABDIR}" PATH) - find_program (MEXEXTPROG "mexext${MATLAB_COMPILER_EXT}" - PATHS "${MATLABDIR}") - execute_process (COMMAND "${MEXEXTPROG}" - OUTPUT_VARIABLE MEXEXT OUTPUT_STRIP_TRAILING_WHITESPACE) - set (MEXOPTIONS "-largeArrayDims") - else () - set (MEXEXT "mex") - set (MEXOPTIONS "--mex") - endif () - if (NOT MSVC) - # mex files are shared objects => require static lib to be built with - # position independent code - set (CMAKE_POSITION_INDEPENDENT_CODE ON) - endif () - if (NOT MEX) - message (WARNING - "Cannot find Matlab compiler ${MATLAB_COMPILER}${MATLAB_COMPILER_EXT}") - elseif (NOT MEXEXT) - set (MEX OFF) - message (WARNING "Cannot determine extension for Matlab compiled code") - endif () -endif () - -# Set a default build type for single-configuration cmake generators if -# no build type is set. if (NOT CMAKE_CONFIGURATION_TYPES AND NOT CMAKE_BUILD_TYPE) + # Set a default build type for single-configuration cmake generators + # if no build type is set. set (CMAKE_BUILD_TYPE Release) endif () -# Make the compiler more picky. -if (MSVC) - string (REGEX REPLACE "/W[0-4]" "" CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS}") - set (CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} /W4") -else () - set (CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -Wextra") - # check for C++11 support. If available, the C++11 static_assert and - # various math functions (std::atanh, etc.) are used. This flag is - # *not* propagated to clients that use GeographicLib. However, this - # is of no consequence. When the client code is being compiled (and - # the GeographicLib headers being included), work-alike substitutions - # for static_assert and std::atanh are used. - include (CheckCXXCompilerFlag) - set (CXX11FLAG "-std=c++11") - check_cxx_compiler_flag (${CXX11FLAG} CXX11TEST1) - if (NOT CXX11TEST1) - set (CXX11FLAG "-std=c++0x") - check_cxx_compiler_flag (${CXX11FLAG} CXX11TEST2) - if (NOT CXX11TEST2) - unset (CXX11FLAG) - endif () - endif () - if (CXX11FLAG) - set (CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${CXX11FLAG}") - endif () -endif () - -if (APPLE) - if (CMAKE_SYSTEM_PROCESSOR MATCHES "i.86" OR - CMAKE_SYSTEM_PROCESSOR MATCHES "amd64" OR - CMAKE_SYSTEM_PROCESSOR MATCHES "x86") - set (CMAKE_OSX_ARCHITECTURES "i386 -arch x86_64") - endif () +# Set output directories for Windows so that executables and dlls are +# put in the same place +if (WIN32) + # static libaries + set (CMAKE_ARCHIVE_OUTPUT_DIRECTORY "${PROJECT_BINARY_DIR}/lib") + # shared libraries + set (CMAKE_LIBRARY_OUTPUT_DIRECTORY "${PROJECT_BINARY_DIR}/lib") + # executables and dlls + set (CMAKE_RUNTIME_OUTPUT_DIRECTORY "${PROJECT_BINARY_DIR}/bin") endif () # The list of tools (to be installed into, e.g., /usr/local/bin) #set (TOOLS CartConvert ConicProj GeodesicProj GeoConvert GeodSolve -# GeoidEval Gravity MagneticField Planimeter TransverseMercatorProj) +# GeoidEval Gravity MagneticField Planimeter RhumbSolve TransverseMercatorProj) # The list of scripts (to be installed into, e.g., /usr/local/sbin) -set (SCRIPTS - geographiclib-get-geoids geographiclib-get-gravity geographiclib-get-magnetic) +#set (SCRIPTS geographiclib-get-geoids geographiclib-get-gravity +# geographiclib-get-magnetic) set_property (GLOBAL PROPERTY USE_FOLDERS ON) -# Set the include directories. Look in ${PROJECT_BINARY_DIR}/include -# first because that's where Config.h will be -include_directories ("${PROJECT_BINARY_DIR}/include" include) - # The list of subdirectories to process add_subdirectory (src) add_subdirectory (include/GeographicLib) -# add_subdirectory (tools) +add_subdirectory (tools) add_subdirectory (man) add_subdirectory (doc) +add_subdirectory (js) add_subdirectory (matlab) add_subdirectory (python/geographiclib) -# if (GEOGRAPHICLIB_PRECISION EQUAL 2) -# # The examples assume double precision -# add_subdirectory (examples) -# endif () -if (BUILD_NETGEOGRAPHICLIB) - set (NETGEOGRAPHICLIB_LIBRARIES NETGeographicLib) - set (NETLIBNAME NETGeographic) - add_subdirectory (dotnet/NETGeographicLib) - if (GEOGRAPHICLIB_PRECISION EQUAL 2) - add_subdirectory (dotnet/examples/ManagedCPP) - endif () -endif () +#add_subdirectory (examples) +#if (MSVC AND BUILD_NETGEOGRAPHICLIB) +# if (GEOGRAPHICLIB_PRECISION EQUAL 2) +# set (NETGEOGRAPHICLIB_LIBRARIES NETGeographicLib) +# set (NETLIBNAME NETGeographic) +# add_subdirectory (dotnet/NETGeographicLib) +# add_subdirectory (dotnet/examples/ManagedCPP) +# else () +# message (WARNING "Build of NETGeographicLib only works with doubles") +# endif () +#endif () add_subdirectory (cmake) -if (EXISTS ${PROJECT_SOURCE_DIR}/tests/CMakeLists.txt) +if (DEVELOPER) add_subdirectory (tests) endif () @@ -421,10 +546,10 @@ set (CPACK_SOURCE_IGNORE_FILES "${PROJECT_SOURCE_DIR}/BUILD" "${PROJECT_SOURCE_DIR}/(tests|testdata|cgi-bin|.*\\\\.cache)/" "${PROJECT_SOURCE_DIR}/(distrib|.*-distrib|.*-installer|geodesic-papers)/" - "${PROJECT_SOURCE_DIR}/[^/]*\\\\.(html|kmz|pdf)\$" - "${PROJECT_SOURCE_DIR}/(autogen|biblio|js-compress)\\\\.sh\$" - "${PROJECT_SOURCE_DIR}/(geodesic-biblio.txt|makefile-admin|[^/]*\\\\.png)\$" - "${PROJECT_SOURCE_DIR}/matlab/matlab-.*blurb.txt\$" ) + "${PROJECT_SOURCE_DIR}/[^/]*\\\\.(xml|html|css|kmz|pdf)\$" + "${PROJECT_SOURCE_DIR}/(autogen|biblio)\\\\.sh\$" + "${PROJECT_SOURCE_DIR}/(robots.txt|geodesic-biblio.txt|makefile-admin|[^/]*\\\\.png)\$" + "${PROJECT_SOURCE_DIR}/matlab/.*blurb.txt\$") set (CPACK_SOURCE_GENERATOR TGZ) set (CPACK_RESOURCE_FILE_LICENSE ${PROJECT_SOURCE_DIR}/LICENSE.txt) @@ -435,31 +560,31 @@ if (WIN32) # The Windows binary packager is NSIS. Set the necessary variables # for this. set (CPACK_NSIS_CONTACT "charles@karney.com") - set (CPACK_NSIS_URL_INFO_ABOUT "http://geographiclib.sf.net") + set (CPACK_NSIS_URL_INFO_ABOUT "https://geographiclib.sourceforge.io") set (CPACK_NSIS_HELP_LINK "mailto:charles@karney.com") if (CMAKE_SIZEOF_VOID_P EQUAL 8) - # Hardcode the prefix for Visual Studio 10 - set (CPACK_NSIS_INSTALL_ROOT "C:\\\\pkg-vc10-x64") + # Hardcode the prefix for Visual Studio 12 2013 + set (CPACK_NSIS_INSTALL_ROOT "C:\\\\pkg-vc12-x64") set (CPACK_PACKAGE_FILE_NAME "${CPACK_PACKAGE_INSTALL_DIRECTORY}-win64") set (CPACK_NSIS_PACKAGE_NAME "${PROJECT_NAME} x64 ${PROJECT_VERSION}") set (CPACK_PACKAGE_INSTALL_REGISTRY_KEY "${PROJECT_NAME}-x64-${PROJECT_VERSION}") else () - # Hardcode the prefix for Visual Studio 10 - set (CPACK_NSIS_INSTALL_ROOT "C:\\\\pkg-vc10") + # Hardcode the prefix for Visual Studio 12 2013 + set (CPACK_NSIS_INSTALL_ROOT "C:\\\\pkg-vc12-win32") set (CPACK_PACKAGE_FILE_NAME "${CPACK_PACKAGE_INSTALL_DIRECTORY}-win32") - set (CPACK_NSIS_PACKAGE_NAME "${PROJECT_NAME} ${PROJECT_VERSION}") + set (CPACK_NSIS_PACKAGE_NAME "${PROJECT_NAME} win32 ${PROJECT_VERSION}") set (CPACK_PACKAGE_INSTALL_REGISTRY_KEY - "${PROJECT_NAME}-${PROJECT_VERSION}") + "${PROJECT_NAME}-win32-${PROJECT_VERSION}") endif () set (CPACK_NSIS_DISPLAY_NAME ${CPACK_NSIS_PACKAGE_NAME}) set (CPACK_NSIS_MENU_LINKS - "http://geographiclib.sf.net/${PROJECT_VERSION}/index.html" + "https://geographiclib.sourceforge.io/${PROJECT_VERSION}/index.html" "Library documentation" - "http://geographiclib.sf.net/${PROJECT_VERSION}/utilities.html" + "https://geographiclib.sourceforge.io/${PROJECT_VERSION}/utilities.html" "Utilities documentation" - "http://geographiclib.sf.net" "GeographicLib home page" - "http://sf.net/projects/geographiclib/" "Main project page") + "https://geographiclib.sourceforge.io" "GeographicLib home page" + "https://sourceforge.net/projects/geographiclib/" "Main project page") set (CPACK_NSIS_MODIFY_PATH ON) elseif (APPLE) # Not tested @@ -510,7 +635,7 @@ if (MAINTAINER) _CPack_Packages/Linux-Source/TGZ.DOS/ && cd _CPack_Packages/Linux-Source/TGZ.DOS && find . -type f | - egrep '/\(doxyfile.*\\.in|MANIFEST.in|NEWS|AUTHORS|INSTALL|pom\\.xml|dummy.*\\.in|.*\\.\(cpp|hpp|h\\.in|txt|pro|usage|pod|py|m|mac|cmake\\.in|cmake|h|js|c|for|dox|cs|vb|inc|java|html\\.in\)\)$$' | + egrep -v '/\(compile|config[^/]*|depcomp|install-sh|missing|[Mm]akefile[^/]*|[^/]*\\.\(ac|am|csproj|eps|kmz|m4|pdf|png|resx|settings|sh|sln|vcproj|vcxproj\)\)$$' | xargs unix2dos -q -k && find ${CPACK_SOURCE_PACKAGE_FILE_NAME} -type f | zip -q ${CMAKE_BINARY_DIR}/${CPACK_SOURCE_PACKAGE_FILE_NAME}.zip -@ @@ -518,5 +643,5 @@ if (MAINTAINER) add_dependencies (dist distrib-all) endif () -# Add a test target; the tests are in tools. -enable_testing () +# The test suite -- split into a separate file because it's rather large. +#include (tools/tests.cmake) diff --git a/gtsam/3rdparty/GeographicLib/INSTALL b/gtsam/3rdparty/GeographicLib/INSTALL index f669d15f1..79d1162a5 100644 --- a/gtsam/3rdparty/GeographicLib/INSTALL +++ b/gtsam/3rdparty/GeographicLib/INSTALL @@ -1,3 +1,3 @@ For installation instructions, open - http://geographiclib.sourceforge.net/html/install.html + https://geographiclib.sourceforge.io/html/install.html diff --git a/gtsam/3rdparty/GeographicLib/LICENSE.txt b/gtsam/3rdparty/GeographicLib/LICENSE.txt index e70861b2a..d0df4c1aa 100644 --- a/gtsam/3rdparty/GeographicLib/LICENSE.txt +++ b/gtsam/3rdparty/GeographicLib/LICENSE.txt @@ -1,6 +1,7 @@ -This license applies to GeographicLib, versions 1.12 and later. +The MIT License (MIT); this license applies to GeographicLib, +versions 1.12 and later. -Copyright (c) 2008-2013, Charles Karney +Copyright (c) 2008-2017, Charles Karney Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation diff --git a/gtsam/3rdparty/GeographicLib/Makefile.am b/gtsam/3rdparty/GeographicLib/Makefile.am index 8accc4719..f7a0f419f 100644 --- a/gtsam/3rdparty/GeographicLib/Makefile.am +++ b/gtsam/3rdparty/GeographicLib/Makefile.am @@ -7,34 +7,44 @@ AUTOMAKE_OPTIONS = foreign ACLOCAL_AMFLAGS = -I m4 -SUBDIRS = src man tools doc include matlab python cmake examples +SUBDIRS = src man tools doc js include matlab python cmake examples -EXTRA_DIST = AUTHORS 00README.txt LICENSE.txt NEWS INSTALL pom.xml \ - Makefile.mk CMakeLists.txt windows maxima doc legacy java dotnet +EXTRA_DIST = AUTHORS 00README.txt LICENSE.txt NEWS INSTALL README.md \ + Makefile.mk CMakeLists.txt windows maxima doc legacy java js dotnet \ + wrapper + +# Install the pkg-config file; the directory is set using +# PKG_INSTALLDIR in configure.ac. +pkgconfig_DATA = cmake/geographiclib.pc dist-hook: - rm -rf $(distdir)/doc/html $(distdir)/doc/manpages ; \ - find $(distdir)/maxima -type f -name '*.lsp' | xargs rm -rf ; \ - rm -rf $(distdir)/java/targets ; \ - find $(distdir)/java -type f -name '*.class' | xargs rm -rf ; \ - find $(distdir)/windows -mindepth 1 -type d | xargs rm -rf ; \ + rm -rf $(distdir)/doc/html $(distdir)/doc/manpages \ + $(distdir)/doc/GeographicLib.dox + find $(distdir)/maxima -type f -name '*.lsp' | xargs rm -rf + rm -rf $(distdir)/java/targets + find $(distdir)/java -type f -name '*.class' | xargs rm -rf + find $(distdir)/wrapper -mindepth 2 -type d | xargs rm -rf + find $(distdir)/wrapper -type f -name '*.o' -o -name '*.mex*' | \ + xargs rm -f + find $(distdir)/windows -mindepth 1 -type d | xargs rm -rf find $(distdir)/windows -type f \ ! \( -name '*.sln' -o -name '*.vc*proj' -o -name '*.mk' \)| \ - xargs rm -f ; \ + xargs rm -f find $(distdir) \ - \( -name .svn -o -name '.git*' -o -name CVS -o -name Makefile -o -name '*~' -o -name '*#*' -o -name 'CMakeFiles' -o -name '*.log' -o -name '*.tmp' -o -name '*.pyc' -o -name '*.bak' -o -name '*.BAK' -o -name geographiclib.js \)| \ - xargs rm -rf ; \ - echo include Makefile.mk > $(distdir)/Makefile ; \ + \( -name .svn -o -name '.git*' -o -name CVS -o -name Makefile -o -name '*~' -o -name '*#*' -o -name 'CMakeFiles' -o -name '*.log' -o -name '*.tmp' -o -name '*.pyc' -o -name '*.bak' -o -name '*.BAK' -o -name geographiclib.js \) | \ + xargs rm -rf + echo include Makefile.mk > $(distdir)/Makefile sed -e "s/Unconfigured/$(PACKAGE_VERSION)/" \ -e "s/MAJOR .*/MAJOR ${GEOGRAPHICLIB_VERSION_MAJOR}/" \ -e "s/MINOR .*/MINOR ${GEOGRAPHICLIB_VERSION_MINOR}/" \ -e "s/PATCH .*/PATCH ${GEOGRAPHICLIB_VERSION_PATCH}/" \ $(top_srcdir)/include/GeographicLib/Config.h > \ $(distdir)/include/GeographicLib/Config.h + # Custom rules all-local: man doc -install-data-local: install-doc # install-matlab +install-data-local: install-doc doc: man $(MAKE) -C doc doc @@ -45,7 +55,4 @@ install-doc: man: $(MAKE) -C man man -# install-matlab: -# $(MAKE) -C matlab install-matlab - .PHONY: doc install-doc man install-matlab install-python diff --git a/gtsam/3rdparty/GeographicLib/Makefile.in b/gtsam/3rdparty/GeographicLib/Makefile.in index a8345a2e2..1325b01c8 100644 --- a/gtsam/3rdparty/GeographicLib/Makefile.in +++ b/gtsam/3rdparty/GeographicLib/Makefile.in @@ -1,7 +1,7 @@ -# Makefile.in generated by automake 1.12.2 from Makefile.am. +# Makefile.in generated by automake 1.15 from Makefile.am. # @configure_input@ -# Copyright (C) 1994-2012 Free Software Foundation, Inc. +# Copyright (C) 1994-2014 Free Software Foundation, Inc. # This Makefile.in is free software; the Free Software Foundation # gives unlimited permission to copy and/or distribute it, @@ -18,24 +18,63 @@ # Makefile.am # # Copyright (C) 2009, Francesco P. Lovergine + VPATH = @srcdir@ -am__make_dryrun = \ - { \ - am__dry=no; \ +am__is_gnu_make = { \ + if test -z '$(MAKELEVEL)'; then \ + false; \ + elif test -n '$(MAKE_HOST)'; then \ + true; \ + elif test -n '$(MAKE_VERSION)' && test -n '$(CURDIR)'; then \ + true; \ + else \ + false; \ + fi; \ +} +am__make_running_with_option = \ + case $${target_option-} in \ + ?) ;; \ + *) echo "am__make_running_with_option: internal error: invalid" \ + "target option '$${target_option-}' specified" >&2; \ + exit 1;; \ + esac; \ + has_opt=no; \ + sane_makeflags=$$MAKEFLAGS; \ + if $(am__is_gnu_make); then \ + sane_makeflags=$$MFLAGS; \ + else \ case $$MAKEFLAGS in \ *\\[\ \ ]*) \ - echo 'am--echo: ; @echo "AM" OK' | $(MAKE) -f - 2>/dev/null \ - | grep '^AM OK$$' >/dev/null || am__dry=yes;; \ - *) \ - for am__flg in $$MAKEFLAGS; do \ - case $$am__flg in \ - *=*|--*) ;; \ - *n*) am__dry=yes; break;; \ - esac; \ - done;; \ + bs=\\; \ + sane_makeflags=`printf '%s\n' "$$MAKEFLAGS" \ + | sed "s/$$bs$$bs[$$bs $$bs ]*//g"`;; \ esac; \ - test $$am__dry = yes; \ - } + fi; \ + skip_next=no; \ + strip_trailopt () \ + { \ + flg=`printf '%s\n' "$$flg" | sed "s/$$1.*$$//"`; \ + }; \ + for flg in $$sane_makeflags; do \ + test $$skip_next = yes && { skip_next=no; continue; }; \ + case $$flg in \ + *=*|--*) continue;; \ + -*I) strip_trailopt 'I'; skip_next=yes;; \ + -*I?*) strip_trailopt 'I';; \ + -*O) strip_trailopt 'O'; skip_next=yes;; \ + -*O?*) strip_trailopt 'O';; \ + -*l) strip_trailopt 'l'; skip_next=yes;; \ + -*l?*) strip_trailopt 'l';; \ + -[dEDm]) skip_next=yes;; \ + -[JT]) skip_next=yes;; \ + esac; \ + case $$flg in \ + *$$target_option*) has_opt=yes; break;; \ + esac; \ + done; \ + test $$has_opt = yes +am__make_dryrun = (target_option=n; $(am__make_running_with_option)) +am__make_keepgoing = (target_option=k; $(am__make_running_with_option)) pkgdatadir = $(datadir)/@PACKAGE@ pkgincludedir = $(includedir)/@PACKAGE@ pkglibdir = $(libdir)/@PACKAGE@ @@ -56,47 +95,110 @@ build_triplet = @build@ host_triplet = @host@ target_triplet = @target@ subdir = . -DIST_COMMON = $(am__configure_deps) $(srcdir)/Makefile.am \ - $(srcdir)/Makefile.in $(top_srcdir)/configure \ - $(top_srcdir)/include/GeographicLib/Config-ac.h.in AUTHORS \ - INSTALL NEWS config.guess config.sub depcomp install-sh \ - ltmain.sh missing ACLOCAL_M4 = $(top_srcdir)/aclocal.m4 am__aclocal_m4_deps = $(top_srcdir)/m4/libtool.m4 \ $(top_srcdir)/m4/ltoptions.m4 $(top_srcdir)/m4/ltsugar.m4 \ $(top_srcdir)/m4/ltversion.m4 $(top_srcdir)/m4/lt~obsolete.m4 \ - $(top_srcdir)/configure.ac + $(top_srcdir)/m4/pkg.m4 $(top_srcdir)/configure.ac am__configure_deps = $(am__aclocal_m4_deps) $(CONFIGURE_DEPENDENCIES) \ $(ACLOCAL_M4) +DIST_COMMON = $(srcdir)/Makefile.am $(top_srcdir)/configure \ + $(am__configure_deps) $(am__DIST_COMMON) am__CONFIG_DISTCLEAN_FILES = config.status config.cache config.log \ configure.lineno config.status.lineno mkinstalldirs = $(install_sh) -d CONFIG_HEADER = $(top_builddir)/include/GeographicLib/Config-ac.h CONFIG_CLEAN_FILES = CONFIG_CLEAN_VPATH_FILES = +AM_V_P = $(am__v_P_@AM_V@) +am__v_P_ = $(am__v_P_@AM_DEFAULT_V@) +am__v_P_0 = false +am__v_P_1 = : +AM_V_GEN = $(am__v_GEN_@AM_V@) +am__v_GEN_ = $(am__v_GEN_@AM_DEFAULT_V@) +am__v_GEN_0 = @echo " GEN " $@; +am__v_GEN_1 = +AM_V_at = $(am__v_at_@AM_V@) +am__v_at_ = $(am__v_at_@AM_DEFAULT_V@) +am__v_at_0 = @ +am__v_at_1 = SOURCES = DIST_SOURCES = -RECURSIVE_TARGETS = all-recursive check-recursive dvi-recursive \ - html-recursive info-recursive install-data-recursive \ - install-dvi-recursive install-exec-recursive \ - install-html-recursive install-info-recursive \ - install-pdf-recursive install-ps-recursive install-recursive \ - installcheck-recursive installdirs-recursive pdf-recursive \ - ps-recursive uninstall-recursive +RECURSIVE_TARGETS = all-recursive check-recursive cscopelist-recursive \ + ctags-recursive dvi-recursive html-recursive info-recursive \ + install-data-recursive install-dvi-recursive \ + install-exec-recursive install-html-recursive \ + install-info-recursive install-pdf-recursive \ + install-ps-recursive install-recursive installcheck-recursive \ + installdirs-recursive pdf-recursive ps-recursive \ + tags-recursive uninstall-recursive am__can_run_installinfo = \ case $$AM_UPDATE_INFO_DIR in \ n|no|NO) false;; \ *) (install-info --version) >/dev/null 2>&1;; \ esac +am__vpath_adj_setup = srcdirstrip=`echo "$(srcdir)" | sed 's|.|.|g'`; +am__vpath_adj = case $$p in \ + $(srcdir)/*) f=`echo "$$p" | sed "s|^$$srcdirstrip/||"`;; \ + *) f=$$p;; \ + esac; +am__strip_dir = f=`echo $$p | sed -e 's|^.*/||'`; +am__install_max = 40 +am__nobase_strip_setup = \ + srcdirstrip=`echo "$(srcdir)" | sed 's/[].[^$$\\*|]/\\\\&/g'` +am__nobase_strip = \ + for p in $$list; do echo "$$p"; done | sed -e "s|$$srcdirstrip/||" +am__nobase_list = $(am__nobase_strip_setup); \ + for p in $$list; do echo "$$p $$p"; done | \ + sed "s| $$srcdirstrip/| |;"' / .*\//!s/ .*/ ./; s,\( .*\)/[^/]*$$,\1,' | \ + $(AWK) 'BEGIN { files["."] = "" } { files[$$2] = files[$$2] " " $$1; \ + if (++n[$$2] == $(am__install_max)) \ + { print $$2, files[$$2]; n[$$2] = 0; files[$$2] = "" } } \ + END { for (dir in files) print dir, files[dir] }' +am__base_list = \ + sed '$$!N;$$!N;$$!N;$$!N;$$!N;$$!N;$$!N;s/\n/ /g' | \ + sed '$$!N;$$!N;$$!N;$$!N;s/\n/ /g' +am__uninstall_files_from_dir = { \ + test -z "$$files" \ + || { test ! -d "$$dir" && test ! -f "$$dir" && test ! -r "$$dir"; } \ + || { echo " ( cd '$$dir' && rm -f" $$files ")"; \ + $(am__cd) "$$dir" && rm -f $$files; }; \ + } +am__installdirs = "$(DESTDIR)$(pkgconfigdir)" +DATA = $(pkgconfig_DATA) RECURSIVE_CLEAN_TARGETS = mostlyclean-recursive clean-recursive \ distclean-recursive maintainer-clean-recursive -AM_RECURSIVE_TARGETS = $(RECURSIVE_TARGETS:-recursive=) \ - $(RECURSIVE_CLEAN_TARGETS:-recursive=) tags TAGS ctags CTAGS \ +am__recursive_targets = \ + $(RECURSIVE_TARGETS) \ + $(RECURSIVE_CLEAN_TARGETS) \ + $(am__extra_recursive_targets) +AM_RECURSIVE_TARGETS = $(am__recursive_targets:-recursive=) TAGS CTAGS \ cscope distdir dist dist-all distcheck +am__tagged_files = $(HEADERS) $(SOURCES) $(TAGS_FILES) $(LISP) +# Read a list of newline-separated strings from the standard input, +# and print each of them once, without duplicates. Input order is +# *not* preserved. +am__uniquify_input = $(AWK) '\ + BEGIN { nonempty = 0; } \ + { items[$$0] = 1; nonempty = 1; } \ + END { if (nonempty) { for (i in items) print i; }; } \ +' +# Make sure the list of sources is unique. This is necessary because, +# e.g., the same source file might be shared among _SOURCES variables +# for different programs/libraries. +am__define_uniq_tagged_files = \ + list='$(am__tagged_files)'; \ + unique=`for i in $$list; do \ + if test -f "$$i"; then echo $$i; else echo $(srcdir)/$$i; fi; \ + done | $(am__uniquify_input)` ETAGS = etags CTAGS = ctags CSCOPE = cscope DIST_SUBDIRS = $(SUBDIRS) +am__DIST_COMMON = $(srcdir)/Makefile.in \ + $(top_srcdir)/include/GeographicLib/Config-ac.h.in AUTHORS \ + INSTALL NEWS compile config.guess config.sub depcomp \ + install-sh ltmain.sh missing DISTFILES = $(DIST_COMMON) $(DIST_SOURCES) $(TEXINFOS) $(EXTRA_DIST) distdir = $(PACKAGE)-$(VERSION) top_distdir = $(distdir) @@ -141,6 +243,7 @@ am__distuninstallcheck_listfiles = $(distuninstallcheck_listfiles) \ distcleancheck_listfiles = find . -type f -print ACLOCAL = @ACLOCAL@ AMTAR = @AMTAR@ +AM_DEFAULT_VERBOSITY = @AM_DEFAULT_VERBOSITY@ AR = @AR@ AUTOCONF = @AUTOCONF@ AUTOHEADER = @AUTOHEADER@ @@ -189,6 +292,7 @@ LTLIBOBJS = @LTLIBOBJS@ LT_AGE = @LT_AGE@ LT_CURRENT = @LT_CURRENT@ LT_REVISION = @LT_REVISION@ +LT_SYS_LIBRARY_PATH = @LT_SYS_LIBRARY_PATH@ MAINT = @MAINT@ MAKEINFO = @MAKEINFO@ MANIFEST_TOOL = @MANIFEST_TOOL@ @@ -207,9 +311,11 @@ PACKAGE_TARNAME = @PACKAGE_TARNAME@ PACKAGE_URL = @PACKAGE_URL@ PACKAGE_VERSION = @PACKAGE_VERSION@ PATH_SEPARATOR = @PATH_SEPARATOR@ +PKG_CONFIG = @PKG_CONFIG@ +PKG_CONFIG_LIBDIR = @PKG_CONFIG_LIBDIR@ +PKG_CONFIG_PATH = @PKG_CONFIG_PATH@ POD2HTML = @POD2HTML@ POD2MAN = @POD2MAN@ -POW_LIB = @POW_LIB@ RANLIB = @RANLIB@ SED = @SED@ SET_MAKE = @SET_MAKE@ @@ -258,6 +364,7 @@ mandir = @mandir@ mkdir_p = @mkdir_p@ oldincludedir = @oldincludedir@ pdfdir = @pdfdir@ +pkgconfigdir = @pkgconfigdir@ prefix = @prefix@ program_transform_name = @program_transform_name@ psdir = @psdir@ @@ -275,10 +382,15 @@ top_builddir = @top_builddir@ top_srcdir = @top_srcdir@ AUTOMAKE_OPTIONS = foreign ACLOCAL_AMFLAGS = -I m4 -SUBDIRS = src man tools doc include matlab python cmake examples -EXTRA_DIST = AUTHORS 00README.txt LICENSE.txt NEWS INSTALL pom.xml \ - Makefile.mk CMakeLists.txt windows maxima doc legacy java dotnet +SUBDIRS = src man tools doc js include matlab python cmake examples +EXTRA_DIST = AUTHORS 00README.txt LICENSE.txt NEWS INSTALL README.md \ + Makefile.mk CMakeLists.txt windows maxima doc legacy java js dotnet \ + wrapper + +# Install the pkg-config file; the directory is set using +# PKG_INSTALLDIR in configure.ac. +pkgconfig_DATA = cmake/geographiclib.pc all: all-recursive .SUFFIXES: @@ -297,7 +409,6 @@ $(srcdir)/Makefile.in: @MAINTAINER_MODE_TRUE@ $(srcdir)/Makefile.am $(am__confi echo ' cd $(top_srcdir) && $(AUTOMAKE) --foreign Makefile'; \ $(am__cd) $(top_srcdir) && \ $(AUTOMAKE) --foreign Makefile -.PRECIOUS: Makefile Makefile: $(srcdir)/Makefile.in $(top_builddir)/config.status @case '$?' in \ *config.status*) \ @@ -318,8 +429,8 @@ $(ACLOCAL_M4): @MAINTAINER_MODE_TRUE@ $(am__aclocal_m4_deps) $(am__aclocal_m4_deps): include/GeographicLib/Config-ac.h: include/GeographicLib/stamp-h1 - @if test ! -f $@; then rm -f include/GeographicLib/stamp-h1; else :; fi - @if test ! -f $@; then $(MAKE) $(AM_MAKEFLAGS) include/GeographicLib/stamp-h1; else :; fi + @test -f $@ || rm -f include/GeographicLib/stamp-h1 + @test -f $@ || $(MAKE) $(AM_MAKEFLAGS) include/GeographicLib/stamp-h1 include/GeographicLib/stamp-h1: $(top_srcdir)/include/GeographicLib/Config-ac.h.in $(top_builddir)/config.status @rm -f include/GeographicLib/stamp-h1 @@ -340,6 +451,27 @@ clean-libtool: distclean-libtool: -rm -f libtool config.lt +install-pkgconfigDATA: $(pkgconfig_DATA) + @$(NORMAL_INSTALL) + @list='$(pkgconfig_DATA)'; test -n "$(pkgconfigdir)" || list=; \ + if test -n "$$list"; then \ + echo " $(MKDIR_P) '$(DESTDIR)$(pkgconfigdir)'"; \ + $(MKDIR_P) "$(DESTDIR)$(pkgconfigdir)" || exit 1; \ + fi; \ + for p in $$list; do \ + if test -f "$$p"; then d=; else d="$(srcdir)/"; fi; \ + echo "$$d$$p"; \ + done | $(am__base_list) | \ + while read files; do \ + echo " $(INSTALL_DATA) $$files '$(DESTDIR)$(pkgconfigdir)'"; \ + $(INSTALL_DATA) $$files "$(DESTDIR)$(pkgconfigdir)" || exit $$?; \ + done + +uninstall-pkgconfigDATA: + @$(NORMAL_UNINSTALL) + @list='$(pkgconfig_DATA)'; test -n "$(pkgconfigdir)" || list=; \ + files=`for p in $$list; do echo $$p; done | sed -e 's|^.*/||'`; \ + dir='$(DESTDIR)$(pkgconfigdir)'; $(am__uninstall_files_from_dir) # This directory's subdirectories are mostly independent; you can cd # into them and run 'make' without going through this Makefile. @@ -347,14 +479,13 @@ distclean-libtool: # (1) if the variable is set in 'config.status', edit 'config.status' # (which will cause the Makefiles to be regenerated when you run 'make'); # (2) otherwise, pass the desired values on the 'make' command line. -$(RECURSIVE_TARGETS) $(RECURSIVE_CLEAN_TARGETS): - @fail= failcom='exit 1'; \ - for f in x $$MAKEFLAGS; do \ - case $$f in \ - *=* | --[!k]*);; \ - *k*) failcom='fail=yes';; \ - esac; \ - done; \ +$(am__recursive_targets): + @fail=; \ + if $(am__make_keepgoing); then \ + failcom='fail=yes'; \ + else \ + failcom='exit 1'; \ + fi; \ dot_seen=no; \ target=`echo $@ | sed s/-recursive//`; \ case "$@" in \ @@ -375,31 +506,13 @@ $(RECURSIVE_TARGETS) $(RECURSIVE_CLEAN_TARGETS): if test "$$dot_seen" = "no"; then \ $(MAKE) $(AM_MAKEFLAGS) "$$target-am" || exit 1; \ fi; test -z "$$fail" -tags-recursive: - list='$(SUBDIRS)'; for subdir in $$list; do \ - test "$$subdir" = . || ($(am__cd) $$subdir && $(MAKE) $(AM_MAKEFLAGS) tags); \ - done -ctags-recursive: - list='$(SUBDIRS)'; for subdir in $$list; do \ - test "$$subdir" = . || ($(am__cd) $$subdir && $(MAKE) $(AM_MAKEFLAGS) ctags); \ - done -cscopelist-recursive: - list='$(SUBDIRS)'; for subdir in $$list; do \ - test "$$subdir" = . || ($(am__cd) $$subdir && $(MAKE) $(AM_MAKEFLAGS) cscopelist); \ - done -ID: $(HEADERS) $(SOURCES) $(LISP) $(TAGS_FILES) - list='$(SOURCES) $(HEADERS) $(LISP) $(TAGS_FILES)'; \ - unique=`for i in $$list; do \ - if test -f "$$i"; then echo $$i; else echo $(srcdir)/$$i; fi; \ - done | \ - $(AWK) '{ files[$$0] = 1; nonempty = 1; } \ - END { if (nonempty) { for (i in files) print i; }; }'`; \ - mkid -fID $$unique -tags: TAGS +ID: $(am__tagged_files) + $(am__define_uniq_tagged_files); mkid -fID $$unique +tags: tags-recursive +TAGS: tags -TAGS: tags-recursive $(HEADERS) $(SOURCES) $(TAGS_DEPENDENCIES) \ - $(TAGS_FILES) $(LISP) +tags-am: $(TAGS_DEPENDENCIES) $(am__tagged_files) set x; \ here=`pwd`; \ if ($(ETAGS) --etags-include --version) >/dev/null 2>&1; then \ @@ -415,12 +528,7 @@ TAGS: tags-recursive $(HEADERS) $(SOURCES) $(TAGS_DEPENDENCIES) \ set "$$@" "$$include_option=$$here/$$subdir/TAGS"; \ fi; \ done; \ - list='$(SOURCES) $(HEADERS) $(LISP) $(TAGS_FILES)'; \ - unique=`for i in $$list; do \ - if test -f "$$i"; then echo $$i; else echo $(srcdir)/$$i; fi; \ - done | \ - $(AWK) '{ files[$$0] = 1; nonempty = 1; } \ - END { if (nonempty) { for (i in files) print i; }; }'`; \ + $(am__define_uniq_tagged_files); \ shift; \ if test -z "$(ETAGS_ARGS)$$*$$unique"; then :; else \ test -n "$$unique" || unique=$$empty_fix; \ @@ -432,15 +540,11 @@ TAGS: tags-recursive $(HEADERS) $(SOURCES) $(TAGS_DEPENDENCIES) \ $$unique; \ fi; \ fi -ctags: CTAGS -CTAGS: ctags-recursive $(HEADERS) $(SOURCES) $(TAGS_DEPENDENCIES) \ - $(TAGS_FILES) $(LISP) - list='$(SOURCES) $(HEADERS) $(LISP) $(TAGS_FILES)'; \ - unique=`for i in $$list; do \ - if test -f "$$i"; then echo $$i; else echo $(srcdir)/$$i; fi; \ - done | \ - $(AWK) '{ files[$$0] = 1; nonempty = 1; } \ - END { if (nonempty) { for (i in files) print i; }; }'`; \ +ctags: ctags-recursive + +CTAGS: ctags +ctags-am: $(TAGS_DEPENDENCIES) $(am__tagged_files) + $(am__define_uniq_tagged_files); \ test -z "$(CTAGS_ARGS)$$unique" \ || $(CTAGS) $(CTAGSFLAGS) $(AM_CTAGSFLAGS) $(CTAGS_ARGS) \ $$unique @@ -449,18 +553,16 @@ GTAGS: here=`$(am__cd) $(top_builddir) && pwd` \ && $(am__cd) $(top_srcdir) \ && gtags -i $(GTAGS_ARGS) "$$here" - cscope: cscope.files test ! -s cscope.files \ || $(CSCOPE) -b -q $(AM_CSCOPEFLAGS) $(CSCOPEFLAGS) -i cscope.files $(CSCOPE_ARGS) - clean-cscope: -rm -f cscope.files +cscope.files: clean-cscope cscopelist +cscopelist: cscopelist-recursive -cscope.files: clean-cscope cscopelist-recursive cscopelist - -cscopelist: cscopelist-recursive $(HEADERS) $(SOURCES) $(LISP) - list='$(SOURCES) $(HEADERS) $(LISP)'; \ +cscopelist-am: $(am__tagged_files) + list='$(am__tagged_files)'; \ case "$(srcdir)" in \ [\\/]* | ?:[\\/]*) sdir="$(srcdir)" ;; \ *) sdir=$(subdir)/$(srcdir) ;; \ @@ -545,7 +647,7 @@ distdir: $(DISTFILES) ! -type d ! -perm -444 -exec $(install_sh) -c -m a+r {} {} \; \ || chmod -R a+r "$(distdir)" dist-gzip: distdir - tardir=$(distdir) && $(am__tar) | GZIP=$(GZIP_ENV) gzip -c >$(distdir).tar.gz + tardir=$(distdir) && $(am__tar) | eval GZIP= gzip $(GZIP_ENV) -c >$(distdir).tar.gz $(am__post_remove_distdir) dist-bzip2: distdir @@ -561,11 +663,17 @@ dist-xz: distdir $(am__post_remove_distdir) dist-tarZ: distdir + @echo WARNING: "Support for distribution archives compressed with" \ + "legacy program 'compress' is deprecated." >&2 + @echo WARNING: "It will be removed altogether in Automake 2.0" >&2 tardir=$(distdir) && $(am__tar) | compress -c >$(distdir).tar.Z $(am__post_remove_distdir) dist-shar: distdir - shar $(distdir) | GZIP=$(GZIP_ENV) gzip -c >$(distdir).shar.gz + @echo WARNING: "Support for shar distribution archives is" \ + "deprecated." >&2 + @echo WARNING: "It will be removed altogether in Automake 2.0" >&2 + shar $(distdir) | eval GZIP= gzip $(GZIP_ENV) -c >$(distdir).shar.gz $(am__post_remove_distdir) dist-zip: distdir @@ -583,7 +691,7 @@ dist dist-all: distcheck: dist case '$(DIST_ARCHIVES)' in \ *.tar.gz*) \ - GZIP=$(GZIP_ENV) gzip -dc $(distdir).tar.gz | $(am__untar) ;;\ + eval GZIP= gzip $(GZIP_ENV) -dc $(distdir).tar.gz | $(am__untar) ;;\ *.tar.bz2*) \ bzip2 -dc $(distdir).tar.bz2 | $(am__untar) ;;\ *.tar.lz*) \ @@ -593,22 +701,23 @@ distcheck: dist *.tar.Z*) \ uncompress -c $(distdir).tar.Z | $(am__untar) ;;\ *.shar.gz*) \ - GZIP=$(GZIP_ENV) gzip -dc $(distdir).shar.gz | unshar ;;\ + eval GZIP= gzip $(GZIP_ENV) -dc $(distdir).shar.gz | unshar ;;\ *.zip*) \ unzip $(distdir).zip ;;\ esac - chmod -R a-w $(distdir); chmod u+w $(distdir) - mkdir $(distdir)/_build - mkdir $(distdir)/_inst + chmod -R a-w $(distdir) + chmod u+w $(distdir) + mkdir $(distdir)/_build $(distdir)/_build/sub $(distdir)/_inst chmod a-w $(distdir) test -d $(distdir)/_build || exit 0; \ dc_install_base=`$(am__cd) $(distdir)/_inst && pwd | sed -e 's,^[^:\\/]:[\\/],/,'` \ && dc_destdir="$${TMPDIR-/tmp}/am-dc-$$$$/" \ && am__cwd=`pwd` \ - && $(am__cd) $(distdir)/_build \ - && ../configure --srcdir=.. --prefix="$$dc_install_base" \ + && $(am__cd) $(distdir)/_build/sub \ + && ../../configure \ $(AM_DISTCHECK_CONFIGURE_FLAGS) \ $(DISTCHECK_CONFIGURE_FLAGS) \ + --srcdir=../.. --prefix="$$dc_install_base" \ && $(MAKE) $(AM_MAKEFLAGS) \ && $(MAKE) $(AM_MAKEFLAGS) dvi \ && $(MAKE) $(AM_MAKEFLAGS) check \ @@ -663,9 +772,12 @@ distcleancheck: distclean exit 1; } >&2 check-am: all-am check: check-recursive -all-am: Makefile all-local +all-am: Makefile $(DATA) all-local installdirs: installdirs-recursive installdirs-am: + for dir in "$(DESTDIR)$(pkgconfigdir)"; do \ + test -z "$$dir" || $(MKDIR_P) "$$dir"; \ + done install: install-recursive install-exec: install-exec-recursive install-data: install-data-recursive @@ -718,7 +830,7 @@ info: info-recursive info-am: -install-data-am: install-data-local +install-data-am: install-data-local install-pkgconfigDATA install-dvi: install-dvi-recursive @@ -764,54 +876,59 @@ ps: ps-recursive ps-am: -uninstall-am: +uninstall-am: uninstall-pkgconfigDATA -.MAKE: $(RECURSIVE_CLEAN_TARGETS) $(RECURSIVE_TARGETS) \ - cscopelist-recursive ctags-recursive install-am install-strip \ - tags-recursive +.MAKE: $(am__recursive_targets) install-am install-strip -.PHONY: $(RECURSIVE_CLEAN_TARGETS) $(RECURSIVE_TARGETS) CTAGS GTAGS \ - all all-am all-local am--refresh check check-am clean \ - clean-cscope clean-generic clean-libtool cscope cscopelist \ - cscopelist-recursive ctags ctags-recursive dist dist-all \ - dist-bzip2 dist-gzip dist-hook dist-lzip dist-shar dist-tarZ \ - dist-xz dist-zip distcheck distclean distclean-generic \ - distclean-hdr distclean-libtool distclean-tags distcleancheck \ - distdir distuninstallcheck dvi dvi-am html html-am info \ - info-am install install-am install-data install-data-am \ - install-data-local install-dvi install-dvi-am install-exec \ - install-exec-am install-html install-html-am install-info \ - install-info-am install-man install-pdf install-pdf-am \ - install-ps install-ps-am install-strip installcheck \ - installcheck-am installdirs installdirs-am maintainer-clean \ +.PHONY: $(am__recursive_targets) CTAGS GTAGS TAGS all all-am all-local \ + am--refresh check check-am clean clean-cscope clean-generic \ + clean-libtool cscope cscopelist-am ctags ctags-am dist \ + dist-all dist-bzip2 dist-gzip dist-hook dist-lzip dist-shar \ + dist-tarZ dist-xz dist-zip distcheck distclean \ + distclean-generic distclean-hdr distclean-libtool \ + distclean-tags distcleancheck distdir distuninstallcheck dvi \ + dvi-am html html-am info info-am install install-am \ + install-data install-data-am install-data-local install-dvi \ + install-dvi-am install-exec install-exec-am install-html \ + install-html-am install-info install-info-am install-man \ + install-pdf install-pdf-am install-pkgconfigDATA install-ps \ + install-ps-am install-strip installcheck installcheck-am \ + installdirs installdirs-am maintainer-clean \ maintainer-clean-generic mostlyclean mostlyclean-generic \ - mostlyclean-libtool pdf pdf-am ps ps-am tags tags-recursive \ - uninstall uninstall-am + mostlyclean-libtool pdf pdf-am ps ps-am tags tags-am uninstall \ + uninstall-am uninstall-pkgconfigDATA + +.PRECIOUS: Makefile dist-hook: - rm -rf $(distdir)/doc/html $(distdir)/doc/manpages ; \ - find $(distdir)/maxima -type f -name '*.lsp' | xargs rm -rf ; \ - rm -rf $(distdir)/java/targets ; \ - find $(distdir)/java -type f -name '*.class' | xargs rm -rf ; \ - find $(distdir)/windows -mindepth 1 -type d | xargs rm -rf ; \ + rm -rf $(distdir)/doc/html $(distdir)/doc/manpages \ + $(distdir)/doc/GeographicLib.dox + find $(distdir)/maxima -type f -name '*.lsp' | xargs rm -rf + rm -rf $(distdir)/java/targets + find $(distdir)/java -type f -name '*.class' | xargs rm -rf + find $(distdir)/wrapper -mindepth 2 -type d | xargs rm -rf + find $(distdir)/wrapper -type f -name '*.o' -o -name '*.mex*' | \ + xargs rm -f + find $(distdir)/windows -mindepth 1 -type d | xargs rm -rf find $(distdir)/windows -type f \ ! \( -name '*.sln' -o -name '*.vc*proj' -o -name '*.mk' \)| \ - xargs rm -f ; \ + xargs rm -f find $(distdir) \ - \( -name .svn -o -name '.git*' -o -name CVS -o -name Makefile -o -name '*~' -o -name '*#*' -o -name 'CMakeFiles' -o -name '*.log' -o -name '*.tmp' -o -name '*.pyc' -o -name '*.bak' -o -name '*.BAK' -o -name geographiclib.js \)| \ - xargs rm -rf ; \ - echo include Makefile.mk > $(distdir)/Makefile ; \ + \( -name .svn -o -name '.git*' -o -name CVS -o -name Makefile -o -name '*~' -o -name '*#*' -o -name 'CMakeFiles' -o -name '*.log' -o -name '*.tmp' -o -name '*.pyc' -o -name '*.bak' -o -name '*.BAK' -o -name geographiclib.js \) | \ + xargs rm -rf + echo include Makefile.mk > $(distdir)/Makefile sed -e "s/Unconfigured/$(PACKAGE_VERSION)/" \ -e "s/MAJOR .*/MAJOR ${GEOGRAPHICLIB_VERSION_MAJOR}/" \ -e "s/MINOR .*/MINOR ${GEOGRAPHICLIB_VERSION_MINOR}/" \ -e "s/PATCH .*/PATCH ${GEOGRAPHICLIB_VERSION_PATCH}/" \ $(top_srcdir)/include/GeographicLib/Config.h > \ $(distdir)/include/GeographicLib/Config.h + # Custom rules all-local: man doc -install-data-local: install-doc # install-matlab +install-data-local: install-doc doc: man $(MAKE) -C doc doc @@ -822,9 +939,6 @@ install-doc: man: $(MAKE) -C man man -# install-matlab: -# $(MAKE) -C matlab install-matlab - .PHONY: doc install-doc man install-matlab install-python # Tell versions [3.59,3.63) of GNU make to not export all variables. diff --git a/gtsam/3rdparty/GeographicLib/Makefile.mk b/gtsam/3rdparty/GeographicLib/Makefile.mk index e9d2b6368..90fb16f6e 100644 --- a/gtsam/3rdparty/GeographicLib/Makefile.mk +++ b/gtsam/3rdparty/GeographicLib/Makefile.mk @@ -1,17 +1,18 @@ MAKEFILE := $(lastword $(MAKEFILE_LIST)) MAKE := $(MAKE) -f $(MAKEFILE) -SUBDIRS = src man tools doc +SUBDIRS = src man tools doc js ALLDIRS = include $(SUBDIRS) maxima matlab python cmake -all: src man tools +all: src man tools js $(SUBDIRS): $(MAKE) -C $@ tools: src install: install-headers install-lib install-tools install-man install-cmake \ - install-doc install-matlab install-python -clean: clean-src clean-tools clean-doc clean-man clean-matlab clean-python + install-doc install-js install-matlab install-python +clean: clean-src clean-tools clean-doc clean-js clean-man clean-matlab \ + clean-python install-headers: $(MAKE) -C include install @@ -23,6 +24,8 @@ install-cmake: $(MAKE) -C cmake install install-doc: doc $(MAKE) -C doc install +install-js: js + $(MAKE) -C js install install-man: man $(MAKE) -C man install install-matlab: matlab @@ -35,6 +38,8 @@ clean-tools: $(MAKE) -C tools clean clean-doc: $(MAKE) -C doc clean +clean-js: + $(MAKE) -C js clean clean-man: $(MAKE) -C man clean clean-matlab: matlab @@ -44,8 +49,8 @@ clean-python: python VERSION:=$(shell grep '\bVERSION=' configure | cut -f2 -d\' | head -1) -.PHONY: all $(SUBDIRS) install \ - install-headers install-lib install-tools install-cmake install-man \ - install-matlab install-python \ - clean clean-src clean-tools clean-doc clean-man clean-matlab \ +.PHONY: all $(SUBDIRS) install clean \ + install-headers install-lib install-tools install-man install-cmake \ + install-doc install-js install-matlab install-python \ + clean-src clean-tools clean-doc clean-js clean-man clean-matlab \ clean-python diff --git a/gtsam/3rdparty/GeographicLib/NEWS b/gtsam/3rdparty/GeographicLib/NEWS index 71b3d25d2..b1076d60d 100644 --- a/gtsam/3rdparty/GeographicLib/NEWS +++ b/gtsam/3rdparty/GeographicLib/NEWS @@ -2,243 +2,985 @@ A reverse chronological list of changes to GeographicLib For more information, see - http://geographiclib.sourceforge.net/ + https://geographiclib.sourceforge.io/ -The current version of the library is 1.35. +The current version of the library is 1.49. + +Changes between 1.49 (released 2017-10-05) and 1.48 versions: + + * Add the Enhanced Magnetic Model 2017, emm2017. This is valid for + 2000 thru the end of 2021. + + * Avoid potential problems with the order of initializations in DMS, + GARS, Geohash, Georef, MGRS, OSGB, SphericalEngine; this only would + have been an issue if GeographicLib objects were instantiated + globally. Now no GeographicLib initialization code should be run + prior to the entry of main(). + + * To support the previous fix, add an overload, Utility::lookup(const + char* s, char c). + + * NearestNeighbor::Search throws an error if pts is the wrong size + (instead of merely returning no results). + + * Use complex arithmetic for Clenshaw sums in TransverseMercator and + tranmerc_{fwd,inv}.m. + + * Changes in cmake support: + + fix compiler flags for GEOGRAPHICLIB_PRECISION = 4; + + add CONVERT_WARNINGS_TO_ERRORS option (default OFF), if ON then + compiler warnings are treated as errors. + + * Fix warnings about implicit conversions of doubles to bools in C++, + C, and JavaScript packages. + + * Binary installers for Windows now use Visual Studio 14 2015. + +Changes between 1.48 (released 2017-04-09) and 1.47 versions: + + * The "official" URL for GeographicLib is now + https://geographiclib.sourceforge.io (instead of + http://geographiclib.sourceforge.net). + + * The default range for longitude and azimuth is now (-180d, 180d], + instead of [-180d, 180d). This was already the case for the C++ + library; now the change has been made to the other implementations + (C, Fortran, Java, JavaScript, Python, MATLAB, and Maxima). + + * Changes to NearestNeighbor: + + fix BUG in reading a NearestNeighbor object from a stream which + sometimes incorrectly caused a "Bad index" exception to be thrown; + + add operator<<, operator>>, swap, + std::swap(NearestNeighbor&, NearestNeighbor&); + + * Additions to the documentation: + + add documentation on finding nearest neighbors; + + normal gravity documentation is now on its own page and now has an + illustrative figure; + + document the truncation error in the series for auxiliary + latitudes. + + * Fix BUGS in MATLAB function geodreckon with mixed scalar and array + arguments. + + * Workaround bug in math.fmod for Python 2.7 on 32-bit Windows + machines. + + * Changes in cmake support: + + add USE_BOOST_FOR_EXAMPLES option (default OFF), if ON search for + Boost libraries for building examples; + + add APPLE_MULTIPLE_ARCHITECTURES option (default OFF), if ON build + for both i386 and x86_64 on Mac OS X systems; + + don't add flag for C++11 for g++ 6.0 (since it's not needed). + + * Fix compiler warnings with Visual Studio 2017 and for the C library. + +Changes between 1.47 (released 2017-02-15) and 1.46 versions: + + * Add NearestNeighbor class. + + * Improve accuracy of area calculation (fixing a flaw introduced in + version 1.46); fix applied in Geodesic, GeodesicExact, and the + implementations in C, Fortran, Java, JavaScript, Python, MATLAB, and + Maxima. + + * Generalize NormalGravity to allow oblate and prolate ellipsoids. As + a consequence a new form of constructor has been introduced and the + old form is now deprecated (and because the signatures of the two + constructors are similar, the compiler will warn about the use of + the old one). + + * Changes in Math class: + + Math::sincosd, Math::sind, Math::cosd only return -0 for the case + sin(-0); + + Math::atan2d and Math::AngNormalize return results in (-180deg, + 180deg]; this may affect the longitudes and azimuth returned by + several other functions. + + * Add Utility::trim() and Utility::val(); Utility::num() is now + DEPRECATED. + + * Changes in cmake support: + + remove support of PACKAGE_PATH and INSTALL_PATH in cmake + configuration; + + fix to FindGeographicLib.cmake to make it work on Debian systems; + + use $ (cmake version >= 3.1); + + use NAMESPACE for exported targets; + + geographiclib-config.cmake exports GEOGRAPHICLIB_DATA, + GEOGRAPHICLIB_PRECISION, and GeographicLib_HIGHPREC_LIBRARIES. + + * Add pkg-config support for cmake and autoconf builds. + + * Minor fixes: + + fix the order of declarations in C library, incorporating the + patches in version 1.46.1; + + fix the packaging of the python library, incorporating the patches + in version 1.46.3; + + restrict junit dependency in the Java package to testing scope + (thanks to Mick Killianey); + + various behind-the-scenes fixes to EllipticFunction; + + fix documentation and default install location for Windows binary + installers; + + fix clang compiler warnings in GeodesicExactC4 and + TransverseMercator. + +Changes between 1.46 (released 2016-02-15) and 1.45 versions: + + * The following BUGS have been fixed: + + the -w flag to Planimeter(1) was being ignored; + + in the Java package, the wrong longitude was being returned with + direct geodesic calculation with a negative distance when starting + point was at a pole (this bug was introduced in version 1.44); + + in the JavaScript package, PolygonArea.TestEdge contained a + misspelling of a variable name and other typos (problem found by + threepointone). + + * INCOMPATIBLE CHANGES: + + make the -w flag (to swap the default order of latitude and + longitude) a toggle for all utility programs; + + the -a option to GeodSolve(1) now toggles (instead of sets) arc + mode; + + swap order coslon and sinlon arguments in CircularEngine class. + + * Remove deprecated functionality: + + remove gradient calculation from the Geoid class and GeoidEval(1) + (this was inaccurate and of dubious utility); + + remove reciprocal flattening functions, InverseFlattening in many + classes and Constants::WGS84_r(); stop treating flattening > 1 as + the reciprocal flattening in constructors; + + remove DMS::Decode(string), DMS::DecodeFraction, + EllipticFunction:m, EllipticFunction:m1, Math::extradigits, + Math::AngNormalize2, PolygonArea::TestCompute; + + stop treating LONG_NOWRAP as an alias for LONG_UNROLL in Geodesic + (and related classes) and Rhumb; + + stop treating full/schmidt as aliases for FULL/SCHMIDT in + SphericalEngine (and related classes); + + remove qmake project file src/GeographicLib.pro because QtCreator + can handle cmake projects now; + + remove deprecated Visual Studio 2005 project and solution files. + + * Changes to GeodesicLine and GeodesicLineExact classes; these changes + (1) simplify the process of computing waypoints on a geodesic given + two endpoints and (2) allow a GeodesicLine to be defined which is + consistent with the solution of the inverse problem (in particular + Geodesic::InverseLine the specification of south-going lines which + pass the poles in a westerly direction by setting sin alpha_1 = -0): + + the class stores the distance s13 and arc length a13 to a + reference point 3; by default these quantities are NaNs; + + GeodesicLine::SetDistance (and GeodesicLine::SetArc) specify the + distance (and arc length) to point 3; + + GeodesicLine::Distance (and GeodesicLine::Arc) return the distance + (and arc length) to point 3; + + new methods Geodesic::InverseLine and Geodesic::DirectLine return + a GeodesicLine with the reference point 3 defined as point 2 of + the corresponding geodesic calculation; + + these changes are also included in the C, Java, JavaScript, and + Python packages. + + * Other changes to the geodesic routines: + + more accurate solution of the inverse problem when longitude + difference is close to 180deg (also in C, Fortran, Java, + JavaScript, Python, MATLAB, and Maxima packages); + + more accurate calculation of lon2 in the inverse calculation with + LONG_UNROLL (also in Java, JavaScript, Python packages). + + * Changes to GeodSolve(1) utility: + + the -I and -D options now specify geodesic line calculation via + the standard inverse or direct geodesic problems; + + rename -l flag to -L to parallel the new -I and -D flags (-l is is + retained for backward compatibility but is deprecated), and + similarly for RhumbSolve(1); + + the -F flag (in conjunction with the -I or -D flags) specifies + that distances read on standard input are fractions of s13 or a13; + + the -a option now toggles arc mode (noted above); + + the -w option now toggles longitude first mode (noted above). + + * Changes to Math class: + + Math::copysign added; + + add overloaded version of Math::AngDiff which returns the error in + the difference. This allows a more accurate treatment of inverse + geodesic problem when lon12 is close to 180deg; + + Math::AngRound now converts tiny negative numbers to -0 (instead + of +0), however -0 is still converted to +0. + + * Add -S and -T options to GeoConvert(1). + + * Add Sphinx documentation for Python package. + + * Samples of wrapping the C++ library, so it's accessible in other + languages, are given in wrapper/C, wrapper/python, and + wrapper/matlab. + + * Binary installers for Windows now use Visual Studio 12 2013. + + * Remove top-level pom.xml from release (it was specific to SRI). + + * A reminder: because of the JavaScript changes introduced in version + 1.45, you should remove the following installation directories from + your system: + + Windows: ${CMAKE_INSTALL_PREFIX}/doc/scripts + + Others: ${CMAKE_INSTALL_PREFIX}/share/doc/GeographicLib/scripts + +Changes between 1.45 (released 2015-09-30) and 1.44 versions: + + * Fix BUG in solution of inverse geodesic caused by misbehavior of + some versions of Visual Studio on Windows (fmod(-0.0, 360.0) returns + +0.0 instead of -0.0) and Octave (sind(-0.0) returns +0.0 instead of + -0.0). These bugs were exposed because max(-0.0, +0.0) returns -0.0 + for some languages. + + * Geodesic::Inverse now correctly returns NaNs if one of the latitudes + is a NaN. + + * Changes to JavaScript package: + + thanks to help from Yurij Mikhalevich, it is a now a node package + that can be installed with npm; + + make install now installs the node package in + lib/node_modules/geographiclib; + + add unit tests using mocha; + + add documentation via JSDoc; + + fix bug Geodesic.GenInverse (this bug, introduced in version 1.44, + resulted in the wrong azimuth being reported for points at the + pole). + + * Changes to Java package: + + add implementation of ellipsoidal Gnomonic projection (courtesy of + Sebastian Mattheis); + + add unit tests using JUnit; + + Math.toRadians and Math.toDegrees are used instead of + GeoMath.degree (which is now removed), as a result... + + Java version 1.2 (released 1998-12) or later is now required. + + * Changes to Python package: + + add unit tests using the unittest framework; + + fixed bug in normalization of the area. + + * Changes to MATLAB package: + + fix array size mismatch in geoddistance by avoiding calls to + subfunctions with zero-length arrays; + + fix tranmerc_{fwd,inv} so that they work with arrays and mixed + array/scalar arguments; + + work around Octave problem which causes mgrs_fwd to return garbage + with prec = 10 or 11; + + add geographiclib_test.m to run a test suite. + + * Behavior of substituting 1/f for f if f > 1 is now deprecated. This + behavior has been removed from the JavaScript, C, and Python + implementations (it was never documented). Maxima, MATLAB, and + Fortran implementations never included this behavior. + + * Other changes: + + fix bug, introduced in version 1.42, in the C++ implementation to + the computation of area which causes NaNs to be returned in the + case of a sphere; + + fixed bug, introduced in version 1.44, in the detection of C++11 + math functions in configure.ac; + + throw error on non-convergence in Gnomonic::Reverse if + GEOGRAPHICLIB_PRECISION > 3; + + add geod_polygon_clear to C library; + + turn illegal latitudes into NaNs for Fortran library; + + add test suites for the C and Fortran libraries. + +Changes between 1.44 (released 2015-08-14) and 1.43 versions: + + * Various changes to improve accuracy, e.g., by minimizing round-off + errors: + + Add Math::sincosd, Math::sind, Math::cosd which take their + arguments in degrees. These functions do exact range reduction + and thus they obey exactly the elementary properties of the + trigonometric functions, e.g., sin 9d = cos 81d + = - sin 123456789d. + + Math::AngNormalize now works for any angles, instead of angles in + the range [-540d, 540d); the function Math::AngNormalize2 is now + deprecated. + + This means that there is now no restriction on longitudes and + azimuths; any values can be used. + + Improve the accuracy of Math::atan2d. + + DMS::Decode avoids unnecessary round-off errors; thus 7:33:36 and + 7.56 result in identical values. DMS::Encode rounds ties to even. + These changes have also been made to DMS.js. + + More accurate rounding in MGRS::Reverse and mgrs_inv.m; this + change only makes a difference at sub-meter precisions. + + With MGRS::Forward and mgrs_fwd.m, ensure that digits in lower + precision results match those at higher precision; as a result, + strings of trailing 9s are less likely to be generated. This + change only makes a difference at sub-meter precisions. + + Replace the series for A2 in the Geodesic class with one with + smaller truncation errors. + + Geodesic::Inverse sets s12 to zero for coincident points at pole + (instead of returning a tiny quantity). + + Math::LatFix returns its argument if it is in [-90d, 90d]; if not, + it returns NaN. + + Using Math::LatFix, routines which don't check their arguments now + interpret a latitude outside the legal range of [-90d, 90d] as a + NaN; such routines will return NaNs instead of finite but + incorrect results; caution: code that (dangerously) relied on the + "reasonable" results being returned for values of the latitude + outside the allowed range will now malfunction. + + * All the utility programs accept the -w option to swap the + latitude-longitude order on input and output (and where appropriate + on the command-line arguments). CartConvert now accepts the -p + option to set the precision; now all of the utilities except + GeoidEval accept -p. + + * Add classes for GARS, the Global Area Reference System, and for + Georef, the World Geographic Reference System. + + * Changes to DMS::Decode and DMS.js: + + tighten up the rules: + o 30:70.0 and 30:60 are illegal (minutes and second must be + strictly less than 60), however + o 30:60.0 and 30:60. are legal (floating point 60 is OK, since it + might have been generated by rounding 59.99...); + + generalize a+b concept, introduced in version 1.42, to any number + of pieces; thus 8+0:40-0:0:10 is interpreted as 8:39:50. + + * Documentation fixes: + + update man pages to refer to GeoConvert(1) on handling of + geographic coordinates; + + document limitations of the series used for TransverseMercator; + + hide the documentation of the computation of the gradient of the + geoid height (now deprecated) in the Geoid class; + + warn about the possible misinterpretation of 7.0E+1 by + DMS::Decode; + + swaplatlong optional argument of DMS::DecodeLatLon and various + functions in the GeoCoords class is now called longfirst; + + require Doxygen 1.8.7 or later. + + * More systematic treatment of version numbers: + + Python: __init__.py defines __version__ and __version_info__; + + JavaScript: + o Math.js defines Constants.version and Constants.version_string; + o version number included as comment in packed script + geographiclib.js; + o geod-calc.html and geod-google.html report the version number; + o https://geographiclib.sourceforge.io/scripts/ gives access to + earlier versions of geographiclib.js as geographiclib-m.nn.js; + + Fortran: add geover subroutine to return version numbers; + + Maxima: geodesic.mac defines geod_version; + + CGI scripts: these report the version numbers of the utilities. + + * BUG FIXES: + + NormalGravity now works properly for a sphere (omega = f = J2 = + 0), instead of returning NaNs (problem found by htallon); + + CassiniSoldner::Forward and cassini_fwd.m now returns the correct + azimuth for points at the pole. + + * MATLAB-specific fixes: + + mgrs_fwd now treats treats prec > 11 as prec = 11; + + illegal letter combinations are now correctly detected by + mgrs_inv; + + fixed bug where mgrs_inv returned the wrong results for prec = 0 + strings and center = 0; + + mgrs_inv now decodes prec = 11 strings properly; + + routines now return array results with the right shape; + + routines now properly handle mixed scalar and array arguments. + + * Add Accumulator::operator*=(T y). + + * Geohash uses "invalid" instead of "nan" when the latitude or + longitude is a nan. + +Changes between 1.43 (released 2015-05-23) and 1.42 versions: + + * Add the Enhanced Magnetic Model 2015, emm2015. This is valid for + 2000 thru the end of 2019. This required some changes in the + MagneticModel and MagneticCircle classes; so this model cannot be + used with versions of GeographicLib prior to 1.43. + + * Fix BLUNDER in PolarStereographic constructor introduced in version + 1.42. This affected UTMUPS conversions for UPS which could be + incorrect by up to 0.5 km. + + * Changes in the LONG_NOWRAP option (added in version 1.39) in the + Geodesic and GeodesicLine classes: + + The option is now called LONG_UNROLL (a less negative sounding + term); the original name, LONG_NOWRAP, is retained for backwards + compatibility. + + There were two bad BUGS in the implementation of this capability: + (a) it gave incorrect results for west-going geodesics; (b) the + option was ignored if used directly via the GeodesicLine class. + The first bug affected the implementations in all languages. The + second affected the implementation in C++ (GeodesicLine and + GeodesicLineExact), JavaScript, Java, C, Python. These bugs have + now been FIXED. + + The GeodSolve utility now accepts a -u option, which turns on the + LONG_UNROLL treatment. With this option lon1 is reported as + entered and lon2 is given such that lon2 - lon1 indicates how + often and in what sense the geodesic has encircled the earth. + (This option also affects the value of longitude reported when an + inverse calculation is run with the -f option.) + + The inverse calculation with the JavaScript and python libraries + similarly sets lon1 and lon2 in output dictionary respecting the + LONG_UNROLL flag. + + The online version of GeodSolve now offers an option to unroll the + longitude. + + To support these changes DMS::DecodeLatLon no longer reduces the + longitude to the range [-180deg, 180deg) and Math::AngRound now + coverts -0 to +0. + + * Add Math::polyval (also to C, Java, JavaScript, Fortran, python + versions of the library; this is a built-in function for + MATLAB/Octave). This evaluates a polynomial using Horner's method. + The Maxima-generated code fragments for the evaluation of series in + the Geodesic, TransverseMercator, and Rhumb classes and MATLAB + routines for great ellipses have been replaced by Maxima-generated + arrays of polynomial coefficients which are used as input to + Math::polyval. + + * Add MGRS::Check() to verify that a, f, k_UTM, and k_UPS are + consistent with the assumptions in the UTMUPS and MGRS classes. + This is invoked with GeoConvert --version. (This function was added + to document and check the assumptions used in the UTMUPS and MGRS + classes in case they are extended to deal with ellipsoids other than + WS84.) + + * MATLAB function mgrs_inv now takes an optional center argument and + strips white space from both beginning and end of the string. + + * Minor internal changes: + + GeodSolve sets the geodesic mask so that unnecessary calculations + are avoided; + + some routines have migrated into a math class for for python, + Java, JavaScript libraries. + + * A reminder: because of changes in the installation directories for + non-Windows systems introduced in version 1.42, you should remove + the following directories from your system: + + ${CMAKE_INSTALL_PREFIX}/share/cmake/GeographicLib* + + ${CMAKE_INSTALL_PREFIX}/libexec/GeographicLib/matlab + +Changes between 1.42 (released 2015-04-28) and 1.41 versions: + + * DMS::Decode allows a single addition or subtraction operation, e.g., + 70W+0:0:15. This affects the GeoCoords class and the utilities + (which use the DMS class for reading coordinates). + + * Add Math::norm, Math::AngRound, Math::tand, Math::atan2d, + Math::eatanhe, Math::taupf, Math::tauf, Math::fma and remove + duplicated (but private) functionality from other classes. + + * On non-Windows systems, the cmake config-style find_package files + are now installed under ${CMAKE_INSTALL_PREFIX}/lib${LIB_SUFFIX} + instead of ${CMAKE_INSTALL_PREFIX}/share, because the files are + architecture-specific. This change will let 32-bit and 64-bit + versions coexist on the same machine (in lib and lib64). You should + remove the versions in the old "share" location. + + * MATLAB changes: + + provide native MATLAB implementations for compiled interface + functions; + + the compiled MATLAB interface is now deprecated and so the + MATLAB_COMPILER option in the cmake build has been removed; + + reorganize directories, so that + o matlab/geographiclib contains the native matlab code; + o matlab/geographiclib-legacy contains wrapper functions to mimic + the previous compiled functionality; + + the installed MATLAB code mirrors this layout, but the parent + installation directory on non-Windows systems is + ${CMAKE_INSTALL_PREFIX}/share (instead of + ${CMAKE_INSTALL_PREFIX}/libexec), because the files are now + architecture independent; + + matlab/geographiclib is now packaged and distributed as MATLAB + File Exchange package 50605 (this supersedes three earlier MATLAB + packages); + + point fix for geodarea.m to correct bug in area of polygons which + encircle a pole multiple times (released as version 1.41.1 of + MATLAB File Exchange package 39108, 2014-04-22). + + * artifactId for Java package changed from GeographicLib to + GeographicLib-Java and the package is now deployed to Maven Central + (thanks to Chris Bennight for help on this). + + * Fix autoconf mismatch of version numbers (which were inconsistent in + versions 1.40 and 1.41). + + * Mark the computation of the gradient of the geoid height in the + Geoid class and the GeoidEval utility + as deprecated. + + * Work around the boost-quadmath bug with setprecision(0). + + * Deprecate use of Visual Studio 2005 "-vc8" project files in the + windows directory. + +Changes between 1.41 (released 2015-03-09) and 1.40 versions: + + * Fix bug in Rhumb::Inverse (with exact = true) and related functions + which causes the wrong distance to be reported if one of the end + points is at a pole. Thanks to Thomas Murray for reporting this. + + * Add International Geomagnetic Reference Field (12th generation), + which approximates the main magnetic field of the earth for the + period 1900-2020. + + * Split information about Jacobi's conformal projection to a separate + section and include more material. + +Changes between 1.40 (released 2014-12-18) and 1.39 versions: + + * Add the World Magnetic Model 2015, wmm2015. This is now the default + magnetic model for MagneticField (replacing wmm2010 which is valid + thru the end of 2014). + + * Geodesic::Inverse didn't return NaN if one of the longitudes was a + NaN (bug introduced in version 1.25). Fixed in the C++, Java, + JavaScript, C, Fortran, and Python implementations of the geodesic + routines. This bug was not present in the Matlab version. + + * Fix bug in Utility::readarray and Utility::writearray which caused + an exception in debug mode with zero-sized arrays. + + * Fix BLUNDER in OSGB::GridReference (found by kalderami) where the + wrong result was returned if the easting or northing was negative. + + * OSGB::GridReference now returns "INVALID" if either coordinate is + NaN. Similarly a grid reference starting with "IN" results in NaNs + for the coordinates. + + * Default constructor for GeoCoords corresponds to an undefined + position (latitude and longitude = NaN), instead of the north pole. + + * Add an online version of RhumbSolve at + https://geographiclib.sourceforge.io/cgi-bin/RhumbSolve. + + * Additions to the documentation: + + documentation on Jacobi's conformal projection; + + a page on Auxiliary latitudes (actually, this was added in + version 1.39); + + document the use of two single quotes to stand for a double quote + in DMS (this feature was introduced in version 1.13). + + * The Matlab function, geographiclibinterface, which compiles the + wrapper routines for Matlab now works with Matlab 2014b on a Mac. + +Changes between 1.39 (released 2014-11-11) and 1.38 versions: + + * GeographicLib usually normalizes longitudes to the range [-180deg, + 180deg). However, when solving the direct geodesic and rhumb line + problems, it is sometimes necessary to know how many lines the line + encircled the earth by returning the longitude "unwrapped". So the + following changes have been made: + + add a LONG_NOWRAP flag to mask enums for the outmask arguments for + Geodesic, GeodesicLine, Rhumb, and RhumbLine; + + similar changes have been made to the Python, Javascript, and + Java implementations of the geodesic routines; + + for the C, Fortran, and Matlab implementations the arcmode + argument to the routines was generalized to allow a combination of + ARCMODE and LONG_NOWRAP bits; + + the Maxima version now returns the longitude unwrapped. + These changes were necessary to fix the PolygonAreaT::AddEdge (see + the next item). + + * Changes in area calculations: + + fix BUG in PolygonAreaT::AddEdge (also in C, Java, Javascript, and + Python implementations) which sometimes causes the wrong area to + be returned if the edge spanned more than 180deg; + + add area calculation to the Rhumb and RhumbLine classes and the + RhumbSolve utility; + + add PolygonAreaRhumb typedef for PolygonAreaT; + + add -R option to Planimeter to use PolygonAreaRhumb (and -G option + for the default geodesic polygon); + + fix BLUNDER in area calculation in Matlab routine geodreckon; + + add area calculation to Matlab/Octave routines for great ellipses. + + * Fix bad BUG in Geohash::Reverse; this was introduced in version 1.37 + and affected all platforms where unsigned longs are 32-bits. Thanks + to Christian Csar for reporting and diagnosing this. + + * Binary installers for Windows are now built with Visual Studio 11 + 2012 (instead of Visual Studio 10 2010). Compiled Matlab support + still with version 2013a (64-bit). + + * Update GeographicLib.pro for builds with qmake to include all the + source files. + + * Cmake updates: + + include cross-compiling checks in cmake config file; + + improve the way unsuitable versions are reported; + + include_directories (${GeographicLib_INCLUDE_DIRS}) is no longer + necessary with cmake 2.8.11 or later. + + * legacy/Fortran now includes drop-in replacements for the geodesic + utilities from the NGS. + + * geographiclib-get-{geoids,gravity,magnetic} with no arguments now + print the usage instead of loading the minimal sets. + + * Utility::date(const std::string&, int&, int&, int&) and hence the + MagneticField utility accepts the string "now" as a legal time + (meaning today). + +Changes between 1.38 (released 2014-10-02) and 1.37 versions: + + * On MacOSX, the installed package is relocatable (for cmake version + 2.8.12 and later). + + * On Mac OSX, GeographicLib can be installed using homebrew. + + * In cmake builds under Windows, set the output directories so that + binaries and shared libraries are together. + + * Accept the minus sign as a synonym for - in DMS.{cpp,js}. + + * The cmake configuration file geographiclib-depends.cmake has been + renamed to geographiclib-targets.cmake. + + * Matlab/Octave routines for great ellipses added. + + * Provide man pages for geographiclib-get-{geoids,gravity,magnetic}. + +Changes between 1.37 (released 2014-08-08) and 1.36 versions: + + * Add support for high precision arithmetic. + + * INCOMPATIBLE CHANGE: the static instantiations of various classes + for the WGS84 ellipsoid have been changed to a "construct on first + use idiom". This avoids a lot of wasteful initialization before the + user's code starts. Unfortunately it means that existing source + code that relies on any of the following static variables will need + to be changed to a function call: + + AlbersEqualArea::AzimuthalEqualAreaNorth + + AlbersEqualArea::AzimuthalEqualAreaSouth + + AlbersEqualArea::CylindricalEqualArea + + Ellipsoid::WGS84 + + Geocentric::WGS84 + + Geodesic::WGS84 + + GeodesicExact::WGS84 + + LambertConformalConic::Mercator + + NormalGravity::GRS80 + + NormalGravity::WGS84 + + PolarStereographic::UPS + + TransverseMercator::UTM + + TransverseMercatorExact::UTM + Thus, occurrences of, for example, + const Geodesic& geod = Geodesic::WGS84; // version 1.36 and earlier + need to be changed to + const Geodesic& geod = Geodesic::WGS84(); // version 1.37 and later + (note the parentheses!); alternatively use + // works with all versions + const Geodesic geod(Constants::WGS84_a(), Constants::WGS84_a()); + + * Incompatible change: the environment variables + {GEOID,GRAVITY,MAGNETIC}_{NAME,PATH} are now prefixed with + GEOGRAPHICLIB_. + + * Incompatible change for Windows XP: retire the Windows XP common + data path. If you're still using Windows XP, then you might have to + move the folder C:\Documents and Settings\All Users\Application + Data\GeographicLib to C:\ProgramData\GeographicLib. + + * All macro names affecting the compilation now start with + GEOGRAPHICLIB_; this applies to GEOID_DEFAULT_NAME, + GRAVITY_DEFAULT_NAME, MAGNETIC_DEFAULT_NAME, PGM_PIXEL_WIDTH, + HAVE_LONG_DOUBLE, STATIC_ASSERT, WORDS_BIGENDIAN. + + * Changes to PolygonArea: + + introduce PolygonAreaT which takes a geodesic class as a + parameter; + + PolygonArea and PolygonAreaExact are typedef'ed to + PolygonAreaT and PolygonAreaT; + + add -E option to Planimeter to use PolygonAreaExact; + + add -Q option to Planimeter to calculate the area on the authalic + sphere. + + * Add -p option to Planimeter, ConicProj, GeodesicProj, + TransverseMercatorProj. + + * Add Rhumb and RhumbLine classes and the RhumbSolve utility. + + * Minor changes to NormalGravity: + + add J2ToFlattening and FlatteningToJ2; + + use Newton's method to determine f from J2; + + in constructor, allow omega = 0 (i.e., treat the spherical case). + + * Add grs80 GravityModel. + + * Make geographiclib-get-{geoids,gravity,magnetic} scripts work on + MacOS. + + * Minor changes: + + simplify cross-platform support for C++11 mathematical functions; + + change way area coefficients are given in GeodesicExact to improve + compile times; + + enable searching the online documentation; + + add macros GEOGRAPHICLIB_VERSION and GEOGRAPHICLIB_VERSION_NUM; + + add solution and project files for Visual Studio Express 2010. + +Changes between 1.36 (released 2014-05-13) and 1.35 versions: + + * Changes to comply with NGA's prohibition of the use of the + upper-case letters N/S to designate the hemisphere when displaying + UTM/UPS coordinates: + + UTMUPS::DecodeZone allows north/south as hemisphere designators + (in addition to n/s); + + UTMUPS::EncodeZone now encodes the hemisphere in lower case (to + distinguish this use from a grid zone designator); + + UTMUPS::EncodeZone takes an optional parameter abbrev to + indicate whether to use n/s or north/south as the hemisphere + designator; + + GeoCoords::UTMUPSRepresentation and AltUTMUPSRepresentation + similarly accept the abbrev parameter; + + GeoConvert uses the flags -a and -l to govern whether UTM/UPS + output uses n/s (the -a flag) or north/south (the -l flag) to + denote the hemisphere; + + Fixed a bug what allowed +3N to be accepted as an alternation + UTM zone designation (instead of 3N). + WARNING: The use of lower case n/s for the hemisphere might cause + compatibility problems. However DecodeZone has always accepted + either case; so the issue will only arise with other software + reading the zone information. To avoid possible misinterpretation + of the zone designator, consider calling EncodeZone with abbrev = + false and GeoConvert with -l, so that north/south are used to + denote the hemisphere. + + * MGRS::Forward with prec = -1 will produce a grid zone designation. + Similarly MGRS::Reverse will decode a grid zone designation (and + return prec = -1). + + * Stop using the throw() declaration specification which is + deprecated in C++11. + + * Add missing std:: qualifications to copy in LocalCartesion and + Geocentric headers (bug found by Clemens). Changes between 1.35 (released 2014-03-13) and 1.34 versions: - * Fix blunder in UTMUPS::EncodeEPSG (found by Ben Adler). + * Fix blunder in UTMUPS::EncodeEPSG (found by Ben Adler). - * Matlab wrapper routines geodesic{direct,inverse,line} switch to - "exact" routes if |f| > 0.02. + * Matlab wrapper routines geodesic{direct,inverse,line} switch to + "exact" routes if |f| > 0.02. - * GeodSolve.cgi allows ellipsoid to be set (and uses the -E option - for GeodSolve). + * GeodSolve.cgi allows ellipsoid to be set (and uses the -E option + for GeodSolve). - * Set title in HTML versions of man pages for the utility programs. + * Set title in HTML versions of man pages for the utility programs. - * Changes in cmake support: - + add _d to names of executables in debug mode of Visual Studio; - + add support for Android (cmake-only), thanks to Pullan Yu; - + check CPACK version numbers supplied on command line; - + configured version of project-config.cmake.in is - project-config.cmake (instead of geographiclib-config.cmake), to - prevent find_package incorrectly using this file; - + fix tests with multi-line output; - + this release includes a file, pom.xml, which is used by an - experimental build system (based on maven) at SRI. + * Changes in cmake support: + + add _d to names of executables in debug mode of Visual Studio; + + add support for Android (cmake-only), thanks to Pullan Yu; + + check CPACK version numbers supplied on command line; + + configured version of project-config.cmake.in is + project-config.cmake (instead of geographiclib-config.cmake), to + prevent find_package incorrectly using this file; + + fix tests with multi-line output; + + this release includes a file, pom.xml, which is used by an + experimental build system (based on maven) at SRI. Changes between 1.34 (released 2013-12-11) and 1.33 versions: - * Many changes in cmake support: - + minimum version of cmake needed increased to 2.8.4 (which was - released in 2011-02); - + allow building both shared and static librarys with - -D GEOGRAPHICLIB_LIB_TYPE=BOTH; - + both shared and static libraries (Release plus Debug) included in - binary installer; - + find_package uses COMPONENTS and GeographicLib_USE_STATIC_LIBS to - select the library to use; - + find_package version checking allows nmake and Visual Studio - generators to interoperate on Windows; - + find_package (GeographicLib ...) requires that GeographicLib be - capitalized correctly; - + on Unix/Linux, don't include the version number in directory for - the cmake configuration files; - + defaults for GEOGRAPHICLIB_DOCUMENTATION and - BUILD_NETGEOGRAPHICLIB are now OFF; - + the GEOGRAPHICLIB_EXAMPLES configuration parameter is no longer - used; cmake always configures to build the examples, but they are - not built by default (instead build targets: exampleprograms and - netexamples); - + matlab-all target renamed to matlabinterface; - + the configuration parameters PACKAGE_PATH and INSTALL_PATH are - now deprecated (use CMAKE_INSTALL_PREFIX instead); - + on Linux, the installed package is relocatable; - + on MacOSX, the installed utilities can find the shared library. + * Many changes in cmake support: + + minimum version of cmake needed increased to 2.8.4 (which was + released in 2011-02); + + allow building both shared and static librarys with + -D GEOGRAPHICLIB_LIB_TYPE=BOTH; + + both shared and static libraries (Release plus Debug) included in + binary installer; + + find_package uses COMPONENTS and GeographicLib_USE_STATIC_LIBS to + select the library to use; + + find_package version checking allows nmake and Visual Studio + generators to interoperate on Windows; + + find_package (GeographicLib ...) requires that GeographicLib be + capitalized correctly; + + on Unix/Linux, don't include the version number in directory for + the cmake configuration files; + + defaults for GEOGRAPHICLIB_DOCUMENTATION and + BUILD_NETGEOGRAPHICLIB are now OFF; + + the GEOGRAPHICLIB_EXAMPLES configuration parameter is no longer + used; cmake always configures to build the examples, but they are + not built by default (instead build targets: exampleprograms and + netexamples); + + matlab-all target renamed to matlabinterface; + + the configuration parameters PACKAGE_PATH and INSTALL_PATH are + now deprecated (use CMAKE_INSTALL_PREFIX instead); + + on Linux, the installed package is relocatable; + + on MacOSX, the installed utilities can find the shared library. - * Use a more precise value for OSGB::CentralScale(). + * Use a more precise value for OSGB::CentralScale(). - * Add Arc routines to python interface. + * Add Arc routines to python interface. - * The Geod utility has been removed; the same functionality lives on - with GeodSolve (introduced in version 1.30). + * The Geod utility has been removed; the same functionality lives on + with GeodSolve (introduced in version 1.30). Changes between 1.33 (released 2013-10-08) and 1.32 versions: - * Add NETGeographic .NET wrapper library (courtesy of Scott Heiman). + * Add NETGeographic .NET wrapper library (courtesy of Scott Heiman). - * Make inspector functions in GeographicLib::Ellipsoid const. + * Make inspector functions in GeographicLib::Ellipsoid const. - * Add Accumulator.cpp to instantiate GeographicLib::Accumulator. + * Add Accumulator.cpp to instantiate GeographicLib::Accumulator. - * Defer some of the initialization of GeographicLib::OSGB to when it - is first called. + * Defer some of the initialization of GeographicLib::OSGB to when it + is first called. - * Fix bug in autoconf builds under MacOS. + * Fix bug in autoconf builds under MacOS. Changes between 1.32 (released 2013-07-12) and 1.31 versions: - * Generalize C interface for polygon areas to allow vertices to be - specified incrementally. + * Generalize C interface for polygon areas to allow vertices to be + specified incrementally. - * Fix way flags for C++11 support are determined. + * Fix way flags for C++11 support are determined. Changes between 1.31 (released 2013-07-01) and 1.30 versions: - * Changes breaking binary compatibility (source compatibility is - maintained): - + overloaded versions of DMS::Encode, - EllipticFunction::EllipticFunction, and - GeoCoords::DMSRepresentation, have been eliminated by the use of - optional arguments; - + correct the declaration of first arg to UTMUPS::DecodeEPSG. + * Changes breaking binary compatibility (source compatibility is + maintained): + + overloaded versions of DMS::Encode, + EllipticFunction::EllipticFunction, and + GeoCoords::DMSRepresentation, have been eliminated by the use of + optional arguments; + + correct the declaration of first arg to UTMUPS::DecodeEPSG. - * FIX BUG in GeographicLib::GravityCircle constructor (found by - Mathieu Peyréga) which caused bogus results for the gravity - disturbance and gravity anomaly vectors. (This only affected - calculations using GravityCircle. GravityModel calculations did not - suffer from this bug.) + * FIX BUG in GeographicLib::GravityCircle constructor (found by + Mathieu Peyréga) which caused bogus results for the gravity + disturbance and gravity anomaly vectors. (This only affected + calculations using GravityCircle. GravityModel calculations did not + suffer from this bug.) - * Improvements to the build: - + add macros GEOGRAPHICLIB_VERSION_{MAJOR,MINOR,PATCH} to Config.h; - + fix documentation for new version of perlpod; - + improving setting of runtime path for Unix-like systems with - cmake; - + install PDB files when compiling with Visual Studio to aid - debugging; - + Windows binary release now uses Matlab R2013a (64-bit) and uses - the -largeArrayDims option. + * Improvements to the build: + + add macros GEOGRAPHICLIB_VERSION_{MAJOR,MINOR,PATCH} to Config.h; + + fix documentation for new version of perlpod; + + improving setting of runtime path for Unix-like systems with + cmake; + + install PDB files when compiling with Visual Studio to aid + debugging; + + Windows binary release now uses Matlab R2013a (64-bit) and uses + the -largeArrayDims option. - * Changes to the geodesic routines: - + add Java implementation of the geodesic routines (thanks to Skip - Breidbach for the maven support); - + FIX BUG: avoid altering input args in Fortran implementation; - + more systematic treatment of very short geodesic; - + fixes to python port so that they work with version 3.x, in - addition to 2.x (courtesy of Amato); - + accumulate the perimeter and area of polygons via a double-wide - accumulator in Fortran, C, and Matlab implementations (this is - already included in the other implementations); - + port PolygonArea::AddEdge and PolygonArea::TestEdge to JavaScript - and python interfaces; - + include documentation on short geodesics. + * Changes to the geodesic routines: + + add Java implementation of the geodesic routines (thanks to Skip + Breidbach for the maven support); + + FIX BUG: avoid altering input args in Fortran implementation; + + more systematic treatment of very short geodesic; + + fixes to python port so that they work with version 3.x, in + addition to 2.x (courtesy of Amato); + + accumulate the perimeter and area of polygons via a double-wide + accumulator in Fortran, C, and Matlab implementations (this is + already included in the other implementations); + + port PolygonArea::AddEdge and PolygonArea::TestEdge to JavaScript + and python interfaces; + + include documentation on short geodesics. - * Unix scripts for downloading datasets, - geographiclib-get-{geoids,gravity,magnetic}, skip already download - models by default, unless the -f flag is given. + * Unix scripts for downloading datasets, + geographiclib-get-{geoids,gravity,magnetic}, skip already download + models by default, unless the -f flag is given. - * FIX BUGS: meridian convergence and scale returned by - TransverseMercatorExact was wrong at a pole. + * FIX BUGS: meridian convergence and scale returned by + TransverseMercatorExact was wrong at a pole. - * Improve efficiency of MGRS::Forward by avoiding the calculation of - the latitude if possible (adapting an idea of Craig Rollins). + * Improve efficiency of MGRS::Forward by avoiding the calculation of + the latitude if possible (adapting an idea of Craig Rollins). - * Fixes to the way the Matlab interface routines are built (thanks to - Phil Miller and Chris F.). + * Fixes to the way the Matlab interface routines are built (thanks to + Phil Miller and Chris F.). Changes between 1.30 (released 2013-02-27) and 1.29 versions: - * Changes to geodesic routines: - + fix BUG in fail-safe mechanisms in Geodesic::Inverse; - + the command line utility Geod is now called GeodSolve; - + allow addition of polygon edges in PolygonArea; - + add full Maxima implementation of geodesic algorithms. + * Changes to geodesic routines: + + fix BUG in fail-safe mechanisms in Geodesic::Inverse; + + the command line utility Geod is now called GeodSolve; + + allow addition of polygon edges in PolygonArea; + + add full Maxima implementation of geodesic algorithms. Changes between 1.29 (released 2013-01-16) and 1.28 versions: - * Changes to allow compilation with libc++ (courtesy of Kal Conley). + * Changes to allow compilation with libc++ (courtesy of Kal Conley). - * Add description of geodesics on triaxial ellipsoid to - documentation. + * Add description of geodesics on triaxial ellipsoid to + documentation. - * Update journal reference for "Algorithms for geodesics". + * Update journal reference for "Algorithms for geodesics". Changes between 1.28 (released 2012-12-11) and 1.27 versions: - * Changes to geodesic routines: - + compute longitude difference exactly; - + hence fix BUG in area calculations for polygons with vertices very - close to the prime meridian; - + fix BUG is geoddistance.m where the value of m12 was wrong for - meridional geodesics; - + add Matlab implementations of the geodesic projections; - + remove unneeded special code for geodesics which start at a pole; - + include polygon area routine in C and Fortran implementations; - + add doxygen documentation for C and Fortran libraries. + * Changes to geodesic routines: + + compute longitude difference exactly; + + hence fix BUG in area calculations for polygons with vertices very + close to the prime meridian; + + fix BUG is geoddistance.m where the value of m12 was wrong for + meridional geodesics; + + add Matlab implementations of the geodesic projections; + + remove unneeded special code for geodesics which start at a pole; + + include polygon area routine in C and Fortran implementations; + + add doxygen documentation for C and Fortran libraries. Changes between 1.27 (released 2012-11-29) and 1.26 versions: - * Changes to geodesic routines: - + add native Matlab implementations: geoddistance.m, geodreckon.m, - geodarea.m; - + add C and Fortran implementations; - + improve the solution of the direct problem so that the series - solution is accurate to round off for |f| < 1/50; - + tighten up the convergence criteria for solution of the inverse - problem; - + no longer signal failures of convergence with NaNs (a slightly - less accurate answer is returned instead). + * Changes to geodesic routines: + + add native Matlab implementations: geoddistance.m, geodreckon.m, + geodarea.m; + + add C and Fortran implementations; + + improve the solution of the direct problem so that the series + solution is accurate to round off for |f| < 1/50; + + tighten up the convergence criteria for solution of the inverse + problem; + + no longer signal failures of convergence with NaNs (a slightly + less accurate answer is returned instead). - * Fix DMS::Decode double rounding BUG. + * Fix DMS::Decode double rounding BUG. - * On MacOSX platforms with the cmake configuration, universal - binaries are built. + * On MacOSX platforms with the cmake configuration, universal + binaries are built. Changes between 1.26 (released 2012-10-22) and 1.25 versions: - * Replace the series used for geodesic areas by one with better - convergence (this only makes an appreciable difference if |f| > - 1/150). + * Replace the series used for geodesic areas by one with better + convergence (this only makes an appreciable difference if |f| > + 1/150). Changes between 1.25 (released 2012-10-16) and 1.24 versions: - * Changes to geodesic calculations: - + restart Newton's method in Geodesic::Inverse when it goes awry; - + back up Newton's method with the bisection method; - + Geodesic::Inverse now converges for any value of f; - + add GeodesicExact and GeodesicLineExact which are formulated in - terms of elliptic integrals and thus yield accurate results - even for very eccentric ellipsoids. - + the -E option to Geod invokes these exact classes. + * Changes to geodesic calculations: + + restart Newton's method in Geodesic::Inverse when it goes awry; + + back up Newton's method with the bisection method; + + Geodesic::Inverse now converges for any value of f; + + add GeodesicExact and GeodesicLineExact which are formulated in + terms of elliptic integrals and thus yield accurate results + even for very eccentric ellipsoids; + + the -E option to Geod invokes these exact classes. - * Add functionality to EllipticFunction: - + add all the traditional elliptic integrals; - + remove restrictions on argument range for incomplete elliptic - integrals; - + allow imaginary modulus for elliptic integrals and elliptic - functions; - + make interface to the symmetric elliptic integrals public. + * Add functionality to EllipticFunction: + + add all the traditional elliptic integrals; + + remove restrictions on argument range for incomplete elliptic + integrals; + + allow imaginary modulus for elliptic integrals and elliptic + functions; + + make interface to the symmetric elliptic integrals public. - * Allow GeographicLib::Ellipsoid to be copied. + * Allow GeographicLib::Ellipsoid to be copied. - * Changes to the build tools: - + cmake uses folders in Visual Studio to reduce clutter; - + allow precision of reals to be set in cmake; - + fail gracefully in the absence of pod documentation tools; - + remove support for maintainer tasks in Makefile.mk. + * Changes to the build tools: + + cmake uses folders in Visual Studio to reduce clutter; + + allow precision of reals to be set in cmake; + + fail gracefully in the absence of pod documentation tools; + + remove support for maintainer tasks in Makefile.mk; + + upgrade to automake 1.11.6 to fix the "make distcheck" security + vulnerability; see + http://cve.mitre.org/cgi-bin/cvename.cgi?name=CVE-2012-3386 Changes between 1.24 (released 2012-09-22) and 1.23 versions: - * Allow the specification of the hemisphere in UTM coordinates in - order to provide continuity across the equator: - + add UTMUPS::Transfer; - + add GeoCoords::UTMUPSRepresentation(bool, int) and - GeoCoords::AltUTMUPSRepresentation(bool, int); - + use the hemisphere letter in, e.g., GeoConvert -u -z 31N. + * Allow the specification of the hemisphere in UTM coordinates in + order to provide continuity across the equator: + + add UTMUPS::Transfer; + + add GeoCoords::UTMUPSRepresentation(bool, int) and + GeoCoords::AltUTMUPSRepresentation(bool, int); + + use the hemisphere letter in, e.g., GeoConvert -u -z 31N. - * Add UTMUPS::DecodeEPSG and UTMUPS::EncodeEPSG. + * Add UTMUPS::DecodeEPSG and UTMUPS::EncodeEPSG. - * cmake changes: - + restore support for cmake 2.4.x; - + explicitly check version of doxygen. + * cmake changes: + + restore support for cmake 2.4.x; + + explicitly check version of doxygen. - * Fix building under cygwin. + * Fix building under cygwin. - * Document restrictions on f in the Introduction. + * Document restrictions on f in the Introduction. - * Fix python interface to work with version 2.6.x. + * Fix python interface to work with version 2.6.x. Changes between 1.23 (released 2012-07-17) and 1.22 versions: @@ -303,7 +1045,8 @@ Changes between 1.21 (released 2012-04-25) and 1.20 versions: * cmake tweaks: + simplify the configuration of doxygen; - + allow the Matlab compiler to be specified with the MATLAB_COMPILER option. + + allow the Matlab compiler to be specified with the MATLAB_COMPILER + option. Changes between 1.20 (released 2012-03-23) and 1.19 versions: @@ -313,7 +1056,7 @@ Changes between 1.20 (released 2012-03-23) and 1.19 versions: + add "x64" to the package name for the 64-bit binary installer; + fix cmake warning with Visual Studio Express. - * Fix SphericalEngine to deal with aggessive iterator checking by + * Fix SphericalEngine to deal with aggressive iterator checking by Visual Studio. * Fix transcription BUG is Geodesic.js. @@ -509,16 +1252,16 @@ Changes between 1.11 (released 2011-06-27) and 1.10 versions: Changes between 1.10 (released 2011-06-11) and 1.9 versions: * Improvements to Matlab/Octave interface: - + add {geocentric,localcartesian}{forward,reverse}; - + make geographiclibinterface more general; - + install the source for the interface; - + cmake compiles the interface if ENABLE_MATLAB=ON; - + include compiled interface with Windows binary installer. + + add {geocentric,localcartesian}{forward,reverse}; + + make geographiclibinterface more general; + + install the source for the interface; + + cmake compiles the interface if ENABLE_MATLAB=ON; + + include compiled interface with Windows binary installer. * Fix various configuration issues - + autoconf did not install Config.h; - + cmake installed in man/man1 instead of share/man/man1; - + cmake did not set the rpath on the tools. + + autoconf did not install Config.h; + + cmake installed in man/man1 instead of share/man/man1; + + cmake did not set the rpath on the tools. Changes between 1.9 (released 2011-05-28) and 1.8 versions: @@ -664,7 +1407,7 @@ Changes between 1.4 (released 2010-09-12) and 1.3 versions: * Add GeographicLib::Geoid::ConvertHeight. - * Add -msltohae, -haetomsl, and -z options to \ref geoideval. + * Add -msltohae, -haetomsl, and -z options to GeoidEval. * Constructors check that minor radius is positive. @@ -792,7 +1535,7 @@ Changes between 2009-11 and 2009-10 versions: Changes between 2009-10 and 2009-09 versions: - * Change web site to http://geographiclib.sourceforge.net + * Change web site to https://geographiclib.sourceforge.io * Several house-cleaning changes: + Change from the a flat directory structure to a more easily diff --git a/gtsam/3rdparty/GeographicLib/README.md b/gtsam/3rdparty/GeographicLib/README.md new file mode 100644 index 000000000..3ab31c8d0 --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/README.md @@ -0,0 +1,11 @@ +GeographicLib +============= + +A C++ library for geographic projections. The web site for the package +is + +> https://geographiclib.sourceforge.io + +The API for the library is documented at + +> https://geographiclib.sourceforge.io/html diff --git a/gtsam/3rdparty/GeographicLib/aclocal.m4 b/gtsam/3rdparty/GeographicLib/aclocal.m4 index ec1e5deda..59ed64414 100644 --- a/gtsam/3rdparty/GeographicLib/aclocal.m4 +++ b/gtsam/3rdparty/GeographicLib/aclocal.m4 @@ -1,6 +1,6 @@ -# generated automatically by aclocal 1.12.2 -*- Autoconf -*- +# generated automatically by aclocal 1.15 -*- Autoconf -*- -# Copyright (C) 1996-2012 Free Software Foundation, Inc. +# Copyright (C) 1996-2014 Free Software Foundation, Inc. # This file is free software; the Free Software Foundation # gives unlimited permission to copy and/or distribute it, @@ -11,6 +11,7 @@ # even the implied warranty of MERCHANTABILITY or FITNESS FOR A # PARTICULAR PURPOSE. +m4_ifndef([AC_CONFIG_MACRO_DIRS], [m4_defun([_AM_CONFIG_MACRO_DIRS], [])m4_defun([AC_CONFIG_MACRO_DIRS], [_AM_CONFIG_MACRO_DIRS($@)])]) m4_ifndef([AC_AUTOCONF_VERSION], [m4_copy([m4_PACKAGE_VERSION], [AC_AUTOCONF_VERSION])])dnl m4_if(m4_defn([AC_AUTOCONF_VERSION]), [2.69],, @@ -19,24 +20,97 @@ You have another version of autoconf. It may work, but is not guaranteed to. If you have problems, you may need to regenerate the build system entirely. To do so, use the procedure documented by the package, typically 'autoreconf'.])]) -# Copyright (C) 2002-2012 Free Software Foundation, Inc. +# =========================================================================== +# https://www.gnu.org/software/autoconf-archive/ax_check_compile_flag.html +# =========================================================================== +# +# SYNOPSIS +# +# AX_CHECK_COMPILE_FLAG(FLAG, [ACTION-SUCCESS], [ACTION-FAILURE], [EXTRA-FLAGS], [INPUT]) +# +# DESCRIPTION +# +# Check whether the given FLAG works with the current language's compiler +# or gives an error. (Warnings, however, are ignored) +# +# ACTION-SUCCESS/ACTION-FAILURE are shell commands to execute on +# success/failure. +# +# If EXTRA-FLAGS is defined, it is added to the current language's default +# flags (e.g. CFLAGS) when the check is done. The check is thus made with +# the flags: "CFLAGS EXTRA-FLAGS FLAG". This can for example be used to +# force the compiler to issue an error when a bad flag is given. +# +# INPUT gives an alternative input source to AC_COMPILE_IFELSE. +# +# NOTE: Implementation based on AX_CFLAGS_GCC_OPTION. Please keep this +# macro in sync with AX_CHECK_{PREPROC,LINK}_FLAG. +# +# LICENSE +# +# Copyright (c) 2008 Guido U. Draheim +# Copyright (c) 2011 Maarten Bosmans +# +# 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 . +# +# As a special exception, the respective Autoconf Macro's copyright owner +# gives unlimited permission to copy, distribute and modify the configure +# scripts that are the output of Autoconf when processing the Macro. You +# need not follow the terms of the GNU General Public License when using +# or distributing such scripts, even though portions of the text of the +# Macro appear in them. The GNU General Public License (GPL) does govern +# all other use of the material that constitutes the Autoconf Macro. +# +# This special exception to the GPL applies to versions of the Autoconf +# Macro released by the Autoconf Archive. When you make and distribute a +# modified version of the Autoconf Macro, you may extend this special +# exception to the GPL to apply to your modified version as well. + +#serial 5 + +AC_DEFUN([AX_CHECK_COMPILE_FLAG], +[AC_PREREQ(2.64)dnl for _AC_LANG_PREFIX and AS_VAR_IF +AS_VAR_PUSHDEF([CACHEVAR],[ax_cv_check_[]_AC_LANG_ABBREV[]flags_$4_$1])dnl +AC_CACHE_CHECK([whether _AC_LANG compiler accepts $1], CACHEVAR, [ + ax_check_save_flags=$[]_AC_LANG_PREFIX[]FLAGS + _AC_LANG_PREFIX[]FLAGS="$[]_AC_LANG_PREFIX[]FLAGS $4 $1" + AC_COMPILE_IFELSE([m4_default([$5],[AC_LANG_PROGRAM()])], + [AS_VAR_SET(CACHEVAR,[yes])], + [AS_VAR_SET(CACHEVAR,[no])]) + _AC_LANG_PREFIX[]FLAGS=$ax_check_save_flags]) +AS_VAR_IF(CACHEVAR,yes, + [m4_default([$2], :)], + [m4_default([$3], :)]) +AS_VAR_POPDEF([CACHEVAR])dnl +])dnl AX_CHECK_COMPILE_FLAGS + +# Copyright (C) 2002-2014 Free Software Foundation, Inc. # # This file is free software; the Free Software Foundation # gives unlimited permission to copy and/or distribute it, # with or without modifications, as long as this notice is preserved. -# serial 8 - # AM_AUTOMAKE_VERSION(VERSION) # ---------------------------- # Automake X.Y traces this macro to ensure aclocal.m4 has been # generated from the m4 files accompanying Automake X.Y. # (This private macro should not be called outside this file.) AC_DEFUN([AM_AUTOMAKE_VERSION], -[am__api_version='1.12' +[am__api_version='1.15' dnl Some users find AM_AUTOMAKE_VERSION and mistake it for a way to dnl require some minimum version. Point them to the right macro. -m4_if([$1], [1.12.2], [], +m4_if([$1], [1.15], [], [AC_FATAL([Do not call $0, use AM_INIT_AUTOMAKE([$1]).])])dnl ]) @@ -52,21 +126,19 @@ m4_define([_AM_AUTOCONF_VERSION], []) # Call AM_AUTOMAKE_VERSION and AM_AUTOMAKE_VERSION so they can be traced. # This function is AC_REQUIREd by AM_INIT_AUTOMAKE. AC_DEFUN([AM_SET_CURRENT_AUTOMAKE_VERSION], -[AM_AUTOMAKE_VERSION([1.12.2])dnl +[AM_AUTOMAKE_VERSION([1.15])dnl m4_ifndef([AC_AUTOCONF_VERSION], [m4_copy([m4_PACKAGE_VERSION], [AC_AUTOCONF_VERSION])])dnl _AM_AUTOCONF_VERSION(m4_defn([AC_AUTOCONF_VERSION]))]) # AM_AUX_DIR_EXPAND -*- Autoconf -*- -# Copyright (C) 2001-2012 Free Software Foundation, Inc. +# Copyright (C) 2001-2014 Free Software Foundation, Inc. # # This file is free software; the Free Software Foundation # gives unlimited permission to copy and/or distribute it, # with or without modifications, as long as this notice is preserved. -# serial 2 - # For projects using AC_CONFIG_AUX_DIR([foo]), Autoconf sets # $ac_aux_dir to '$srcdir/foo'. In other projects, it is set to # '$srcdir', '$srcdir/..', or '$srcdir/../..'. @@ -106,22 +178,19 @@ _AM_AUTOCONF_VERSION(m4_defn([AC_AUTOCONF_VERSION]))]) # configured tree to be moved without reconfiguration. AC_DEFUN([AM_AUX_DIR_EXPAND], -[dnl Rely on autoconf to set up CDPATH properly. -AC_PREREQ([2.50])dnl -# expand $ac_aux_dir to an absolute path -am_aux_dir=`cd $ac_aux_dir && pwd` +[AC_REQUIRE([AC_CONFIG_AUX_DIR_DEFAULT])dnl +# Expand $ac_aux_dir to an absolute path. +am_aux_dir=`cd "$ac_aux_dir" && pwd` ]) # AM_CONDITIONAL -*- Autoconf -*- -# Copyright (C) 1997-2012 Free Software Foundation, Inc. +# Copyright (C) 1997-2014 Free Software Foundation, Inc. # # This file is free software; the Free Software Foundation # gives unlimited permission to copy and/or distribute it, # with or without modifications, as long as this notice is preserved. -# serial 10 - # AM_CONDITIONAL(NAME, SHELL-CONDITION) # ------------------------------------- # Define a conditional. @@ -147,13 +216,12 @@ AC_CONFIG_COMMANDS_PRE( Usually this means the macro was only invoked conditionally.]]) fi])]) -# Copyright (C) 1999-2012 Free Software Foundation, Inc. +# Copyright (C) 1999-2014 Free Software Foundation, Inc. # # This file is free software; the Free Software Foundation # gives unlimited permission to copy and/or distribute it, # with or without modifications, as long as this notice is preserved. -# serial 17 # There are a few dirty hacks below to avoid letting 'AC_PROG_CC' be # written in clear, in which case automake, when reading aclocal.m4, @@ -339,19 +407,18 @@ _AM_SUBST_NOTMAKE([am__nodep])dnl # Generate code to set up dependency tracking. -*- Autoconf -*- -# Copyright (C) 1999-2012 Free Software Foundation, Inc. +# Copyright (C) 1999-2014 Free Software Foundation, Inc. # # This file is free software; the Free Software Foundation # gives unlimited permission to copy and/or distribute it, # with or without modifications, as long as this notice is preserved. -# serial 6 # _AM_OUTPUT_DEPENDENCY_COMMANDS # ------------------------------ AC_DEFUN([_AM_OUTPUT_DEPENDENCY_COMMANDS], [{ - # Autoconf 2.62 quotes --file arguments for eval, but not when files + # Older Autoconf quotes --file arguments for eval, but not when files # are listed without --file. Let's play safe and only enable the eval # if we detect the quoting. case $CONFIG_FILES in @@ -380,7 +447,7 @@ AC_DEFUN([_AM_OUTPUT_DEPENDENCY_COMMANDS], DEPDIR=`sed -n 's/^DEPDIR = //p' < "$mf"` test -z "$DEPDIR" && continue am__include=`sed -n 's/^am__include = //p' < "$mf"` - test -z "am__include" && continue + test -z "$am__include" && continue am__quote=`sed -n 's/^am__quote = //p' < "$mf"` # Find all dependency output files, they are included files with # $(DEPDIR) in their names. We invoke sed twice because it is the @@ -416,17 +483,21 @@ AC_DEFUN([AM_OUTPUT_DEPENDENCY_COMMANDS], # Do all the work for Automake. -*- Autoconf -*- -# Copyright (C) 1996-2012 Free Software Foundation, Inc. +# Copyright (C) 1996-2014 Free Software Foundation, Inc. # # This file is free software; the Free Software Foundation # gives unlimited permission to copy and/or distribute it, # with or without modifications, as long as this notice is preserved. -# serial 19 - # This macro actually does too much. Some checks are only needed if # your package does certain things. But this isn't really a big deal. +dnl Redefine AC_PROG_CC to automatically invoke _AM_PROG_CC_C_O. +m4_define([AC_PROG_CC], +m4_defn([AC_PROG_CC]) +[_AM_PROG_CC_C_O +]) + # AM_INIT_AUTOMAKE(PACKAGE, VERSION, [NO-DEFINE]) # AM_INIT_AUTOMAKE([OPTIONS]) # ----------------------------------------------- @@ -439,7 +510,7 @@ AC_DEFUN([AM_OUTPUT_DEPENDENCY_COMMANDS], # arguments mandatory, and then we can depend on a new Autoconf # release and drop the old call support. AC_DEFUN([AM_INIT_AUTOMAKE], -[AC_PREREQ([2.62])dnl +[AC_PREREQ([2.65])dnl dnl Autoconf wants to disallow AM_ names. We explicitly allow dnl the ones we care about. m4_pattern_allow([^AM_[A-Z]+FLAGS$])dnl @@ -469,8 +540,7 @@ AC_SUBST([CYGPATH_W]) dnl Distinguish between old-style and new-style calls. m4_ifval([$2], [AC_DIAGNOSE([obsolete], -[$0: two- and three-arguments forms are deprecated. For more info, see: -http://www.gnu.org/software/automake/manual/automake.html#Modernize-AM_INIT_AUTOMAKE-invocation]) + [$0: two- and three-arguments forms are deprecated.]) m4_ifval([$3], [_AM_SET_OPTION([no-define])])dnl AC_SUBST([PACKAGE], [$1])dnl AC_SUBST([VERSION], [$2])], @@ -503,8 +573,8 @@ AC_REQUIRE([AC_PROG_MKDIR_P])dnl # # AC_SUBST([mkdir_p], ['$(MKDIR_P)']) -# We need awk for the "check" target. The system "awk" is bad on -# some platforms. +# We need awk for the "check" target (and possibly the TAP driver). The +# system "awk" is bad on some platforms. AC_REQUIRE([AC_PROG_AWK])dnl AC_REQUIRE([AC_PROG_MAKE_SET])dnl AC_REQUIRE([AM_SET_LEADING_DOT])dnl @@ -524,21 +594,63 @@ AC_PROVIDE_IFELSE([AC_PROG_OBJC], [_AM_DEPENDENCIES([OBJC])], [m4_define([AC_PROG_OBJC], m4_defn([AC_PROG_OBJC])[_AM_DEPENDENCIES([OBJC])])])dnl -dnl Support for Objective C++ was only introduced in Autoconf 2.65, -dnl but we still cater to Autoconf 2.62. -m4_ifdef([AC_PROG_OBJCXX], -[AC_PROVIDE_IFELSE([AC_PROG_OBJCXX], +AC_PROVIDE_IFELSE([AC_PROG_OBJCXX], [_AM_DEPENDENCIES([OBJCXX])], [m4_define([AC_PROG_OBJCXX], - m4_defn([AC_PROG_OBJCXX])[_AM_DEPENDENCIES([OBJCXX])])])])dnl + m4_defn([AC_PROG_OBJCXX])[_AM_DEPENDENCIES([OBJCXX])])])dnl ]) -_AM_IF_OPTION([silent-rules], [AC_REQUIRE([AM_SILENT_RULES])])dnl -dnl The 'parallel-tests' driver may need to know about EXEEXT, so add the -dnl 'am__EXEEXT' conditional if _AM_COMPILER_EXEEXT was seen. This macro -dnl is hooked onto _AC_COMPILER_EXEEXT early, see below. +AC_REQUIRE([AM_SILENT_RULES])dnl +dnl The testsuite driver may need to know about EXEEXT, so add the +dnl 'am__EXEEXT' conditional if _AM_COMPILER_EXEEXT was seen. This +dnl macro is hooked onto _AC_COMPILER_EXEEXT early, see below. AC_CONFIG_COMMANDS_PRE(dnl [m4_provide_if([_AM_COMPILER_EXEEXT], [AM_CONDITIONAL([am__EXEEXT], [test -n "$EXEEXT"])])])dnl + +# POSIX will say in a future version that running "rm -f" with no argument +# is OK; and we want to be able to make that assumption in our Makefile +# recipes. So use an aggressive probe to check that the usage we want is +# actually supported "in the wild" to an acceptable degree. +# See automake bug#10828. +# To make any issue more visible, cause the running configure to be aborted +# by default if the 'rm' program in use doesn't match our expectations; the +# user can still override this though. +if rm -f && rm -fr && rm -rf; then : OK; else + cat >&2 <<'END' +Oops! + +Your 'rm' program seems unable to run without file operands specified +on the command line, even when the '-f' option is present. This is contrary +to the behaviour of most rm programs out there, and not conforming with +the upcoming POSIX standard: + +Please tell bug-automake@gnu.org about your system, including the value +of your $PATH and any error possibly output before this message. This +can help us improve future automake versions. + +END + if test x"$ACCEPT_INFERIOR_RM_PROGRAM" = x"yes"; then + echo 'Configuration will proceed anyway, since you have set the' >&2 + echo 'ACCEPT_INFERIOR_RM_PROGRAM variable to "yes"' >&2 + echo >&2 + else + cat >&2 <<'END' +Aborting the configuration process, to ensure you take notice of the issue. + +You can download and install GNU coreutils to get an 'rm' implementation +that behaves properly: . + +If you want to complete the configuration process using your problematic +'rm' anyway, export the environment variable ACCEPT_INFERIOR_RM_PROGRAM +to "yes", and re-run configure. + +END + AC_MSG_ERROR([Your 'rm' program is bad, sorry.]) + fi +fi +dnl The trailing newline in this macro's definition is deliberate, for +dnl backward compatibility and to allow trailing 'dnl'-style comments +dnl after the AM_INIT_AUTOMAKE invocation. See automake bug#16841. ]) dnl Hook into '_AC_COMPILER_EXEEXT' early to learn its expansion. Do not @@ -547,7 +659,6 @@ dnl mangled by Autoconf and run in a shell conditional statement. m4_define([_AC_COMPILER_EXEEXT], m4_defn([_AC_COMPILER_EXEEXT])[m4_provide([_AM_COMPILER_EXEEXT])]) - # When config.status generates a header, we must update the stamp-h file. # This file resides in the same directory as the config header # that is generated. The stamp files are numbered to have different names. @@ -569,20 +680,18 @@ for _am_header in $config_headers :; do done echo "timestamp for $_am_arg" >`AS_DIRNAME(["$_am_arg"])`/stamp-h[]$_am_stamp_count]) -# Copyright (C) 2001-2012 Free Software Foundation, Inc. +# Copyright (C) 2001-2014 Free Software Foundation, Inc. # # This file is free software; the Free Software Foundation # gives unlimited permission to copy and/or distribute it, # with or without modifications, as long as this notice is preserved. -# serial 8 - # AM_PROG_INSTALL_SH # ------------------ # Define $install_sh. AC_DEFUN([AM_PROG_INSTALL_SH], [AC_REQUIRE([AM_AUX_DIR_EXPAND])dnl -if test x"${install_sh}" != xset; then +if test x"${install_sh+set}" != xset; then case $am_aux_dir in *\ * | *\ *) install_sh="\${SHELL} '$am_aux_dir/install-sh'" ;; @@ -592,14 +701,12 @@ if test x"${install_sh}" != xset; then fi AC_SUBST([install_sh])]) -# Copyright (C) 2003-2012 Free Software Foundation, Inc. +# Copyright (C) 2003-2014 Free Software Foundation, Inc. # # This file is free software; the Free Software Foundation # gives unlimited permission to copy and/or distribute it, # with or without modifications, as long as this notice is preserved. -# serial 2 - # Check whether the underlying file-system supports filenames # with a leading dot. For instance MS-DOS doesn't. AC_DEFUN([AM_SET_LEADING_DOT], @@ -616,14 +723,12 @@ AC_SUBST([am__leading_dot])]) # Add --enable-maintainer-mode option to configure. -*- Autoconf -*- # From Jim Meyering -# Copyright (C) 1996-2012 Free Software Foundation, Inc. +# Copyright (C) 1996-2014 Free Software Foundation, Inc. # # This file is free software; the Free Software Foundation # gives unlimited permission to copy and/or distribute it, # with or without modifications, as long as this notice is preserved. -# serial 7 - # AM_MAINTAINER_MODE([DEFAULT-MODE]) # ---------------------------------- # Control maintainer-specific portions of Makefiles. @@ -651,18 +756,14 @@ AC_MSG_CHECKING([whether to enable maintainer-specific portions of Makefiles]) ] ) -AU_DEFUN([jm_MAINTAINER_MODE], [AM_MAINTAINER_MODE]) - # Check to see how 'make' treats includes. -*- Autoconf -*- -# Copyright (C) 2001-2012 Free Software Foundation, Inc. +# Copyright (C) 2001-2014 Free Software Foundation, Inc. # # This file is free software; the Free Software Foundation # gives unlimited permission to copy and/or distribute it, # with or without modifications, as long as this notice is preserved. -# serial 5 - # AM_MAKE_INCLUDE() # ----------------- # Check to see how make treats includes. @@ -707,14 +808,12 @@ rm -f confinc confmf # Fake the existence of programs that GNU maintainers use. -*- Autoconf -*- -# Copyright (C) 1997-2012 Free Software Foundation, Inc. +# Copyright (C) 1997-2014 Free Software Foundation, Inc. # # This file is free software; the Free Software Foundation # gives unlimited permission to copy and/or distribute it, # with or without modifications, as long as this notice is preserved. -# serial 7 - # AM_MISSING_PROG(NAME, PROGRAM) # ------------------------------ AC_DEFUN([AM_MISSING_PROG], @@ -722,11 +821,10 @@ AC_DEFUN([AM_MISSING_PROG], $1=${$1-"${am_missing_run}$2"} AC_SUBST($1)]) - # AM_MISSING_HAS_RUN # ------------------ -# Define MISSING if not defined so far and test if it supports --run. -# If it does, set am_missing_run to use it, otherwise, to nothing. +# Define MISSING if not defined so far and test if it is modern enough. +# If it is, set am_missing_run to use it, otherwise, to nothing. AC_DEFUN([AM_MISSING_HAS_RUN], [AC_REQUIRE([AM_AUX_DIR_EXPAND])dnl AC_REQUIRE_AUX_FILE([missing])dnl @@ -739,8 +837,8 @@ if test x"${MISSING+set}" != xset; then esac fi # Use eval to expand $SHELL -if eval "$MISSING --run true"; then - am_missing_run="$MISSING --run " +if eval "$MISSING --is-lightweight"; then + am_missing_run="$MISSING " else am_missing_run= AC_MSG_WARN(['missing' script is too old or missing]) @@ -749,14 +847,12 @@ fi # Helper functions for option handling. -*- Autoconf -*- -# Copyright (C) 2001-2012 Free Software Foundation, Inc. +# Copyright (C) 2001-2014 Free Software Foundation, Inc. # # This file is free software; the Free Software Foundation # gives unlimited permission to copy and/or distribute it, # with or without modifications, as long as this notice is preserved. -# serial 6 - # _AM_MANGLE_OPTION(NAME) # ----------------------- AC_DEFUN([_AM_MANGLE_OPTION], @@ -780,15 +876,77 @@ AC_DEFUN([_AM_SET_OPTIONS], AC_DEFUN([_AM_IF_OPTION], [m4_ifset(_AM_MANGLE_OPTION([$1]), [$2], [$3])]) -# Check to make sure that the build environment is sane. -*- Autoconf -*- - -# Copyright (C) 1996-2012 Free Software Foundation, Inc. +# Copyright (C) 1999-2014 Free Software Foundation, Inc. # # This file is free software; the Free Software Foundation # gives unlimited permission to copy and/or distribute it, # with or without modifications, as long as this notice is preserved. -# serial 9 +# _AM_PROG_CC_C_O +# --------------- +# Like AC_PROG_CC_C_O, but changed for automake. We rewrite AC_PROG_CC +# to automatically call this. +AC_DEFUN([_AM_PROG_CC_C_O], +[AC_REQUIRE([AM_AUX_DIR_EXPAND])dnl +AC_REQUIRE_AUX_FILE([compile])dnl +AC_LANG_PUSH([C])dnl +AC_CACHE_CHECK( + [whether $CC understands -c and -o together], + [am_cv_prog_cc_c_o], + [AC_LANG_CONFTEST([AC_LANG_PROGRAM([])]) + # Make sure it works both with $CC and with simple cc. + # Following AC_PROG_CC_C_O, we do the test twice because some + # compilers refuse to overwrite an existing .o file with -o, + # though they will create one. + am_cv_prog_cc_c_o=yes + for am_i in 1 2; do + if AM_RUN_LOG([$CC -c conftest.$ac_ext -o conftest2.$ac_objext]) \ + && test -f conftest2.$ac_objext; then + : OK + else + am_cv_prog_cc_c_o=no + break + fi + done + rm -f core conftest* + unset am_i]) +if test "$am_cv_prog_cc_c_o" != yes; then + # Losing compiler, so override with the script. + # FIXME: It is wrong to rewrite CC. + # But if we don't then we get into trouble of one sort or another. + # A longer-term fix would be to have automake use am__CC in this case, + # and then we could set am__CC="\$(top_srcdir)/compile \$(CC)" + CC="$am_aux_dir/compile $CC" +fi +AC_LANG_POP([C])]) + +# For backward compatibility. +AC_DEFUN_ONCE([AM_PROG_CC_C_O], [AC_REQUIRE([AC_PROG_CC])]) + +# Copyright (C) 2001-2014 Free Software Foundation, Inc. +# +# This file is free software; the Free Software Foundation +# gives unlimited permission to copy and/or distribute it, +# with or without modifications, as long as this notice is preserved. + +# AM_RUN_LOG(COMMAND) +# ------------------- +# Run COMMAND, save the exit status in ac_status, and log it. +# (This has been adapted from Autoconf's _AC_RUN_LOG macro.) +AC_DEFUN([AM_RUN_LOG], +[{ echo "$as_me:$LINENO: $1" >&AS_MESSAGE_LOG_FD + ($1) >&AS_MESSAGE_LOG_FD 2>&AS_MESSAGE_LOG_FD + ac_status=$? + echo "$as_me:$LINENO: \$? = $ac_status" >&AS_MESSAGE_LOG_FD + (exit $ac_status); }]) + +# Check to make sure that the build environment is sane. -*- Autoconf -*- + +# Copyright (C) 1996-2014 Free Software Foundation, Inc. +# +# This file is free software; the Free Software Foundation +# gives unlimited permission to copy and/or distribute it, +# with or without modifications, as long as this notice is preserved. # AM_SANITY_CHECK # --------------- @@ -865,13 +1023,71 @@ AC_CONFIG_COMMANDS_PRE( rm -f conftest.file ]) -# Copyright (C) 2001-2012 Free Software Foundation, Inc. +# Copyright (C) 2009-2014 Free Software Foundation, Inc. # # This file is free software; the Free Software Foundation # gives unlimited permission to copy and/or distribute it, # with or without modifications, as long as this notice is preserved. -# serial 2 +# AM_SILENT_RULES([DEFAULT]) +# -------------------------- +# Enable less verbose build rules; with the default set to DEFAULT +# ("yes" being less verbose, "no" or empty being verbose). +AC_DEFUN([AM_SILENT_RULES], +[AC_ARG_ENABLE([silent-rules], [dnl +AS_HELP_STRING( + [--enable-silent-rules], + [less verbose build output (undo: "make V=1")]) +AS_HELP_STRING( + [--disable-silent-rules], + [verbose build output (undo: "make V=0")])dnl +]) +case $enable_silent_rules in @%:@ ((( + yes) AM_DEFAULT_VERBOSITY=0;; + no) AM_DEFAULT_VERBOSITY=1;; + *) AM_DEFAULT_VERBOSITY=m4_if([$1], [yes], [0], [1]);; +esac +dnl +dnl A few 'make' implementations (e.g., NonStop OS and NextStep) +dnl do not support nested variable expansions. +dnl See automake bug#9928 and bug#10237. +am_make=${MAKE-make} +AC_CACHE_CHECK([whether $am_make supports nested variables], + [am_cv_make_support_nested_variables], + [if AS_ECHO([['TRUE=$(BAR$(V)) +BAR0=false +BAR1=true +V=1 +am__doit: + @$(TRUE) +.PHONY: am__doit']]) | $am_make -f - >/dev/null 2>&1; then + am_cv_make_support_nested_variables=yes +else + am_cv_make_support_nested_variables=no +fi]) +if test $am_cv_make_support_nested_variables = yes; then + dnl Using '$V' instead of '$(V)' breaks IRIX make. + AM_V='$(V)' + AM_DEFAULT_V='$(AM_DEFAULT_VERBOSITY)' +else + AM_V=$AM_DEFAULT_VERBOSITY + AM_DEFAULT_V=$AM_DEFAULT_VERBOSITY +fi +AC_SUBST([AM_V])dnl +AM_SUBST_NOTMAKE([AM_V])dnl +AC_SUBST([AM_DEFAULT_V])dnl +AM_SUBST_NOTMAKE([AM_DEFAULT_V])dnl +AC_SUBST([AM_DEFAULT_VERBOSITY])dnl +AM_BACKSLASH='\' +AC_SUBST([AM_BACKSLASH])dnl +_AM_SUBST_NOTMAKE([AM_BACKSLASH])dnl +]) + +# Copyright (C) 2001-2014 Free Software Foundation, Inc. +# +# This file is free software; the Free Software Foundation +# gives unlimited permission to copy and/or distribute it, +# with or without modifications, as long as this notice is preserved. # AM_PROG_INSTALL_STRIP # --------------------- @@ -895,14 +1111,12 @@ fi INSTALL_STRIP_PROGRAM="\$(install_sh) -c -s" AC_SUBST([INSTALL_STRIP_PROGRAM])]) -# Copyright (C) 2006-2012 Free Software Foundation, Inc. +# Copyright (C) 2006-2014 Free Software Foundation, Inc. # # This file is free software; the Free Software Foundation # gives unlimited permission to copy and/or distribute it, # with or without modifications, as long as this notice is preserved. -# serial 3 - # _AM_SUBST_NOTMAKE(VARIABLE) # --------------------------- # Prevent Automake from outputting VARIABLE = @VARIABLE@ in Makefile.in. @@ -916,14 +1130,12 @@ AC_DEFUN([AM_SUBST_NOTMAKE], [_AM_SUBST_NOTMAKE($@)]) # Check how to create a tarball. -*- Autoconf -*- -# Copyright (C) 2004-2012 Free Software Foundation, Inc. +# Copyright (C) 2004-2014 Free Software Foundation, Inc. # # This file is free software; the Free Software Foundation # gives unlimited permission to copy and/or distribute it, # with or without modifications, as long as this notice is preserved. -# serial 3 - # _AM_PROG_TAR(FORMAT) # -------------------- # Check how to create a tarball in format FORMAT. @@ -937,76 +1149,114 @@ AC_DEFUN([AM_SUBST_NOTMAKE], [_AM_SUBST_NOTMAKE($@)]) # Substitute a variable $(am__untar) that extract such # a tarball read from stdin. # $(am__untar) < result.tar +# AC_DEFUN([_AM_PROG_TAR], [# Always define AMTAR for backward compatibility. Yes, it's still used # in the wild :-( We should find a proper way to deprecate it ... AC_SUBST([AMTAR], ['$${TAR-tar}']) -m4_if([$1], [v7], - [am__tar='$${TAR-tar} chof - "$$tardir"' am__untar='$${TAR-tar} xf -'], - [m4_case([$1], [ustar],, [pax],, - [m4_fatal([Unknown tar format])]) -AC_MSG_CHECKING([how to create a $1 tar archive]) -# Loop over all known methods to create a tar archive until one works. + +# We'll loop over all known methods to create a tar archive until one works. _am_tools='gnutar m4_if([$1], [ustar], [plaintar]) pax cpio none' -_am_tools=${am_cv_prog_tar_$1-$_am_tools} -# Do not fold the above two line into one, because Tru64 sh and -# Solaris sh will not grok spaces in the rhs of '-'. -for _am_tool in $_am_tools -do - case $_am_tool in - gnutar) - for _am_tar in tar gnutar gtar; - do - AM_RUN_LOG([$_am_tar --version]) && break - done - am__tar="$_am_tar --format=m4_if([$1], [pax], [posix], [$1]) -chf - "'"$$tardir"' - am__tar_="$_am_tar --format=m4_if([$1], [pax], [posix], [$1]) -chf - "'"$tardir"' - am__untar="$_am_tar -xf -" - ;; - plaintar) - # Must skip GNU tar: if it does not support --format= it doesn't create - # ustar tarball either. - (tar --version) >/dev/null 2>&1 && continue - am__tar='tar chf - "$$tardir"' - am__tar_='tar chf - "$tardir"' - am__untar='tar xf -' - ;; - pax) - am__tar='pax -L -x $1 -w "$$tardir"' - am__tar_='pax -L -x $1 -w "$tardir"' - am__untar='pax -r' - ;; - cpio) - am__tar='find "$$tardir" -print | cpio -o -H $1 -L' - am__tar_='find "$tardir" -print | cpio -o -H $1 -L' - am__untar='cpio -i -H $1 -d' - ;; - none) - am__tar=false - am__tar_=false - am__untar=false - ;; - esac - # If the value was cached, stop now. We just wanted to have am__tar - # and am__untar set. - test -n "${am_cv_prog_tar_$1}" && break +m4_if([$1], [v7], + [am__tar='$${TAR-tar} chof - "$$tardir"' am__untar='$${TAR-tar} xf -'], - # tar/untar a dummy directory, and stop if the command works + [m4_case([$1], + [ustar], + [# The POSIX 1988 'ustar' format is defined with fixed-size fields. + # There is notably a 21 bits limit for the UID and the GID. In fact, + # the 'pax' utility can hang on bigger UID/GID (see automake bug#8343 + # and bug#13588). + am_max_uid=2097151 # 2^21 - 1 + am_max_gid=$am_max_uid + # The $UID and $GID variables are not portable, so we need to resort + # to the POSIX-mandated id(1) utility. Errors in the 'id' calls + # below are definitely unexpected, so allow the users to see them + # (that is, avoid stderr redirection). + am_uid=`id -u || echo unknown` + am_gid=`id -g || echo unknown` + AC_MSG_CHECKING([whether UID '$am_uid' is supported by ustar format]) + if test $am_uid -le $am_max_uid; then + AC_MSG_RESULT([yes]) + else + AC_MSG_RESULT([no]) + _am_tools=none + fi + AC_MSG_CHECKING([whether GID '$am_gid' is supported by ustar format]) + if test $am_gid -le $am_max_gid; then + AC_MSG_RESULT([yes]) + else + AC_MSG_RESULT([no]) + _am_tools=none + fi], + + [pax], + [], + + [m4_fatal([Unknown tar format])]) + + AC_MSG_CHECKING([how to create a $1 tar archive]) + + # Go ahead even if we have the value already cached. We do so because we + # need to set the values for the 'am__tar' and 'am__untar' variables. + _am_tools=${am_cv_prog_tar_$1-$_am_tools} + + for _am_tool in $_am_tools; do + case $_am_tool in + gnutar) + for _am_tar in tar gnutar gtar; do + AM_RUN_LOG([$_am_tar --version]) && break + done + am__tar="$_am_tar --format=m4_if([$1], [pax], [posix], [$1]) -chf - "'"$$tardir"' + am__tar_="$_am_tar --format=m4_if([$1], [pax], [posix], [$1]) -chf - "'"$tardir"' + am__untar="$_am_tar -xf -" + ;; + plaintar) + # Must skip GNU tar: if it does not support --format= it doesn't create + # ustar tarball either. + (tar --version) >/dev/null 2>&1 && continue + am__tar='tar chf - "$$tardir"' + am__tar_='tar chf - "$tardir"' + am__untar='tar xf -' + ;; + pax) + am__tar='pax -L -x $1 -w "$$tardir"' + am__tar_='pax -L -x $1 -w "$tardir"' + am__untar='pax -r' + ;; + cpio) + am__tar='find "$$tardir" -print | cpio -o -H $1 -L' + am__tar_='find "$tardir" -print | cpio -o -H $1 -L' + am__untar='cpio -i -H $1 -d' + ;; + none) + am__tar=false + am__tar_=false + am__untar=false + ;; + esac + + # If the value was cached, stop now. We just wanted to have am__tar + # and am__untar set. + test -n "${am_cv_prog_tar_$1}" && break + + # tar/untar a dummy directory, and stop if the command works. + rm -rf conftest.dir + mkdir conftest.dir + echo GrepMe > conftest.dir/file + AM_RUN_LOG([tardir=conftest.dir && eval $am__tar_ >conftest.tar]) + rm -rf conftest.dir + if test -s conftest.tar; then + AM_RUN_LOG([$am__untar /dev/null 2>&1 && break + fi + done rm -rf conftest.dir - mkdir conftest.dir - echo GrepMe > conftest.dir/file - AM_RUN_LOG([tardir=conftest.dir && eval $am__tar_ >conftest.tar]) - rm -rf conftest.dir - if test -s conftest.tar; then - AM_RUN_LOG([$am__untar /dev/null 2>&1 && break - fi -done -rm -rf conftest.dir -AC_CACHE_VAL([am_cv_prog_tar_$1], [am_cv_prog_tar_$1=$_am_tool]) -AC_MSG_RESULT([$am_cv_prog_tar_$1])]) + AC_CACHE_VAL([am_cv_prog_tar_$1], [am_cv_prog_tar_$1=$_am_tool]) + AC_MSG_RESULT([$am_cv_prog_tar_$1])]) + AC_SUBST([am__tar]) AC_SUBST([am__untar]) ]) # _AM_PROG_TAR @@ -1016,3 +1266,4 @@ m4_include([m4/ltoptions.m4]) m4_include([m4/ltsugar.m4]) m4_include([m4/ltversion.m4]) m4_include([m4/lt~obsolete.m4]) +m4_include([m4/pkg.m4]) diff --git a/gtsam/3rdparty/GeographicLib/cmake/CMakeLists.txt b/gtsam/3rdparty/GeographicLib/cmake/CMakeLists.txt index bbb5192cf..0c8ad6447 100644 --- a/gtsam/3rdparty/GeographicLib/cmake/CMakeLists.txt +++ b/gtsam/3rdparty/GeographicLib/cmake/CMakeLists.txt @@ -8,20 +8,27 @@ # geographiclib-config.cmake for the build tree set (PROJECT_ROOT_DIR "${PROJECT_BINARY_DIR}") set (PROJECT_INCLUDE_DIRS - "${PROJECT_BINARY_DIR}/include" "${PROJECT_SOURCE_DIR}/include" ) + "${PROJECT_BINARY_DIR}/include" "${PROJECT_SOURCE_DIR}/include") configure_file (project-config.cmake.in "${PROJECT_BINARY_DIR}/${PROJECT_NAME_LOWER}-config.cmake" @ONLY) configure_file (project-config-version.cmake.in "${PROJECT_BINARY_DIR}/${PROJECT_NAME_LOWER}-config-version.cmake" @ONLY) -export (TARGETS ${PROJECT_SHARED_LIBRARIES} ${PROJECT_STATIC_LIBRARIES} ${TOOLS} - FILE "${PROJECT_BINARY_DIR}/${PROJECT_NAME_LOWER}-depends.cmake") +export (TARGETS + ${PROJECT_SHARED_LIBRARIES} ${PROJECT_STATIC_LIBRARIES} ${TOOLS} + FILE "${PROJECT_BINARY_DIR}/${PROJECT_NAME_LOWER}-targets.cmake") +export (TARGETS + ${PROJECT_SHARED_LIBRARIES} ${PROJECT_STATIC_LIBRARIES} ${TOOLS} + NAMESPACE ${PROJECT_NAME}:: + FILE "${PROJECT_BINARY_DIR}/${PROJECT_NAME_LOWER}-namespace-targets.cmake") # geographiclib-config.cmake for the install tree. It's installed in # ${INSTALL_CMAKE_DIR} and @PROJECT_ROOT_DIR@ is the relative # path to the root from there. (Note that the whole install tree can # be relocated.) if (COMMON_INSTALL_PATH) - set (INSTALL_CMAKE_DIR "share/cmake/${PROJECT_NAME}") + # Install under lib${LIB_SUFFIX} so that 32-bit and 64-bit packages + # can be installed on a single machine. + set (INSTALL_CMAKE_DIR "lib${LIB_SUFFIX}/cmake/${PROJECT_NAME}") set (PROJECT_ROOT_DIR "../../..") else () set (INSTALL_CMAKE_DIR "cmake") @@ -44,12 +51,30 @@ install (FILES RENAME "${PROJECT_NAME_LOWER}-config-version.cmake") # Make information about the cmake targets (the library and the tools) # available. -install (EXPORT depends - FILE ${PROJECT_NAME_LOWER}-depends.cmake +install (EXPORT targets + FILE ${PROJECT_NAME_LOWER}-targets.cmake + DESTINATION "${INSTALL_CMAKE_DIR}") +install (EXPORT targets + NAMESPACE ${PROJECT_NAME}:: + FILE ${PROJECT_NAME_LOWER}-namespace-targets.cmake DESTINATION "${INSTALL_CMAKE_DIR}") if (MSVC AND PACKAGE_DEBUG_LIBS) install (FILES - "${PROJECT_BINARY_DIR}/cmake/CMakeFiles/Export/cmake/${PROJECT_NAME_LOWER}-depends-debug.cmake" + "${PROJECT_BINARY_DIR}/cmake/CMakeFiles/Export/cmake/${PROJECT_NAME_LOWER}-targets-debug.cmake" DESTINATION "${INSTALL_CMAKE_DIR}" CONFIGURATIONS Release) endif () + +# Support for pkgconfig/geographiclib.pc +set (prefix ${CMAKE_INSTALL_PREFIX}) +set (exec_prefix "\${prefix}") +set (libdir "\${exec_prefix}/lib${LIB_SUFFIX}") +set (includedir "\${prefix}/include") +set (bindir "\${exec_prefix}/bin") +set (PACKAGE_NAME "${PROJECT_NAME}") +set (PACKAGE_VERSION "${PROJECT_VERSION}") + +configure_file (project.pc.in geographiclib.pc @ONLY) +install (FILES + "${CMAKE_CURRENT_BINARY_DIR}/geographiclib.pc" + DESTINATION "lib${LIB_SUFFIX}/pkgconfig") diff --git a/gtsam/3rdparty/GeographicLib/cmake/FindGeographicLib.cmake b/gtsam/3rdparty/GeographicLib/cmake/FindGeographicLib.cmake index 9c52b3e7f..58932cc70 100644 --- a/gtsam/3rdparty/GeographicLib/cmake/FindGeographicLib.cmake +++ b/gtsam/3rdparty/GeographicLib/cmake/FindGeographicLib.cmake @@ -1,7 +1,7 @@ # Look for GeographicLib # # Set -# GEOGRAPHICLIB_FOUND = TRUE +# GeographicLib_FOUND = GEOGRAPHICLIB_FOUND = TRUE # GeographicLib_INCLUDE_DIRS = /usr/local/include # GeographicLib_LIBRARIES = /usr/local/lib/libGeographic.so # GeographicLib_LIBRARY_DIRS = /usr/local/lib @@ -15,17 +15,26 @@ if (GeographicLib_LIBRARIES) get_filename_component (_ROOT_DIR "${GeographicLib_LIBRARY_DIRS}" PATH) set (GeographicLib_INCLUDE_DIRS "${_ROOT_DIR}/include") set (GeographicLib_BINARY_DIRS "${_ROOT_DIR}/bin") - unset (_ROOT_DIR) if (NOT EXISTS "${GeographicLib_INCLUDE_DIRS}/GeographicLib/Config.h") - unset (GeographicLib_INCLUDE_DIRS) - unset (GeographicLib_LIBRARIES) - unset (GeographicLib_LIBRARY_DIRS) - unset (GeographicLib_BINARY_DIRS) + # On Debian systems the library is in e.g., + # /usr/lib/x86_64-linux-gnu/libGeographic.so + # so try stripping another element off _ROOT_DIR + get_filename_component (_ROOT_DIR "${_ROOT_DIR}" PATH) + set (GeographicLib_INCLUDE_DIRS "${_ROOT_DIR}/include") + set (GeographicLib_BINARY_DIRS "${_ROOT_DIR}/bin") + if (NOT EXISTS "${GeographicLib_INCLUDE_DIRS}/GeographicLib/Config.h") + unset (GeographicLib_INCLUDE_DIRS) + unset (GeographicLib_LIBRARIES) + unset (GeographicLib_LIBRARY_DIRS) + unset (GeographicLib_BINARY_DIRS) + endif () endif () + unset (_ROOT_DIR) endif () include (FindPackageHandleStandardArgs) find_package_handle_standard_args (GeographicLib DEFAULT_MSG - GeographicLib_LIBRARY_DIRS GeographicLib_LIBRARIES GeographicLib_INCLUDE_DIRS) + GeographicLib_LIBRARY_DIRS GeographicLib_LIBRARIES + GeographicLib_INCLUDE_DIRS) mark_as_advanced (GeographicLib_LIBRARY_DIRS GeographicLib_LIBRARIES GeographicLib_INCLUDE_DIRS) diff --git a/gtsam/3rdparty/GeographicLib/cmake/Makefile.in b/gtsam/3rdparty/GeographicLib/cmake/Makefile.in index a781b6583..2e7b11ca2 100644 --- a/gtsam/3rdparty/GeographicLib/cmake/Makefile.in +++ b/gtsam/3rdparty/GeographicLib/cmake/Makefile.in @@ -1,7 +1,7 @@ -# Makefile.in generated by automake 1.12.2 from Makefile.am. +# Makefile.in generated by automake 1.15 from Makefile.am. # @configure_input@ -# Copyright (C) 1994-2012 Free Software Foundation, Inc. +# Copyright (C) 1994-2014 Free Software Foundation, Inc. # This Makefile.in is free software; the Free Software Foundation # gives unlimited permission to copy and/or distribute it, @@ -19,23 +19,61 @@ # # Copyright (C) 2011, Charles Karney VPATH = @srcdir@ -am__make_dryrun = \ - { \ - am__dry=no; \ +am__is_gnu_make = { \ + if test -z '$(MAKELEVEL)'; then \ + false; \ + elif test -n '$(MAKE_HOST)'; then \ + true; \ + elif test -n '$(MAKE_VERSION)' && test -n '$(CURDIR)'; then \ + true; \ + else \ + false; \ + fi; \ +} +am__make_running_with_option = \ + case $${target_option-} in \ + ?) ;; \ + *) echo "am__make_running_with_option: internal error: invalid" \ + "target option '$${target_option-}' specified" >&2; \ + exit 1;; \ + esac; \ + has_opt=no; \ + sane_makeflags=$$MAKEFLAGS; \ + if $(am__is_gnu_make); then \ + sane_makeflags=$$MFLAGS; \ + else \ case $$MAKEFLAGS in \ *\\[\ \ ]*) \ - echo 'am--echo: ; @echo "AM" OK' | $(MAKE) -f - 2>/dev/null \ - | grep '^AM OK$$' >/dev/null || am__dry=yes;; \ - *) \ - for am__flg in $$MAKEFLAGS; do \ - case $$am__flg in \ - *=*|--*) ;; \ - *n*) am__dry=yes; break;; \ - esac; \ - done;; \ + bs=\\; \ + sane_makeflags=`printf '%s\n' "$$MAKEFLAGS" \ + | sed "s/$$bs$$bs[$$bs $$bs ]*//g"`;; \ esac; \ - test $$am__dry = yes; \ - } + fi; \ + skip_next=no; \ + strip_trailopt () \ + { \ + flg=`printf '%s\n' "$$flg" | sed "s/$$1.*$$//"`; \ + }; \ + for flg in $$sane_makeflags; do \ + test $$skip_next = yes && { skip_next=no; continue; }; \ + case $$flg in \ + *=*|--*) continue;; \ + -*I) strip_trailopt 'I'; skip_next=yes;; \ + -*I?*) strip_trailopt 'I';; \ + -*O) strip_trailopt 'O'; skip_next=yes;; \ + -*O?*) strip_trailopt 'O';; \ + -*l) strip_trailopt 'l'; skip_next=yes;; \ + -*l?*) strip_trailopt 'l';; \ + -[dEDm]) skip_next=yes;; \ + -[JT]) skip_next=yes;; \ + esac; \ + case $$flg in \ + *$$target_option*) has_opt=yes; break;; \ + esac; \ + done; \ + test $$has_opt = yes +am__make_dryrun = (target_option=n; $(am__make_running_with_option)) +am__make_keepgoing = (target_option=k; $(am__make_running_with_option)) pkgdatadir = $(datadir)/@PACKAGE@ pkgincludedir = $(includedir)/@PACKAGE@ pkglibdir = $(libdir)/@PACKAGE@ @@ -56,18 +94,30 @@ build_triplet = @build@ host_triplet = @host@ target_triplet = @target@ subdir = cmake -DIST_COMMON = $(srcdir)/Makefile.am $(srcdir)/Makefile.in ACLOCAL_M4 = $(top_srcdir)/aclocal.m4 am__aclocal_m4_deps = $(top_srcdir)/m4/libtool.m4 \ $(top_srcdir)/m4/ltoptions.m4 $(top_srcdir)/m4/ltsugar.m4 \ $(top_srcdir)/m4/ltversion.m4 $(top_srcdir)/m4/lt~obsolete.m4 \ - $(top_srcdir)/configure.ac + $(top_srcdir)/m4/pkg.m4 $(top_srcdir)/configure.ac am__configure_deps = $(am__aclocal_m4_deps) $(CONFIGURE_DEPENDENCIES) \ $(ACLOCAL_M4) +DIST_COMMON = $(srcdir)/Makefile.am $(am__DIST_COMMON) mkinstalldirs = $(install_sh) -d CONFIG_HEADER = $(top_builddir)/include/GeographicLib/Config-ac.h -CONFIG_CLEAN_FILES = +CONFIG_CLEAN_FILES = geographiclib.pc CONFIG_CLEAN_VPATH_FILES = +AM_V_P = $(am__v_P_@AM_V@) +am__v_P_ = $(am__v_P_@AM_DEFAULT_V@) +am__v_P_0 = false +am__v_P_1 = : +AM_V_GEN = $(am__v_GEN_@AM_V@) +am__v_GEN_ = $(am__v_GEN_@AM_DEFAULT_V@) +am__v_GEN_0 = @echo " GEN " $@; +am__v_GEN_1 = +AM_V_at = $(am__v_at_@AM_V@) +am__v_at_ = $(am__v_at_@AM_DEFAULT_V@) +am__v_at_0 = @ +am__v_at_1 = SOURCES = DIST_SOURCES = am__can_run_installinfo = \ @@ -75,9 +125,12 @@ am__can_run_installinfo = \ n|no|NO) false;; \ *) (install-info --version) >/dev/null 2>&1;; \ esac +am__tagged_files = $(HEADERS) $(SOURCES) $(TAGS_FILES) $(LISP) +am__DIST_COMMON = $(srcdir)/Makefile.in $(srcdir)/project.pc.in DISTFILES = $(DIST_COMMON) $(DIST_SOURCES) $(TEXINFOS) $(EXTRA_DIST) ACLOCAL = @ACLOCAL@ AMTAR = @AMTAR@ +AM_DEFAULT_VERBOSITY = @AM_DEFAULT_VERBOSITY@ AR = @AR@ AUTOCONF = @AUTOCONF@ AUTOHEADER = @AUTOHEADER@ @@ -126,6 +179,7 @@ LTLIBOBJS = @LTLIBOBJS@ LT_AGE = @LT_AGE@ LT_CURRENT = @LT_CURRENT@ LT_REVISION = @LT_REVISION@ +LT_SYS_LIBRARY_PATH = @LT_SYS_LIBRARY_PATH@ MAINT = @MAINT@ MAKEINFO = @MAKEINFO@ MANIFEST_TOOL = @MANIFEST_TOOL@ @@ -144,9 +198,11 @@ PACKAGE_TARNAME = @PACKAGE_TARNAME@ PACKAGE_URL = @PACKAGE_URL@ PACKAGE_VERSION = @PACKAGE_VERSION@ PATH_SEPARATOR = @PATH_SEPARATOR@ +PKG_CONFIG = @PKG_CONFIG@ +PKG_CONFIG_LIBDIR = @PKG_CONFIG_LIBDIR@ +PKG_CONFIG_PATH = @PKG_CONFIG_PATH@ POD2HTML = @POD2HTML@ POD2MAN = @POD2MAN@ -POW_LIB = @POW_LIB@ RANLIB = @RANLIB@ SED = @SED@ SET_MAKE = @SET_MAKE@ @@ -195,6 +251,7 @@ mandir = @mandir@ mkdir_p = @mkdir_p@ oldincludedir = @oldincludedir@ pdfdir = @pdfdir@ +pkgconfigdir = @pkgconfigdir@ prefix = @prefix@ program_transform_name = @program_transform_name@ psdir = @psdir@ @@ -229,7 +286,6 @@ $(srcdir)/Makefile.in: @MAINTAINER_MODE_TRUE@ $(srcdir)/Makefile.am $(am__confi echo ' cd $(top_srcdir) && $(AUTOMAKE) --gnu cmake/Makefile'; \ $(am__cd) $(top_srcdir) && \ $(AUTOMAKE) --gnu cmake/Makefile -.PRECIOUS: Makefile Makefile: $(srcdir)/Makefile.in $(top_builddir)/config.status @case '$?' in \ *config.status*) \ @@ -247,17 +303,17 @@ $(top_srcdir)/configure: @MAINTAINER_MODE_TRUE@ $(am__configure_deps) $(ACLOCAL_M4): @MAINTAINER_MODE_TRUE@ $(am__aclocal_m4_deps) cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh $(am__aclocal_m4_deps): +geographiclib.pc: $(top_builddir)/config.status $(srcdir)/project.pc.in + cd $(top_builddir) && $(SHELL) ./config.status $(subdir)/$@ mostlyclean-libtool: -rm -f *.lo clean-libtool: -rm -rf .libs _libs -tags: TAGS -TAGS: +tags TAGS: -ctags: CTAGS -CTAGS: +ctags CTAGS: cscope cscopelist: @@ -394,15 +450,18 @@ uninstall-am: .MAKE: install-am install-strip .PHONY: all all-am check check-am clean clean-generic clean-libtool \ - distclean distclean-generic distclean-libtool distdir dvi \ - dvi-am html html-am info info-am install install-am \ - install-data install-data-am install-dvi install-dvi-am \ - install-exec install-exec-am install-html install-html-am \ - install-info install-info-am install-man install-pdf \ - install-pdf-am install-ps install-ps-am install-strip \ - installcheck installcheck-am installdirs maintainer-clean \ - maintainer-clean-generic mostlyclean mostlyclean-generic \ - mostlyclean-libtool pdf pdf-am ps ps-am uninstall uninstall-am + cscopelist-am ctags-am distclean distclean-generic \ + distclean-libtool distdir dvi dvi-am html html-am info info-am \ + install install-am install-data install-data-am install-dvi \ + install-dvi-am install-exec install-exec-am install-html \ + install-html-am install-info install-info-am install-man \ + install-pdf install-pdf-am install-ps install-ps-am \ + install-strip installcheck installcheck-am installdirs \ + maintainer-clean maintainer-clean-generic mostlyclean \ + mostlyclean-generic mostlyclean-libtool pdf pdf-am ps ps-am \ + tags-am uninstall uninstall-am + +.PRECIOUS: Makefile install: diff --git a/gtsam/3rdparty/GeographicLib/cmake/project-config-version.cmake.in b/gtsam/3rdparty/GeographicLib/cmake/project-config-version.cmake.in index 2b20f0bc6..3b3b9e864 100644 --- a/gtsam/3rdparty/GeographicLib/cmake/project-config-version.cmake.in +++ b/gtsam/3rdparty/GeographicLib/cmake/project-config-version.cmake.in @@ -9,24 +9,28 @@ if (NOT PACKAGE_FIND_NAME STREQUAL "@PROJECT_NAME@") # Check package name (in particular, because of the way cmake finds # package config files, the capitalization could easily be "wrong"). # This is necessary to ensure that the automatically generated - # variables, e.g., _FOUND, are consistently spelled. Make - # this a WARNING, because this is a user error that needs to be fixed. - message (WARNING - "Mismatched package names: use find_package(@PROJECT_NAME@ ...) instead" - " of find_package(${PACKAGE_FIND_NAME} ...)") + # variables, e.g., _FOUND, are consistently spelled. + set (REASON "package = @PROJECT_NAME@, NOT ${PACKAGE_FIND_NAME}") set (PACKAGE_VERSION_UNSUITABLE TRUE) -elseif (NOT (APPLE OR CMAKE_SIZEOF_VOID_P EQUAL @CMAKE_SIZEOF_VOID_P@)) +elseif (NOT (APPLE OR (NOT DEFINED CMAKE_SIZEOF_VOID_P) OR + CMAKE_SIZEOF_VOID_P EQUAL @CMAKE_SIZEOF_VOID_P@)) # Reject if there's a 32-bit/64-bit mismatch (not necessary with Apple # since a multi-architecture library is built for that platform). - message (STATUS - "${CMAKE_CURRENT_LIST_FILE} unsuitable because package built with " - "sizeof(*void) = @CMAKE_SIZEOF_VOID_P@") + set (REASON "sizeof(*void) = @CMAKE_SIZEOF_VOID_P@") set (PACKAGE_VERSION_UNSUITABLE TRUE) elseif (MSVC AND NOT MSVC_VERSION STREQUAL "@MSVC_VERSION@") # Reject if there's a mismatch in MSVC compiler versions - message (STATUS - "${CMAKE_CURRENT_LIST_FILE} unsuitable because package built with " - "_MSC_VER = @MSVC_VERSION@") + set (REASON "_MSC_VER = @MSVC_VERSION@") + set (PACKAGE_VERSION_UNSUITABLE TRUE) +elseif (NOT CMAKE_CROSSCOMPILING STREQUAL "@CMAKE_CROSSCOMPILING@") + # Reject if there's a mismatch in ${CMAKE_CROSSCOMPILING} + set (REASON "cross-compiling = @CMAKE_CROSSCOMPILING@") + set (PACKAGE_VERSION_UNSUITABLE TRUE) +elseif (CMAKE_CROSSCOMPILING AND + NOT (CMAKE_SYSTEM_NAME STREQUAL "@CMAKE_SYSTEM_NAME@" AND + CMAKE_SYSTEM_PROCESSOR STREQUAL "@CMAKE_SYSTEM_PROCESSOR@")) + # Reject if cross-compiling and there's a mismatch in the target system + set (REASON "target = @CMAKE_SYSTEM_NAME@-@CMAKE_SYSTEM_PROCESSOR@") set (PACKAGE_VERSION_UNSUITABLE TRUE) elseif (PACKAGE_FIND_VERSION) if (PACKAGE_FIND_VERSION VERSION_EQUAL PACKAGE_VERSION) @@ -42,13 +46,20 @@ set (@PROJECT_NAME@_STATIC_FOUND @GEOGRAPHICLIB_STATIC_LIB@) set (@PROJECT_NAME@_NETGeographicLib_FOUND @BUILD_NETGEOGRAPHICLIB@) # Check for the components requested. The convention is that -# GeographicLib_${comp}_FOUND should be true for all the required +# @PROJECT_NAME@_${comp}_FOUND should be true for all the required # components. if (@PROJECT_NAME@_FIND_COMPONENTS) foreach (comp ${@PROJECT_NAME@_FIND_COMPONENTS}) if (@PROJECT_NAME@_FIND_REQUIRED_${comp} AND NOT @PROJECT_NAME@_${comp}_FOUND) + set (REASON "without ${comp}") set (PACKAGE_VERSION_UNSUITABLE TRUE) endif () endforeach () endif () + +# If unsuitable, append the reason to the package version so that it's +# visible to the user. +if (PACKAGE_VERSION_UNSUITABLE) + set (PACKAGE_VERSION "${PACKAGE_VERSION} (${REASON})") +endif () diff --git a/gtsam/3rdparty/GeographicLib/cmake/project-config.cmake.in b/gtsam/3rdparty/GeographicLib/cmake/project-config.cmake.in index 9bd50c24d..2120d9f17 100644 --- a/gtsam/3rdparty/GeographicLib/cmake/project-config.cmake.in +++ b/gtsam/3rdparty/GeographicLib/cmake/project-config.cmake.in @@ -9,7 +9,8 @@ # @PROJECT_NAME@_STATIC_DEFINITIONS = GEOGRAPHICLIB_SHARED_LIB=0 # @PROJECT_NAME@_LIBRARY_DIRS = /usr/local/lib # @PROJECT_NAME@_BINARY_DIRS = /usr/local/bin -# @PROJECT_NAME@_VERSION = 1.9 (for example) +# @PROJECT_NAME@_VERSION = 1.34 (for example) +# @PROJECT_NAME_UPPER@_DATA = /usr/local/share/GeographicLib (for example) # Depending on @PROJECT_NAME@_USE_STATIC_LIBS # @PROJECT_NAME@_LIBRARIES = ${@PROJECT_NAME@_SHARED_LIBRARIES}, if OFF # @PROJECT_NAME@_LIBRARIES = ${@PROJECT_NAME@_STATIC_LIBRARIES}, if ON @@ -17,9 +18,18 @@ # @PROJECT_NAME@_DEFINITIONS = ${@PROJECT_NAME@_STATIC_DEFINITIONS}, if ON # If only one of the libraries is provided, then # @PROJECT_NAME@_USE_STATIC_LIBS is ignored. +# +# For cmake 2.8.11 or later, there's no need to include +# include_directories (${GeographicLib_INCLUDE_DIRS}) +# add_definitions (${GeographicLib_DEFINITIONS}) +# +# The following variables are only relevant if the library has been +# compiled with a default precision different from double: +# @PROJECT_NAME_UPPER@_PRECISION = the precision of the library (usually 2) +# @PROJECT_NAME@_HIGHPREC_LIBRARIES = the libraries need for high precision message (STATUS "Reading ${CMAKE_CURRENT_LIST_FILE}") -set (@PROJECT_NAME@_VERSION "@PROJECT_VERSION@") +# @PROJECT_NAME@_VERSION is set by version file message (STATUS "@PROJECT_NAME@ configuration, version ${@PROJECT_NAME@_VERSION}") @@ -36,17 +46,23 @@ else () # current directory. get_filename_component (_ROOT "${_DIR}/@PROJECT_ROOT_DIR@" ABSOLUTE) set (@PROJECT_NAME@_INCLUDE_DIRS "${_ROOT}/include") - set (@PROJECT_NAME@_LIBRARY_DIRS "${_ROOT}/lib") + set (@PROJECT_NAME@_LIBRARY_DIRS "${_ROOT}/lib@LIB_SUFFIX@") set (@PROJECT_NAME@_BINARY_DIRS "${_ROOT}/bin") endif () -message (STATUS " include directory: \${@PROJECT_NAME@_INCLUDE_DIRS}") +set (@PROJECT_NAME_UPPER@_DATA "@GEOGRAPHICLIB_DATA@") +set (@PROJECT_NAME_UPPER@_PRECISION @GEOGRAPHICLIB_PRECISION@) +set (@PROJECT_NAME@_HIGHPREC_LIBRARIES "@HIGHPREC_LIBRARIES@") set (@PROJECT_NAME@_SHARED_LIBRARIES @PROJECT_SHARED_LIBRARIES@) set (@PROJECT_NAME@_STATIC_LIBRARIES @PROJECT_STATIC_LIBRARIES@) set (@PROJECT_NAME@_SHARED_DEFINITIONS @PROJECT_SHARED_DEFINITIONS@) set (@PROJECT_NAME@_STATIC_DEFINITIONS @PROJECT_STATIC_DEFINITIONS@) # Read in the exported definition of the library -include ("${_DIR}/@PROJECT_NAME_LOWER@-depends.cmake") +include ("${_DIR}/@PROJECT_NAME_LOWER@-targets.cmake") +include ("${_DIR}/@PROJECT_NAME_LOWER@-namespace-targets.cmake") + +unset (_ROOT) +unset (_DIR) if ((NOT @PROJECT_NAME@_SHARED_LIBRARIES) OR (@PROJECT_NAME@_USE_STATIC_LIBS AND @PROJECT_NAME@_STATIC_LIBRARIES)) diff --git a/gtsam/3rdparty/GeographicLib/cmake/project.pc.in b/gtsam/3rdparty/GeographicLib/cmake/project.pc.in new file mode 100644 index 000000000..2eb0c4ca4 --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/cmake/project.pc.in @@ -0,0 +1,14 @@ +prefix=@prefix@ +exec_prefix=@exec_prefix@ +libdir=@libdir@ +includedir=@includedir@ +bindir=@bindir@ + +Name: @PACKAGE_NAME@ +Description: A library for geographic projections +Version: @PACKAGE_VERSION@ +URL: https://geographiclib.sourceforge.io + +Requires: +Libs: -L${libdir} -lGeographic +Cflags: -I${includedir} diff --git a/gtsam/3rdparty/GeographicLib/compile b/gtsam/3rdparty/GeographicLib/compile new file mode 100755 index 000000000..a85b723c7 --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/compile @@ -0,0 +1,347 @@ +#! /bin/sh +# Wrapper for compilers which do not understand '-c -o'. + +scriptversion=2012-10-14.11; # UTC + +# Copyright (C) 1999-2014 Free Software Foundation, Inc. +# Written by Tom Tromey . +# +# 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 2, 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 . + +# As a special exception to the GNU General Public License, if you +# distribute this file as part of a program that contains a +# configuration script generated by Autoconf, you may include it under +# the same distribution terms that you use for the rest of that program. + +# This file is maintained in Automake, please report +# bugs to or send patches to +# . + +nl=' +' + +# We need space, tab and new line, in precisely that order. Quoting is +# there to prevent tools from complaining about whitespace usage. +IFS=" "" $nl" + +file_conv= + +# func_file_conv build_file lazy +# Convert a $build file to $host form and store it in $file +# Currently only supports Windows hosts. If the determined conversion +# type is listed in (the comma separated) LAZY, no conversion will +# take place. +func_file_conv () +{ + file=$1 + case $file in + / | /[!/]*) # absolute file, and not a UNC file + if test -z "$file_conv"; then + # lazily determine how to convert abs files + case `uname -s` in + MINGW*) + file_conv=mingw + ;; + CYGWIN*) + file_conv=cygwin + ;; + *) + file_conv=wine + ;; + esac + fi + case $file_conv/,$2, in + *,$file_conv,*) + ;; + mingw/*) + file=`cmd //C echo "$file " | sed -e 's/"\(.*\) " *$/\1/'` + ;; + cygwin/*) + file=`cygpath -m "$file" || echo "$file"` + ;; + wine/*) + file=`winepath -w "$file" || echo "$file"` + ;; + esac + ;; + esac +} + +# func_cl_dashL linkdir +# Make cl look for libraries in LINKDIR +func_cl_dashL () +{ + func_file_conv "$1" + if test -z "$lib_path"; then + lib_path=$file + else + lib_path="$lib_path;$file" + fi + linker_opts="$linker_opts -LIBPATH:$file" +} + +# func_cl_dashl library +# Do a library search-path lookup for cl +func_cl_dashl () +{ + lib=$1 + found=no + save_IFS=$IFS + IFS=';' + for dir in $lib_path $LIB + do + IFS=$save_IFS + if $shared && test -f "$dir/$lib.dll.lib"; then + found=yes + lib=$dir/$lib.dll.lib + break + fi + if test -f "$dir/$lib.lib"; then + found=yes + lib=$dir/$lib.lib + break + fi + if test -f "$dir/lib$lib.a"; then + found=yes + lib=$dir/lib$lib.a + break + fi + done + IFS=$save_IFS + + if test "$found" != yes; then + lib=$lib.lib + fi +} + +# func_cl_wrapper cl arg... +# Adjust compile command to suit cl +func_cl_wrapper () +{ + # Assume a capable shell + lib_path= + shared=: + linker_opts= + for arg + do + if test -n "$eat"; then + eat= + else + case $1 in + -o) + # configure might choose to run compile as 'compile cc -o foo foo.c'. + eat=1 + case $2 in + *.o | *.[oO][bB][jJ]) + func_file_conv "$2" + set x "$@" -Fo"$file" + shift + ;; + *) + func_file_conv "$2" + set x "$@" -Fe"$file" + shift + ;; + esac + ;; + -I) + eat=1 + func_file_conv "$2" mingw + set x "$@" -I"$file" + shift + ;; + -I*) + func_file_conv "${1#-I}" mingw + set x "$@" -I"$file" + shift + ;; + -l) + eat=1 + func_cl_dashl "$2" + set x "$@" "$lib" + shift + ;; + -l*) + func_cl_dashl "${1#-l}" + set x "$@" "$lib" + shift + ;; + -L) + eat=1 + func_cl_dashL "$2" + ;; + -L*) + func_cl_dashL "${1#-L}" + ;; + -static) + shared=false + ;; + -Wl,*) + arg=${1#-Wl,} + save_ifs="$IFS"; IFS=',' + for flag in $arg; do + IFS="$save_ifs" + linker_opts="$linker_opts $flag" + done + IFS="$save_ifs" + ;; + -Xlinker) + eat=1 + linker_opts="$linker_opts $2" + ;; + -*) + set x "$@" "$1" + shift + ;; + *.cc | *.CC | *.cxx | *.CXX | *.[cC]++) + func_file_conv "$1" + set x "$@" -Tp"$file" + shift + ;; + *.c | *.cpp | *.CPP | *.lib | *.LIB | *.Lib | *.OBJ | *.obj | *.[oO]) + func_file_conv "$1" mingw + set x "$@" "$file" + shift + ;; + *) + set x "$@" "$1" + shift + ;; + esac + fi + shift + done + if test -n "$linker_opts"; then + linker_opts="-link$linker_opts" + fi + exec "$@" $linker_opts + exit 1 +} + +eat= + +case $1 in + '') + echo "$0: No command. Try '$0 --help' for more information." 1>&2 + exit 1; + ;; + -h | --h*) + cat <<\EOF +Usage: compile [--help] [--version] PROGRAM [ARGS] + +Wrapper for compilers which do not understand '-c -o'. +Remove '-o dest.o' from ARGS, run PROGRAM with the remaining +arguments, and rename the output as expected. + +If you are trying to build a whole package this is not the +right script to run: please start by reading the file 'INSTALL'. + +Report bugs to . +EOF + exit $? + ;; + -v | --v*) + echo "compile $scriptversion" + exit $? + ;; + cl | *[/\\]cl | cl.exe | *[/\\]cl.exe ) + func_cl_wrapper "$@" # Doesn't return... + ;; +esac + +ofile= +cfile= + +for arg +do + if test -n "$eat"; then + eat= + else + case $1 in + -o) + # configure might choose to run compile as 'compile cc -o foo foo.c'. + # So we strip '-o arg' only if arg is an object. + eat=1 + case $2 in + *.o | *.obj) + ofile=$2 + ;; + *) + set x "$@" -o "$2" + shift + ;; + esac + ;; + *.c) + cfile=$1 + set x "$@" "$1" + shift + ;; + *) + set x "$@" "$1" + shift + ;; + esac + fi + shift +done + +if test -z "$ofile" || test -z "$cfile"; then + # If no '-o' option was seen then we might have been invoked from a + # pattern rule where we don't need one. That is ok -- this is a + # normal compilation that the losing compiler can handle. If no + # '.c' file was seen then we are probably linking. That is also + # ok. + exec "$@" +fi + +# Name of file we expect compiler to create. +cofile=`echo "$cfile" | sed 's|^.*[\\/]||; s|^[a-zA-Z]:||; s/\.c$/.o/'` + +# Create the lock directory. +# Note: use '[/\\:.-]' here to ensure that we don't use the same name +# that we are using for the .o file. Also, base the name on the expected +# object file name, since that is what matters with a parallel build. +lockdir=`echo "$cofile" | sed -e 's|[/\\:.-]|_|g'`.d +while true; do + if mkdir "$lockdir" >/dev/null 2>&1; then + break + fi + sleep 1 +done +# FIXME: race condition here if user kills between mkdir and trap. +trap "rmdir '$lockdir'; exit 1" 1 2 15 + +# Run the compile. +"$@" +ret=$? + +if test -f "$cofile"; then + test "$cofile" = "$ofile" || mv "$cofile" "$ofile" +elif test -f "${cofile}bj"; then + test "${cofile}bj" = "$ofile" || mv "${cofile}bj" "$ofile" +fi + +rmdir "$lockdir" +exit $ret + +# Local Variables: +# mode: shell-script +# sh-indentation: 2 +# eval: (add-hook 'write-file-hooks 'time-stamp) +# time-stamp-start: "scriptversion=" +# time-stamp-format: "%:y-%02m-%02d.%02H" +# time-stamp-time-zone: "UTC" +# time-stamp-end: "; # UTC" +# End: diff --git a/gtsam/3rdparty/GeographicLib/config.guess b/gtsam/3rdparty/GeographicLib/config.guess index c0adba94b..dbfb9786c 100755 --- a/gtsam/3rdparty/GeographicLib/config.guess +++ b/gtsam/3rdparty/GeographicLib/config.guess @@ -1,14 +1,12 @@ #! /bin/sh # Attempt to guess a canonical system name. -# Copyright (C) 1992, 1993, 1994, 1995, 1996, 1997, 1998, 1999, -# 2000, 2001, 2002, 2003, 2004, 2005, 2006, 2007, 2008, 2009, 2010, -# 2011, 2012 Free Software Foundation, Inc. +# Copyright 1992-2015 Free Software Foundation, Inc. -timestamp='2012-06-10' +timestamp='2015-01-01' # This file 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 2 of the License, or +# 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 @@ -22,19 +20,17 @@ timestamp='2012-06-10' # As a special exception to the GNU General Public License, if you # distribute this file as part of a program that contains a # configuration script generated by Autoconf, you may include it under -# the same distribution terms that you use for the rest of that program. - - -# Originally written by Per Bothner. Please send patches (context -# diff format) to and include a ChangeLog -# entry. +# the same distribution terms that you use for the rest of that +# program. This Exception is an additional permission under section 7 +# of the GNU General Public License, version 3 ("GPLv3"). # -# This script attempts to guess a canonical system name similar to -# config.sub. If it succeeds, it prints the system name on stdout, and -# exits with 0. Otherwise, it exits with 1. +# Originally written by Per Bothner; maintained since 2000 by Ben Elliston. # # You can get the latest version of this script from: # http://git.savannah.gnu.org/gitweb/?p=config.git;a=blob_plain;f=config.guess;hb=HEAD +# +# Please send patches to . + me=`echo "$0" | sed -e 's,.*/,,'` @@ -54,9 +50,7 @@ version="\ GNU config.guess ($timestamp) Originally written by Per Bothner. -Copyright (C) 1992, 1993, 1994, 1995, 1996, 1997, 1998, 1999, 2000, -2001, 2002, 2003, 2004, 2005, 2006, 2007, 2008, 2009, 2010, 2011, 2012 -Free Software Foundation, Inc. +Copyright 1992-2015 Free Software Foundation, Inc. This is free software; see the source for copying conditions. There is NO warranty; not even for MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE." @@ -138,6 +132,27 @@ UNAME_RELEASE=`(uname -r) 2>/dev/null` || UNAME_RELEASE=unknown UNAME_SYSTEM=`(uname -s) 2>/dev/null` || UNAME_SYSTEM=unknown UNAME_VERSION=`(uname -v) 2>/dev/null` || UNAME_VERSION=unknown +case "${UNAME_SYSTEM}" in +Linux|GNU|GNU/*) + # If the system lacks a compiler, then just pick glibc. + # We could probably try harder. + LIBC=gnu + + eval $set_cc_for_build + cat <<-EOF > $dummy.c + #include + #if defined(__UCLIBC__) + LIBC=uclibc + #elif defined(__dietlibc__) + LIBC=dietlibc + #else + LIBC=gnu + #endif + EOF + eval `$CC_FOR_BUILD -E $dummy.c 2>/dev/null | grep '^LIBC' | sed 's, ,,g'` + ;; +esac + # Note: order is significant - the case branches are not exclusive. case "${UNAME_MACHINE}:${UNAME_SYSTEM}:${UNAME_RELEASE}:${UNAME_VERSION}" in @@ -200,6 +215,10 @@ case "${UNAME_MACHINE}:${UNAME_SYSTEM}:${UNAME_RELEASE}:${UNAME_VERSION}" in # CPU_TYPE-MANUFACTURER-OPERATING_SYSTEM is used. echo "${machine}-${os}${release}" exit ;; + *:Bitrig:*:*) + UNAME_MACHINE_ARCH=`arch | sed 's/Bitrig.//'` + echo ${UNAME_MACHINE_ARCH}-unknown-bitrig${UNAME_RELEASE} + exit ;; *:OpenBSD:*:*) UNAME_MACHINE_ARCH=`arch | sed 's/OpenBSD.//'` echo ${UNAME_MACHINE_ARCH}-unknown-openbsd${UNAME_RELEASE} @@ -302,7 +321,7 @@ case "${UNAME_MACHINE}:${UNAME_SYSTEM}:${UNAME_RELEASE}:${UNAME_VERSION}" in arm:RISC*:1.[012]*:*|arm:riscix:1.[012]*:*) echo arm-acorn-riscix${UNAME_RELEASE} exit ;; - arm:riscos:*:*|arm:RISCOS:*:*) + arm*:riscos:*:*|arm*:RISCOS:*:*) echo arm-unknown-riscos exit ;; SR2?01:HI-UX/MPP:*:* | SR8000:HI-UX/MPP:*:*) @@ -560,8 +579,9 @@ EOF else IBM_ARCH=powerpc fi - if [ -x /usr/bin/oslevel ] ; then - IBM_REV=`/usr/bin/oslevel` + if [ -x /usr/bin/lslpp ] ; then + IBM_REV=`/usr/bin/lslpp -Lqc bos.rte.libc | + awk -F: '{ print $3 }' | sed s/[0-9]*$/0/` else IBM_REV=${UNAME_VERSION}.${UNAME_RELEASE} fi @@ -801,10 +821,13 @@ EOF i*:CYGWIN*:*) echo ${UNAME_MACHINE}-pc-cygwin exit ;; + *:MINGW64*:*) + echo ${UNAME_MACHINE}-pc-mingw64 + exit ;; *:MINGW*:*) echo ${UNAME_MACHINE}-pc-mingw32 exit ;; - i*:MSYS*:*) + *:MSYS*:*) echo ${UNAME_MACHINE}-pc-msys exit ;; i*:windows32*:*) @@ -852,21 +875,21 @@ EOF exit ;; *:GNU:*:*) # the GNU system - echo `echo ${UNAME_MACHINE}|sed -e 's,[-/].*$,,'`-unknown-gnu`echo ${UNAME_RELEASE}|sed -e 's,/.*$,,'` + echo `echo ${UNAME_MACHINE}|sed -e 's,[-/].*$,,'`-unknown-${LIBC}`echo ${UNAME_RELEASE}|sed -e 's,/.*$,,'` exit ;; *:GNU/*:*:*) # other systems with GNU libc and userland - echo ${UNAME_MACHINE}-unknown-`echo ${UNAME_SYSTEM} | sed 's,^[^/]*/,,' | tr '[A-Z]' '[a-z]'``echo ${UNAME_RELEASE}|sed -e 's/[-(].*//'`-gnu + echo ${UNAME_MACHINE}-unknown-`echo ${UNAME_SYSTEM} | sed 's,^[^/]*/,,' | tr '[A-Z]' '[a-z]'``echo ${UNAME_RELEASE}|sed -e 's/[-(].*//'`-${LIBC} exit ;; i*86:Minix:*:*) echo ${UNAME_MACHINE}-pc-minix exit ;; aarch64:Linux:*:*) - echo ${UNAME_MACHINE}-unknown-linux-gnu + echo ${UNAME_MACHINE}-unknown-linux-${LIBC} exit ;; aarch64_be:Linux:*:*) UNAME_MACHINE=aarch64_be - echo ${UNAME_MACHINE}-unknown-linux-gnu + echo ${UNAME_MACHINE}-unknown-linux-${LIBC} exit ;; alpha:Linux:*:*) case `sed -n '/^cpu model/s/^.*: \(.*\)/\1/p' < /proc/cpuinfo` in @@ -879,59 +902,54 @@ EOF EV68*) UNAME_MACHINE=alphaev68 ;; esac objdump --private-headers /bin/sh | grep -q ld.so.1 - if test "$?" = 0 ; then LIBC="libc1" ; else LIBC="" ; fi - echo ${UNAME_MACHINE}-unknown-linux-gnu${LIBC} + if test "$?" = 0 ; then LIBC="gnulibc1" ; fi + echo ${UNAME_MACHINE}-unknown-linux-${LIBC} + exit ;; + arc:Linux:*:* | arceb:Linux:*:*) + echo ${UNAME_MACHINE}-unknown-linux-${LIBC} exit ;; arm*:Linux:*:*) eval $set_cc_for_build if echo __ARM_EABI__ | $CC_FOR_BUILD -E - 2>/dev/null \ | grep -q __ARM_EABI__ then - echo ${UNAME_MACHINE}-unknown-linux-gnu + echo ${UNAME_MACHINE}-unknown-linux-${LIBC} else if echo __ARM_PCS_VFP | $CC_FOR_BUILD -E - 2>/dev/null \ | grep -q __ARM_PCS_VFP then - echo ${UNAME_MACHINE}-unknown-linux-gnueabi + echo ${UNAME_MACHINE}-unknown-linux-${LIBC}eabi else - echo ${UNAME_MACHINE}-unknown-linux-gnueabihf + echo ${UNAME_MACHINE}-unknown-linux-${LIBC}eabihf fi fi exit ;; avr32*:Linux:*:*) - echo ${UNAME_MACHINE}-unknown-linux-gnu + echo ${UNAME_MACHINE}-unknown-linux-${LIBC} exit ;; cris:Linux:*:*) - echo ${UNAME_MACHINE}-axis-linux-gnu + echo ${UNAME_MACHINE}-axis-linux-${LIBC} exit ;; crisv32:Linux:*:*) - echo ${UNAME_MACHINE}-axis-linux-gnu + echo ${UNAME_MACHINE}-axis-linux-${LIBC} exit ;; frv:Linux:*:*) - echo ${UNAME_MACHINE}-unknown-linux-gnu + echo ${UNAME_MACHINE}-unknown-linux-${LIBC} exit ;; hexagon:Linux:*:*) - echo ${UNAME_MACHINE}-unknown-linux-gnu + echo ${UNAME_MACHINE}-unknown-linux-${LIBC} exit ;; i*86:Linux:*:*) - LIBC=gnu - eval $set_cc_for_build - sed 's/^ //' << EOF >$dummy.c - #ifdef __dietlibc__ - LIBC=dietlibc - #endif -EOF - eval `$CC_FOR_BUILD -E $dummy.c 2>/dev/null | grep '^LIBC'` - echo "${UNAME_MACHINE}-pc-linux-${LIBC}" + echo ${UNAME_MACHINE}-pc-linux-${LIBC} exit ;; ia64:Linux:*:*) - echo ${UNAME_MACHINE}-unknown-linux-gnu + echo ${UNAME_MACHINE}-unknown-linux-${LIBC} exit ;; m32r*:Linux:*:*) - echo ${UNAME_MACHINE}-unknown-linux-gnu + echo ${UNAME_MACHINE}-unknown-linux-${LIBC} exit ;; m68*:Linux:*:*) - echo ${UNAME_MACHINE}-unknown-linux-gnu + echo ${UNAME_MACHINE}-unknown-linux-${LIBC} exit ;; mips:Linux:*:* | mips64:Linux:*:*) eval $set_cc_for_build @@ -950,54 +968,63 @@ EOF #endif EOF eval `$CC_FOR_BUILD -E $dummy.c 2>/dev/null | grep '^CPU'` - test x"${CPU}" != x && { echo "${CPU}-unknown-linux-gnu"; exit; } + test x"${CPU}" != x && { echo "${CPU}-unknown-linux-${LIBC}"; exit; } ;; - or32:Linux:*:*) - echo ${UNAME_MACHINE}-unknown-linux-gnu + openrisc*:Linux:*:*) + echo or1k-unknown-linux-${LIBC} + exit ;; + or32:Linux:*:* | or1k*:Linux:*:*) + echo ${UNAME_MACHINE}-unknown-linux-${LIBC} exit ;; padre:Linux:*:*) - echo sparc-unknown-linux-gnu + echo sparc-unknown-linux-${LIBC} exit ;; parisc64:Linux:*:* | hppa64:Linux:*:*) - echo hppa64-unknown-linux-gnu + echo hppa64-unknown-linux-${LIBC} exit ;; parisc:Linux:*:* | hppa:Linux:*:*) # Look for CPU level case `grep '^cpu[^a-z]*:' /proc/cpuinfo 2>/dev/null | cut -d' ' -f2` in - PA7*) echo hppa1.1-unknown-linux-gnu ;; - PA8*) echo hppa2.0-unknown-linux-gnu ;; - *) echo hppa-unknown-linux-gnu ;; + PA7*) echo hppa1.1-unknown-linux-${LIBC} ;; + PA8*) echo hppa2.0-unknown-linux-${LIBC} ;; + *) echo hppa-unknown-linux-${LIBC} ;; esac exit ;; ppc64:Linux:*:*) - echo powerpc64-unknown-linux-gnu + echo powerpc64-unknown-linux-${LIBC} exit ;; ppc:Linux:*:*) - echo powerpc-unknown-linux-gnu + echo powerpc-unknown-linux-${LIBC} + exit ;; + ppc64le:Linux:*:*) + echo powerpc64le-unknown-linux-${LIBC} + exit ;; + ppcle:Linux:*:*) + echo powerpcle-unknown-linux-${LIBC} exit ;; s390:Linux:*:* | s390x:Linux:*:*) - echo ${UNAME_MACHINE}-ibm-linux + echo ${UNAME_MACHINE}-ibm-linux-${LIBC} exit ;; sh64*:Linux:*:*) - echo ${UNAME_MACHINE}-unknown-linux-gnu + echo ${UNAME_MACHINE}-unknown-linux-${LIBC} exit ;; sh*:Linux:*:*) - echo ${UNAME_MACHINE}-unknown-linux-gnu + echo ${UNAME_MACHINE}-unknown-linux-${LIBC} exit ;; sparc:Linux:*:* | sparc64:Linux:*:*) - echo ${UNAME_MACHINE}-unknown-linux-gnu + echo ${UNAME_MACHINE}-unknown-linux-${LIBC} exit ;; tile*:Linux:*:*) - echo ${UNAME_MACHINE}-unknown-linux-gnu + echo ${UNAME_MACHINE}-unknown-linux-${LIBC} exit ;; vax:Linux:*:*) - echo ${UNAME_MACHINE}-dec-linux-gnu + echo ${UNAME_MACHINE}-dec-linux-${LIBC} exit ;; x86_64:Linux:*:*) - echo ${UNAME_MACHINE}-unknown-linux-gnu + echo ${UNAME_MACHINE}-unknown-linux-${LIBC} exit ;; xtensa*:Linux:*:*) - echo ${UNAME_MACHINE}-unknown-linux-gnu + echo ${UNAME_MACHINE}-unknown-linux-${LIBC} exit ;; i*86:DYNIX/ptx:4*:*) # ptx 4.0 does uname -s correctly, with DYNIX/ptx in there. @@ -1201,6 +1228,9 @@ EOF BePC:Haiku:*:*) # Haiku running on Intel PC compatible. echo i586-pc-haiku exit ;; + x86_64:Haiku:*:*) + echo x86_64-unknown-haiku + exit ;; SX-4:SUPER-UX:*:*) echo sx4-nec-superux${UNAME_RELEASE} exit ;; @@ -1227,19 +1257,31 @@ EOF exit ;; *:Darwin:*:*) UNAME_PROCESSOR=`uname -p` || UNAME_PROCESSOR=unknown - case $UNAME_PROCESSOR in - i386) - eval $set_cc_for_build - if [ "$CC_FOR_BUILD" != 'no_compiler_found' ]; then - if (echo '#ifdef __LP64__'; echo IS_64BIT_ARCH; echo '#endif') | \ - (CCOPTS= $CC_FOR_BUILD -E - 2>/dev/null) | \ - grep IS_64BIT_ARCH >/dev/null - then - UNAME_PROCESSOR="x86_64" - fi - fi ;; - unknown) UNAME_PROCESSOR=powerpc ;; - esac + eval $set_cc_for_build + if test "$UNAME_PROCESSOR" = unknown ; then + UNAME_PROCESSOR=powerpc + fi + if test `echo "$UNAME_RELEASE" | sed -e 's/\..*//'` -le 10 ; then + if [ "$CC_FOR_BUILD" != 'no_compiler_found' ]; then + if (echo '#ifdef __LP64__'; echo IS_64BIT_ARCH; echo '#endif') | \ + (CCOPTS= $CC_FOR_BUILD -E - 2>/dev/null) | \ + grep IS_64BIT_ARCH >/dev/null + then + case $UNAME_PROCESSOR in + i386) UNAME_PROCESSOR=x86_64 ;; + powerpc) UNAME_PROCESSOR=powerpc64 ;; + esac + fi + fi + elif test "$UNAME_PROCESSOR" = i386 ; then + # Avoid executing cc on OS X 10.9, as it ships with a stub + # that puts up a graphical alert prompting to install + # developer tools. Any system running Mac OS X 10.7 or + # later (Darwin 11 and later) is required to have a 64-bit + # processor. This is not true of the ARM version of Darwin + # that Apple uses in portable devices. + UNAME_PROCESSOR=x86_64 + fi echo ${UNAME_PROCESSOR}-apple-darwin${UNAME_RELEASE} exit ;; *:procnto*:*:* | *:QNX:[0123456789]*:*) @@ -1330,157 +1372,6 @@ EOF exit ;; esac -#echo '(No uname command or uname output not recognized.)' 1>&2 -#echo "${UNAME_MACHINE}:${UNAME_SYSTEM}:${UNAME_RELEASE}:${UNAME_VERSION}" 1>&2 - -eval $set_cc_for_build -cat >$dummy.c < -# include -#endif -main () -{ -#if defined (sony) -#if defined (MIPSEB) - /* BFD wants "bsd" instead of "newsos". Perhaps BFD should be changed, - I don't know.... */ - printf ("mips-sony-bsd\n"); exit (0); -#else -#include - printf ("m68k-sony-newsos%s\n", -#ifdef NEWSOS4 - "4" -#else - "" -#endif - ); exit (0); -#endif -#endif - -#if defined (__arm) && defined (__acorn) && defined (__unix) - printf ("arm-acorn-riscix\n"); exit (0); -#endif - -#if defined (hp300) && !defined (hpux) - printf ("m68k-hp-bsd\n"); exit (0); -#endif - -#if defined (NeXT) -#if !defined (__ARCHITECTURE__) -#define __ARCHITECTURE__ "m68k" -#endif - int version; - version=`(hostinfo | sed -n 's/.*NeXT Mach \([0-9]*\).*/\1/p') 2>/dev/null`; - if (version < 4) - printf ("%s-next-nextstep%d\n", __ARCHITECTURE__, version); - else - printf ("%s-next-openstep%d\n", __ARCHITECTURE__, version); - exit (0); -#endif - -#if defined (MULTIMAX) || defined (n16) -#if defined (UMAXV) - printf ("ns32k-encore-sysv\n"); exit (0); -#else -#if defined (CMU) - printf ("ns32k-encore-mach\n"); exit (0); -#else - printf ("ns32k-encore-bsd\n"); exit (0); -#endif -#endif -#endif - -#if defined (__386BSD__) - printf ("i386-pc-bsd\n"); exit (0); -#endif - -#if defined (sequent) -#if defined (i386) - printf ("i386-sequent-dynix\n"); exit (0); -#endif -#if defined (ns32000) - printf ("ns32k-sequent-dynix\n"); exit (0); -#endif -#endif - -#if defined (_SEQUENT_) - struct utsname un; - - uname(&un); - - if (strncmp(un.version, "V2", 2) == 0) { - printf ("i386-sequent-ptx2\n"); exit (0); - } - if (strncmp(un.version, "V1", 2) == 0) { /* XXX is V1 correct? */ - printf ("i386-sequent-ptx1\n"); exit (0); - } - printf ("i386-sequent-ptx\n"); exit (0); - -#endif - -#if defined (vax) -# if !defined (ultrix) -# include -# if defined (BSD) -# if BSD == 43 - printf ("vax-dec-bsd4.3\n"); exit (0); -# else -# if BSD == 199006 - printf ("vax-dec-bsd4.3reno\n"); exit (0); -# else - printf ("vax-dec-bsd\n"); exit (0); -# endif -# endif -# else - printf ("vax-dec-bsd\n"); exit (0); -# endif -# else - printf ("vax-dec-ultrix\n"); exit (0); -# endif -#endif - -#if defined (alliant) && defined (i860) - printf ("i860-alliant-bsd\n"); exit (0); -#endif - - exit (1); -} -EOF - -$CC_FOR_BUILD -o $dummy $dummy.c 2>/dev/null && SYSTEM_NAME=`$dummy` && - { echo "$SYSTEM_NAME"; exit; } - -# Apollos put the system type in the environment. - -test -d /usr/apollo && { echo ${ISP}-apollo-${SYSTYPE}; exit; } - -# Convex versions that predate uname can use getsysinfo(1) - -if [ -x /usr/convex/getsysinfo ] -then - case `getsysinfo -f cpu_type` in - c1*) - echo c1-convex-bsd - exit ;; - c2*) - if getsysinfo -f scalar_acc - then echo c32-convex-bsd - else echo c2-convex-bsd - fi - exit ;; - c34*) - echo c34-convex-bsd - exit ;; - c38*) - echo c38-convex-bsd - exit ;; - c4*) - echo c4-convex-bsd - exit ;; - esac -fi - cat >&2 <. @@ -26,11 +20,12 @@ timestamp='2012-04-18' # As a special exception to the GNU General Public License, if you # distribute this file as part of a program that contains a # configuration script generated by Autoconf, you may include it under -# the same distribution terms that you use for the rest of that program. +# the same distribution terms that you use for the rest of that +# program. This Exception is an additional permission under section 7 +# of the GNU General Public License, version 3 ("GPLv3"). -# Please send patches to . Submit a context -# diff and a properly formatted GNU ChangeLog entry. +# Please send patches to . # # Configuration subroutine to validate and canonicalize a configuration type. # Supply the specified configuration type as an argument. @@ -73,9 +68,7 @@ Report bugs and patches to ." version="\ GNU config.sub ($timestamp) -Copyright (C) 1992, 1993, 1994, 1995, 1996, 1997, 1998, 1999, 2000, -2001, 2002, 2003, 2004, 2005, 2006, 2007, 2008, 2009, 2010, 2011, 2012 -Free Software Foundation, Inc. +Copyright 1992-2015 Free Software Foundation, Inc. This is free software; see the source for copying conditions. There is NO warranty; not even for MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE." @@ -123,7 +116,7 @@ esac maybe_os=`echo $1 | sed 's/^\(.*\)-\([^-]*-[^-]*\)$/\2/'` case $maybe_os in nto-qnx* | linux-gnu* | linux-android* | linux-dietlibc | linux-newlib* | \ - linux-uclibc* | uclinux-uclibc* | uclinux-gnu* | kfreebsd*-gnu* | \ + linux-musl* | linux-uclibc* | uclinux-uclibc* | uclinux-gnu* | kfreebsd*-gnu* | \ knetbsd*-gnu* | netbsd*-gnu* | \ kopensolaris*-gnu* | \ storm-chaos* | os2-emx* | rtmk-nova*) @@ -156,7 +149,7 @@ case $os in -convergent* | -ncr* | -news | -32* | -3600* | -3100* | -hitachi* |\ -c[123]* | -convex* | -sun | -crds | -omron* | -dg | -ultra | -tti* | \ -harris | -dolphin | -highlevel | -gould | -cbm | -ns | -masscomp | \ - -apple | -axis | -knuth | -cray | -microblaze) + -apple | -axis | -knuth | -cray | -microblaze*) os= basic_machine=$1 ;; @@ -259,21 +252,24 @@ case $basic_machine in | alpha | alphaev[4-8] | alphaev56 | alphaev6[78] | alphapca5[67] \ | alpha64 | alpha64ev[4-8] | alpha64ev56 | alpha64ev6[78] | alpha64pca5[67] \ | am33_2.0 \ - | arc | arm | arm[bl]e | arme[lb] | armv[2345] | armv[345][lb] | avr | avr32 \ - | be32 | be64 \ + | arc | arceb \ + | arm | arm[bl]e | arme[lb] | armv[2-8] | armv[3-8][lb] | armv7[arm] \ + | avr | avr32 \ + | be32 | be64 \ | bfin \ - | c4x | clipper \ + | c4x | c8051 | clipper \ | d10v | d30v | dlx | dsp16xx \ | epiphany \ - | fido | fr30 | frv \ + | fido | fr30 | frv | ft32 \ | h8300 | h8500 | hppa | hppa1.[01] | hppa2.0 | hppa2.0[nw] | hppa64 \ | hexagon \ | i370 | i860 | i960 | ia64 \ | ip2k | iq2000 \ + | k1om \ | le32 | le64 \ | lm32 \ | m32c | m32r | m32rle | m68000 | m68k | m88k \ - | maxq | mb | microblaze | mcore | mep | metag \ + | maxq | mb | microblaze | microblazeel | mcore | mep | metag \ | mips | mipsbe | mipseb | mipsel | mipsle \ | mips16 \ | mips64 | mips64el \ @@ -287,23 +283,26 @@ case $basic_machine in | mips64vr5900 | mips64vr5900el \ | mipsisa32 | mipsisa32el \ | mipsisa32r2 | mipsisa32r2el \ + | mipsisa32r6 | mipsisa32r6el \ | mipsisa64 | mipsisa64el \ | mipsisa64r2 | mipsisa64r2el \ + | mipsisa64r6 | mipsisa64r6el \ | mipsisa64sb1 | mipsisa64sb1el \ | mipsisa64sr71k | mipsisa64sr71kel \ + | mipsr5900 | mipsr5900el \ | mipstx39 | mipstx39el \ | mn10200 | mn10300 \ | moxie \ | mt \ | msp430 \ | nds32 | nds32le | nds32be \ - | nios | nios2 \ + | nios | nios2 | nios2eb | nios2el \ | ns16k | ns32k \ - | open8 \ - | or32 \ + | open8 | or1k | or1knd | or32 \ | pdp10 | pdp11 | pj | pjl \ | powerpc | powerpc64 | powerpc64le | powerpcle \ | pyramid \ + | riscv32 | riscv64 \ | rl78 | rx \ | score \ | sh | sh[1234] | sh[24]a | sh[24]aeb | sh[23]e | sh[34]eb | sheb | shbe | shle | sh[1234]le | sh3ele \ @@ -314,6 +313,7 @@ case $basic_machine in | tahoe | tic4x | tic54x | tic55x | tic6x | tic80 | tron \ | ubicom32 \ | v850 | v850e | v850e1 | v850e2 | v850es | v850e2v3 \ + | visium \ | we32k \ | x86 | xc16x | xstormy16 | xtensa \ | z8k | z80) @@ -328,7 +328,10 @@ case $basic_machine in c6x) basic_machine=tic6x-unknown ;; - m6811 | m68hc11 | m6812 | m68hc12 | m68hcs12x | picochip) + leon|leon[3-9]) + basic_machine=sparc-$basic_machine + ;; + m6811 | m68hc11 | m6812 | m68hc12 | m68hcs12x | nvptx | picochip) basic_machine=$basic_machine-unknown os=-none ;; @@ -370,13 +373,13 @@ case $basic_machine in | aarch64-* | aarch64_be-* \ | alpha-* | alphaev[4-8]-* | alphaev56-* | alphaev6[78]-* \ | alpha64-* | alpha64ev[4-8]-* | alpha64ev56-* | alpha64ev6[78]-* \ - | alphapca5[67]-* | alpha64pca5[67]-* | arc-* \ + | alphapca5[67]-* | alpha64pca5[67]-* | arc-* | arceb-* \ | arm-* | armbe-* | armle-* | armeb-* | armv*-* \ | avr-* | avr32-* \ | be32-* | be64-* \ | bfin-* | bs2000-* \ | c[123]* | c30-* | [cjt]90-* | c4x-* \ - | clipper-* | craynv-* | cydra-* \ + | c8051-* | clipper-* | craynv-* | cydra-* \ | d10v-* | d30v-* | dlx-* \ | elxsi-* \ | f30[01]-* | f700-* | fido-* | fr30-* | frv-* | fx80-* \ @@ -385,11 +388,13 @@ case $basic_machine in | hexagon-* \ | i*86-* | i860-* | i960-* | ia64-* \ | ip2k-* | iq2000-* \ + | k1om-* \ | le32-* | le64-* \ | lm32-* \ | m32c-* | m32r-* | m32rle-* \ | m68000-* | m680[012346]0-* | m68360-* | m683?2-* | m68k-* \ - | m88110-* | m88k-* | maxq-* | mcore-* | metag-* | microblaze-* \ + | m88110-* | m88k-* | maxq-* | mcore-* | metag-* \ + | microblaze-* | microblazeel-* \ | mips-* | mipsbe-* | mipseb-* | mipsel-* | mipsle-* \ | mips16-* \ | mips64-* | mips64el-* \ @@ -403,18 +408,22 @@ case $basic_machine in | mips64vr5900-* | mips64vr5900el-* \ | mipsisa32-* | mipsisa32el-* \ | mipsisa32r2-* | mipsisa32r2el-* \ + | mipsisa32r6-* | mipsisa32r6el-* \ | mipsisa64-* | mipsisa64el-* \ | mipsisa64r2-* | mipsisa64r2el-* \ + | mipsisa64r6-* | mipsisa64r6el-* \ | mipsisa64sb1-* | mipsisa64sb1el-* \ | mipsisa64sr71k-* | mipsisa64sr71kel-* \ + | mipsr5900-* | mipsr5900el-* \ | mipstx39-* | mipstx39el-* \ | mmix-* \ | mt-* \ | msp430-* \ | nds32-* | nds32le-* | nds32be-* \ - | nios-* | nios2-* \ + | nios-* | nios2-* | nios2eb-* | nios2el-* \ | none-* | np1-* | ns16k-* | ns32k-* \ | open8-* \ + | or1k*-* \ | orion-* \ | pdp10-* | pdp11-* | pj-* | pjl-* | pn-* | power-* \ | powerpc-* | powerpc64-* | powerpc64le-* | powerpcle-* \ @@ -432,6 +441,7 @@ case $basic_machine in | ubicom32-* \ | v850-* | v850e-* | v850e1-* | v850es-* | v850e2-* | v850e2v3-* \ | vax-* \ + | visium-* \ | we32k-* \ | x86-* | x86_64-* | xc16x-* | xps100-* \ | xstormy16-* | xtensa*-* \ @@ -769,6 +779,9 @@ case $basic_machine in basic_machine=m68k-isi os=-sysv ;; + leon-*|leon[3-9]-*) + basic_machine=sparc-`echo $basic_machine | sed 's/-.*//'` + ;; m68knommu) basic_machine=m68k-unknown os=-linux @@ -788,11 +801,15 @@ case $basic_machine in basic_machine=ns32k-utek os=-sysv ;; - microblaze) + microblaze*) basic_machine=microblaze-xilinx ;; + mingw64) + basic_machine=x86_64-pc + os=-mingw64 + ;; mingw32) - basic_machine=i386-pc + basic_machine=i686-pc os=-mingw32 ;; mingw32ce) @@ -820,6 +837,10 @@ case $basic_machine in basic_machine=powerpc-unknown os=-morphos ;; + moxiebox) + basic_machine=moxie-unknown + os=-moxiebox + ;; msdos) basic_machine=i386-pc os=-msdos @@ -828,7 +849,7 @@ case $basic_machine in basic_machine=`echo $basic_machine | sed -e 's/ms1-/mt-/'` ;; msys) - basic_machine=i386-pc + basic_machine=i686-pc os=-msys ;; mvs) @@ -1004,7 +1025,7 @@ case $basic_machine in ;; ppc64) basic_machine=powerpc64-unknown ;; - ppc64-*) basic_machine=powerpc64-`echo $basic_machine | sed 's/^[^-]*-//'` + ppc64-* | ppc64p7-*) basic_machine=powerpc64-`echo $basic_machine | sed 's/^[^-]*-//'` ;; ppc64le | powerpc64little | ppc64-le | powerpc64-little) basic_machine=powerpc64le-unknown @@ -1019,7 +1040,11 @@ case $basic_machine in basic_machine=i586-unknown os=-pw32 ;; - rdos) + rdos | rdos64) + basic_machine=x86_64-pc + os=-rdos + ;; + rdos32) basic_machine=i386-pc os=-rdos ;; @@ -1346,29 +1371,29 @@ case $os in -gnu* | -bsd* | -mach* | -minix* | -genix* | -ultrix* | -irix* \ | -*vms* | -sco* | -esix* | -isc* | -aix* | -cnk* | -sunos | -sunos[34]*\ | -hpux* | -unos* | -osf* | -luna* | -dgux* | -auroraux* | -solaris* \ - | -sym* | -kopensolaris* \ + | -sym* | -kopensolaris* | -plan9* \ | -amigaos* | -amigados* | -msdos* | -newsos* | -unicos* | -aof* \ | -aos* | -aros* \ | -nindy* | -vxsim* | -vxworks* | -ebmon* | -hms* | -mvs* \ | -clix* | -riscos* | -uniplus* | -iris* | -rtu* | -xenix* \ | -hiux* | -386bsd* | -knetbsd* | -mirbsd* | -netbsd* \ - | -openbsd* | -solidbsd* \ + | -bitrig* | -openbsd* | -solidbsd* \ | -ekkobsd* | -kfreebsd* | -freebsd* | -riscix* | -lynxos* \ | -bosx* | -nextstep* | -cxux* | -aout* | -elf* | -oabi* \ | -ptx* | -coff* | -ecoff* | -winnt* | -domain* | -vsta* \ | -udi* | -eabi* | -lites* | -ieee* | -go32* | -aux* \ | -chorusos* | -chorusrdb* | -cegcc* \ | -cygwin* | -msys* | -pe* | -psos* | -moss* | -proelf* | -rtems* \ - | -mingw32* | -linux-gnu* | -linux-android* \ - | -linux-newlib* | -linux-uclibc* \ - | -uxpv* | -beos* | -mpeix* | -udk* \ + | -mingw32* | -mingw64* | -linux-gnu* | -linux-android* \ + | -linux-newlib* | -linux-musl* | -linux-uclibc* \ + | -uxpv* | -beos* | -mpeix* | -udk* | -moxiebox* \ | -interix* | -uwin* | -mks* | -rhapsody* | -darwin* | -opened* \ | -openstep* | -oskit* | -conix* | -pw32* | -nonstopux* \ | -storm-chaos* | -tops10* | -tenex* | -tops20* | -its* \ | -os2* | -vos* | -palmos* | -uclinux* | -nucleus* \ | -morphos* | -superux* | -rtmk* | -rtmk-nova* | -windiss* \ | -powermax* | -dnix* | -nx6 | -nx7 | -sei* | -dragonfly* \ - | -skyos* | -haiku* | -rdos* | -toppers* | -drops* | -es*) + | -skyos* | -haiku* | -rdos* | -toppers* | -drops* | -es* | -tirtos*) # Remember, each alternative MUST END IN *, to match a version number. ;; -qnx*) @@ -1492,9 +1517,6 @@ case $os in -aros*) os=-aros ;; - -kaos*) - os=-kaos - ;; -zvmoe) os=-zvmoe ;; @@ -1543,6 +1565,9 @@ case $basic_machine in c4x-* | tic4x-*) os=-coff ;; + c8051-*) + os=-elf + ;; hexagon-*) os=-elf ;; diff --git a/gtsam/3rdparty/GeographicLib/configure b/gtsam/3rdparty/GeographicLib/configure index a9a70828a..13fe3f5af 100755 --- a/gtsam/3rdparty/GeographicLib/configure +++ b/gtsam/3rdparty/GeographicLib/configure @@ -1,6 +1,6 @@ #! /bin/sh # Guess values for system-dependent variables and create Makefiles. -# Generated by GNU Autoconf 2.69 for GeographicLib 1.35. +# Generated by GNU Autoconf 2.69 for GeographicLib 1.49. # # Report bugs to . # @@ -590,8 +590,8 @@ MAKEFLAGS= # Identity of this package. PACKAGE_NAME='GeographicLib' PACKAGE_TARNAME='geographiclib' -PACKAGE_VERSION='1.35' -PACKAGE_STRING='GeographicLib 1.35' +PACKAGE_VERSION='1.49' +PACKAGE_STRING='GeographicLib 1.49' PACKAGE_BUGREPORT='charles@karney.com' PACKAGE_URL='' @@ -635,6 +635,11 @@ ac_includes_default="\ ac_subst_vars='am__EXEEXT_FALSE am__EXEEXT_TRUE LTLIBOBJS +LIBOBJS +pkgconfigdir +PKG_CONFIG_LIBDIR +PKG_CONFIG_PATH +PKG_CONFIG HAVE_PODPROGS_FALSE HAVE_PODPROGS_TRUE COL @@ -643,9 +648,8 @@ POD2MAN HAVE_DOXYGEN_FALSE HAVE_DOXYGEN_TRUE DOXYGEN -LIBOBJS -POW_LIB CXXCPP +LT_SYS_LIBRARY_PATH OTOOL64 OTOOL LIPO @@ -700,6 +704,10 @@ MAINTAINER_MODE_TRUE GEOGRAPHICLIB_VERSION_PATCH GEOGRAPHICLIB_VERSION_MINOR GEOGRAPHICLIB_VERSION_MAJOR +AM_BACKSLASH +AM_DEFAULT_VERBOSITY +AM_DEFAULT_V +AM_V am__untar am__tar AMTAR @@ -776,15 +784,18 @@ SHELL' ac_subst_files='' ac_user_opts=' enable_option_checking +enable_silent_rules enable_maintainer_mode enable_dependency_tracking enable_shared enable_static with_pic enable_fast_install +with_aix_soname with_gnu_ld with_sysroot enable_libtool_lock +with_pkgconfigdir ' ac_precious_vars='build_alias host_alias @@ -798,7 +809,11 @@ CPP CXX CXXFLAGS CCC -CXXCPP' +LT_SYS_LIBRARY_PATH +CXXCPP +PKG_CONFIG +PKG_CONFIG_PATH +PKG_CONFIG_LIBDIR' # Initialize some variables set by options. @@ -1339,7 +1354,7 @@ if test "$ac_init_help" = "long"; then # Omit some internal or obsolete options to make the list less imposing. # This message is too long to be a string in the A/UX 3.1 sh. cat <<_ACEOF -\`configure' configures GeographicLib 1.35 to adapt to many kinds of systems. +\`configure' configures GeographicLib 1.49 to adapt to many kinds of systems. Usage: $0 [OPTION]... [VAR=VALUE]... @@ -1410,7 +1425,7 @@ fi if test -n "$ac_init_help"; then case $ac_init_help in - short | recursive ) echo "Configuration of GeographicLib 1.35:";; + short | recursive ) echo "Configuration of GeographicLib 1.49:";; esac cat <<\_ACEOF @@ -1418,6 +1433,8 @@ Optional Features: --disable-option-checking ignore unrecognized --enable/--with options --disable-FEATURE do not include FEATURE (same as --enable-FEATURE=no) --enable-FEATURE[=ARG] include FEATURE [ARG=yes] + --enable-silent-rules less verbose build output (undo: "make V=1") + --disable-silent-rules verbose build output (undo: "make V=0") --enable-maintainer-mode enable make rules and dependencies not useful (and sometimes confusing) to the casual installer @@ -1436,9 +1453,14 @@ Optional Packages: --without-PACKAGE do not use PACKAGE (same as --with-PACKAGE=no) --with-pic[=PKGS] try to use only PIC/non-PIC objects [default=use both] + --with-aix-soname=aix|svr4|both + shared library versioning (aka "SONAME") variant to + provide on AIX, [default=aix]. --with-gnu-ld assume the C compiler uses GNU ld [default=no] - --with-sysroot=DIR Search for dependent libraries within DIR - (or the compiler's sysroot if not specified). + --with-sysroot[=DIR] Search for dependent libraries within DIR (or the + compiler's sysroot if not specified). + --with-pkgconfigdir pkg-config installation directory + ['${libdir}/pkgconfig'] Some influential environment variables: CC C compiler command @@ -1451,7 +1473,14 @@ Some influential environment variables: CPP C preprocessor CXX C++ compiler command CXXFLAGS C++ compiler flags + LT_SYS_LIBRARY_PATH + User-defined run-time library search path. CXXCPP C++ preprocessor + PKG_CONFIG path to pkg-config utility + PKG_CONFIG_PATH + directories to add to pkg-config's search path + PKG_CONFIG_LIBDIR + path overriding pkg-config's built-in search path Use these variables to override the choices made by `configure' or to help it to find libraries and programs with nonstandard names/locations. @@ -1519,7 +1548,7 @@ fi test -n "$ac_init_help" && exit $ac_status if $ac_init_version; then cat <<\_ACEOF -GeographicLib configure 1.35 +GeographicLib configure 1.49 generated by GNU Autoconf 2.69 Copyright (C) 2012 Free Software Foundation, Inc. @@ -1915,155 +1944,52 @@ fi } # ac_fn_cxx_try_link -# ac_fn_c_check_header_mongrel LINENO HEADER VAR INCLUDES -# ------------------------------------------------------- -# Tests whether HEADER exists, giving a warning if it cannot be compiled using -# the include files in INCLUDES and setting the cache variable VAR -# accordingly. -ac_fn_c_check_header_mongrel () +# ac_fn_cxx_try_run LINENO +# ------------------------ +# Try to link conftest.$ac_ext, and return whether this succeeded. Assumes +# that executables *can* be run. +ac_fn_cxx_try_run () { as_lineno=${as_lineno-"$1"} as_lineno_stack=as_lineno_stack=$as_lineno_stack - if eval \${$3+:} false; then : - { $as_echo "$as_me:${as_lineno-$LINENO}: checking for $2" >&5 -$as_echo_n "checking for $2... " >&6; } -if eval \${$3+:} false; then : - $as_echo_n "(cached) " >&6 -fi -eval ac_res=\$$3 - { $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_res" >&5 -$as_echo "$ac_res" >&6; } -else - # Is the header compilable? -{ $as_echo "$as_me:${as_lineno-$LINENO}: checking $2 usability" >&5 -$as_echo_n "checking $2 usability... " >&6; } -cat confdefs.h - <<_ACEOF >conftest.$ac_ext -/* end confdefs.h. */ -$4 -#include <$2> -_ACEOF -if ac_fn_c_try_compile "$LINENO"; then : - ac_header_compiler=yes -else - ac_header_compiler=no -fi -rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext -{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_header_compiler" >&5 -$as_echo "$ac_header_compiler" >&6; } - -# Is the header present? -{ $as_echo "$as_me:${as_lineno-$LINENO}: checking $2 presence" >&5 -$as_echo_n "checking $2 presence... " >&6; } -cat confdefs.h - <<_ACEOF >conftest.$ac_ext -/* end confdefs.h. */ -#include <$2> -_ACEOF -if ac_fn_c_try_cpp "$LINENO"; then : - ac_header_preproc=yes -else - ac_header_preproc=no -fi -rm -f conftest.err conftest.i conftest.$ac_ext -{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_header_preproc" >&5 -$as_echo "$ac_header_preproc" >&6; } - -# So? What about this header? -case $ac_header_compiler:$ac_header_preproc:$ac_c_preproc_warn_flag in #(( - yes:no: ) - { $as_echo "$as_me:${as_lineno-$LINENO}: WARNING: $2: accepted by the compiler, rejected by the preprocessor!" >&5 -$as_echo "$as_me: WARNING: $2: accepted by the compiler, rejected by the preprocessor!" >&2;} - { $as_echo "$as_me:${as_lineno-$LINENO}: WARNING: $2: proceeding with the compiler's result" >&5 -$as_echo "$as_me: WARNING: $2: proceeding with the compiler's result" >&2;} - ;; - no:yes:* ) - { $as_echo "$as_me:${as_lineno-$LINENO}: WARNING: $2: present but cannot be compiled" >&5 -$as_echo "$as_me: WARNING: $2: present but cannot be compiled" >&2;} - { $as_echo "$as_me:${as_lineno-$LINENO}: WARNING: $2: check for missing prerequisite headers?" >&5 -$as_echo "$as_me: WARNING: $2: check for missing prerequisite headers?" >&2;} - { $as_echo "$as_me:${as_lineno-$LINENO}: WARNING: $2: see the Autoconf documentation" >&5 -$as_echo "$as_me: WARNING: $2: see the Autoconf documentation" >&2;} - { $as_echo "$as_me:${as_lineno-$LINENO}: WARNING: $2: section \"Present But Cannot Be Compiled\"" >&5 -$as_echo "$as_me: WARNING: $2: section \"Present But Cannot Be Compiled\"" >&2;} - { $as_echo "$as_me:${as_lineno-$LINENO}: WARNING: $2: proceeding with the compiler's result" >&5 -$as_echo "$as_me: WARNING: $2: proceeding with the compiler's result" >&2;} -( $as_echo "## --------------------------------- ## -## Report this to charles@karney.com ## -## --------------------------------- ##" - ) | sed "s/^/$as_me: WARNING: /" >&2 - ;; + if { { ac_try="$ac_link" +case "(($ac_try" in + *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;; + *) ac_try_echo=$ac_try;; esac - { $as_echo "$as_me:${as_lineno-$LINENO}: checking for $2" >&5 -$as_echo_n "checking for $2... " >&6; } -if eval \${$3+:} false; then : - $as_echo_n "(cached) " >&6 +eval ac_try_echo="\"\$as_me:${as_lineno-$LINENO}: $ac_try_echo\"" +$as_echo "$ac_try_echo"; } >&5 + (eval "$ac_link") 2>&5 + ac_status=$? + $as_echo "$as_me:${as_lineno-$LINENO}: \$? = $ac_status" >&5 + test $ac_status = 0; } && { ac_try='./conftest$ac_exeext' + { { case "(($ac_try" in + *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;; + *) ac_try_echo=$ac_try;; +esac +eval ac_try_echo="\"\$as_me:${as_lineno-$LINENO}: $ac_try_echo\"" +$as_echo "$ac_try_echo"; } >&5 + (eval "$ac_try") 2>&5 + ac_status=$? + $as_echo "$as_me:${as_lineno-$LINENO}: \$? = $ac_status" >&5 + test $ac_status = 0; }; }; then : + ac_retval=0 else - eval "$3=\$ac_header_compiler" -fi -eval ac_res=\$$3 - { $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_res" >&5 -$as_echo "$ac_res" >&6; } + $as_echo "$as_me: program exited with status $ac_status" >&5 + $as_echo "$as_me: failed program was:" >&5 +sed 's/^/| /' conftest.$ac_ext >&5 + + ac_retval=$ac_status fi + rm -rf conftest.dSYM conftest_ipa8_conftest.oo eval $as_lineno_stack; ${as_lineno_stack:+:} unset as_lineno + as_fn_set_status $ac_retval -} # ac_fn_c_check_header_mongrel - -# ac_fn_c_check_type LINENO TYPE VAR INCLUDES -# ------------------------------------------- -# Tests whether TYPE exists after having included INCLUDES, setting cache -# variable VAR accordingly. -ac_fn_c_check_type () -{ - as_lineno=${as_lineno-"$1"} as_lineno_stack=as_lineno_stack=$as_lineno_stack - { $as_echo "$as_me:${as_lineno-$LINENO}: checking for $2" >&5 -$as_echo_n "checking for $2... " >&6; } -if eval \${$3+:} false; then : - $as_echo_n "(cached) " >&6 -else - eval "$3=no" - cat confdefs.h - <<_ACEOF >conftest.$ac_ext -/* end confdefs.h. */ -$4 -int -main () -{ -if (sizeof ($2)) - return 0; - ; - return 0; -} -_ACEOF -if ac_fn_c_try_compile "$LINENO"; then : - cat confdefs.h - <<_ACEOF >conftest.$ac_ext -/* end confdefs.h. */ -$4 -int -main () -{ -if (sizeof (($2))) - return 0; - ; - return 0; -} -_ACEOF -if ac_fn_c_try_compile "$LINENO"; then : - -else - eval "$3=yes" -fi -rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext -fi -rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext -fi -eval ac_res=\$$3 - { $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_res" >&5 -$as_echo "$ac_res" >&6; } - eval $as_lineno_stack; ${as_lineno_stack:+:} unset as_lineno - -} # ac_fn_c_check_type +} # ac_fn_cxx_try_run cat >config.log <<_ACEOF This file contains any messages produced by compilers while running configure, to aid debugging if configure makes a mistake. -It was created by GeographicLib $as_me 1.35, which was +It was created by GeographicLib $as_me 1.49, which was generated by GNU Autoconf 2.69. Invocation command line was $ $0 $@ @@ -2554,7 +2480,7 @@ test -n "$target_alias" && -am__api_version='1.12' +am__api_version='1.15' # Find a good install program. We prefer a C program (faster), # so one script is as good as another. But avoid the broken or @@ -2726,8 +2652,8 @@ test "$program_suffix" != NONE && ac_script='s/[\\$]/&&/g;s/;s,x,x,$//' program_transform_name=`$as_echo "$program_transform_name" | sed "$ac_script"` -# expand $ac_aux_dir to an absolute path -am_aux_dir=`cd $ac_aux_dir && pwd` +# Expand $ac_aux_dir to an absolute path. +am_aux_dir=`cd "$ac_aux_dir" && pwd` if test x"${MISSING+set}" != xset; then case $am_aux_dir in @@ -2738,15 +2664,15 @@ if test x"${MISSING+set}" != xset; then esac fi # Use eval to expand $SHELL -if eval "$MISSING --run true"; then - am_missing_run="$MISSING --run " +if eval "$MISSING --is-lightweight"; then + am_missing_run="$MISSING " else am_missing_run= { $as_echo "$as_me:${as_lineno-$LINENO}: WARNING: 'missing' script is too old or missing" >&5 $as_echo "$as_me: WARNING: 'missing' script is too old or missing" >&2;} fi -if test x"${install_sh}" != xset; then +if test x"${install_sh+set}" != xset; then case $am_aux_dir in *\ * | *\ *) install_sh="\${SHELL} '$am_aux_dir/install-sh'" ;; @@ -2979,6 +2905,45 @@ else fi rmdir .tst 2>/dev/null +# Check whether --enable-silent-rules was given. +if test "${enable_silent_rules+set}" = set; then : + enableval=$enable_silent_rules; +fi + +case $enable_silent_rules in # ((( + yes) AM_DEFAULT_VERBOSITY=0;; + no) AM_DEFAULT_VERBOSITY=1;; + *) AM_DEFAULT_VERBOSITY=1;; +esac +am_make=${MAKE-make} +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking whether $am_make supports nested variables" >&5 +$as_echo_n "checking whether $am_make supports nested variables... " >&6; } +if ${am_cv_make_support_nested_variables+:} false; then : + $as_echo_n "(cached) " >&6 +else + if $as_echo 'TRUE=$(BAR$(V)) +BAR0=false +BAR1=true +V=1 +am__doit: + @$(TRUE) +.PHONY: am__doit' | $am_make -f - >/dev/null 2>&1; then + am_cv_make_support_nested_variables=yes +else + am_cv_make_support_nested_variables=no +fi +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $am_cv_make_support_nested_variables" >&5 +$as_echo "$am_cv_make_support_nested_variables" >&6; } +if test $am_cv_make_support_nested_variables = yes; then + AM_V='$(V)' + AM_DEFAULT_V='$(AM_DEFAULT_VERBOSITY)' +else + AM_V=$AM_DEFAULT_VERBOSITY + AM_DEFAULT_V=$AM_DEFAULT_VERBOSITY +fi +AM_BACKSLASH='\' + if test "`cd $srcdir && pwd`" != "`pwd`"; then # Use -I$(srcdir) only when $(srcdir) != ., so that make's output # is not polluted with repeated "-I." @@ -3001,7 +2966,7 @@ fi # Define the identity of the package. PACKAGE='geographiclib' - VERSION='1.35' + VERSION='1.49' cat >>confdefs.h <<_ACEOF @@ -3035,12 +3000,16 @@ MAKEINFO=${MAKEINFO-"${am_missing_run}makeinfo"} # mkdir_p='$(MKDIR_P)' -# We need awk for the "check" target. The system "awk" is bad on -# some platforms. +# We need awk for the "check" target (and possibly the TAP driver). The +# system "awk" is bad on some platforms. # Always define AMTAR for backward compatibility. Yes, it's still used # in the wild :-( We should find a proper way to deprecate it ... AMTAR='$${TAR-tar}' + +# We'll loop over all known methods to create a tar archive until one works. +_am_tools='gnutar pax cpio none' + am__tar='$${TAR-tar} chof - "$$tardir"' am__untar='$${TAR-tar} xf -' @@ -3048,8 +3017,51 @@ am__tar='$${TAR-tar} chof - "$$tardir"' am__untar='$${TAR-tar} xf -' +# POSIX will say in a future version that running "rm -f" with no argument +# is OK; and we want to be able to make that assumption in our Makefile +# recipes. So use an aggressive probe to check that the usage we want is +# actually supported "in the wild" to an acceptable degree. +# See automake bug#10828. +# To make any issue more visible, cause the running configure to be aborted +# by default if the 'rm' program in use doesn't match our expectations; the +# user can still override this though. +if rm -f && rm -fr && rm -rf; then : OK; else + cat >&2 <<'END' +Oops! + +Your 'rm' program seems unable to run without file operands specified +on the command line, even when the '-f' option is present. This is contrary +to the behaviour of most rm programs out there, and not conforming with +the upcoming POSIX standard: + +Please tell bug-automake@gnu.org about your system, including the value +of your $PATH and any error possibly output before this message. This +can help us improve future automake versions. + +END + if test x"$ACCEPT_INFERIOR_RM_PROGRAM" = x"yes"; then + echo 'Configuration will proceed anyway, since you have set the' >&2 + echo 'ACCEPT_INFERIOR_RM_PROGRAM variable to "yes"' >&2 + echo >&2 + else + cat >&2 <<'END' +Aborting the configuration process, to ensure you take notice of the issue. + +You can download and install GNU coreutils to get an 'rm' implementation +that behaves properly: . + +If you want to complete the configuration process using your problematic +'rm' anyway, export the environment variable ACCEPT_INFERIOR_RM_PROGRAM +to "yes", and re-run configure. + +END + as_fn_error $? "Your 'rm' program is bad, sorry." "$LINENO" 5 + fi +fi + + GEOGRAPHICLIB_VERSION_MAJOR=1 -GEOGRAPHICLIB_VERSION_MINOR=35 +GEOGRAPHICLIB_VERSION_MINOR=49 GEOGRAPHICLIB_VERSION_PATCH=0 cat >>confdefs.h <<_ACEOF @@ -3097,7 +3109,7 @@ fi ac_config_headers="$ac_config_headers include/GeographicLib/Config-ac.h" -LT_CURRENT=11 +LT_CURRENT=18 LT_REVISION=2 LT_AGE=1 @@ -3957,6 +3969,65 @@ ac_compile='$CC -c $CFLAGS $CPPFLAGS conftest.$ac_ext >&5' ac_link='$CC -o conftest$ac_exeext $CFLAGS $CPPFLAGS $LDFLAGS conftest.$ac_ext $LIBS >&5' ac_compiler_gnu=$ac_cv_c_compiler_gnu +ac_ext=c +ac_cpp='$CPP $CPPFLAGS' +ac_compile='$CC -c $CFLAGS $CPPFLAGS conftest.$ac_ext >&5' +ac_link='$CC -o conftest$ac_exeext $CFLAGS $CPPFLAGS $LDFLAGS conftest.$ac_ext $LIBS >&5' +ac_compiler_gnu=$ac_cv_c_compiler_gnu +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking whether $CC understands -c and -o together" >&5 +$as_echo_n "checking whether $CC understands -c and -o together... " >&6; } +if ${am_cv_prog_cc_c_o+:} false; then : + $as_echo_n "(cached) " >&6 +else + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ + +int +main () +{ + + ; + return 0; +} +_ACEOF + # Make sure it works both with $CC and with simple cc. + # Following AC_PROG_CC_C_O, we do the test twice because some + # compilers refuse to overwrite an existing .o file with -o, + # though they will create one. + am_cv_prog_cc_c_o=yes + for am_i in 1 2; do + if { echo "$as_me:$LINENO: $CC -c conftest.$ac_ext -o conftest2.$ac_objext" >&5 + ($CC -c conftest.$ac_ext -o conftest2.$ac_objext) >&5 2>&5 + ac_status=$? + echo "$as_me:$LINENO: \$? = $ac_status" >&5 + (exit $ac_status); } \ + && test -f conftest2.$ac_objext; then + : OK + else + am_cv_prog_cc_c_o=no + break + fi + done + rm -f core conftest* + unset am_i +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $am_cv_prog_cc_c_o" >&5 +$as_echo "$am_cv_prog_cc_c_o" >&6; } +if test "$am_cv_prog_cc_c_o" != yes; then + # Losing compiler, so override with the script. + # FIXME: It is wrong to rewrite CC. + # But if we don't then we get into trouble of one sort or another. + # A longer-term fix would be to have automake use am__CC in this case, + # and then we could set am__CC="\$(top_srcdir)/compile \$(CC)" + CC="$am_aux_dir/compile $CC" +fi +ac_ext=c +ac_cpp='$CPP $CPPFLAGS' +ac_compile='$CC -c $CFLAGS $CPPFLAGS conftest.$ac_ext >&5' +ac_link='$CC -o conftest$ac_exeext $CFLAGS $CPPFLAGS $LDFLAGS conftest.$ac_ext $LIBS >&5' +ac_compiler_gnu=$ac_cv_c_compiler_gnu + + depcc="$CC" am_compiler_list= { $as_echo "$as_me:${as_lineno-$LINENO}: checking dependency style of $depcc" >&5 @@ -4647,8 +4718,8 @@ esac -macro_version='2.4.2' -macro_revision='1.3337' +macro_version='2.4.6' +macro_revision='2.4.6' @@ -4662,7 +4733,7 @@ macro_revision='1.3337' -ltmain="$ac_aux_dir/ltmain.sh" +ltmain=$ac_aux_dir/ltmain.sh # Backslashify metacharacters that are still active within # double-quoted strings. @@ -4711,7 +4782,7 @@ func_echo_all () $ECHO "" } -case "$ECHO" in +case $ECHO in printf*) { $as_echo "$as_me:${as_lineno-$LINENO}: result: printf" >&5 $as_echo "printf" >&6; } ;; print*) { $as_echo "$as_me:${as_lineno-$LINENO}: result: print -r" >&5 @@ -5034,19 +5105,19 @@ test -z "$GREP" && GREP=grep # Check whether --with-gnu-ld was given. if test "${with_gnu_ld+set}" = set; then : - withval=$with_gnu_ld; test "$withval" = no || with_gnu_ld=yes + withval=$with_gnu_ld; test no = "$withval" || with_gnu_ld=yes else with_gnu_ld=no fi ac_prog=ld -if test "$GCC" = yes; then +if test yes = "$GCC"; then # Check if gcc -print-prog-name=ld gives a path. { $as_echo "$as_me:${as_lineno-$LINENO}: checking for ld used by $CC" >&5 $as_echo_n "checking for ld used by $CC... " >&6; } case $host in *-*-mingw*) - # gcc leaves a trailing carriage return which upsets mingw + # gcc leaves a trailing carriage return, which upsets mingw ac_prog=`($CC -print-prog-name=ld) 2>&5 | tr -d '\015'` ;; *) ac_prog=`($CC -print-prog-name=ld) 2>&5` ;; @@ -5060,7 +5131,7 @@ $as_echo_n "checking for ld used by $CC... " >&6; } while $ECHO "$ac_prog" | $GREP "$re_direlt" > /dev/null 2>&1; do ac_prog=`$ECHO $ac_prog| $SED "s%$re_direlt%/%"` done - test -z "$LD" && LD="$ac_prog" + test -z "$LD" && LD=$ac_prog ;; "") # If it fails, then pretend we aren't using GCC. @@ -5071,7 +5142,7 @@ $as_echo_n "checking for ld used by $CC... " >&6; } with_gnu_ld=unknown ;; esac -elif test "$with_gnu_ld" = yes; then +elif test yes = "$with_gnu_ld"; then { $as_echo "$as_me:${as_lineno-$LINENO}: checking for GNU ld" >&5 $as_echo_n "checking for GNU ld... " >&6; } else @@ -5082,32 +5153,32 @@ if ${lt_cv_path_LD+:} false; then : $as_echo_n "(cached) " >&6 else if test -z "$LD"; then - lt_save_ifs="$IFS"; IFS=$PATH_SEPARATOR + lt_save_ifs=$IFS; IFS=$PATH_SEPARATOR for ac_dir in $PATH; do - IFS="$lt_save_ifs" + IFS=$lt_save_ifs test -z "$ac_dir" && ac_dir=. if test -f "$ac_dir/$ac_prog" || test -f "$ac_dir/$ac_prog$ac_exeext"; then - lt_cv_path_LD="$ac_dir/$ac_prog" + lt_cv_path_LD=$ac_dir/$ac_prog # Check to see if the program is GNU ld. I'd rather use --version, # but apparently some variants of GNU ld only accept -v. # Break only if it was the GNU/non-GNU ld that we prefer. case `"$lt_cv_path_LD" -v 2>&1 &5 $as_echo "$LD" >&6; } @@ -5150,33 +5221,38 @@ if ${lt_cv_path_NM+:} false; then : else if test -n "$NM"; then # Let the user override the test. - lt_cv_path_NM="$NM" + lt_cv_path_NM=$NM else - lt_nm_to_check="${ac_tool_prefix}nm" + lt_nm_to_check=${ac_tool_prefix}nm if test -n "$ac_tool_prefix" && test "$build" = "$host"; then lt_nm_to_check="$lt_nm_to_check nm" fi for lt_tmp_nm in $lt_nm_to_check; do - lt_save_ifs="$IFS"; IFS=$PATH_SEPARATOR + lt_save_ifs=$IFS; IFS=$PATH_SEPARATOR for ac_dir in $PATH /usr/ccs/bin/elf /usr/ccs/bin /usr/ucb /bin; do - IFS="$lt_save_ifs" + IFS=$lt_save_ifs test -z "$ac_dir" && ac_dir=. - tmp_nm="$ac_dir/$lt_tmp_nm" - if test -f "$tmp_nm" || test -f "$tmp_nm$ac_exeext" ; then + tmp_nm=$ac_dir/$lt_tmp_nm + if test -f "$tmp_nm" || test -f "$tmp_nm$ac_exeext"; then # Check to see if the nm accepts a BSD-compat flag. - # Adding the `sed 1q' prevents false positives on HP-UX, which says: + # Adding the 'sed 1q' prevents false positives on HP-UX, which says: # nm: unknown option "B" ignored # Tru64's nm complains that /dev/null is an invalid object file - case `"$tmp_nm" -B /dev/null 2>&1 | sed '1q'` in - */dev/null* | *'Invalid file or object type'*) + # MSYS converts /dev/null to NUL, MinGW nm treats NUL as empty + case $build_os in + mingw*) lt_bad_file=conftest.nm/nofile ;; + *) lt_bad_file=/dev/null ;; + esac + case `"$tmp_nm" -B $lt_bad_file 2>&1 | sed '1q'` in + *$lt_bad_file* | *'Invalid file or object type'*) lt_cv_path_NM="$tmp_nm -B" - break + break 2 ;; *) case `"$tmp_nm" -p /dev/null 2>&1 | sed '1q'` in */dev/null*) lt_cv_path_NM="$tmp_nm -p" - break + break 2 ;; *) lt_cv_path_NM=${lt_cv_path_NM="$tmp_nm"} # keep the first match, but @@ -5187,15 +5263,15 @@ else esac fi done - IFS="$lt_save_ifs" + IFS=$lt_save_ifs done : ${lt_cv_path_NM=no} fi fi { $as_echo "$as_me:${as_lineno-$LINENO}: result: $lt_cv_path_NM" >&5 $as_echo "$lt_cv_path_NM" >&6; } -if test "$lt_cv_path_NM" != "no"; then - NM="$lt_cv_path_NM" +if test no != "$lt_cv_path_NM"; then + NM=$lt_cv_path_NM else # Didn't find any BSD compatible name lister, look for dumpbin. if test -n "$DUMPBIN"; then : @@ -5301,9 +5377,9 @@ esac fi fi - case `$DUMPBIN -symbols /dev/null 2>&1 | sed '1q'` in + case `$DUMPBIN -symbols -headers /dev/null 2>&1 | sed '1q'` in *COFF*) - DUMPBIN="$DUMPBIN -symbols" + DUMPBIN="$DUMPBIN -symbols -headers" ;; *) DUMPBIN=: @@ -5311,8 +5387,8 @@ fi esac fi - if test "$DUMPBIN" != ":"; then - NM="$DUMPBIN" + if test : != "$DUMPBIN"; then + NM=$DUMPBIN fi fi test -z "$NM" && NM=nm @@ -5363,7 +5439,7 @@ if ${lt_cv_sys_max_cmd_len+:} false; then : $as_echo_n "(cached) " >&6 else i=0 - teststring="ABCD" + teststring=ABCD case $build_os in msdosdjgpp*) @@ -5403,7 +5479,7 @@ else lt_cv_sys_max_cmd_len=8192; ;; - netbsd* | freebsd* | openbsd* | darwin* | dragonfly*) + bitrig* | darwin* | dragonfly* | freebsd* | netbsd* | openbsd*) # This has been around since 386BSD, at least. Likely further. if test -x /sbin/sysctl; then lt_cv_sys_max_cmd_len=`/sbin/sysctl -n kern.argmax` @@ -5453,22 +5529,23 @@ else ;; *) lt_cv_sys_max_cmd_len=`(getconf ARG_MAX) 2> /dev/null` - if test -n "$lt_cv_sys_max_cmd_len"; then + if test -n "$lt_cv_sys_max_cmd_len" && \ + test undefined != "$lt_cv_sys_max_cmd_len"; then lt_cv_sys_max_cmd_len=`expr $lt_cv_sys_max_cmd_len \/ 4` lt_cv_sys_max_cmd_len=`expr $lt_cv_sys_max_cmd_len \* 3` else # Make teststring a little bigger before we do anything with it. # a 1K string should be a reasonable start. - for i in 1 2 3 4 5 6 7 8 ; do + for i in 1 2 3 4 5 6 7 8; do teststring=$teststring$teststring done SHELL=${SHELL-${CONFIG_SHELL-/bin/sh}} # If test is not a shell built-in, we'll probably end up computing a # maximum length that is only half of the actual maximum length, but # we can't tell. - while { test "X"`env echo "$teststring$teststring" 2>/dev/null` \ + while { test X`env echo "$teststring$teststring" 2>/dev/null` \ = "X$teststring$teststring"; } >/dev/null 2>&1 && - test $i != 17 # 1/2 MB should be enough + test 17 != "$i" # 1/2 MB should be enough do i=`expr $i + 1` teststring=$teststring$teststring @@ -5486,7 +5563,7 @@ else fi -if test -n $lt_cv_sys_max_cmd_len ; then +if test -n "$lt_cv_sys_max_cmd_len"; then { $as_echo "$as_me:${as_lineno-$LINENO}: result: $lt_cv_sys_max_cmd_len" >&5 $as_echo "$lt_cv_sys_max_cmd_len" >&6; } else @@ -5504,30 +5581,6 @@ max_cmd_len=$lt_cv_sys_max_cmd_len : ${MV="mv -f"} : ${RM="rm -f"} -{ $as_echo "$as_me:${as_lineno-$LINENO}: checking whether the shell understands some XSI constructs" >&5 -$as_echo_n "checking whether the shell understands some XSI constructs... " >&6; } -# Try some XSI features -xsi_shell=no -( _lt_dummy="a/b/c" - test "${_lt_dummy##*/},${_lt_dummy%/*},${_lt_dummy#??}"${_lt_dummy%"$_lt_dummy"}, \ - = c,a/b,b/c, \ - && eval 'test $(( 1 + 1 )) -eq 2 \ - && test "${#_lt_dummy}" -eq 5' ) >/dev/null 2>&1 \ - && xsi_shell=yes -{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $xsi_shell" >&5 -$as_echo "$xsi_shell" >&6; } - - -{ $as_echo "$as_me:${as_lineno-$LINENO}: checking whether the shell understands \"+=\"" >&5 -$as_echo_n "checking whether the shell understands \"+=\"... " >&6; } -lt_shell_append=no -( foo=bar; set foo baz; eval "$1+=\$2" && test "$foo" = barbaz ) \ - >/dev/null 2>&1 \ - && lt_shell_append=yes -{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $lt_shell_append" >&5 -$as_echo "$lt_shell_append" >&6; } - - if ( (MAIL=60; unset MAIL) || exit) >/dev/null 2>&1; then lt_unset=unset else @@ -5650,13 +5703,13 @@ esac reload_cmds='$LD$reload_flag -o $output$reload_objs' case $host_os in cygwin* | mingw* | pw32* | cegcc*) - if test "$GCC" != yes; then + if test yes != "$GCC"; then reload_cmds=false fi ;; darwin*) - if test "$GCC" = yes; then - reload_cmds='$LTCC $LTCFLAGS -nostdlib ${wl}-r -o $output$reload_objs' + if test yes = "$GCC"; then + reload_cmds='$LTCC $LTCFLAGS -nostdlib $wl-r -o $output$reload_objs' else reload_cmds='$LD$reload_flag -o $output$reload_objs' fi @@ -5784,13 +5837,13 @@ lt_cv_deplibs_check_method='unknown' # Need to set the preceding variable on all platforms that support # interlibrary dependencies. # 'none' -- dependencies not supported. -# `unknown' -- same as none, but documents that we really don't know. +# 'unknown' -- same as none, but documents that we really don't know. # 'pass_all' -- all dependencies passed with no checks. # 'test_compile' -- check by making test program. # 'file_magic [[regex]]' -- check by looking for files in library path -# which responds to the $file_magic_cmd with a given extended regex. -# If you have `file' or equivalent on your system and you're not sure -# whether `pass_all' will *always* work, you probably want this one. +# that responds to the $file_magic_cmd with a given extended regex. +# If you have 'file' or equivalent on your system and you're not sure +# whether 'pass_all' will *always* work, you probably want this one. case $host_os in aix[4-9]*) @@ -5817,8 +5870,7 @@ mingw* | pw32*) # Base MSYS/MinGW do not provide the 'file' command needed by # func_win32_libid shell function, so use a weaker test based on 'objdump', # unless we find 'file', for example because we are cross-compiling. - # func_win32_libid assumes BSD nm, so disallow it if using MS dumpbin. - if ( test "$lt_cv_nm_interface" = "BSD nm" && file / ) >/dev/null 2>&1; then + if ( file / ) >/dev/null 2>&1; then lt_cv_deplibs_check_method='file_magic ^x86 archive import|^x86 DLL' lt_cv_file_magic_cmd='func_win32_libid' else @@ -5854,10 +5906,6 @@ freebsd* | dragonfly*) fi ;; -gnu*) - lt_cv_deplibs_check_method=pass_all - ;; - haiku*) lt_cv_deplibs_check_method=pass_all ;; @@ -5896,7 +5944,7 @@ irix5* | irix6* | nonstopux*) ;; # This must be glibc/ELF. -linux* | k*bsd*-gnu | kopensolaris*-gnu) +linux* | k*bsd*-gnu | kopensolaris*-gnu | gnu*) lt_cv_deplibs_check_method=pass_all ;; @@ -5918,8 +5966,8 @@ newos6*) lt_cv_deplibs_check_method=pass_all ;; -openbsd*) - if test -z "`echo __ELF__ | $CC -E - | $GREP __ELF__`" || test "$host_os-$host_cpu" = "openbsd2.8-powerpc"; then +openbsd* | bitrig*) + if test -z "`echo __ELF__ | $CC -E - | $GREP __ELF__`"; then lt_cv_deplibs_check_method='match_pattern /lib[^/]+(\.so\.[0-9]+\.[0-9]+|\.so|_pic\.a)$' else lt_cv_deplibs_check_method='match_pattern /lib[^/]+(\.so\.[0-9]+\.[0-9]+|_pic\.a)$' @@ -5972,6 +6020,9 @@ sysv4 | sysv4.3*) tpf*) lt_cv_deplibs_check_method=pass_all ;; +os2*) + lt_cv_deplibs_check_method=pass_all + ;; esac fi @@ -6129,8 +6180,8 @@ else case $host_os in cygwin* | mingw* | pw32* | cegcc*) - # two different shell functions defined in ltmain.sh - # decide which to use based on capabilities of $DLLTOOL + # two different shell functions defined in ltmain.sh; + # decide which one to use based on capabilities of $DLLTOOL case `$DLLTOOL --help 2>&1` in *--identify-strict*) lt_cv_sharedlib_from_linklib_cmd=func_cygming_dll_for_implib @@ -6142,7 +6193,7 @@ cygwin* | mingw* | pw32* | cegcc*) ;; *) # fallback: assume linklib IS sharedlib - lt_cv_sharedlib_from_linklib_cmd="$ECHO" + lt_cv_sharedlib_from_linklib_cmd=$ECHO ;; esac @@ -6297,7 +6348,7 @@ if ac_fn_c_try_compile "$LINENO"; then : ac_status=$? $as_echo "$as_me:${as_lineno-$LINENO}: \$? = $ac_status" >&5 test $ac_status = 0; } - if test "$ac_status" -eq 0; then + if test 0 -eq "$ac_status"; then # Ensure the archiver fails upon bogus file names. rm -f conftest.$ac_objext libconftest.a { { eval echo "\"\$as_me\":${as_lineno-$LINENO}: \"$lt_ar_try\""; } >&5 @@ -6305,7 +6356,7 @@ if ac_fn_c_try_compile "$LINENO"; then : ac_status=$? $as_echo "$as_me:${as_lineno-$LINENO}: \$? = $ac_status" >&5 test $ac_status = 0; } - if test "$ac_status" -ne 0; then + if test 0 -ne "$ac_status"; then lt_cv_ar_at_file=@ fi fi @@ -6318,7 +6369,7 @@ fi { $as_echo "$as_me:${as_lineno-$LINENO}: result: $lt_cv_ar_at_file" >&5 $as_echo "$lt_cv_ar_at_file" >&6; } -if test "x$lt_cv_ar_at_file" = xno; then +if test no = "$lt_cv_ar_at_file"; then archiver_list_spec= else archiver_list_spec=$lt_cv_ar_at_file @@ -6535,7 +6586,7 @@ old_postuninstall_cmds= if test -n "$RANLIB"; then case $host_os in - openbsd*) + bitrig* | openbsd*) old_postinstall_cmds="$old_postinstall_cmds~\$RANLIB -t \$tool_oldlib" ;; *) @@ -6625,7 +6676,7 @@ cygwin* | mingw* | pw32* | cegcc*) symcode='[ABCDGISTW]' ;; hpux*) - if test "$host_cpu" = ia64; then + if test ia64 = "$host_cpu"; then symcode='[ABCDEGRST]' fi ;; @@ -6658,14 +6709,44 @@ case `$NM -V 2>&1` in symcode='[ABCDGIRSTW]' ;; esac +if test "$lt_cv_nm_interface" = "MS dumpbin"; then + # Gets list of data symbols to import. + lt_cv_sys_global_symbol_to_import="sed -n -e 's/^I .* \(.*\)$/\1/p'" + # Adjust the below global symbol transforms to fixup imported variables. + lt_cdecl_hook=" -e 's/^I .* \(.*\)$/extern __declspec(dllimport) char \1;/p'" + lt_c_name_hook=" -e 's/^I .* \(.*\)$/ {\"\1\", (void *) 0},/p'" + lt_c_name_lib_hook="\ + -e 's/^I .* \(lib.*\)$/ {\"\1\", (void *) 0},/p'\ + -e 's/^I .* \(.*\)$/ {\"lib\1\", (void *) 0},/p'" +else + # Disable hooks by default. + lt_cv_sys_global_symbol_to_import= + lt_cdecl_hook= + lt_c_name_hook= + lt_c_name_lib_hook= +fi + # Transform an extracted symbol line into a proper C declaration. # Some systems (esp. on ia64) link data and code symbols differently, # so use this general approach. -lt_cv_sys_global_symbol_to_cdecl="sed -n -e 's/^T .* \(.*\)$/extern int \1();/p' -e 's/^$symcode* .* \(.*\)$/extern char \1;/p'" +lt_cv_sys_global_symbol_to_cdecl="sed -n"\ +$lt_cdecl_hook\ +" -e 's/^T .* \(.*\)$/extern int \1();/p'"\ +" -e 's/^$symcode$symcode* .* \(.*\)$/extern char \1;/p'" # Transform an extracted symbol line into symbol name and symbol address -lt_cv_sys_global_symbol_to_c_name_address="sed -n -e 's/^: \([^ ]*\)[ ]*$/ {\\\"\1\\\", (void *) 0},/p' -e 's/^$symcode* \([^ ]*\) \([^ ]*\)$/ {\"\2\", (void *) \&\2},/p'" -lt_cv_sys_global_symbol_to_c_name_address_lib_prefix="sed -n -e 's/^: \([^ ]*\)[ ]*$/ {\\\"\1\\\", (void *) 0},/p' -e 's/^$symcode* \([^ ]*\) \(lib[^ ]*\)$/ {\"\2\", (void *) \&\2},/p' -e 's/^$symcode* \([^ ]*\) \([^ ]*\)$/ {\"lib\2\", (void *) \&\2},/p'" +lt_cv_sys_global_symbol_to_c_name_address="sed -n"\ +$lt_c_name_hook\ +" -e 's/^: \(.*\) .*$/ {\"\1\", (void *) 0},/p'"\ +" -e 's/^$symcode$symcode* .* \(.*\)$/ {\"\1\", (void *) \&\1},/p'" + +# Transform an extracted symbol line into symbol name with lib prefix and +# symbol address. +lt_cv_sys_global_symbol_to_c_name_address_lib_prefix="sed -n"\ +$lt_c_name_lib_hook\ +" -e 's/^: \(.*\) .*$/ {\"\1\", (void *) 0},/p'"\ +" -e 's/^$symcode$symcode* .* \(lib.*\)$/ {\"\1\", (void *) \&\1},/p'"\ +" -e 's/^$symcode$symcode* .* \(.*\)$/ {\"lib\1\", (void *) \&\1},/p'" # Handle CRLF in mingw tool chain opt_cr= @@ -6683,21 +6764,24 @@ for ac_symprfx in "" "_"; do # Write the raw and C identifiers. if test "$lt_cv_nm_interface" = "MS dumpbin"; then - # Fake it for dumpbin and say T for any non-static function - # and D for any global variable. + # Fake it for dumpbin and say T for any non-static function, + # D for any global variable and I for any imported variable. # Also find C++ and __fastcall symbols from MSVC++, # which start with @ or ?. lt_cv_sys_global_symbol_pipe="$AWK '"\ " {last_section=section; section=\$ 3};"\ " /^COFF SYMBOL TABLE/{for(i in hide) delete hide[i]};"\ " /Section length .*#relocs.*(pick any)/{hide[last_section]=1};"\ +" /^ *Symbol name *: /{split(\$ 0,sn,\":\"); si=substr(sn[2],2)};"\ +" /^ *Type *: code/{print \"T\",si,substr(si,length(prfx))};"\ +" /^ *Type *: data/{print \"I\",si,substr(si,length(prfx))};"\ " \$ 0!~/External *\|/{next};"\ " / 0+ UNDEF /{next}; / UNDEF \([^|]\)*()/{next};"\ " {if(hide[section]) next};"\ -" {f=0}; \$ 0~/\(\).*\|/{f=1}; {printf f ? \"T \" : \"D \"};"\ -" {split(\$ 0, a, /\||\r/); split(a[2], s)};"\ -" s[1]~/^[@?]/{print s[1], s[1]; next};"\ -" s[1]~prfx {split(s[1],t,\"@\"); print t[1], substr(t[1],length(prfx))}"\ +" {f=\"D\"}; \$ 0~/\(\).*\|/{f=\"T\"};"\ +" {split(\$ 0,a,/\||\r/); split(a[2],s)};"\ +" s[1]~/^[@?]/{print f,s[1],s[1]; next};"\ +" s[1]~prfx {split(s[1],t,\"@\"); print f,t[1],substr(t[1],length(prfx))}"\ " ' prfx=^$ac_symprfx" else lt_cv_sys_global_symbol_pipe="sed -n -e 's/^.*[ ]\($symcode$symcode*\)[ ][ ]*$ac_symprfx$sympat$opt_cr$/$symxfrm/p'" @@ -6745,11 +6829,11 @@ _LT_EOF if $GREP ' nm_test_func$' "$nlist" >/dev/null; then cat <<_LT_EOF > conftest.$ac_ext /* Keep this code in sync between libtool.m4, ltmain, lt_system.h, and tests. */ -#if defined(_WIN32) || defined(__CYGWIN__) || defined(_WIN32_WCE) -/* DATA imports from DLLs on WIN32 con't be const, because runtime +#if defined _WIN32 || defined __CYGWIN__ || defined _WIN32_WCE +/* DATA imports from DLLs on WIN32 can't be const, because runtime relocations are performed -- see ld's documentation on pseudo-relocs. */ # define LT_DLSYM_CONST -#elif defined(__osf__) +#elif defined __osf__ /* This system does not cope well with relocations in const data. */ # define LT_DLSYM_CONST #else @@ -6775,7 +6859,7 @@ lt__PROGRAM__LTX_preloaded_symbols[] = { { "@PROGRAM@", (void *) 0 }, _LT_EOF - $SED "s/^$symcode$symcode* \(.*\) \(.*\)$/ {\"\2\", (void *) \&\2},/" < "$nlist" | $GREP -v main >> conftest.$ac_ext + $SED "s/^$symcode$symcode* .* \(.*\)$/ {\"\1\", (void *) \&\1},/" < "$nlist" | $GREP -v main >> conftest.$ac_ext cat <<\_LT_EOF >> conftest.$ac_ext {0, (void *) 0} }; @@ -6795,13 +6879,13 @@ _LT_EOF mv conftest.$ac_objext conftstm.$ac_objext lt_globsym_save_LIBS=$LIBS lt_globsym_save_CFLAGS=$CFLAGS - LIBS="conftstm.$ac_objext" + LIBS=conftstm.$ac_objext CFLAGS="$CFLAGS$lt_prog_compiler_no_builtin_flag" if { { eval echo "\"\$as_me\":${as_lineno-$LINENO}: \"$ac_link\""; } >&5 (eval $ac_link) 2>&5 ac_status=$? $as_echo "$as_me:${as_lineno-$LINENO}: \$? = $ac_status" >&5 - test $ac_status = 0; } && test -s conftest${ac_exeext}; then + test $ac_status = 0; } && test -s conftest$ac_exeext; then pipe_works=yes fi LIBS=$lt_globsym_save_LIBS @@ -6822,7 +6906,7 @@ _LT_EOF rm -rf conftest* conftst* # Do not use the global_symbol_pipe unless it works. - if test "$pipe_works" = yes; then + if test yes = "$pipe_works"; then break else lt_cv_sys_global_symbol_pipe= @@ -6864,6 +6948,16 @@ fi + + + + + + + + + + @@ -6887,9 +6981,9 @@ fi lt_sysroot= -case ${with_sysroot} in #( +case $with_sysroot in #( yes) - if test "$GCC" = yes; then + if test yes = "$GCC"; then lt_sysroot=`$CC --print-sysroot 2>/dev/null` fi ;; #( @@ -6899,8 +6993,8 @@ case ${with_sysroot} in #( no|'') ;; #( *) - { $as_echo "$as_me:${as_lineno-$LINENO}: result: ${with_sysroot}" >&5 -$as_echo "${with_sysroot}" >&6; } + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $with_sysroot" >&5 +$as_echo "$with_sysroot" >&6; } as_fn_error $? "The sysroot must be an absolute path." "$LINENO" 5 ;; esac @@ -6912,18 +7006,99 @@ $as_echo "${lt_sysroot:-no}" >&6; } +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for a working dd" >&5 +$as_echo_n "checking for a working dd... " >&6; } +if ${ac_cv_path_lt_DD+:} false; then : + $as_echo_n "(cached) " >&6 +else + printf 0123456789abcdef0123456789abcdef >conftest.i +cat conftest.i conftest.i >conftest2.i +: ${lt_DD:=$DD} +if test -z "$lt_DD"; then + ac_path_lt_DD_found=false + # Loop through the user's path and test for each of PROGNAME-LIST + as_save_IFS=$IFS; IFS=$PATH_SEPARATOR +for as_dir in $PATH +do + IFS=$as_save_IFS + test -z "$as_dir" && as_dir=. + for ac_prog in dd; do + for ac_exec_ext in '' $ac_executable_extensions; do + ac_path_lt_DD="$as_dir/$ac_prog$ac_exec_ext" + as_fn_executable_p "$ac_path_lt_DD" || continue +if "$ac_path_lt_DD" bs=32 count=1 conftest.out 2>/dev/null; then + cmp -s conftest.i conftest.out \ + && ac_cv_path_lt_DD="$ac_path_lt_DD" ac_path_lt_DD_found=: +fi + $ac_path_lt_DD_found && break 3 + done + done + done +IFS=$as_save_IFS + if test -z "$ac_cv_path_lt_DD"; then + : + fi +else + ac_cv_path_lt_DD=$lt_DD +fi + +rm -f conftest.i conftest2.i conftest.out +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_cv_path_lt_DD" >&5 +$as_echo "$ac_cv_path_lt_DD" >&6; } + + +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking how to truncate binary pipes" >&5 +$as_echo_n "checking how to truncate binary pipes... " >&6; } +if ${lt_cv_truncate_bin+:} false; then : + $as_echo_n "(cached) " >&6 +else + printf 0123456789abcdef0123456789abcdef >conftest.i +cat conftest.i conftest.i >conftest2.i +lt_cv_truncate_bin= +if "$ac_cv_path_lt_DD" bs=32 count=1 conftest.out 2>/dev/null; then + cmp -s conftest.i conftest.out \ + && lt_cv_truncate_bin="$ac_cv_path_lt_DD bs=4096 count=1" +fi +rm -f conftest.i conftest2.i conftest.out +test -z "$lt_cv_truncate_bin" && lt_cv_truncate_bin="$SED -e 4q" +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $lt_cv_truncate_bin" >&5 +$as_echo "$lt_cv_truncate_bin" >&6; } + + + + + + + +# Calculate cc_basename. Skip known compiler wrappers and cross-prefix. +func_cc_basename () +{ + for cc_temp in $*""; do + case $cc_temp in + compile | *[\\/]compile | ccache | *[\\/]ccache ) ;; + distcc | *[\\/]distcc | purify | *[\\/]purify ) ;; + \-*) ;; + *) break;; + esac + done + func_cc_basename_result=`$ECHO "$cc_temp" | $SED "s%.*/%%; s%^$host_alias-%%"` +} + # Check whether --enable-libtool-lock was given. if test "${enable_libtool_lock+set}" = set; then : enableval=$enable_libtool_lock; fi -test "x$enable_libtool_lock" != xno && enable_libtool_lock=yes +test no = "$enable_libtool_lock" || enable_libtool_lock=yes # Some flags need to be propagated to the compiler or linker for good # libtool support. case $host in ia64-*-hpux*) - # Find out which ABI we are using. + # Find out what ABI is being produced by ac_compile, and set mode + # options accordingly. echo 'int i;' > conftest.$ac_ext if { { eval echo "\"\$as_me\":${as_lineno-$LINENO}: \"$ac_compile\""; } >&5 (eval $ac_compile) 2>&5 @@ -6932,24 +7107,25 @@ ia64-*-hpux*) test $ac_status = 0; }; then case `/usr/bin/file conftest.$ac_objext` in *ELF-32*) - HPUX_IA64_MODE="32" + HPUX_IA64_MODE=32 ;; *ELF-64*) - HPUX_IA64_MODE="64" + HPUX_IA64_MODE=64 ;; esac fi rm -rf conftest* ;; *-*-irix6*) - # Find out which ABI we are using. + # Find out what ABI is being produced by ac_compile, and set linker + # options accordingly. echo '#line '$LINENO' "configure"' > conftest.$ac_ext if { { eval echo "\"\$as_me\":${as_lineno-$LINENO}: \"$ac_compile\""; } >&5 (eval $ac_compile) 2>&5 ac_status=$? $as_echo "$as_me:${as_lineno-$LINENO}: \$? = $ac_status" >&5 test $ac_status = 0; }; then - if test "$lt_cv_prog_gnu_ld" = yes; then + if test yes = "$lt_cv_prog_gnu_ld"; then case `/usr/bin/file conftest.$ac_objext` in *32-bit*) LD="${LD-ld} -melf32bsmip" @@ -6978,9 +7154,50 @@ ia64-*-hpux*) rm -rf conftest* ;; -x86_64-*kfreebsd*-gnu|x86_64-*linux*|ppc*-*linux*|powerpc*-*linux*| \ +mips64*-*linux*) + # Find out what ABI is being produced by ac_compile, and set linker + # options accordingly. + echo '#line '$LINENO' "configure"' > conftest.$ac_ext + if { { eval echo "\"\$as_me\":${as_lineno-$LINENO}: \"$ac_compile\""; } >&5 + (eval $ac_compile) 2>&5 + ac_status=$? + $as_echo "$as_me:${as_lineno-$LINENO}: \$? = $ac_status" >&5 + test $ac_status = 0; }; then + emul=elf + case `/usr/bin/file conftest.$ac_objext` in + *32-bit*) + emul="${emul}32" + ;; + *64-bit*) + emul="${emul}64" + ;; + esac + case `/usr/bin/file conftest.$ac_objext` in + *MSB*) + emul="${emul}btsmip" + ;; + *LSB*) + emul="${emul}ltsmip" + ;; + esac + case `/usr/bin/file conftest.$ac_objext` in + *N32*) + emul="${emul}n32" + ;; + esac + LD="${LD-ld} -m $emul" + fi + rm -rf conftest* + ;; + +x86_64-*kfreebsd*-gnu|x86_64-*linux*|powerpc*-*linux*| \ s390*-*linux*|s390*-*tpf*|sparc*-*linux*) - # Find out which ABI we are using. + # Find out what ABI is being produced by ac_compile, and set linker + # options accordingly. Note that the listed cases only cover the + # situations where additional linker options are needed (such as when + # doing 32-bit compilation for a host where ld defaults to 64-bit, or + # vice versa); the common cases where no linker options are needed do + # not appear in the list. echo 'int i;' > conftest.$ac_ext if { { eval echo "\"\$as_me\":${as_lineno-$LINENO}: \"$ac_compile\""; } >&5 (eval $ac_compile) 2>&5 @@ -6994,9 +7211,19 @@ s390*-*linux*|s390*-*tpf*|sparc*-*linux*) LD="${LD-ld} -m elf_i386_fbsd" ;; x86_64-*linux*) - LD="${LD-ld} -m elf_i386" + case `/usr/bin/file conftest.o` in + *x86-64*) + LD="${LD-ld} -m elf32_x86_64" + ;; + *) + LD="${LD-ld} -m elf_i386" + ;; + esac ;; - ppc64-*linux*|powerpc64-*linux*) + powerpc64le-*linux*) + LD="${LD-ld} -m elf32lppclinux" + ;; + powerpc64-*linux*) LD="${LD-ld} -m elf32ppclinux" ;; s390x-*linux*) @@ -7015,7 +7242,10 @@ s390*-*linux*|s390*-*tpf*|sparc*-*linux*) x86_64-*linux*) LD="${LD-ld} -m elf_x86_64" ;; - ppc*-*linux*|powerpc*-*linux*) + powerpcle-*linux*) + LD="${LD-ld} -m elf64lppc" + ;; + powerpc-*linux*) LD="${LD-ld} -m elf64ppc" ;; s390*-*linux*|s390*-*tpf*) @@ -7033,7 +7263,7 @@ s390*-*linux*|s390*-*tpf*|sparc*-*linux*) *-*-sco3.2v5*) # On SCO OpenServer 5, we need -belf to get full-featured binaries. - SAVE_CFLAGS="$CFLAGS" + SAVE_CFLAGS=$CFLAGS CFLAGS="$CFLAGS -belf" { $as_echo "$as_me:${as_lineno-$LINENO}: checking whether the C compiler needs -belf" >&5 $as_echo_n "checking whether the C compiler needs -belf... " >&6; } @@ -7073,13 +7303,14 @@ ac_compiler_gnu=$ac_cv_c_compiler_gnu fi { $as_echo "$as_me:${as_lineno-$LINENO}: result: $lt_cv_cc_needs_belf" >&5 $as_echo "$lt_cv_cc_needs_belf" >&6; } - if test x"$lt_cv_cc_needs_belf" != x"yes"; then + if test yes != "$lt_cv_cc_needs_belf"; then # this is probably gcc 2.8.0, egcs 1.0 or newer; no need for -belf - CFLAGS="$SAVE_CFLAGS" + CFLAGS=$SAVE_CFLAGS fi ;; *-*solaris*) - # Find out which ABI we are using. + # Find out what ABI is being produced by ac_compile, and set linker + # options accordingly. echo 'int i;' > conftest.$ac_ext if { { eval echo "\"\$as_me\":${as_lineno-$LINENO}: \"$ac_compile\""; } >&5 (eval $ac_compile) 2>&5 @@ -7091,7 +7322,7 @@ $as_echo "$lt_cv_cc_needs_belf" >&6; } case $lt_cv_prog_gnu_ld in yes*) case $host in - i?86-*-solaris*) + i?86-*-solaris*|x86_64-*-solaris*) LD="${LD-ld} -m elf_x86_64" ;; sparc*-*-solaris*) @@ -7100,7 +7331,7 @@ $as_echo "$lt_cv_cc_needs_belf" >&6; } esac # GNU ld 2.21 introduced _sol2 emulations. Use them if available. if ${LD-ld} -V | grep _sol2 >/dev/null 2>&1; then - LD="${LD-ld}_sol2" + LD=${LD-ld}_sol2 fi ;; *) @@ -7116,7 +7347,7 @@ $as_echo "$lt_cv_cc_needs_belf" >&6; } ;; esac -need_locks="$enable_libtool_lock" +need_locks=$enable_libtool_lock if test -n "$ac_tool_prefix"; then # Extract the first word of "${ac_tool_prefix}mt", so it can be a program name with args. @@ -7227,7 +7458,7 @@ else fi { $as_echo "$as_me:${as_lineno-$LINENO}: result: $lt_cv_path_mainfest_tool" >&5 $as_echo "$lt_cv_path_mainfest_tool" >&6; } -if test "x$lt_cv_path_mainfest_tool" != xyes; then +if test yes != "$lt_cv_path_mainfest_tool"; then MANIFEST_TOOL=: fi @@ -7730,7 +7961,7 @@ if ${lt_cv_apple_cc_single_mod+:} false; then : $as_echo_n "(cached) " >&6 else lt_cv_apple_cc_single_mod=no - if test -z "${LT_MULTI_MODULE}"; then + if test -z "$LT_MULTI_MODULE"; then # By default we will add the -single_module flag. You can override # by either setting the environment variable LT_MULTI_MODULE # non-empty at configure time, or by adding -multi_module to the @@ -7748,7 +7979,7 @@ else cat conftest.err >&5 # Otherwise, if the output was created with a 0 exit code from # the compiler, it worked. - elif test -f libconftest.dylib && test $_lt_result -eq 0; then + elif test -f libconftest.dylib && test 0 = "$_lt_result"; then lt_cv_apple_cc_single_mod=yes else cat conftest.err >&5 @@ -7787,7 +8018,7 @@ else fi rm -f core conftest.err conftest.$ac_objext \ conftest$ac_exeext conftest.$ac_ext - LDFLAGS="$save_LDFLAGS" + LDFLAGS=$save_LDFLAGS fi { $as_echo "$as_me:${as_lineno-$LINENO}: result: $lt_cv_ld_exported_symbols_list" >&5 @@ -7816,7 +8047,7 @@ _LT_EOF _lt_result=$? if test -s conftest.err && $GREP force_load conftest.err; then cat conftest.err >&5 - elif test -f conftest && test $_lt_result -eq 0 && $GREP forced_load conftest >/dev/null 2>&1 ; then + elif test -f conftest && test 0 = "$_lt_result" && $GREP forced_load conftest >/dev/null 2>&1; then lt_cv_ld_force_load=yes else cat conftest.err >&5 @@ -7829,32 +8060,32 @@ fi $as_echo "$lt_cv_ld_force_load" >&6; } case $host_os in rhapsody* | darwin1.[012]) - _lt_dar_allow_undefined='${wl}-undefined ${wl}suppress' ;; + _lt_dar_allow_undefined='$wl-undefined ${wl}suppress' ;; darwin1.*) - _lt_dar_allow_undefined='${wl}-flat_namespace ${wl}-undefined ${wl}suppress' ;; + _lt_dar_allow_undefined='$wl-flat_namespace $wl-undefined ${wl}suppress' ;; darwin*) # darwin 5.x on # if running on 10.5 or later, the deployment target defaults # to the OS version, if on x86, and 10.4, the deployment # target defaults to 10.4. Don't you love it? case ${MACOSX_DEPLOYMENT_TARGET-10.0},$host in 10.0,*86*-darwin8*|10.0,*-darwin[91]*) - _lt_dar_allow_undefined='${wl}-undefined ${wl}dynamic_lookup' ;; - 10.[012]*) - _lt_dar_allow_undefined='${wl}-flat_namespace ${wl}-undefined ${wl}suppress' ;; + _lt_dar_allow_undefined='$wl-undefined ${wl}dynamic_lookup' ;; + 10.[012][,.]*) + _lt_dar_allow_undefined='$wl-flat_namespace $wl-undefined ${wl}suppress' ;; 10.*) - _lt_dar_allow_undefined='${wl}-undefined ${wl}dynamic_lookup' ;; + _lt_dar_allow_undefined='$wl-undefined ${wl}dynamic_lookup' ;; esac ;; esac - if test "$lt_cv_apple_cc_single_mod" = "yes"; then + if test yes = "$lt_cv_apple_cc_single_mod"; then _lt_dar_single_mod='$single_module' fi - if test "$lt_cv_ld_exported_symbols_list" = "yes"; then - _lt_dar_export_syms=' ${wl}-exported_symbols_list,$output_objdir/${libname}-symbols.expsym' + if test yes = "$lt_cv_ld_exported_symbols_list"; then + _lt_dar_export_syms=' $wl-exported_symbols_list,$output_objdir/$libname-symbols.expsym' else - _lt_dar_export_syms='~$NMEDIT -s $output_objdir/${libname}-symbols.expsym ${lib}' + _lt_dar_export_syms='~$NMEDIT -s $output_objdir/$libname-symbols.expsym $lib' fi - if test "$DSYMUTIL" != ":" && test "$lt_cv_ld_force_load" = "no"; then + if test : != "$DSYMUTIL" && test no = "$lt_cv_ld_force_load"; then _lt_dsymutil='~$DSYMUTIL $lib || :' else _lt_dsymutil= @@ -7862,6 +8093,41 @@ $as_echo "$lt_cv_ld_force_load" >&6; } ;; esac +# func_munge_path_list VARIABLE PATH +# ----------------------------------- +# VARIABLE is name of variable containing _space_ separated list of +# directories to be munged by the contents of PATH, which is string +# having a format: +# "DIR[:DIR]:" +# string "DIR[ DIR]" will be prepended to VARIABLE +# ":DIR[:DIR]" +# string "DIR[ DIR]" will be appended to VARIABLE +# "DIRP[:DIRP]::[DIRA:]DIRA" +# string "DIRP[ DIRP]" will be prepended to VARIABLE and string +# "DIRA[ DIRA]" will be appended to VARIABLE +# "DIR[:DIR]" +# VARIABLE will be replaced by "DIR[ DIR]" +func_munge_path_list () +{ + case x$2 in + x) + ;; + *:) + eval $1=\"`$ECHO $2 | $SED 's/:/ /g'` \$$1\" + ;; + x:*) + eval $1=\"\$$1 `$ECHO $2 | $SED 's/:/ /g'`\" + ;; + *::*) + eval $1=\"\$$1\ `$ECHO $2 | $SED -e 's/.*:://' -e 's/:/ /g'`\" + eval $1=\"`$ECHO $2 | $SED -e 's/::.*//' -e 's/:/ /g'`\ \$$1\" + ;; + *) + eval $1=\"`$ECHO $2 | $SED 's/:/ /g'`\" + ;; + esac +} + { $as_echo "$as_me:${as_lineno-$LINENO}: checking for ANSI C header files" >&5 $as_echo_n "checking for ANSI C header files... " >&6; } @@ -8010,9 +8276,9 @@ done func_stripname_cnf () { - case ${2} in - .*) func_stripname_result=`$ECHO "${3}" | $SED "s%^${1}%%; s%\\\\${2}\$%%"`;; - *) func_stripname_result=`$ECHO "${3}" | $SED "s%^${1}%%; s%${2}\$%%"`;; + case $2 in + .*) func_stripname_result=`$ECHO "$3" | $SED "s%^$1%%; s%\\\\$2\$%%"`;; + *) func_stripname_result=`$ECHO "$3" | $SED "s%^$1%%; s%$2\$%%"`;; esac } # func_stripname_cnf @@ -8039,14 +8305,14 @@ if test "${enable_shared+set}" = set; then : *) enable_shared=no # Look at the argument we got. We use all the common list separators. - lt_save_ifs="$IFS"; IFS="${IFS}$PATH_SEPARATOR," + lt_save_ifs=$IFS; IFS=$IFS$PATH_SEPARATOR, for pkg in $enableval; do - IFS="$lt_save_ifs" + IFS=$lt_save_ifs if test "X$pkg" = "X$p"; then enable_shared=yes fi done - IFS="$lt_save_ifs" + IFS=$lt_save_ifs ;; esac else @@ -8070,14 +8336,14 @@ if test "${enable_static+set}" = set; then : *) enable_static=no # Look at the argument we got. We use all the common list separators. - lt_save_ifs="$IFS"; IFS="${IFS}$PATH_SEPARATOR," + lt_save_ifs=$IFS; IFS=$IFS$PATH_SEPARATOR, for pkg in $enableval; do - IFS="$lt_save_ifs" + IFS=$lt_save_ifs if test "X$pkg" = "X$p"; then enable_static=yes fi done - IFS="$lt_save_ifs" + IFS=$lt_save_ifs ;; esac else @@ -8101,14 +8367,14 @@ if test "${with_pic+set}" = set; then : *) pic_mode=default # Look at the argument we got. We use all the common list separators. - lt_save_ifs="$IFS"; IFS="${IFS}$PATH_SEPARATOR," + lt_save_ifs=$IFS; IFS=$IFS$PATH_SEPARATOR, for lt_pkg in $withval; do - IFS="$lt_save_ifs" + IFS=$lt_save_ifs if test "X$lt_pkg" = "X$lt_p"; then pic_mode=yes fi done - IFS="$lt_save_ifs" + IFS=$lt_save_ifs ;; esac else @@ -8116,8 +8382,6 @@ else fi -test -z "$pic_mode" && pic_mode=default - @@ -8133,14 +8397,14 @@ if test "${enable_fast_install+set}" = set; then : *) enable_fast_install=no # Look at the argument we got. We use all the common list separators. - lt_save_ifs="$IFS"; IFS="${IFS}$PATH_SEPARATOR," + lt_save_ifs=$IFS; IFS=$IFS$PATH_SEPARATOR, for pkg in $enableval; do - IFS="$lt_save_ifs" + IFS=$lt_save_ifs if test "X$pkg" = "X$p"; then enable_fast_install=yes fi done - IFS="$lt_save_ifs" + IFS=$lt_save_ifs ;; esac else @@ -8154,11 +8418,63 @@ fi + shared_archive_member_spec= +case $host,$enable_shared in +power*-*-aix[5-9]*,yes) + { $as_echo "$as_me:${as_lineno-$LINENO}: checking which variant of shared library versioning to provide" >&5 +$as_echo_n "checking which variant of shared library versioning to provide... " >&6; } + +# Check whether --with-aix-soname was given. +if test "${with_aix_soname+set}" = set; then : + withval=$with_aix_soname; case $withval in + aix|svr4|both) + ;; + *) + as_fn_error $? "Unknown argument to --with-aix-soname" "$LINENO" 5 + ;; + esac + lt_cv_with_aix_soname=$with_aix_soname +else + if ${lt_cv_with_aix_soname+:} false; then : + $as_echo_n "(cached) " >&6 +else + lt_cv_with_aix_soname=aix +fi + + with_aix_soname=$lt_cv_with_aix_soname +fi + + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $with_aix_soname" >&5 +$as_echo "$with_aix_soname" >&6; } + if test aix != "$with_aix_soname"; then + # For the AIX way of multilib, we name the shared archive member + # based on the bitwidth used, traditionally 'shr.o' or 'shr_64.o', + # and 'shr.imp' or 'shr_64.imp', respectively, for the Import File. + # Even when GNU compilers ignore OBJECT_MODE but need '-maix64' flag, + # the AIX toolchain works better with OBJECT_MODE set (default 32). + if test 64 = "${OBJECT_MODE-32}"; then + shared_archive_member_spec=shr_64 + else + shared_archive_member_spec=shr + fi + fi + ;; +*) + with_aix_soname=aix + ;; +esac + + + + + + + # This can be used to rebuild libtool when needed -LIBTOOL_DEPS="$ltmain" +LIBTOOL_DEPS=$ltmain # Always use our own libtool. LIBTOOL='$(SHELL) $(top_builddir)/libtool' @@ -8207,7 +8523,7 @@ test -z "$LN_S" && LN_S="ln -s" -if test -n "${ZSH_VERSION+set}" ; then +if test -n "${ZSH_VERSION+set}"; then setopt NO_GLOB_SUBST fi @@ -8246,7 +8562,7 @@ aix3*) # AIX sometimes has problems with the GCC collect2 program. For some # reason, if we set the COLLECT_NAMES environment variable, the problems # vanish in a puff of smoke. - if test "X${COLLECT_NAMES+set}" != Xset; then + if test set != "${COLLECT_NAMES+set}"; then COLLECT_NAMES= export COLLECT_NAMES fi @@ -8257,14 +8573,14 @@ esac ofile=libtool can_build_shared=yes -# All known linkers require a `.a' archive for static linking (except MSVC, +# All known linkers require a '.a' archive for static linking (except MSVC, # which needs '.lib'). libext=a -with_gnu_ld="$lt_cv_prog_gnu_ld" +with_gnu_ld=$lt_cv_prog_gnu_ld -old_CC="$CC" -old_CFLAGS="$CFLAGS" +old_CC=$CC +old_CFLAGS=$CFLAGS # Set sane defaults for various variables test -z "$CC" && CC=cc @@ -8273,15 +8589,8 @@ test -z "$LTCFLAGS" && LTCFLAGS=$CFLAGS test -z "$LD" && LD=ld test -z "$ac_objext" && ac_objext=o -for cc_temp in $compiler""; do - case $cc_temp in - compile | *[\\/]compile | ccache | *[\\/]ccache ) ;; - distcc | *[\\/]distcc | purify | *[\\/]purify ) ;; - \-*) ;; - *) break;; - esac -done -cc_basename=`$ECHO "$cc_temp" | $SED "s%.*/%%; s%^$host_alias-%%"` +func_cc_basename $compiler +cc_basename=$func_cc_basename_result # Only perform the check for file, if the check method requires it @@ -8296,22 +8605,22 @@ if ${lt_cv_path_MAGIC_CMD+:} false; then : else case $MAGIC_CMD in [\\/*] | ?:[\\/]*) - lt_cv_path_MAGIC_CMD="$MAGIC_CMD" # Let the user override the test with a path. + lt_cv_path_MAGIC_CMD=$MAGIC_CMD # Let the user override the test with a path. ;; *) - lt_save_MAGIC_CMD="$MAGIC_CMD" - lt_save_ifs="$IFS"; IFS=$PATH_SEPARATOR + lt_save_MAGIC_CMD=$MAGIC_CMD + lt_save_ifs=$IFS; IFS=$PATH_SEPARATOR ac_dummy="/usr/bin$PATH_SEPARATOR$PATH" for ac_dir in $ac_dummy; do - IFS="$lt_save_ifs" + IFS=$lt_save_ifs test -z "$ac_dir" && ac_dir=. - if test -f $ac_dir/${ac_tool_prefix}file; then - lt_cv_path_MAGIC_CMD="$ac_dir/${ac_tool_prefix}file" + if test -f "$ac_dir/${ac_tool_prefix}file"; then + lt_cv_path_MAGIC_CMD=$ac_dir/"${ac_tool_prefix}file" if test -n "$file_magic_test_file"; then case $deplibs_check_method in "file_magic "*) file_magic_regex=`expr "$deplibs_check_method" : "file_magic \(.*\)"` - MAGIC_CMD="$lt_cv_path_MAGIC_CMD" + MAGIC_CMD=$lt_cv_path_MAGIC_CMD if eval $file_magic_cmd \$file_magic_test_file 2> /dev/null | $EGREP "$file_magic_regex" > /dev/null; then : @@ -8334,13 +8643,13 @@ _LT_EOF break fi done - IFS="$lt_save_ifs" - MAGIC_CMD="$lt_save_MAGIC_CMD" + IFS=$lt_save_ifs + MAGIC_CMD=$lt_save_MAGIC_CMD ;; esac fi -MAGIC_CMD="$lt_cv_path_MAGIC_CMD" +MAGIC_CMD=$lt_cv_path_MAGIC_CMD if test -n "$MAGIC_CMD"; then { $as_echo "$as_me:${as_lineno-$LINENO}: result: $MAGIC_CMD" >&5 $as_echo "$MAGIC_CMD" >&6; } @@ -8362,22 +8671,22 @@ if ${lt_cv_path_MAGIC_CMD+:} false; then : else case $MAGIC_CMD in [\\/*] | ?:[\\/]*) - lt_cv_path_MAGIC_CMD="$MAGIC_CMD" # Let the user override the test with a path. + lt_cv_path_MAGIC_CMD=$MAGIC_CMD # Let the user override the test with a path. ;; *) - lt_save_MAGIC_CMD="$MAGIC_CMD" - lt_save_ifs="$IFS"; IFS=$PATH_SEPARATOR + lt_save_MAGIC_CMD=$MAGIC_CMD + lt_save_ifs=$IFS; IFS=$PATH_SEPARATOR ac_dummy="/usr/bin$PATH_SEPARATOR$PATH" for ac_dir in $ac_dummy; do - IFS="$lt_save_ifs" + IFS=$lt_save_ifs test -z "$ac_dir" && ac_dir=. - if test -f $ac_dir/file; then - lt_cv_path_MAGIC_CMD="$ac_dir/file" + if test -f "$ac_dir/file"; then + lt_cv_path_MAGIC_CMD=$ac_dir/"file" if test -n "$file_magic_test_file"; then case $deplibs_check_method in "file_magic "*) file_magic_regex=`expr "$deplibs_check_method" : "file_magic \(.*\)"` - MAGIC_CMD="$lt_cv_path_MAGIC_CMD" + MAGIC_CMD=$lt_cv_path_MAGIC_CMD if eval $file_magic_cmd \$file_magic_test_file 2> /dev/null | $EGREP "$file_magic_regex" > /dev/null; then : @@ -8400,13 +8709,13 @@ _LT_EOF break fi done - IFS="$lt_save_ifs" - MAGIC_CMD="$lt_save_MAGIC_CMD" + IFS=$lt_save_ifs + MAGIC_CMD=$lt_save_MAGIC_CMD ;; esac fi -MAGIC_CMD="$lt_cv_path_MAGIC_CMD" +MAGIC_CMD=$lt_cv_path_MAGIC_CMD if test -n "$MAGIC_CMD"; then { $as_echo "$as_me:${as_lineno-$LINENO}: result: $MAGIC_CMD" >&5 $as_echo "$MAGIC_CMD" >&6; } @@ -8427,7 +8736,7 @@ esac # Use C for the default configuration in the libtool script -lt_save_CC="$CC" +lt_save_CC=$CC ac_ext=c ac_cpp='$CPP $CPPFLAGS' ac_compile='$CC -c $CFLAGS $CPPFLAGS conftest.$ac_ext >&5' @@ -8489,7 +8798,7 @@ if test -n "$compiler"; then lt_prog_compiler_no_builtin_flag= -if test "$GCC" = yes; then +if test yes = "$GCC"; then case $cc_basename in nvcc*) lt_prog_compiler_no_builtin_flag=' -Xcompiler -fno-builtin' ;; @@ -8505,7 +8814,7 @@ else lt_cv_prog_compiler_rtti_exceptions=no ac_outfile=conftest.$ac_objext echo "$lt_simple_compile_test_code" > conftest.$ac_ext - lt_compiler_flag="-fno-rtti -fno-exceptions" + lt_compiler_flag="-fno-rtti -fno-exceptions" ## exclude from sc_useless_quotes_in_assignment # Insert the option either (1) after the last *FLAGS variable, or # (2) before a word containing "conftest.", or (3) at the end. # Note that $ac_compile itself does not contain backslashes and begins @@ -8535,7 +8844,7 @@ fi { $as_echo "$as_me:${as_lineno-$LINENO}: result: $lt_cv_prog_compiler_rtti_exceptions" >&5 $as_echo "$lt_cv_prog_compiler_rtti_exceptions" >&6; } -if test x"$lt_cv_prog_compiler_rtti_exceptions" = xyes; then +if test yes = "$lt_cv_prog_compiler_rtti_exceptions"; then lt_prog_compiler_no_builtin_flag="$lt_prog_compiler_no_builtin_flag -fno-rtti -fno-exceptions" else : @@ -8553,17 +8862,18 @@ lt_prog_compiler_pic= lt_prog_compiler_static= - if test "$GCC" = yes; then + if test yes = "$GCC"; then lt_prog_compiler_wl='-Wl,' lt_prog_compiler_static='-static' case $host_os in aix*) # All AIX code is PIC. - if test "$host_cpu" = ia64; then + if test ia64 = "$host_cpu"; then # AIX 5 now supports IA64 processor lt_prog_compiler_static='-Bstatic' fi + lt_prog_compiler_pic='-fPIC' ;; amigaos*) @@ -8574,8 +8884,8 @@ lt_prog_compiler_static= ;; m68k) # FIXME: we need at least 68020 code to build shared libraries, but - # adding the `-m68020' flag to GCC prevents building anything better, - # like `-m68040'. + # adding the '-m68020' flag to GCC prevents building anything better, + # like '-m68040'. lt_prog_compiler_pic='-m68020 -resident32 -malways-restore-a4' ;; esac @@ -8591,6 +8901,11 @@ lt_prog_compiler_static= # Although the cygwin gcc ignores -fPIC, still need this for old-style # (--disable-auto-import) libraries lt_prog_compiler_pic='-DDLL_EXPORT' + case $host_os in + os2*) + lt_prog_compiler_static='$wl-static' + ;; + esac ;; darwin* | rhapsody*) @@ -8661,7 +8976,7 @@ lt_prog_compiler_static= case $host_os in aix*) lt_prog_compiler_wl='-Wl,' - if test "$host_cpu" = ia64; then + if test ia64 = "$host_cpu"; then # AIX 5 now supports IA64 processor lt_prog_compiler_static='-Bstatic' else @@ -8669,10 +8984,29 @@ lt_prog_compiler_static= fi ;; + darwin* | rhapsody*) + # PIC is the default on this platform + # Common symbols not allowed in MH_DYLIB files + lt_prog_compiler_pic='-fno-common' + case $cc_basename in + nagfor*) + # NAG Fortran compiler + lt_prog_compiler_wl='-Wl,-Wl,,' + lt_prog_compiler_pic='-PIC' + lt_prog_compiler_static='-Bstatic' + ;; + esac + ;; + mingw* | cygwin* | pw32* | os2* | cegcc*) # This hack is so that the source file can tell whether it is being # built for inclusion in a dll (and should export symbols for example). lt_prog_compiler_pic='-DDLL_EXPORT' + case $host_os in + os2*) + lt_prog_compiler_static='$wl-static' + ;; + esac ;; hpux9* | hpux10* | hpux11*) @@ -8688,7 +9022,7 @@ lt_prog_compiler_static= ;; esac # Is there a better lt_prog_compiler_static that works with the bundled CC? - lt_prog_compiler_static='${wl}-a ${wl}archive' + lt_prog_compiler_static='$wl-a ${wl}archive' ;; irix5* | irix6* | nonstopux*) @@ -8697,9 +9031,9 @@ lt_prog_compiler_static= lt_prog_compiler_static='-non_shared' ;; - linux* | k*bsd*-gnu | kopensolaris*-gnu) + linux* | k*bsd*-gnu | kopensolaris*-gnu | gnu*) case $cc_basename in - # old Intel for x86_64 which still supported -KPIC. + # old Intel for x86_64, which still supported -KPIC. ecc*) lt_prog_compiler_wl='-Wl,' lt_prog_compiler_pic='-KPIC' @@ -8724,6 +9058,12 @@ lt_prog_compiler_static= lt_prog_compiler_pic='-PIC' lt_prog_compiler_static='-Bstatic' ;; + tcc*) + # Fabrice Bellard et al's Tiny C Compiler + lt_prog_compiler_wl='-Wl,' + lt_prog_compiler_pic='-fPIC' + lt_prog_compiler_static='-static' + ;; pgcc* | pgf77* | pgf90* | pgf95* | pgfortran*) # Portland Group compilers (*not* the Pentium gcc compiler, # which looks to be a dead project) @@ -8821,7 +9161,7 @@ lt_prog_compiler_static= ;; sysv4*MP*) - if test -d /usr/nec ;then + if test -d /usr/nec; then lt_prog_compiler_pic='-Kconform_pic' lt_prog_compiler_static='-Bstatic' fi @@ -8850,7 +9190,7 @@ lt_prog_compiler_static= fi case $host_os in - # For platforms which do not support PIC, -DPIC is meaningless: + # For platforms that do not support PIC, -DPIC is meaningless: *djgpp*) lt_prog_compiler_pic= ;; @@ -8882,7 +9222,7 @@ else lt_cv_prog_compiler_pic_works=no ac_outfile=conftest.$ac_objext echo "$lt_simple_compile_test_code" > conftest.$ac_ext - lt_compiler_flag="$lt_prog_compiler_pic -DPIC" + lt_compiler_flag="$lt_prog_compiler_pic -DPIC" ## exclude from sc_useless_quotes_in_assignment # Insert the option either (1) after the last *FLAGS variable, or # (2) before a word containing "conftest.", or (3) at the end. # Note that $ac_compile itself does not contain backslashes and begins @@ -8912,7 +9252,7 @@ fi { $as_echo "$as_me:${as_lineno-$LINENO}: result: $lt_cv_prog_compiler_pic_works" >&5 $as_echo "$lt_cv_prog_compiler_pic_works" >&6; } -if test x"$lt_cv_prog_compiler_pic_works" = xyes; then +if test yes = "$lt_cv_prog_compiler_pic_works"; then case $lt_prog_compiler_pic in "" | " "*) ;; *) lt_prog_compiler_pic=" $lt_prog_compiler_pic" ;; @@ -8944,7 +9284,7 @@ if ${lt_cv_prog_compiler_static_works+:} false; then : $as_echo_n "(cached) " >&6 else lt_cv_prog_compiler_static_works=no - save_LDFLAGS="$LDFLAGS" + save_LDFLAGS=$LDFLAGS LDFLAGS="$LDFLAGS $lt_tmp_static_flag" echo "$lt_simple_link_test_code" > conftest.$ac_ext if (eval $ac_link 2>conftest.err) && test -s conftest$ac_exeext; then @@ -8963,13 +9303,13 @@ else fi fi $RM -r conftest* - LDFLAGS="$save_LDFLAGS" + LDFLAGS=$save_LDFLAGS fi { $as_echo "$as_me:${as_lineno-$LINENO}: result: $lt_cv_prog_compiler_static_works" >&5 $as_echo "$lt_cv_prog_compiler_static_works" >&6; } -if test x"$lt_cv_prog_compiler_static_works" = xyes; then +if test yes = "$lt_cv_prog_compiler_static_works"; then : else lt_prog_compiler_static= @@ -9089,8 +9429,8 @@ $as_echo "$lt_cv_prog_compiler_c_o" >&6; } -hard_links="nottested" -if test "$lt_cv_prog_compiler_c_o" = no && test "$need_locks" != no; then +hard_links=nottested +if test no = "$lt_cv_prog_compiler_c_o" && test no != "$need_locks"; then # do not overwrite the value of need_locks provided by the user { $as_echo "$as_me:${as_lineno-$LINENO}: checking if we can lock with hard links" >&5 $as_echo_n "checking if we can lock with hard links... " >&6; } @@ -9102,9 +9442,9 @@ $as_echo_n "checking if we can lock with hard links... " >&6; } ln conftest.a conftest.b 2>/dev/null && hard_links=no { $as_echo "$as_me:${as_lineno-$LINENO}: result: $hard_links" >&5 $as_echo "$hard_links" >&6; } - if test "$hard_links" = no; then - { $as_echo "$as_me:${as_lineno-$LINENO}: WARNING: \`$CC' does not support \`-c -o', so \`make -j' may be unsafe" >&5 -$as_echo "$as_me: WARNING: \`$CC' does not support \`-c -o', so \`make -j' may be unsafe" >&2;} + if test no = "$hard_links"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: WARNING: '$CC' does not support '-c -o', so 'make -j' may be unsafe" >&5 +$as_echo "$as_me: WARNING: '$CC' does not support '-c -o', so 'make -j' may be unsafe" >&2;} need_locks=warn fi else @@ -9147,9 +9487,9 @@ $as_echo_n "checking whether the $compiler linker ($LD) supports shared librarie # included in the symbol list include_expsyms= # exclude_expsyms can be an extended regexp of symbols to exclude - # it will be wrapped by ` (' and `)$', so one must not match beginning or - # end of line. Example: `a|bc|.*d.*' will exclude the symbols `a' and `bc', - # as well as any symbol that contains `d'. + # it will be wrapped by ' (' and ')$', so one must not match beginning or + # end of line. Example: 'a|bc|.*d.*' will exclude the symbols 'a' and 'bc', + # as well as any symbol that contains 'd'. exclude_expsyms='_GLOBAL_OFFSET_TABLE_|_GLOBAL__F[ID]_.*' # Although _GLOBAL_OFFSET_TABLE_ is a valid symbol C name, most a.out # platforms (ab)use it in PIC code, but their linkers get confused if @@ -9164,7 +9504,7 @@ $as_echo_n "checking whether the $compiler linker ($LD) supports shared librarie # FIXME: the MSVC++ port hasn't been tested in a loooong time # When not using gcc, we currently assume that we are using # Microsoft Visual C++. - if test "$GCC" != yes; then + if test yes != "$GCC"; then with_gnu_ld=no fi ;; @@ -9172,7 +9512,7 @@ $as_echo_n "checking whether the $compiler linker ($LD) supports shared librarie # we just hope/assume this is gcc and not c89 (= MSVC++) with_gnu_ld=yes ;; - openbsd*) + openbsd* | bitrig*) with_gnu_ld=no ;; esac @@ -9182,7 +9522,7 @@ $as_echo_n "checking whether the $compiler linker ($LD) supports shared librarie # On some targets, GNU ld is compatible enough with the native linker # that we're better off using the native interface for both. lt_use_gnu_ld_interface=no - if test "$with_gnu_ld" = yes; then + if test yes = "$with_gnu_ld"; then case $host_os in aix*) # The AIX port of GNU ld has always aspired to compatibility @@ -9204,24 +9544,24 @@ $as_echo_n "checking whether the $compiler linker ($LD) supports shared librarie esac fi - if test "$lt_use_gnu_ld_interface" = yes; then + if test yes = "$lt_use_gnu_ld_interface"; then # If archive_cmds runs LD, not CC, wlarc should be empty - wlarc='${wl}' + wlarc='$wl' # Set some defaults for GNU ld with shared library support. These # are reset later if shared libraries are not supported. Putting them # here allows them to be overridden if necessary. runpath_var=LD_RUN_PATH - hardcode_libdir_flag_spec='${wl}-rpath ${wl}$libdir' - export_dynamic_flag_spec='${wl}--export-dynamic' + hardcode_libdir_flag_spec='$wl-rpath $wl$libdir' + export_dynamic_flag_spec='$wl--export-dynamic' # ancient GNU ld didn't support --whole-archive et. al. if $LD --help 2>&1 | $GREP 'no-whole-archive' > /dev/null; then - whole_archive_flag_spec="$wlarc"'--whole-archive$convenience '"$wlarc"'--no-whole-archive' + whole_archive_flag_spec=$wlarc'--whole-archive$convenience '$wlarc'--no-whole-archive' else whole_archive_flag_spec= fi supports_anon_versioning=no - case `$LD -v 2>&1` in + case `$LD -v | $SED -e 's/(^)\+)\s\+//' 2>&1` in *GNU\ gold*) supports_anon_versioning=yes ;; *\ [01].* | *\ 2.[0-9].* | *\ 2.10.*) ;; # catch versions < 2.11 *\ 2.11.93.0.2\ *) supports_anon_versioning=yes ;; # RH7.3 ... @@ -9234,7 +9574,7 @@ $as_echo_n "checking whether the $compiler linker ($LD) supports shared librarie case $host_os in aix[3-9]*) # On AIX/PPC, the GNU linker is very broken - if test "$host_cpu" != ia64; then + if test ia64 != "$host_cpu"; then ld_shlibs=no cat <<_LT_EOF 1>&2 @@ -9253,7 +9593,7 @@ _LT_EOF case $host_cpu in powerpc) # see comment about AmigaOS4 .so support - archive_cmds='$CC -shared $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname -o $lib' + archive_cmds='$CC -shared $libobjs $deplibs $compiler_flags $wl-soname $wl$soname -o $lib' archive_expsym_cmds='' ;; m68k) @@ -9269,7 +9609,7 @@ _LT_EOF allow_undefined_flag=unsupported # Joseph Beckenbach says some releases of gcc # support --undefined. This deserves some investigation. FIXME - archive_cmds='$CC -nostart $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname -o $lib' + archive_cmds='$CC -nostart $libobjs $deplibs $compiler_flags $wl-soname $wl$soname -o $lib' else ld_shlibs=no fi @@ -9279,7 +9619,7 @@ _LT_EOF # _LT_TAGVAR(hardcode_libdir_flag_spec, ) is actually meaningless, # as there is no search path for DLLs. hardcode_libdir_flag_spec='-L$libdir' - export_dynamic_flag_spec='${wl}--export-all-symbols' + export_dynamic_flag_spec='$wl--export-all-symbols' allow_undefined_flag=unsupported always_export_symbols=no enable_shared_with_static_runtimes=yes @@ -9287,61 +9627,89 @@ _LT_EOF exclude_expsyms='[_]+GLOBAL_OFFSET_TABLE_|[_]+GLOBAL__[FID]_.*|[_]+head_[A-Za-z0-9_]+_dll|[A-Za-z0-9_]+_dll_iname' if $LD --help 2>&1 | $GREP 'auto-import' > /dev/null; then - archive_cmds='$CC -shared $libobjs $deplibs $compiler_flags -o $output_objdir/$soname ${wl}--enable-auto-image-base -Xlinker --out-implib -Xlinker $lib' - # If the export-symbols file already is a .def file (1st line - # is EXPORTS), use it as is; otherwise, prepend... - archive_expsym_cmds='if test "x`$SED 1q $export_symbols`" = xEXPORTS; then - cp $export_symbols $output_objdir/$soname.def; - else - echo EXPORTS > $output_objdir/$soname.def; - cat $export_symbols >> $output_objdir/$soname.def; - fi~ - $CC -shared $output_objdir/$soname.def $libobjs $deplibs $compiler_flags -o $output_objdir/$soname ${wl}--enable-auto-image-base -Xlinker --out-implib -Xlinker $lib' + archive_cmds='$CC -shared $libobjs $deplibs $compiler_flags -o $output_objdir/$soname $wl--enable-auto-image-base -Xlinker --out-implib -Xlinker $lib' + # If the export-symbols file already is a .def file, use it as + # is; otherwise, prepend EXPORTS... + archive_expsym_cmds='if test DEF = "`$SED -n -e '\''s/^[ ]*//'\'' -e '\''/^\(;.*\)*$/d'\'' -e '\''s/^\(EXPORTS\|LIBRARY\)\([ ].*\)*$/DEF/p'\'' -e q $export_symbols`" ; then + cp $export_symbols $output_objdir/$soname.def; + else + echo EXPORTS > $output_objdir/$soname.def; + cat $export_symbols >> $output_objdir/$soname.def; + fi~ + $CC -shared $output_objdir/$soname.def $libobjs $deplibs $compiler_flags -o $output_objdir/$soname $wl--enable-auto-image-base -Xlinker --out-implib -Xlinker $lib' else ld_shlibs=no fi ;; haiku*) - archive_cmds='$CC -shared $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname -o $lib' + archive_cmds='$CC -shared $libobjs $deplibs $compiler_flags $wl-soname $wl$soname -o $lib' link_all_deplibs=yes ;; + os2*) + hardcode_libdir_flag_spec='-L$libdir' + hardcode_minus_L=yes + allow_undefined_flag=unsupported + shrext_cmds=.dll + archive_cmds='$ECHO "LIBRARY ${soname%$shared_ext} INITINSTANCE TERMINSTANCE" > $output_objdir/$libname.def~ + $ECHO "DESCRIPTION \"$libname\"" >> $output_objdir/$libname.def~ + $ECHO "DATA MULTIPLE NONSHARED" >> $output_objdir/$libname.def~ + $ECHO EXPORTS >> $output_objdir/$libname.def~ + emxexp $libobjs | $SED /"_DLL_InitTerm"/d >> $output_objdir/$libname.def~ + $CC -Zdll -Zcrtdll -o $output_objdir/$soname $libobjs $deplibs $compiler_flags $output_objdir/$libname.def~ + emximp -o $lib $output_objdir/$libname.def' + archive_expsym_cmds='$ECHO "LIBRARY ${soname%$shared_ext} INITINSTANCE TERMINSTANCE" > $output_objdir/$libname.def~ + $ECHO "DESCRIPTION \"$libname\"" >> $output_objdir/$libname.def~ + $ECHO "DATA MULTIPLE NONSHARED" >> $output_objdir/$libname.def~ + $ECHO EXPORTS >> $output_objdir/$libname.def~ + prefix_cmds="$SED"~ + if test EXPORTS = "`$SED 1q $export_symbols`"; then + prefix_cmds="$prefix_cmds -e 1d"; + fi~ + prefix_cmds="$prefix_cmds -e \"s/^\(.*\)$/_\1/g\""~ + cat $export_symbols | $prefix_cmds >> $output_objdir/$libname.def~ + $CC -Zdll -Zcrtdll -o $output_objdir/$soname $libobjs $deplibs $compiler_flags $output_objdir/$libname.def~ + emximp -o $lib $output_objdir/$libname.def' + old_archive_From_new_cmds='emximp -o $output_objdir/${libname}_dll.a $output_objdir/$libname.def' + enable_shared_with_static_runtimes=yes + ;; + interix[3-9]*) hardcode_direct=no hardcode_shlibpath_var=no - hardcode_libdir_flag_spec='${wl}-rpath,$libdir' - export_dynamic_flag_spec='${wl}-E' + hardcode_libdir_flag_spec='$wl-rpath,$libdir' + export_dynamic_flag_spec='$wl-E' # Hack: On Interix 3.x, we cannot compile PIC because of a broken gcc. # Instead, shared libraries are loaded at an image base (0x10000000 by # default) and relocated if they conflict, which is a slow very memory # consuming and fragmenting process. To avoid this, we pick a random, # 256 KiB-aligned image base between 0x50000000 and 0x6FFC0000 at link # time. Moving up from 0x10000000 also allows more sbrk(2) space. - archive_cmds='$CC -shared $pic_flag $libobjs $deplibs $compiler_flags ${wl}-h,$soname ${wl}--image-base,`expr ${RANDOM-$$} % 4096 / 2 \* 262144 + 1342177280` -o $lib' - archive_expsym_cmds='sed "s,^,_," $export_symbols >$output_objdir/$soname.expsym~$CC -shared $pic_flag $libobjs $deplibs $compiler_flags ${wl}-h,$soname ${wl}--retain-symbols-file,$output_objdir/$soname.expsym ${wl}--image-base,`expr ${RANDOM-$$} % 4096 / 2 \* 262144 + 1342177280` -o $lib' + archive_cmds='$CC -shared $pic_flag $libobjs $deplibs $compiler_flags $wl-h,$soname $wl--image-base,`expr ${RANDOM-$$} % 4096 / 2 \* 262144 + 1342177280` -o $lib' + archive_expsym_cmds='sed "s|^|_|" $export_symbols >$output_objdir/$soname.expsym~$CC -shared $pic_flag $libobjs $deplibs $compiler_flags $wl-h,$soname $wl--retain-symbols-file,$output_objdir/$soname.expsym $wl--image-base,`expr ${RANDOM-$$} % 4096 / 2 \* 262144 + 1342177280` -o $lib' ;; gnu* | linux* | tpf* | k*bsd*-gnu | kopensolaris*-gnu) tmp_diet=no - if test "$host_os" = linux-dietlibc; then + if test linux-dietlibc = "$host_os"; then case $cc_basename in diet\ *) tmp_diet=yes;; # linux-dietlibc with static linking (!diet-dyn) esac fi if $LD --help 2>&1 | $EGREP ': supported targets:.* elf' > /dev/null \ - && test "$tmp_diet" = no + && test no = "$tmp_diet" then tmp_addflag=' $pic_flag' tmp_sharedflag='-shared' case $cc_basename,$host_cpu in pgcc*) # Portland Group C compiler - whole_archive_flag_spec='${wl}--whole-archive`for conv in $convenience\"\"; do test -n \"$conv\" && new_convenience=\"$new_convenience,$conv\"; done; func_echo_all \"$new_convenience\"` ${wl}--no-whole-archive' + whole_archive_flag_spec='$wl--whole-archive`for conv in $convenience\"\"; do test -n \"$conv\" && new_convenience=\"$new_convenience,$conv\"; done; func_echo_all \"$new_convenience\"` $wl--no-whole-archive' tmp_addflag=' $pic_flag' ;; pgf77* | pgf90* | pgf95* | pgfortran*) # Portland Group f77 and f90 compilers - whole_archive_flag_spec='${wl}--whole-archive`for conv in $convenience\"\"; do test -n \"$conv\" && new_convenience=\"$new_convenience,$conv\"; done; func_echo_all \"$new_convenience\"` ${wl}--no-whole-archive' + whole_archive_flag_spec='$wl--whole-archive`for conv in $convenience\"\"; do test -n \"$conv\" && new_convenience=\"$new_convenience,$conv\"; done; func_echo_all \"$new_convenience\"` $wl--no-whole-archive' tmp_addflag=' $pic_flag -Mnomain' ;; ecc*,ia64* | icc*,ia64*) # Intel C compiler on ia64 tmp_addflag=' -i_dynamic' ;; @@ -9352,42 +9720,47 @@ _LT_EOF lf95*) # Lahey Fortran 8.1 whole_archive_flag_spec= tmp_sharedflag='--shared' ;; + nagfor*) # NAGFOR 5.3 + tmp_sharedflag='-Wl,-shared' ;; xl[cC]* | bgxl[cC]* | mpixl[cC]*) # IBM XL C 8.0 on PPC (deal with xlf below) tmp_sharedflag='-qmkshrobj' tmp_addflag= ;; nvcc*) # Cuda Compiler Driver 2.2 - whole_archive_flag_spec='${wl}--whole-archive`for conv in $convenience\"\"; do test -n \"$conv\" && new_convenience=\"$new_convenience,$conv\"; done; func_echo_all \"$new_convenience\"` ${wl}--no-whole-archive' + whole_archive_flag_spec='$wl--whole-archive`for conv in $convenience\"\"; do test -n \"$conv\" && new_convenience=\"$new_convenience,$conv\"; done; func_echo_all \"$new_convenience\"` $wl--no-whole-archive' compiler_needs_object=yes ;; esac case `$CC -V 2>&1 | sed 5q` in *Sun\ C*) # Sun C 5.9 - whole_archive_flag_spec='${wl}--whole-archive`new_convenience=; for conv in $convenience\"\"; do test -z \"$conv\" || new_convenience=\"$new_convenience,$conv\"; done; func_echo_all \"$new_convenience\"` ${wl}--no-whole-archive' + whole_archive_flag_spec='$wl--whole-archive`new_convenience=; for conv in $convenience\"\"; do test -z \"$conv\" || new_convenience=\"$new_convenience,$conv\"; done; func_echo_all \"$new_convenience\"` $wl--no-whole-archive' compiler_needs_object=yes tmp_sharedflag='-G' ;; *Sun\ F*) # Sun Fortran 8.3 tmp_sharedflag='-G' ;; esac - archive_cmds='$CC '"$tmp_sharedflag""$tmp_addflag"' $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname -o $lib' + archive_cmds='$CC '"$tmp_sharedflag""$tmp_addflag"' $libobjs $deplibs $compiler_flags $wl-soname $wl$soname -o $lib' - if test "x$supports_anon_versioning" = xyes; then + if test yes = "$supports_anon_versioning"; then archive_expsym_cmds='echo "{ global:" > $output_objdir/$libname.ver~ - cat $export_symbols | sed -e "s/\(.*\)/\1;/" >> $output_objdir/$libname.ver~ - echo "local: *; };" >> $output_objdir/$libname.ver~ - $CC '"$tmp_sharedflag""$tmp_addflag"' $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname ${wl}-version-script ${wl}$output_objdir/$libname.ver -o $lib' + cat $export_symbols | sed -e "s/\(.*\)/\1;/" >> $output_objdir/$libname.ver~ + echo "local: *; };" >> $output_objdir/$libname.ver~ + $CC '"$tmp_sharedflag""$tmp_addflag"' $libobjs $deplibs $compiler_flags $wl-soname $wl$soname $wl-version-script $wl$output_objdir/$libname.ver -o $lib' fi case $cc_basename in + tcc*) + export_dynamic_flag_spec='-rdynamic' + ;; xlf* | bgf* | bgxlf* | mpixlf*) # IBM XL Fortran 10.1 on PPC cannot create shared libs itself whole_archive_flag_spec='--whole-archive$convenience --no-whole-archive' - hardcode_libdir_flag_spec='${wl}-rpath ${wl}$libdir' + hardcode_libdir_flag_spec='$wl-rpath $wl$libdir' archive_cmds='$LD -shared $libobjs $deplibs $linker_flags -soname $soname -o $lib' - if test "x$supports_anon_versioning" = xyes; then + if test yes = "$supports_anon_versioning"; then archive_expsym_cmds='echo "{ global:" > $output_objdir/$libname.ver~ - cat $export_symbols | sed -e "s/\(.*\)/\1;/" >> $output_objdir/$libname.ver~ - echo "local: *; };" >> $output_objdir/$libname.ver~ - $LD -shared $libobjs $deplibs $linker_flags -soname $soname -version-script $output_objdir/$libname.ver -o $lib' + cat $export_symbols | sed -e "s/\(.*\)/\1;/" >> $output_objdir/$libname.ver~ + echo "local: *; };" >> $output_objdir/$libname.ver~ + $LD -shared $libobjs $deplibs $linker_flags -soname $soname -version-script $output_objdir/$libname.ver -o $lib' fi ;; esac @@ -9401,8 +9774,8 @@ _LT_EOF archive_cmds='$LD -Bshareable $libobjs $deplibs $linker_flags -o $lib' wlarc= else - archive_cmds='$CC -shared $pic_flag $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname -o $lib' - archive_expsym_cmds='$CC -shared $pic_flag $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname ${wl}-retain-symbols-file $wl$export_symbols -o $lib' + archive_cmds='$CC -shared $pic_flag $libobjs $deplibs $compiler_flags $wl-soname $wl$soname -o $lib' + archive_expsym_cmds='$CC -shared $pic_flag $libobjs $deplibs $compiler_flags $wl-soname $wl$soname $wl-retain-symbols-file $wl$export_symbols -o $lib' fi ;; @@ -9420,8 +9793,8 @@ _LT_EOF _LT_EOF elif $LD --help 2>&1 | $GREP ': supported targets:.* elf' > /dev/null; then - archive_cmds='$CC -shared $pic_flag $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname -o $lib' - archive_expsym_cmds='$CC -shared $pic_flag $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname ${wl}-retain-symbols-file $wl$export_symbols -o $lib' + archive_cmds='$CC -shared $pic_flag $libobjs $deplibs $compiler_flags $wl-soname $wl$soname -o $lib' + archive_expsym_cmds='$CC -shared $pic_flag $libobjs $deplibs $compiler_flags $wl-soname $wl$soname $wl-retain-symbols-file $wl$export_symbols -o $lib' else ld_shlibs=no fi @@ -9433,7 +9806,7 @@ _LT_EOF ld_shlibs=no cat <<_LT_EOF 1>&2 -*** Warning: Releases of the GNU linker prior to 2.16.91.0.3 can not +*** Warning: Releases of the GNU linker prior to 2.16.91.0.3 cannot *** reliably create shared libraries on SCO systems. Therefore, libtool *** is disabling shared libraries support. We urge you to upgrade GNU *** binutils to release 2.16.91.0.3 or newer. Another option is to modify @@ -9448,9 +9821,9 @@ _LT_EOF # DT_RUNPATH tag from executables and libraries. But doing so # requires that you compile everything twice, which is a pain. if $LD --help 2>&1 | $GREP ': supported targets:.* elf' > /dev/null; then - hardcode_libdir_flag_spec='${wl}-rpath ${wl}$libdir' - archive_cmds='$CC -shared $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname -o $lib' - archive_expsym_cmds='$CC -shared $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname ${wl}-retain-symbols-file $wl$export_symbols -o $lib' + hardcode_libdir_flag_spec='$wl-rpath $wl$libdir' + archive_cmds='$CC -shared $libobjs $deplibs $compiler_flags $wl-soname $wl$soname -o $lib' + archive_expsym_cmds='$CC -shared $libobjs $deplibs $compiler_flags $wl-soname $wl$soname $wl-retain-symbols-file $wl$export_symbols -o $lib' else ld_shlibs=no fi @@ -9467,15 +9840,15 @@ _LT_EOF *) if $LD --help 2>&1 | $GREP ': supported targets:.* elf' > /dev/null; then - archive_cmds='$CC -shared $pic_flag $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname -o $lib' - archive_expsym_cmds='$CC -shared $pic_flag $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname ${wl}-retain-symbols-file $wl$export_symbols -o $lib' + archive_cmds='$CC -shared $pic_flag $libobjs $deplibs $compiler_flags $wl-soname $wl$soname -o $lib' + archive_expsym_cmds='$CC -shared $pic_flag $libobjs $deplibs $compiler_flags $wl-soname $wl$soname $wl-retain-symbols-file $wl$export_symbols -o $lib' else ld_shlibs=no fi ;; esac - if test "$ld_shlibs" = no; then + if test no = "$ld_shlibs"; then runpath_var= hardcode_libdir_flag_spec= export_dynamic_flag_spec= @@ -9491,7 +9864,7 @@ _LT_EOF # Note: this linker hardcodes the directories in LIBPATH if there # are no directories specified by -L. hardcode_minus_L=yes - if test "$GCC" = yes && test -z "$lt_prog_compiler_static"; then + if test yes = "$GCC" && test -z "$lt_prog_compiler_static"; then # Neither direct hardcoding nor static linking is supported with a # broken collect2. hardcode_direct=unsupported @@ -9499,34 +9872,57 @@ _LT_EOF ;; aix[4-9]*) - if test "$host_cpu" = ia64; then + if test ia64 = "$host_cpu"; then # On IA64, the linker does run time linking by default, so we don't # have to do anything special. aix_use_runtimelinking=no exp_sym_flag='-Bexport' - no_entry_flag="" + no_entry_flag= else # If we're using GNU nm, then we don't want the "-C" option. - # -C means demangle to AIX nm, but means don't demangle with GNU nm - # Also, AIX nm treats weak defined symbols like other global - # defined symbols, whereas GNU nm marks them as "W". + # -C means demangle to GNU nm, but means don't demangle to AIX nm. + # Without the "-l" option, or with the "-B" option, AIX nm treats + # weak defined symbols like other global defined symbols, whereas + # GNU nm marks them as "W". + # While the 'weak' keyword is ignored in the Export File, we need + # it in the Import File for the 'aix-soname' feature, so we have + # to replace the "-B" option with "-P" for AIX nm. if $NM -V 2>&1 | $GREP 'GNU' > /dev/null; then - export_symbols_cmds='$NM -Bpg $libobjs $convenience | awk '\''{ if (((\$ 2 == "T") || (\$ 2 == "D") || (\$ 2 == "B") || (\$ 2 == "W")) && (substr(\$ 3,1,1) != ".")) { print \$ 3 } }'\'' | sort -u > $export_symbols' + export_symbols_cmds='$NM -Bpg $libobjs $convenience | awk '\''{ if (((\$ 2 == "T") || (\$ 2 == "D") || (\$ 2 == "B") || (\$ 2 == "W")) && (substr(\$ 3,1,1) != ".")) { if (\$ 2 == "W") { print \$ 3 " weak" } else { print \$ 3 } } }'\'' | sort -u > $export_symbols' else - export_symbols_cmds='$NM -BCpg $libobjs $convenience | awk '\''{ if (((\$ 2 == "T") || (\$ 2 == "D") || (\$ 2 == "B")) && (substr(\$ 3,1,1) != ".")) { print \$ 3 } }'\'' | sort -u > $export_symbols' + export_symbols_cmds='`func_echo_all $NM | $SED -e '\''s/B\([^B]*\)$/P\1/'\''` -PCpgl $libobjs $convenience | awk '\''{ if (((\$ 2 == "T") || (\$ 2 == "D") || (\$ 2 == "B") || (\$ 2 == "W") || (\$ 2 == "V") || (\$ 2 == "Z")) && (substr(\$ 1,1,1) != ".")) { if ((\$ 2 == "W") || (\$ 2 == "V") || (\$ 2 == "Z")) { print \$ 1 " weak" } else { print \$ 1 } } }'\'' | sort -u > $export_symbols' fi aix_use_runtimelinking=no # Test if we are trying to use run time linking or normal # AIX style linking. If -brtl is somewhere in LDFLAGS, we - # need to do runtime linking. + # have runtime linking enabled, and use it for executables. + # For shared libraries, we enable/disable runtime linking + # depending on the kind of the shared library created - + # when "with_aix_soname,aix_use_runtimelinking" is: + # "aix,no" lib.a(lib.so.V) shared, rtl:no, for executables + # "aix,yes" lib.so shared, rtl:yes, for executables + # lib.a static archive + # "both,no" lib.so.V(shr.o) shared, rtl:yes + # lib.a(lib.so.V) shared, rtl:no, for executables + # "both,yes" lib.so.V(shr.o) shared, rtl:yes, for executables + # lib.a(lib.so.V) shared, rtl:no + # "svr4,*" lib.so.V(shr.o) shared, rtl:yes, for executables + # lib.a static archive case $host_os in aix4.[23]|aix4.[23].*|aix[5-9]*) for ld_flag in $LDFLAGS; do - if (test $ld_flag = "-brtl" || test $ld_flag = "-Wl,-brtl"); then + if (test x-brtl = "x$ld_flag" || test x-Wl,-brtl = "x$ld_flag"); then aix_use_runtimelinking=yes break fi done + if test svr4,no = "$with_aix_soname,$aix_use_runtimelinking"; then + # With aix-soname=svr4, we create the lib.so.V shared archives only, + # so we don't have lib.a shared libs to link our executables. + # We have to force runtime linking in this case. + aix_use_runtimelinking=yes + LDFLAGS="$LDFLAGS -Wl,-brtl" + fi ;; esac @@ -9545,13 +9941,21 @@ _LT_EOF hardcode_direct_absolute=yes hardcode_libdir_separator=':' link_all_deplibs=yes - file_list_spec='${wl}-f,' + file_list_spec='$wl-f,' + case $with_aix_soname,$aix_use_runtimelinking in + aix,*) ;; # traditional, no import file + svr4,* | *,yes) # use import file + # The Import File defines what to hardcode. + hardcode_direct=no + hardcode_direct_absolute=no + ;; + esac - if test "$GCC" = yes; then + if test yes = "$GCC"; then case $host_os in aix4.[012]|aix4.[012].*) # We only want to do this on AIX 4.2 and lower, the check # below for broken collect2 doesn't work under 4.3+ - collect2name=`${CC} -print-prog-name=collect2` + collect2name=`$CC -print-prog-name=collect2` if test -f "$collect2name" && strings "$collect2name" | $GREP resolve_lib_name >/dev/null then @@ -9570,35 +9974,42 @@ _LT_EOF ;; esac shared_flag='-shared' - if test "$aix_use_runtimelinking" = yes; then - shared_flag="$shared_flag "'${wl}-G' + if test yes = "$aix_use_runtimelinking"; then + shared_flag="$shared_flag "'$wl-G' fi + # Need to ensure runtime linking is disabled for the traditional + # shared library, or the linker may eventually find shared libraries + # /with/ Import File - we do not want to mix them. + shared_flag_aix='-shared' + shared_flag_svr4='-shared $wl-G' else # not using gcc - if test "$host_cpu" = ia64; then + if test ia64 = "$host_cpu"; then # VisualAge C++, Version 5.5 for AIX 5L for IA-64, Beta 3 Release # chokes on -Wl,-G. The following line is correct: shared_flag='-G' else - if test "$aix_use_runtimelinking" = yes; then - shared_flag='${wl}-G' + if test yes = "$aix_use_runtimelinking"; then + shared_flag='$wl-G' else - shared_flag='${wl}-bM:SRE' + shared_flag='$wl-bM:SRE' fi + shared_flag_aix='$wl-bM:SRE' + shared_flag_svr4='$wl-G' fi fi - export_dynamic_flag_spec='${wl}-bexpall' + export_dynamic_flag_spec='$wl-bexpall' # It seems that -bexpall does not export symbols beginning with # underscore (_), so it is better to generate a list of symbols to export. always_export_symbols=yes - if test "$aix_use_runtimelinking" = yes; then + if test aix,yes = "$with_aix_soname,$aix_use_runtimelinking"; then # Warning - without using the other runtime loading flags (-brtl), # -berok will link without error, but may produce a broken library. allow_undefined_flag='-berok' # Determine the default libpath from the value encoded in an # empty executable. - if test "${lt_cv_aix_libpath+set}" = set; then + if test set = "${lt_cv_aix_libpath+set}"; then aix_libpath=$lt_cv_aix_libpath else if ${lt_cv_aix_libpath_+:} false; then : @@ -9633,7 +10044,7 @@ fi rm -f core conftest.err conftest.$ac_objext \ conftest$ac_exeext conftest.$ac_ext if test -z "$lt_cv_aix_libpath_"; then - lt_cv_aix_libpath_="/usr/lib:/lib" + lt_cv_aix_libpath_=/usr/lib:/lib fi fi @@ -9641,17 +10052,17 @@ fi aix_libpath=$lt_cv_aix_libpath_ fi - hardcode_libdir_flag_spec='${wl}-blibpath:$libdir:'"$aix_libpath" - archive_expsym_cmds='$CC -o $output_objdir/$soname $libobjs $deplibs '"\${wl}$no_entry_flag"' $compiler_flags `if test "x${allow_undefined_flag}" != "x"; then func_echo_all "${wl}${allow_undefined_flag}"; else :; fi` '"\${wl}$exp_sym_flag:\$export_symbols $shared_flag" + hardcode_libdir_flag_spec='$wl-blibpath:$libdir:'"$aix_libpath" + archive_expsym_cmds='$CC -o $output_objdir/$soname $libobjs $deplibs $wl'$no_entry_flag' $compiler_flags `if test -n "$allow_undefined_flag"; then func_echo_all "$wl$allow_undefined_flag"; else :; fi` $wl'$exp_sym_flag:\$export_symbols' '$shared_flag else - if test "$host_cpu" = ia64; then - hardcode_libdir_flag_spec='${wl}-R $libdir:/usr/lib:/lib' + if test ia64 = "$host_cpu"; then + hardcode_libdir_flag_spec='$wl-R $libdir:/usr/lib:/lib' allow_undefined_flag="-z nodefs" - archive_expsym_cmds="\$CC $shared_flag"' -o $output_objdir/$soname $libobjs $deplibs '"\${wl}$no_entry_flag"' $compiler_flags ${wl}${allow_undefined_flag} '"\${wl}$exp_sym_flag:\$export_symbols" + archive_expsym_cmds="\$CC $shared_flag"' -o $output_objdir/$soname $libobjs $deplibs '"\$wl$no_entry_flag"' $compiler_flags $wl$allow_undefined_flag '"\$wl$exp_sym_flag:\$export_symbols" else # Determine the default libpath from the value encoded in an # empty executable. - if test "${lt_cv_aix_libpath+set}" = set; then + if test set = "${lt_cv_aix_libpath+set}"; then aix_libpath=$lt_cv_aix_libpath else if ${lt_cv_aix_libpath_+:} false; then : @@ -9686,7 +10097,7 @@ fi rm -f core conftest.err conftest.$ac_objext \ conftest$ac_exeext conftest.$ac_ext if test -z "$lt_cv_aix_libpath_"; then - lt_cv_aix_libpath_="/usr/lib:/lib" + lt_cv_aix_libpath_=/usr/lib:/lib fi fi @@ -9694,21 +10105,33 @@ fi aix_libpath=$lt_cv_aix_libpath_ fi - hardcode_libdir_flag_spec='${wl}-blibpath:$libdir:'"$aix_libpath" + hardcode_libdir_flag_spec='$wl-blibpath:$libdir:'"$aix_libpath" # Warning - without using the other run time loading flags, # -berok will link without error, but may produce a broken library. - no_undefined_flag=' ${wl}-bernotok' - allow_undefined_flag=' ${wl}-berok' - if test "$with_gnu_ld" = yes; then + no_undefined_flag=' $wl-bernotok' + allow_undefined_flag=' $wl-berok' + if test yes = "$with_gnu_ld"; then # We only use this code for GNU lds that support --whole-archive. - whole_archive_flag_spec='${wl}--whole-archive$convenience ${wl}--no-whole-archive' + whole_archive_flag_spec='$wl--whole-archive$convenience $wl--no-whole-archive' else # Exported symbols can be pulled into shared objects from archives whole_archive_flag_spec='$convenience' fi archive_cmds_need_lc=yes - # This is similar to how AIX traditionally builds its shared libraries. - archive_expsym_cmds="\$CC $shared_flag"' -o $output_objdir/$soname $libobjs $deplibs ${wl}-bnoentry $compiler_flags ${wl}-bE:$export_symbols${allow_undefined_flag}~$AR $AR_FLAGS $output_objdir/$libname$release.a $output_objdir/$soname' + archive_expsym_cmds='$RM -r $output_objdir/$realname.d~$MKDIR $output_objdir/$realname.d' + # -brtl affects multiple linker settings, -berok does not and is overridden later + compiler_flags_filtered='`func_echo_all "$compiler_flags " | $SED -e "s%-brtl\\([, ]\\)%-berok\\1%g"`' + if test svr4 != "$with_aix_soname"; then + # This is similar to how AIX traditionally builds its shared libraries. + archive_expsym_cmds="$archive_expsym_cmds"'~$CC '$shared_flag_aix' -o $output_objdir/$realname.d/$soname $libobjs $deplibs $wl-bnoentry '$compiler_flags_filtered'$wl-bE:$export_symbols$allow_undefined_flag~$AR $AR_FLAGS $output_objdir/$libname$release.a $output_objdir/$realname.d/$soname' + fi + if test aix != "$with_aix_soname"; then + archive_expsym_cmds="$archive_expsym_cmds"'~$CC '$shared_flag_svr4' -o $output_objdir/$realname.d/$shared_archive_member_spec.o $libobjs $deplibs $wl-bnoentry '$compiler_flags_filtered'$wl-bE:$export_symbols$allow_undefined_flag~$STRIP -e $output_objdir/$realname.d/$shared_archive_member_spec.o~( func_echo_all "#! $soname($shared_archive_member_spec.o)"; if test shr_64 = "$shared_archive_member_spec"; then func_echo_all "# 64"; else func_echo_all "# 32"; fi; cat $export_symbols ) > $output_objdir/$realname.d/$shared_archive_member_spec.imp~$AR $AR_FLAGS $output_objdir/$soname $output_objdir/$realname.d/$shared_archive_member_spec.o $output_objdir/$realname.d/$shared_archive_member_spec.imp' + else + # used by -dlpreopen to get the symbols + archive_expsym_cmds="$archive_expsym_cmds"'~$MV $output_objdir/$realname.d/$soname $output_objdir' + fi + archive_expsym_cmds="$archive_expsym_cmds"'~$RM -r $output_objdir/$realname.d' fi fi ;; @@ -9717,7 +10140,7 @@ fi case $host_cpu in powerpc) # see comment about AmigaOS4 .so support - archive_cmds='$CC -shared $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname -o $lib' + archive_cmds='$CC -shared $libobjs $deplibs $compiler_flags $wl-soname $wl$soname -o $lib' archive_expsym_cmds='' ;; m68k) @@ -9747,16 +10170,17 @@ fi # Tell ltmain to make .lib files, not .a files. libext=lib # Tell ltmain to make .dll files, not .so files. - shrext_cmds=".dll" + shrext_cmds=.dll # FIXME: Setting linknames here is a bad hack. - archive_cmds='$CC -o $output_objdir/$soname $libobjs $compiler_flags $deplibs -Wl,-dll~linknames=' - archive_expsym_cmds='if test "x`$SED 1q $export_symbols`" = xEXPORTS; then - sed -n -e 's/\\\\\\\(.*\\\\\\\)/-link\\\ -EXPORT:\\\\\\\1/' -e '1\\\!p' < $export_symbols > $output_objdir/$soname.exp; - else - sed -e 's/\\\\\\\(.*\\\\\\\)/-link\\\ -EXPORT:\\\\\\\1/' < $export_symbols > $output_objdir/$soname.exp; - fi~ - $CC -o $tool_output_objdir$soname $libobjs $compiler_flags $deplibs "@$tool_output_objdir$soname.exp" -Wl,-DLL,-IMPLIB:"$tool_output_objdir$libname.dll.lib"~ - linknames=' + archive_cmds='$CC -o $output_objdir/$soname $libobjs $compiler_flags $deplibs -Wl,-DLL,-IMPLIB:"$tool_output_objdir$libname.dll.lib"~linknames=' + archive_expsym_cmds='if test DEF = "`$SED -n -e '\''s/^[ ]*//'\'' -e '\''/^\(;.*\)*$/d'\'' -e '\''s/^\(EXPORTS\|LIBRARY\)\([ ].*\)*$/DEF/p'\'' -e q $export_symbols`" ; then + cp "$export_symbols" "$output_objdir/$soname.def"; + echo "$tool_output_objdir$soname.def" > "$output_objdir/$soname.exp"; + else + $SED -e '\''s/^/-link -EXPORT:/'\'' < $export_symbols > $output_objdir/$soname.exp; + fi~ + $CC -o $tool_output_objdir$soname $libobjs $compiler_flags $deplibs "@$tool_output_objdir$soname.exp" -Wl,-DLL,-IMPLIB:"$tool_output_objdir$libname.dll.lib"~ + linknames=' # The linker will not automatically build a static lib if we build a DLL. # _LT_TAGVAR(old_archive_from_new_cmds, )='true' enable_shared_with_static_runtimes=yes @@ -9765,18 +10189,18 @@ fi # Don't use ranlib old_postinstall_cmds='chmod 644 $oldlib' postlink_cmds='lt_outputfile="@OUTPUT@"~ - lt_tool_outputfile="@TOOL_OUTPUT@"~ - case $lt_outputfile in - *.exe|*.EXE) ;; - *) - lt_outputfile="$lt_outputfile.exe" - lt_tool_outputfile="$lt_tool_outputfile.exe" - ;; - esac~ - if test "$MANIFEST_TOOL" != ":" && test -f "$lt_outputfile.manifest"; then - $MANIFEST_TOOL -manifest "$lt_tool_outputfile.manifest" -outputresource:"$lt_tool_outputfile" || exit 1; - $RM "$lt_outputfile.manifest"; - fi' + lt_tool_outputfile="@TOOL_OUTPUT@"~ + case $lt_outputfile in + *.exe|*.EXE) ;; + *) + lt_outputfile=$lt_outputfile.exe + lt_tool_outputfile=$lt_tool_outputfile.exe + ;; + esac~ + if test : != "$MANIFEST_TOOL" && test -f "$lt_outputfile.manifest"; then + $MANIFEST_TOOL -manifest "$lt_tool_outputfile.manifest" -outputresource:"$lt_tool_outputfile" || exit 1; + $RM "$lt_outputfile.manifest"; + fi' ;; *) # Assume MSVC wrapper @@ -9785,7 +10209,7 @@ fi # Tell ltmain to make .lib files, not .a files. libext=lib # Tell ltmain to make .dll files, not .so files. - shrext_cmds=".dll" + shrext_cmds=.dll # FIXME: Setting linknames here is a bad hack. archive_cmds='$CC -o $lib $libobjs $compiler_flags `func_echo_all "$deplibs" | $SED '\''s/ -lc$//'\''` -link -dll~linknames=' # The linker will automatically build a .lib file if we build a DLL. @@ -9804,24 +10228,24 @@ fi hardcode_direct=no hardcode_automatic=yes hardcode_shlibpath_var=unsupported - if test "$lt_cv_ld_force_load" = "yes"; then - whole_archive_flag_spec='`for conv in $convenience\"\"; do test -n \"$conv\" && new_convenience=\"$new_convenience ${wl}-force_load,$conv\"; done; func_echo_all \"$new_convenience\"`' + if test yes = "$lt_cv_ld_force_load"; then + whole_archive_flag_spec='`for conv in $convenience\"\"; do test -n \"$conv\" && new_convenience=\"$new_convenience $wl-force_load,$conv\"; done; func_echo_all \"$new_convenience\"`' else whole_archive_flag_spec='' fi link_all_deplibs=yes - allow_undefined_flag="$_lt_dar_allow_undefined" + allow_undefined_flag=$_lt_dar_allow_undefined case $cc_basename in - ifort*) _lt_dar_can_shared=yes ;; + ifort*|nagfor*) _lt_dar_can_shared=yes ;; *) _lt_dar_can_shared=$GCC ;; esac - if test "$_lt_dar_can_shared" = "yes"; then + if test yes = "$_lt_dar_can_shared"; then output_verbose_link_cmd=func_echo_all - archive_cmds="\$CC -dynamiclib \$allow_undefined_flag -o \$lib \$libobjs \$deplibs \$compiler_flags -install_name \$rpath/\$soname \$verstring $_lt_dar_single_mod${_lt_dsymutil}" - module_cmds="\$CC \$allow_undefined_flag -o \$lib -bundle \$libobjs \$deplibs \$compiler_flags${_lt_dsymutil}" - archive_expsym_cmds="sed 's,^,_,' < \$export_symbols > \$output_objdir/\${libname}-symbols.expsym~\$CC -dynamiclib \$allow_undefined_flag -o \$lib \$libobjs \$deplibs \$compiler_flags -install_name \$rpath/\$soname \$verstring ${_lt_dar_single_mod}${_lt_dar_export_syms}${_lt_dsymutil}" - module_expsym_cmds="sed -e 's,^,_,' < \$export_symbols > \$output_objdir/\${libname}-symbols.expsym~\$CC \$allow_undefined_flag -o \$lib -bundle \$libobjs \$deplibs \$compiler_flags${_lt_dar_export_syms}${_lt_dsymutil}" + archive_cmds="\$CC -dynamiclib \$allow_undefined_flag -o \$lib \$libobjs \$deplibs \$compiler_flags -install_name \$rpath/\$soname \$verstring $_lt_dar_single_mod$_lt_dsymutil" + module_cmds="\$CC \$allow_undefined_flag -o \$lib -bundle \$libobjs \$deplibs \$compiler_flags$_lt_dsymutil" + archive_expsym_cmds="sed 's|^|_|' < \$export_symbols > \$output_objdir/\$libname-symbols.expsym~\$CC -dynamiclib \$allow_undefined_flag -o \$lib \$libobjs \$deplibs \$compiler_flags -install_name \$rpath/\$soname \$verstring $_lt_dar_single_mod$_lt_dar_export_syms$_lt_dsymutil" + module_expsym_cmds="sed -e 's|^|_|' < \$export_symbols > \$output_objdir/\$libname-symbols.expsym~\$CC \$allow_undefined_flag -o \$lib -bundle \$libobjs \$deplibs \$compiler_flags$_lt_dar_export_syms$_lt_dsymutil" else ld_shlibs=no @@ -9863,33 +10287,33 @@ fi ;; hpux9*) - if test "$GCC" = yes; then - archive_cmds='$RM $output_objdir/$soname~$CC -shared $pic_flag ${wl}+b ${wl}$install_libdir -o $output_objdir/$soname $libobjs $deplibs $compiler_flags~test $output_objdir/$soname = $lib || mv $output_objdir/$soname $lib' + if test yes = "$GCC"; then + archive_cmds='$RM $output_objdir/$soname~$CC -shared $pic_flag $wl+b $wl$install_libdir -o $output_objdir/$soname $libobjs $deplibs $compiler_flags~test "x$output_objdir/$soname" = "x$lib" || mv $output_objdir/$soname $lib' else - archive_cmds='$RM $output_objdir/$soname~$LD -b +b $install_libdir -o $output_objdir/$soname $libobjs $deplibs $linker_flags~test $output_objdir/$soname = $lib || mv $output_objdir/$soname $lib' + archive_cmds='$RM $output_objdir/$soname~$LD -b +b $install_libdir -o $output_objdir/$soname $libobjs $deplibs $linker_flags~test "x$output_objdir/$soname" = "x$lib" || mv $output_objdir/$soname $lib' fi - hardcode_libdir_flag_spec='${wl}+b ${wl}$libdir' + hardcode_libdir_flag_spec='$wl+b $wl$libdir' hardcode_libdir_separator=: hardcode_direct=yes # hardcode_minus_L: Not really in the search PATH, # but as the default location of the library. hardcode_minus_L=yes - export_dynamic_flag_spec='${wl}-E' + export_dynamic_flag_spec='$wl-E' ;; hpux10*) - if test "$GCC" = yes && test "$with_gnu_ld" = no; then - archive_cmds='$CC -shared $pic_flag ${wl}+h ${wl}$soname ${wl}+b ${wl}$install_libdir -o $lib $libobjs $deplibs $compiler_flags' + if test yes,no = "$GCC,$with_gnu_ld"; then + archive_cmds='$CC -shared $pic_flag $wl+h $wl$soname $wl+b $wl$install_libdir -o $lib $libobjs $deplibs $compiler_flags' else archive_cmds='$LD -b +h $soname +b $install_libdir -o $lib $libobjs $deplibs $linker_flags' fi - if test "$with_gnu_ld" = no; then - hardcode_libdir_flag_spec='${wl}+b ${wl}$libdir' + if test no = "$with_gnu_ld"; then + hardcode_libdir_flag_spec='$wl+b $wl$libdir' hardcode_libdir_separator=: hardcode_direct=yes hardcode_direct_absolute=yes - export_dynamic_flag_spec='${wl}-E' + export_dynamic_flag_spec='$wl-E' # hardcode_minus_L: Not really in the search PATH, # but as the default location of the library. hardcode_minus_L=yes @@ -9897,25 +10321,25 @@ fi ;; hpux11*) - if test "$GCC" = yes && test "$with_gnu_ld" = no; then + if test yes,no = "$GCC,$with_gnu_ld"; then case $host_cpu in hppa*64*) - archive_cmds='$CC -shared ${wl}+h ${wl}$soname -o $lib $libobjs $deplibs $compiler_flags' + archive_cmds='$CC -shared $wl+h $wl$soname -o $lib $libobjs $deplibs $compiler_flags' ;; ia64*) - archive_cmds='$CC -shared $pic_flag ${wl}+h ${wl}$soname ${wl}+nodefaultrpath -o $lib $libobjs $deplibs $compiler_flags' + archive_cmds='$CC -shared $pic_flag $wl+h $wl$soname $wl+nodefaultrpath -o $lib $libobjs $deplibs $compiler_flags' ;; *) - archive_cmds='$CC -shared $pic_flag ${wl}+h ${wl}$soname ${wl}+b ${wl}$install_libdir -o $lib $libobjs $deplibs $compiler_flags' + archive_cmds='$CC -shared $pic_flag $wl+h $wl$soname $wl+b $wl$install_libdir -o $lib $libobjs $deplibs $compiler_flags' ;; esac else case $host_cpu in hppa*64*) - archive_cmds='$CC -b ${wl}+h ${wl}$soname -o $lib $libobjs $deplibs $compiler_flags' + archive_cmds='$CC -b $wl+h $wl$soname -o $lib $libobjs $deplibs $compiler_flags' ;; ia64*) - archive_cmds='$CC -b ${wl}+h ${wl}$soname ${wl}+nodefaultrpath -o $lib $libobjs $deplibs $compiler_flags' + archive_cmds='$CC -b $wl+h $wl$soname $wl+nodefaultrpath -o $lib $libobjs $deplibs $compiler_flags' ;; *) @@ -9927,7 +10351,7 @@ if ${lt_cv_prog_compiler__b+:} false; then : $as_echo_n "(cached) " >&6 else lt_cv_prog_compiler__b=no - save_LDFLAGS="$LDFLAGS" + save_LDFLAGS=$LDFLAGS LDFLAGS="$LDFLAGS -b" echo "$lt_simple_link_test_code" > conftest.$ac_ext if (eval $ac_link 2>conftest.err) && test -s conftest$ac_exeext; then @@ -9946,14 +10370,14 @@ else fi fi $RM -r conftest* - LDFLAGS="$save_LDFLAGS" + LDFLAGS=$save_LDFLAGS fi { $as_echo "$as_me:${as_lineno-$LINENO}: result: $lt_cv_prog_compiler__b" >&5 $as_echo "$lt_cv_prog_compiler__b" >&6; } -if test x"$lt_cv_prog_compiler__b" = xyes; then - archive_cmds='$CC -b ${wl}+h ${wl}$soname ${wl}+b ${wl}$install_libdir -o $lib $libobjs $deplibs $compiler_flags' +if test yes = "$lt_cv_prog_compiler__b"; then + archive_cmds='$CC -b $wl+h $wl$soname $wl+b $wl$install_libdir -o $lib $libobjs $deplibs $compiler_flags' else archive_cmds='$LD -b +h $soname +b $install_libdir -o $lib $libobjs $deplibs $linker_flags' fi @@ -9961,8 +10385,8 @@ fi ;; esac fi - if test "$with_gnu_ld" = no; then - hardcode_libdir_flag_spec='${wl}+b ${wl}$libdir' + if test no = "$with_gnu_ld"; then + hardcode_libdir_flag_spec='$wl+b $wl$libdir' hardcode_libdir_separator=: case $host_cpu in @@ -9973,7 +10397,7 @@ fi *) hardcode_direct=yes hardcode_direct_absolute=yes - export_dynamic_flag_spec='${wl}-E' + export_dynamic_flag_spec='$wl-E' # hardcode_minus_L: Not really in the search PATH, # but as the default location of the library. @@ -9984,8 +10408,8 @@ fi ;; irix5* | irix6* | nonstopux*) - if test "$GCC" = yes; then - archive_cmds='$CC -shared $pic_flag $libobjs $deplibs $compiler_flags ${wl}-soname ${wl}$soname `test -n "$verstring" && func_echo_all "${wl}-set_version ${wl}$verstring"` ${wl}-update_registry ${wl}${output_objdir}/so_locations -o $lib' + if test yes = "$GCC"; then + archive_cmds='$CC -shared $pic_flag $libobjs $deplibs $compiler_flags $wl-soname $wl$soname `test -n "$verstring" && func_echo_all "$wl-set_version $wl$verstring"` $wl-update_registry $wl$output_objdir/so_locations -o $lib' # Try to use the -exported_symbol ld option, if it does not # work, assume that -exports_file does not work either and # implicitly export all symbols. @@ -9995,8 +10419,8 @@ $as_echo_n "checking whether the $host_os linker accepts -exported_symbol... " > if ${lt_cv_irix_exported_symbol+:} false; then : $as_echo_n "(cached) " >&6 else - save_LDFLAGS="$LDFLAGS" - LDFLAGS="$LDFLAGS -shared ${wl}-exported_symbol ${wl}foo ${wl}-update_registry ${wl}/dev/null" + save_LDFLAGS=$LDFLAGS + LDFLAGS="$LDFLAGS -shared $wl-exported_symbol ${wl}foo $wl-update_registry $wl/dev/null" cat confdefs.h - <<_ACEOF >conftest.$ac_ext /* end confdefs.h. */ int foo (void) { return 0; } @@ -10008,24 +10432,34 @@ else fi rm -f core conftest.err conftest.$ac_objext \ conftest$ac_exeext conftest.$ac_ext - LDFLAGS="$save_LDFLAGS" + LDFLAGS=$save_LDFLAGS fi { $as_echo "$as_me:${as_lineno-$LINENO}: result: $lt_cv_irix_exported_symbol" >&5 $as_echo "$lt_cv_irix_exported_symbol" >&6; } - if test "$lt_cv_irix_exported_symbol" = yes; then - archive_expsym_cmds='$CC -shared $pic_flag $libobjs $deplibs $compiler_flags ${wl}-soname ${wl}$soname `test -n "$verstring" && func_echo_all "${wl}-set_version ${wl}$verstring"` ${wl}-update_registry ${wl}${output_objdir}/so_locations ${wl}-exports_file ${wl}$export_symbols -o $lib' + if test yes = "$lt_cv_irix_exported_symbol"; then + archive_expsym_cmds='$CC -shared $pic_flag $libobjs $deplibs $compiler_flags $wl-soname $wl$soname `test -n "$verstring" && func_echo_all "$wl-set_version $wl$verstring"` $wl-update_registry $wl$output_objdir/so_locations $wl-exports_file $wl$export_symbols -o $lib' fi else - archive_cmds='$CC -shared $libobjs $deplibs $compiler_flags -soname $soname `test -n "$verstring" && func_echo_all "-set_version $verstring"` -update_registry ${output_objdir}/so_locations -o $lib' - archive_expsym_cmds='$CC -shared $libobjs $deplibs $compiler_flags -soname $soname `test -n "$verstring" && func_echo_all "-set_version $verstring"` -update_registry ${output_objdir}/so_locations -exports_file $export_symbols -o $lib' + archive_cmds='$CC -shared $libobjs $deplibs $compiler_flags -soname $soname `test -n "$verstring" && func_echo_all "-set_version $verstring"` -update_registry $output_objdir/so_locations -o $lib' + archive_expsym_cmds='$CC -shared $libobjs $deplibs $compiler_flags -soname $soname `test -n "$verstring" && func_echo_all "-set_version $verstring"` -update_registry $output_objdir/so_locations -exports_file $export_symbols -o $lib' fi archive_cmds_need_lc='no' - hardcode_libdir_flag_spec='${wl}-rpath ${wl}$libdir' + hardcode_libdir_flag_spec='$wl-rpath $wl$libdir' hardcode_libdir_separator=: inherit_rpath=yes link_all_deplibs=yes ;; + linux*) + case $cc_basename in + tcc*) + # Fabrice Bellard et al's Tiny C Compiler + ld_shlibs=yes + archive_cmds='$CC -shared $pic_flag -o $lib $libobjs $deplibs $compiler_flags' + ;; + esac + ;; + netbsd*) if echo __ELF__ | $CC -E - | $GREP __ELF__ >/dev/null; then archive_cmds='$LD -Bshareable -o $lib $libobjs $deplibs $linker_flags' # a.out @@ -10040,7 +10474,7 @@ $as_echo "$lt_cv_irix_exported_symbol" >&6; } newsos6) archive_cmds='$LD -G -h $soname -o $lib $libobjs $deplibs $linker_flags' hardcode_direct=yes - hardcode_libdir_flag_spec='${wl}-rpath ${wl}$libdir' + hardcode_libdir_flag_spec='$wl-rpath $wl$libdir' hardcode_libdir_separator=: hardcode_shlibpath_var=no ;; @@ -10048,27 +10482,19 @@ $as_echo "$lt_cv_irix_exported_symbol" >&6; } *nto* | *qnx*) ;; - openbsd*) + openbsd* | bitrig*) if test -f /usr/libexec/ld.so; then hardcode_direct=yes hardcode_shlibpath_var=no hardcode_direct_absolute=yes - if test -z "`echo __ELF__ | $CC -E - | $GREP __ELF__`" || test "$host_os-$host_cpu" = "openbsd2.8-powerpc"; then + if test -z "`echo __ELF__ | $CC -E - | $GREP __ELF__`"; then archive_cmds='$CC -shared $pic_flag -o $lib $libobjs $deplibs $compiler_flags' - archive_expsym_cmds='$CC -shared $pic_flag -o $lib $libobjs $deplibs $compiler_flags ${wl}-retain-symbols-file,$export_symbols' - hardcode_libdir_flag_spec='${wl}-rpath,$libdir' - export_dynamic_flag_spec='${wl}-E' + archive_expsym_cmds='$CC -shared $pic_flag -o $lib $libobjs $deplibs $compiler_flags $wl-retain-symbols-file,$export_symbols' + hardcode_libdir_flag_spec='$wl-rpath,$libdir' + export_dynamic_flag_spec='$wl-E' else - case $host_os in - openbsd[01].* | openbsd2.[0-7] | openbsd2.[0-7].*) - archive_cmds='$LD -Bshareable -o $lib $libobjs $deplibs $linker_flags' - hardcode_libdir_flag_spec='-R$libdir' - ;; - *) - archive_cmds='$CC -shared $pic_flag -o $lib $libobjs $deplibs $compiler_flags' - hardcode_libdir_flag_spec='${wl}-rpath,$libdir' - ;; - esac + archive_cmds='$CC -shared $pic_flag -o $lib $libobjs $deplibs $compiler_flags' + hardcode_libdir_flag_spec='$wl-rpath,$libdir' fi else ld_shlibs=no @@ -10079,33 +10505,53 @@ $as_echo "$lt_cv_irix_exported_symbol" >&6; } hardcode_libdir_flag_spec='-L$libdir' hardcode_minus_L=yes allow_undefined_flag=unsupported - archive_cmds='$ECHO "LIBRARY $libname INITINSTANCE" > $output_objdir/$libname.def~$ECHO "DESCRIPTION \"$libname\"" >> $output_objdir/$libname.def~echo DATA >> $output_objdir/$libname.def~echo " SINGLE NONSHARED" >> $output_objdir/$libname.def~echo EXPORTS >> $output_objdir/$libname.def~emxexp $libobjs >> $output_objdir/$libname.def~$CC -Zdll -Zcrtdll -o $lib $libobjs $deplibs $compiler_flags $output_objdir/$libname.def' - old_archive_from_new_cmds='emximp -o $output_objdir/$libname.a $output_objdir/$libname.def' + shrext_cmds=.dll + archive_cmds='$ECHO "LIBRARY ${soname%$shared_ext} INITINSTANCE TERMINSTANCE" > $output_objdir/$libname.def~ + $ECHO "DESCRIPTION \"$libname\"" >> $output_objdir/$libname.def~ + $ECHO "DATA MULTIPLE NONSHARED" >> $output_objdir/$libname.def~ + $ECHO EXPORTS >> $output_objdir/$libname.def~ + emxexp $libobjs | $SED /"_DLL_InitTerm"/d >> $output_objdir/$libname.def~ + $CC -Zdll -Zcrtdll -o $output_objdir/$soname $libobjs $deplibs $compiler_flags $output_objdir/$libname.def~ + emximp -o $lib $output_objdir/$libname.def' + archive_expsym_cmds='$ECHO "LIBRARY ${soname%$shared_ext} INITINSTANCE TERMINSTANCE" > $output_objdir/$libname.def~ + $ECHO "DESCRIPTION \"$libname\"" >> $output_objdir/$libname.def~ + $ECHO "DATA MULTIPLE NONSHARED" >> $output_objdir/$libname.def~ + $ECHO EXPORTS >> $output_objdir/$libname.def~ + prefix_cmds="$SED"~ + if test EXPORTS = "`$SED 1q $export_symbols`"; then + prefix_cmds="$prefix_cmds -e 1d"; + fi~ + prefix_cmds="$prefix_cmds -e \"s/^\(.*\)$/_\1/g\""~ + cat $export_symbols | $prefix_cmds >> $output_objdir/$libname.def~ + $CC -Zdll -Zcrtdll -o $output_objdir/$soname $libobjs $deplibs $compiler_flags $output_objdir/$libname.def~ + emximp -o $lib $output_objdir/$libname.def' + old_archive_From_new_cmds='emximp -o $output_objdir/${libname}_dll.a $output_objdir/$libname.def' + enable_shared_with_static_runtimes=yes ;; osf3*) - if test "$GCC" = yes; then - allow_undefined_flag=' ${wl}-expect_unresolved ${wl}\*' - archive_cmds='$CC -shared${allow_undefined_flag} $libobjs $deplibs $compiler_flags ${wl}-soname ${wl}$soname `test -n "$verstring" && func_echo_all "${wl}-set_version ${wl}$verstring"` ${wl}-update_registry ${wl}${output_objdir}/so_locations -o $lib' + if test yes = "$GCC"; then + allow_undefined_flag=' $wl-expect_unresolved $wl\*' + archive_cmds='$CC -shared$allow_undefined_flag $libobjs $deplibs $compiler_flags $wl-soname $wl$soname `test -n "$verstring" && func_echo_all "$wl-set_version $wl$verstring"` $wl-update_registry $wl$output_objdir/so_locations -o $lib' else allow_undefined_flag=' -expect_unresolved \*' - archive_cmds='$CC -shared${allow_undefined_flag} $libobjs $deplibs $compiler_flags -soname $soname `test -n "$verstring" && func_echo_all "-set_version $verstring"` -update_registry ${output_objdir}/so_locations -o $lib' + archive_cmds='$CC -shared$allow_undefined_flag $libobjs $deplibs $compiler_flags -soname $soname `test -n "$verstring" && func_echo_all "-set_version $verstring"` -update_registry $output_objdir/so_locations -o $lib' fi archive_cmds_need_lc='no' - hardcode_libdir_flag_spec='${wl}-rpath ${wl}$libdir' + hardcode_libdir_flag_spec='$wl-rpath $wl$libdir' hardcode_libdir_separator=: ;; osf4* | osf5*) # as osf3* with the addition of -msym flag - if test "$GCC" = yes; then - allow_undefined_flag=' ${wl}-expect_unresolved ${wl}\*' - archive_cmds='$CC -shared${allow_undefined_flag} $pic_flag $libobjs $deplibs $compiler_flags ${wl}-msym ${wl}-soname ${wl}$soname `test -n "$verstring" && func_echo_all "${wl}-set_version ${wl}$verstring"` ${wl}-update_registry ${wl}${output_objdir}/so_locations -o $lib' - hardcode_libdir_flag_spec='${wl}-rpath ${wl}$libdir' + if test yes = "$GCC"; then + allow_undefined_flag=' $wl-expect_unresolved $wl\*' + archive_cmds='$CC -shared$allow_undefined_flag $pic_flag $libobjs $deplibs $compiler_flags $wl-msym $wl-soname $wl$soname `test -n "$verstring" && func_echo_all "$wl-set_version $wl$verstring"` $wl-update_registry $wl$output_objdir/so_locations -o $lib' + hardcode_libdir_flag_spec='$wl-rpath $wl$libdir' else allow_undefined_flag=' -expect_unresolved \*' - archive_cmds='$CC -shared${allow_undefined_flag} $libobjs $deplibs $compiler_flags -msym -soname $soname `test -n "$verstring" && func_echo_all "-set_version $verstring"` -update_registry ${output_objdir}/so_locations -o $lib' + archive_cmds='$CC -shared$allow_undefined_flag $libobjs $deplibs $compiler_flags -msym -soname $soname `test -n "$verstring" && func_echo_all "-set_version $verstring"` -update_registry $output_objdir/so_locations -o $lib' archive_expsym_cmds='for i in `cat $export_symbols`; do printf "%s %s\\n" -exported_symbol "\$i" >> $lib.exp; done; printf "%s\\n" "-hidden">> $lib.exp~ - $CC -shared${allow_undefined_flag} ${wl}-input ${wl}$lib.exp $compiler_flags $libobjs $deplibs -soname $soname `test -n "$verstring" && $ECHO "-set_version $verstring"` -update_registry ${output_objdir}/so_locations -o $lib~$RM $lib.exp' + $CC -shared$allow_undefined_flag $wl-input $wl$lib.exp $compiler_flags $libobjs $deplibs -soname $soname `test -n "$verstring" && $ECHO "-set_version $verstring"` -update_registry $output_objdir/so_locations -o $lib~$RM $lib.exp' # Both c and cxx compiler support -rpath directly hardcode_libdir_flag_spec='-rpath $libdir' @@ -10116,24 +10562,24 @@ $as_echo "$lt_cv_irix_exported_symbol" >&6; } solaris*) no_undefined_flag=' -z defs' - if test "$GCC" = yes; then - wlarc='${wl}' - archive_cmds='$CC -shared $pic_flag ${wl}-z ${wl}text ${wl}-h ${wl}$soname -o $lib $libobjs $deplibs $compiler_flags' + if test yes = "$GCC"; then + wlarc='$wl' + archive_cmds='$CC -shared $pic_flag $wl-z ${wl}text $wl-h $wl$soname -o $lib $libobjs $deplibs $compiler_flags' archive_expsym_cmds='echo "{ global:" > $lib.exp~cat $export_symbols | $SED -e "s/\(.*\)/\1;/" >> $lib.exp~echo "local: *; };" >> $lib.exp~ - $CC -shared $pic_flag ${wl}-z ${wl}text ${wl}-M ${wl}$lib.exp ${wl}-h ${wl}$soname -o $lib $libobjs $deplibs $compiler_flags~$RM $lib.exp' + $CC -shared $pic_flag $wl-z ${wl}text $wl-M $wl$lib.exp $wl-h $wl$soname -o $lib $libobjs $deplibs $compiler_flags~$RM $lib.exp' else case `$CC -V 2>&1` in *"Compilers 5.0"*) wlarc='' - archive_cmds='$LD -G${allow_undefined_flag} -h $soname -o $lib $libobjs $deplibs $linker_flags' + archive_cmds='$LD -G$allow_undefined_flag -h $soname -o $lib $libobjs $deplibs $linker_flags' archive_expsym_cmds='echo "{ global:" > $lib.exp~cat $export_symbols | $SED -e "s/\(.*\)/\1;/" >> $lib.exp~echo "local: *; };" >> $lib.exp~ - $LD -G${allow_undefined_flag} -M $lib.exp -h $soname -o $lib $libobjs $deplibs $linker_flags~$RM $lib.exp' + $LD -G$allow_undefined_flag -M $lib.exp -h $soname -o $lib $libobjs $deplibs $linker_flags~$RM $lib.exp' ;; *) - wlarc='${wl}' - archive_cmds='$CC -G${allow_undefined_flag} -h $soname -o $lib $libobjs $deplibs $compiler_flags' + wlarc='$wl' + archive_cmds='$CC -G$allow_undefined_flag -h $soname -o $lib $libobjs $deplibs $compiler_flags' archive_expsym_cmds='echo "{ global:" > $lib.exp~cat $export_symbols | $SED -e "s/\(.*\)/\1;/" >> $lib.exp~echo "local: *; };" >> $lib.exp~ - $CC -G${allow_undefined_flag} -M $lib.exp -h $soname -o $lib $libobjs $deplibs $compiler_flags~$RM $lib.exp' + $CC -G$allow_undefined_flag -M $lib.exp -h $soname -o $lib $libobjs $deplibs $compiler_flags~$RM $lib.exp' ;; esac fi @@ -10143,11 +10589,11 @@ $as_echo "$lt_cv_irix_exported_symbol" >&6; } solaris2.[0-5] | solaris2.[0-5].*) ;; *) # The compiler driver will combine and reorder linker options, - # but understands `-z linker_flag'. GCC discards it without `$wl', + # but understands '-z linker_flag'. GCC discards it without '$wl', # but is careful enough not to reorder. # Supported since Solaris 2.6 (maybe 2.5.1?) - if test "$GCC" = yes; then - whole_archive_flag_spec='${wl}-z ${wl}allextract$convenience ${wl}-z ${wl}defaultextract' + if test yes = "$GCC"; then + whole_archive_flag_spec='$wl-z ${wl}allextract$convenience $wl-z ${wl}defaultextract' else whole_archive_flag_spec='-z allextract$convenience -z defaultextract' fi @@ -10157,10 +10603,10 @@ $as_echo "$lt_cv_irix_exported_symbol" >&6; } ;; sunos4*) - if test "x$host_vendor" = xsequent; then + if test sequent = "$host_vendor"; then # Use $CC to link under sequent, because it throws in some extra .o # files that make .init and .fini sections work. - archive_cmds='$CC -G ${wl}-h $soname -o $lib $libobjs $deplibs $compiler_flags' + archive_cmds='$CC -G $wl-h $soname -o $lib $libobjs $deplibs $compiler_flags' else archive_cmds='$LD -assert pure-text -Bstatic -o $lib $libobjs $deplibs $linker_flags' fi @@ -10209,43 +10655,43 @@ $as_echo "$lt_cv_irix_exported_symbol" >&6; } ;; sysv4*uw2* | sysv5OpenUNIX* | sysv5UnixWare7.[01].[10]* | unixware7* | sco3.2v5.0.[024]*) - no_undefined_flag='${wl}-z,text' + no_undefined_flag='$wl-z,text' archive_cmds_need_lc=no hardcode_shlibpath_var=no runpath_var='LD_RUN_PATH' - if test "$GCC" = yes; then - archive_cmds='$CC -shared ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' - archive_expsym_cmds='$CC -shared ${wl}-Bexport:$export_symbols ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + if test yes = "$GCC"; then + archive_cmds='$CC -shared $wl-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + archive_expsym_cmds='$CC -shared $wl-Bexport:$export_symbols $wl-h,$soname -o $lib $libobjs $deplibs $compiler_flags' else - archive_cmds='$CC -G ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' - archive_expsym_cmds='$CC -G ${wl}-Bexport:$export_symbols ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + archive_cmds='$CC -G $wl-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + archive_expsym_cmds='$CC -G $wl-Bexport:$export_symbols $wl-h,$soname -o $lib $libobjs $deplibs $compiler_flags' fi ;; sysv5* | sco3.2v5* | sco5v6*) - # Note: We can NOT use -z defs as we might desire, because we do not + # Note: We CANNOT use -z defs as we might desire, because we do not # link with -lc, and that would cause any symbols used from libc to # always be unresolved, which means just about no library would # ever link correctly. If we're not using GNU ld we use -z text # though, which does catch some bad symbols but isn't as heavy-handed # as -z defs. - no_undefined_flag='${wl}-z,text' - allow_undefined_flag='${wl}-z,nodefs' + no_undefined_flag='$wl-z,text' + allow_undefined_flag='$wl-z,nodefs' archive_cmds_need_lc=no hardcode_shlibpath_var=no - hardcode_libdir_flag_spec='${wl}-R,$libdir' + hardcode_libdir_flag_spec='$wl-R,$libdir' hardcode_libdir_separator=':' link_all_deplibs=yes - export_dynamic_flag_spec='${wl}-Bexport' + export_dynamic_flag_spec='$wl-Bexport' runpath_var='LD_RUN_PATH' - if test "$GCC" = yes; then - archive_cmds='$CC -shared ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' - archive_expsym_cmds='$CC -shared ${wl}-Bexport:$export_symbols ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + if test yes = "$GCC"; then + archive_cmds='$CC -shared $wl-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + archive_expsym_cmds='$CC -shared $wl-Bexport:$export_symbols $wl-h,$soname -o $lib $libobjs $deplibs $compiler_flags' else - archive_cmds='$CC -G ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' - archive_expsym_cmds='$CC -G ${wl}-Bexport:$export_symbols ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + archive_cmds='$CC -G $wl-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + archive_expsym_cmds='$CC -G $wl-Bexport:$export_symbols $wl-h,$soname -o $lib $libobjs $deplibs $compiler_flags' fi ;; @@ -10260,10 +10706,10 @@ $as_echo "$lt_cv_irix_exported_symbol" >&6; } ;; esac - if test x$host_vendor = xsni; then + if test sni = "$host_vendor"; then case $host in sysv4 | sysv4.2uw2* | sysv4.3* | sysv5*) - export_dynamic_flag_spec='${wl}-Blargedynsym' + export_dynamic_flag_spec='$wl-Blargedynsym' ;; esac fi @@ -10271,7 +10717,7 @@ $as_echo "$lt_cv_irix_exported_symbol" >&6; } { $as_echo "$as_me:${as_lineno-$LINENO}: result: $ld_shlibs" >&5 $as_echo "$ld_shlibs" >&6; } -test "$ld_shlibs" = no && can_build_shared=no +test no = "$ld_shlibs" && can_build_shared=no with_gnu_ld=$with_gnu_ld @@ -10297,7 +10743,7 @@ x|xyes) # Assume -lc should be added archive_cmds_need_lc=yes - if test "$enable_shared" = yes && test "$GCC" = yes; then + if test yes,yes = "$GCC,$enable_shared"; then case $archive_cmds in *'~'*) # FIXME: we may have to deal with multi-command sequences. @@ -10512,14 +10958,14 @@ esac { $as_echo "$as_me:${as_lineno-$LINENO}: checking dynamic linker characteristics" >&5 $as_echo_n "checking dynamic linker characteristics... " >&6; } -if test "$GCC" = yes; then +if test yes = "$GCC"; then case $host_os in - darwin*) lt_awk_arg="/^libraries:/,/LR/" ;; - *) lt_awk_arg="/^libraries:/" ;; + darwin*) lt_awk_arg='/^libraries:/,/LR/' ;; + *) lt_awk_arg='/^libraries:/' ;; esac case $host_os in - mingw* | cegcc*) lt_sed_strip_eq="s,=\([A-Za-z]:\),\1,g" ;; - *) lt_sed_strip_eq="s,=/,/,g" ;; + mingw* | cegcc*) lt_sed_strip_eq='s|=\([A-Za-z]:\)|\1|g' ;; + *) lt_sed_strip_eq='s|=/|/|g' ;; esac lt_search_path_spec=`$CC -print-search-dirs | awk $lt_awk_arg | $SED -e "s/^libraries://" -e $lt_sed_strip_eq` case $lt_search_path_spec in @@ -10535,28 +10981,35 @@ if test "$GCC" = yes; then ;; esac # Ok, now we have the path, separated by spaces, we can step through it - # and add multilib dir if necessary. + # and add multilib dir if necessary... lt_tmp_lt_search_path_spec= - lt_multi_os_dir=`$CC $CPPFLAGS $CFLAGS $LDFLAGS -print-multi-os-directory 2>/dev/null` + lt_multi_os_dir=/`$CC $CPPFLAGS $CFLAGS $LDFLAGS -print-multi-os-directory 2>/dev/null` + # ...but if some path component already ends with the multilib dir we assume + # that all is fine and trust -print-search-dirs as is (GCC 4.2? or newer). + case "$lt_multi_os_dir; $lt_search_path_spec " in + "/; "* | "/.; "* | "/./; "* | *"$lt_multi_os_dir "* | *"$lt_multi_os_dir/ "*) + lt_multi_os_dir= + ;; + esac for lt_sys_path in $lt_search_path_spec; do - if test -d "$lt_sys_path/$lt_multi_os_dir"; then - lt_tmp_lt_search_path_spec="$lt_tmp_lt_search_path_spec $lt_sys_path/$lt_multi_os_dir" - else + if test -d "$lt_sys_path$lt_multi_os_dir"; then + lt_tmp_lt_search_path_spec="$lt_tmp_lt_search_path_spec $lt_sys_path$lt_multi_os_dir" + elif test -n "$lt_multi_os_dir"; then test -d "$lt_sys_path" && \ lt_tmp_lt_search_path_spec="$lt_tmp_lt_search_path_spec $lt_sys_path" fi done lt_search_path_spec=`$ECHO "$lt_tmp_lt_search_path_spec" | awk ' -BEGIN {RS=" "; FS="/|\n";} { - lt_foo=""; - lt_count=0; +BEGIN {RS = " "; FS = "/|\n";} { + lt_foo = ""; + lt_count = 0; for (lt_i = NF; lt_i > 0; lt_i--) { if ($lt_i != "" && $lt_i != ".") { if ($lt_i == "..") { lt_count++; } else { if (lt_count == 0) { - lt_foo="/" $lt_i lt_foo; + lt_foo = "/" $lt_i lt_foo; } else { lt_count--; } @@ -10570,7 +11023,7 @@ BEGIN {RS=" "; FS="/|\n";} { # for these hosts. case $host_os in mingw* | cegcc*) lt_search_path_spec=`$ECHO "$lt_search_path_spec" |\ - $SED 's,/\([A-Za-z]:\),\1,g'` ;; + $SED 's|/\([A-Za-z]:\)|\1|g'` ;; esac sys_lib_search_path_spec=`$ECHO "$lt_search_path_spec" | $lt_NL2SP` else @@ -10579,7 +11032,7 @@ fi library_names_spec= libname_spec='lib$name' soname_spec= -shrext_cmds=".so" +shrext_cmds=.so postinstall_cmds= postuninstall_cmds= finish_cmds= @@ -10596,14 +11049,16 @@ hardcode_into_libs=no # flags to be left without arguments need_version=unknown + + case $host_os in aix3*) version_type=linux # correct to gnu/linux during the next big refactor - library_names_spec='${libname}${release}${shared_ext}$versuffix $libname.a' + library_names_spec='$libname$release$shared_ext$versuffix $libname.a' shlibpath_var=LIBPATH # AIX 3 has no versioning support, so we append a major version to the name. - soname_spec='${libname}${release}${shared_ext}$major' + soname_spec='$libname$release$shared_ext$major' ;; aix[4-9]*) @@ -10611,41 +11066,91 @@ aix[4-9]*) need_lib_prefix=no need_version=no hardcode_into_libs=yes - if test "$host_cpu" = ia64; then + if test ia64 = "$host_cpu"; then # AIX 5 supports IA64 - library_names_spec='${libname}${release}${shared_ext}$major ${libname}${release}${shared_ext}$versuffix $libname${shared_ext}' + library_names_spec='$libname$release$shared_ext$major $libname$release$shared_ext$versuffix $libname$shared_ext' shlibpath_var=LD_LIBRARY_PATH else # With GCC up to 2.95.x, collect2 would create an import file # for dependence libraries. The import file would start with - # the line `#! .'. This would cause the generated library to - # depend on `.', always an invalid library. This was fixed in + # the line '#! .'. This would cause the generated library to + # depend on '.', always an invalid library. This was fixed in # development snapshots of GCC prior to 3.0. case $host_os in aix4 | aix4.[01] | aix4.[01].*) if { echo '#if __GNUC__ > 2 || (__GNUC__ == 2 && __GNUC_MINOR__ >= 97)' echo ' yes ' - echo '#endif'; } | ${CC} -E - | $GREP yes > /dev/null; then + echo '#endif'; } | $CC -E - | $GREP yes > /dev/null; then : else can_build_shared=no fi ;; esac - # AIX (on Power*) has no versioning support, so currently we can not hardcode correct + # Using Import Files as archive members, it is possible to support + # filename-based versioning of shared library archives on AIX. While + # this would work for both with and without runtime linking, it will + # prevent static linking of such archives. So we do filename-based + # shared library versioning with .so extension only, which is used + # when both runtime linking and shared linking is enabled. + # Unfortunately, runtime linking may impact performance, so we do + # not want this to be the default eventually. Also, we use the + # versioned .so libs for executables only if there is the -brtl + # linker flag in LDFLAGS as well, or --with-aix-soname=svr4 only. + # To allow for filename-based versioning support, we need to create + # libNAME.so.V as an archive file, containing: + # *) an Import File, referring to the versioned filename of the + # archive as well as the shared archive member, telling the + # bitwidth (32 or 64) of that shared object, and providing the + # list of exported symbols of that shared object, eventually + # decorated with the 'weak' keyword + # *) the shared object with the F_LOADONLY flag set, to really avoid + # it being seen by the linker. + # At run time we better use the real file rather than another symlink, + # but for link time we create the symlink libNAME.so -> libNAME.so.V + + case $with_aix_soname,$aix_use_runtimelinking in + # AIX (on Power*) has no versioning support, so currently we cannot hardcode correct # soname into executable. Probably we can add versioning support to # collect2, so additional links can be useful in future. - if test "$aix_use_runtimelinking" = yes; then + aix,yes) # traditional libtool + dynamic_linker='AIX unversionable lib.so' # If using run time linking (on AIX 4.2 or later) use lib.so # instead of lib.a to let people know that these are not # typical AIX shared libraries. - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' - else + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$shared_ext' + ;; + aix,no) # traditional AIX only + dynamic_linker='AIX lib.a(lib.so.V)' # We preserve .a as extension for shared libraries through AIX4.2 # and later when we are not doing run time linking. - library_names_spec='${libname}${release}.a $libname.a' - soname_spec='${libname}${release}${shared_ext}$major' - fi + library_names_spec='$libname$release.a $libname.a' + soname_spec='$libname$release$shared_ext$major' + ;; + svr4,*) # full svr4 only + dynamic_linker="AIX lib.so.V($shared_archive_member_spec.o)" + library_names_spec='$libname$release$shared_ext$major $libname$shared_ext' + # We do not specify a path in Import Files, so LIBPATH fires. + shlibpath_overrides_runpath=yes + ;; + *,yes) # both, prefer svr4 + dynamic_linker="AIX lib.so.V($shared_archive_member_spec.o), lib.a(lib.so.V)" + library_names_spec='$libname$release$shared_ext$major $libname$shared_ext' + # unpreferred sharedlib libNAME.a needs extra handling + postinstall_cmds='test -n "$linkname" || linkname="$realname"~func_stripname "" ".so" "$linkname"~$install_shared_prog "$dir/$func_stripname_result.$libext" "$destdir/$func_stripname_result.$libext"~test -z "$tstripme" || test -z "$striplib" || $striplib "$destdir/$func_stripname_result.$libext"' + postuninstall_cmds='for n in $library_names $old_library; do :; done~func_stripname "" ".so" "$n"~test "$func_stripname_result" = "$n" || func_append rmfiles " $odir/$func_stripname_result.$libext"' + # We do not specify a path in Import Files, so LIBPATH fires. + shlibpath_overrides_runpath=yes + ;; + *,no) # both, prefer aix + dynamic_linker="AIX lib.a(lib.so.V), lib.so.V($shared_archive_member_spec.o)" + library_names_spec='$libname$release.a $libname.a' + soname_spec='$libname$release$shared_ext$major' + # unpreferred sharedlib libNAME.so.V and symlink libNAME.so need extra handling + postinstall_cmds='test -z "$dlname" || $install_shared_prog $dir/$dlname $destdir/$dlname~test -z "$tstripme" || test -z "$striplib" || $striplib $destdir/$dlname~test -n "$linkname" || linkname=$realname~func_stripname "" ".a" "$linkname"~(cd "$destdir" && $LN_S -f $dlname $func_stripname_result.so)' + postuninstall_cmds='test -z "$dlname" || func_append rmfiles " $odir/$dlname"~for n in $old_library $library_names; do :; done~func_stripname "" ".a" "$n"~func_append rmfiles " $odir/$func_stripname_result.so"' + ;; + esac shlibpath_var=LIBPATH fi ;; @@ -10655,18 +11160,18 @@ amigaos*) powerpc) # Since July 2007 AmigaOS4 officially supports .so libraries. # When compiling the executable, add -use-dynld -Lsobjs: to the compileline. - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$shared_ext' ;; m68k) library_names_spec='$libname.ixlibrary $libname.a' # Create ${libname}_ixlibrary.a entries in /sys/libs. - finish_eval='for lib in `ls $libdir/*.ixlibrary 2>/dev/null`; do libname=`func_echo_all "$lib" | $SED '\''s%^.*/\([^/]*\)\.ixlibrary$%\1%'\''`; test $RM /sys/libs/${libname}_ixlibrary.a; $show "cd /sys/libs && $LN_S $lib ${libname}_ixlibrary.a"; cd /sys/libs && $LN_S $lib ${libname}_ixlibrary.a || exit 1; done' + finish_eval='for lib in `ls $libdir/*.ixlibrary 2>/dev/null`; do libname=`func_echo_all "$lib" | $SED '\''s%^.*/\([^/]*\)\.ixlibrary$%\1%'\''`; $RM /sys/libs/${libname}_ixlibrary.a; $show "cd /sys/libs && $LN_S $lib ${libname}_ixlibrary.a"; cd /sys/libs && $LN_S $lib ${libname}_ixlibrary.a || exit 1; done' ;; esac ;; beos*) - library_names_spec='${libname}${shared_ext}' + library_names_spec='$libname$shared_ext' dynamic_linker="$host_os ld.so" shlibpath_var=LIBRARY_PATH ;; @@ -10674,8 +11179,8 @@ beos*) bsdi[45]*) version_type=linux # correct to gnu/linux during the next big refactor need_version=no - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' - soname_spec='${libname}${release}${shared_ext}$major' + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$shared_ext' + soname_spec='$libname$release$shared_ext$major' finish_cmds='PATH="\$PATH:/sbin" ldconfig $libdir' shlibpath_var=LD_LIBRARY_PATH sys_lib_search_path_spec="/shlib /usr/lib /usr/X11/lib /usr/contrib/lib /lib /usr/local/lib" @@ -10687,7 +11192,7 @@ bsdi[45]*) cygwin* | mingw* | pw32* | cegcc*) version_type=windows - shrext_cmds=".dll" + shrext_cmds=.dll need_version=no need_lib_prefix=no @@ -10696,8 +11201,8 @@ cygwin* | mingw* | pw32* | cegcc*) # gcc library_names_spec='$libname.dll.a' # DLL is installed to $(libdir)/../bin by postinstall_cmds - postinstall_cmds='base_file=`basename \${file}`~ - dlpath=`$SHELL 2>&1 -c '\''. $dir/'\''\${base_file}'\''i; echo \$dlname'\''`~ + postinstall_cmds='base_file=`basename \$file`~ + dlpath=`$SHELL 2>&1 -c '\''. $dir/'\''\$base_file'\''i; echo \$dlname'\''`~ dldir=$destdir/`dirname \$dlpath`~ test -d \$dldir || mkdir -p \$dldir~ $install_prog $dir/$dlname \$dldir/$dlname~ @@ -10713,17 +11218,17 @@ cygwin* | mingw* | pw32* | cegcc*) case $host_os in cygwin*) # Cygwin DLLs use 'cyg' prefix rather than 'lib' - soname_spec='`echo ${libname} | sed -e 's/^lib/cyg/'``echo ${release} | $SED -e 's/[.]/-/g'`${versuffix}${shared_ext}' + soname_spec='`echo $libname | sed -e 's/^lib/cyg/'``echo $release | $SED -e 's/[.]/-/g'`$versuffix$shared_ext' sys_lib_search_path_spec="$sys_lib_search_path_spec /usr/lib/w32api" ;; mingw* | cegcc*) # MinGW DLLs use traditional 'lib' prefix - soname_spec='${libname}`echo ${release} | $SED -e 's/[.]/-/g'`${versuffix}${shared_ext}' + soname_spec='$libname`echo $release | $SED -e 's/[.]/-/g'`$versuffix$shared_ext' ;; pw32*) # pw32 DLLs use 'pw' prefix rather than 'lib' - library_names_spec='`echo ${libname} | sed -e 's/^lib/pw/'``echo ${release} | $SED -e 's/[.]/-/g'`${versuffix}${shared_ext}' + library_names_spec='`echo $libname | sed -e 's/^lib/pw/'``echo $release | $SED -e 's/[.]/-/g'`$versuffix$shared_ext' ;; esac dynamic_linker='Win32 ld.exe' @@ -10732,8 +11237,8 @@ cygwin* | mingw* | pw32* | cegcc*) *,cl*) # Native MSVC libname_spec='$name' - soname_spec='${libname}`echo ${release} | $SED -e 's/[.]/-/g'`${versuffix}${shared_ext}' - library_names_spec='${libname}.dll.lib' + soname_spec='$libname`echo $release | $SED -e 's/[.]/-/g'`$versuffix$shared_ext' + library_names_spec='$libname.dll.lib' case $build_os in mingw*) @@ -10760,7 +11265,7 @@ cygwin* | mingw* | pw32* | cegcc*) sys_lib_search_path_spec=`cygpath --path --unix "$sys_lib_search_path_spec" | $SED -e "s/$PATH_SEPARATOR/ /g"` ;; *) - sys_lib_search_path_spec="$LIB" + sys_lib_search_path_spec=$LIB if $ECHO "$sys_lib_search_path_spec" | $GREP ';[c-zC-Z]:/' >/dev/null; then # It is most probably a Windows format PATH. sys_lib_search_path_spec=`$ECHO "$sys_lib_search_path_spec" | $SED -e 's/;/ /g'` @@ -10773,8 +11278,8 @@ cygwin* | mingw* | pw32* | cegcc*) esac # DLL is installed to $(libdir)/../bin by postinstall_cmds - postinstall_cmds='base_file=`basename \${file}`~ - dlpath=`$SHELL 2>&1 -c '\''. $dir/'\''\${base_file}'\''i; echo \$dlname'\''`~ + postinstall_cmds='base_file=`basename \$file`~ + dlpath=`$SHELL 2>&1 -c '\''. $dir/'\''\$base_file'\''i; echo \$dlname'\''`~ dldir=$destdir/`dirname \$dlpath`~ test -d \$dldir || mkdir -p \$dldir~ $install_prog $dir/$dlname \$dldir/$dlname' @@ -10787,7 +11292,7 @@ cygwin* | mingw* | pw32* | cegcc*) *) # Assume MSVC wrapper - library_names_spec='${libname}`echo ${release} | $SED -e 's/[.]/-/g'`${versuffix}${shared_ext} $libname.lib' + library_names_spec='$libname`echo $release | $SED -e 's/[.]/-/g'`$versuffix$shared_ext $libname.lib' dynamic_linker='Win32 ld.exe' ;; esac @@ -10800,8 +11305,8 @@ darwin* | rhapsody*) version_type=darwin need_lib_prefix=no need_version=no - library_names_spec='${libname}${release}${major}$shared_ext ${libname}$shared_ext' - soname_spec='${libname}${release}${major}$shared_ext' + library_names_spec='$libname$release$major$shared_ext $libname$shared_ext' + soname_spec='$libname$release$major$shared_ext' shlibpath_overrides_runpath=yes shlibpath_var=DYLD_LIBRARY_PATH shrext_cmds='`test .$module = .yes && echo .so || echo .dylib`' @@ -10814,8 +11319,8 @@ dgux*) version_type=linux # correct to gnu/linux during the next big refactor need_lib_prefix=no need_version=no - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname$shared_ext' - soname_spec='${libname}${release}${shared_ext}$major' + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$shared_ext' + soname_spec='$libname$release$shared_ext$major' shlibpath_var=LD_LIBRARY_PATH ;; @@ -10833,12 +11338,13 @@ freebsd* | dragonfly*) version_type=freebsd-$objformat case $version_type in freebsd-elf*) - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext} $libname${shared_ext}' + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$shared_ext' + soname_spec='$libname$release$shared_ext$major' need_version=no need_lib_prefix=no ;; freebsd-*) - library_names_spec='${libname}${release}${shared_ext}$versuffix $libname${shared_ext}$versuffix' + library_names_spec='$libname$release$shared_ext$versuffix $libname$shared_ext$versuffix' need_version=yes ;; esac @@ -10863,26 +11369,15 @@ freebsd* | dragonfly*) esac ;; -gnu*) - version_type=linux # correct to gnu/linux during the next big refactor - need_lib_prefix=no - need_version=no - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}${major} ${libname}${shared_ext}' - soname_spec='${libname}${release}${shared_ext}$major' - shlibpath_var=LD_LIBRARY_PATH - shlibpath_overrides_runpath=no - hardcode_into_libs=yes - ;; - haiku*) version_type=linux # correct to gnu/linux during the next big refactor need_lib_prefix=no need_version=no dynamic_linker="$host_os runtime_loader" - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}${major} ${libname}${shared_ext}' - soname_spec='${libname}${release}${shared_ext}$major' + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$shared_ext' + soname_spec='$libname$release$shared_ext$major' shlibpath_var=LIBRARY_PATH - shlibpath_overrides_runpath=yes + shlibpath_overrides_runpath=no sys_lib_dlsearch_path_spec='/boot/home/config/lib /boot/common/lib /boot/system/lib' hardcode_into_libs=yes ;; @@ -10900,14 +11395,15 @@ hpux9* | hpux10* | hpux11*) dynamic_linker="$host_os dld.so" shlibpath_var=LD_LIBRARY_PATH shlibpath_overrides_runpath=yes # Unless +noenvvar is specified. - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' - soname_spec='${libname}${release}${shared_ext}$major' - if test "X$HPUX_IA64_MODE" = X32; then + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$shared_ext' + soname_spec='$libname$release$shared_ext$major' + if test 32 = "$HPUX_IA64_MODE"; then sys_lib_search_path_spec="/usr/lib/hpux32 /usr/local/lib/hpux32 /usr/local/lib" + sys_lib_dlsearch_path_spec=/usr/lib/hpux32 else sys_lib_search_path_spec="/usr/lib/hpux64 /usr/local/lib/hpux64" + sys_lib_dlsearch_path_spec=/usr/lib/hpux64 fi - sys_lib_dlsearch_path_spec=$sys_lib_search_path_spec ;; hppa*64*) shrext_cmds='.sl' @@ -10915,8 +11411,8 @@ hpux9* | hpux10* | hpux11*) dynamic_linker="$host_os dld.sl" shlibpath_var=LD_LIBRARY_PATH # How should we handle SHLIB_PATH shlibpath_overrides_runpath=yes # Unless +noenvvar is specified. - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' - soname_spec='${libname}${release}${shared_ext}$major' + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$shared_ext' + soname_spec='$libname$release$shared_ext$major' sys_lib_search_path_spec="/usr/lib/pa20_64 /usr/ccs/lib/pa20_64" sys_lib_dlsearch_path_spec=$sys_lib_search_path_spec ;; @@ -10925,8 +11421,8 @@ hpux9* | hpux10* | hpux11*) dynamic_linker="$host_os dld.sl" shlibpath_var=SHLIB_PATH shlibpath_overrides_runpath=no # +s is required to enable SHLIB_PATH - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' - soname_spec='${libname}${release}${shared_ext}$major' + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$shared_ext' + soname_spec='$libname$release$shared_ext$major' ;; esac # HP-UX runs *really* slowly unless shared libraries are mode 555, ... @@ -10939,8 +11435,8 @@ interix[3-9]*) version_type=linux # correct to gnu/linux during the next big refactor need_lib_prefix=no need_version=no - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major ${libname}${shared_ext}' - soname_spec='${libname}${release}${shared_ext}$major' + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$shared_ext' + soname_spec='$libname$release$shared_ext$major' dynamic_linker='Interix 3.x ld.so.1 (PE, like ELF)' shlibpath_var=LD_LIBRARY_PATH shlibpath_overrides_runpath=no @@ -10951,7 +11447,7 @@ irix5* | irix6* | nonstopux*) case $host_os in nonstopux*) version_type=nonstopux ;; *) - if test "$lt_cv_prog_gnu_ld" = yes; then + if test yes = "$lt_cv_prog_gnu_ld"; then version_type=linux # correct to gnu/linux during the next big refactor else version_type=irix @@ -10959,8 +11455,8 @@ irix5* | irix6* | nonstopux*) esac need_lib_prefix=no need_version=no - soname_spec='${libname}${release}${shared_ext}$major' - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major ${libname}${release}${shared_ext} $libname${shared_ext}' + soname_spec='$libname$release$shared_ext$major' + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$release$shared_ext $libname$shared_ext' case $host_os in irix5* | nonstopux*) libsuff= shlibsuff= @@ -10979,8 +11475,8 @@ irix5* | irix6* | nonstopux*) esac shlibpath_var=LD_LIBRARY${shlibsuff}_PATH shlibpath_overrides_runpath=no - sys_lib_search_path_spec="/usr/lib${libsuff} /lib${libsuff} /usr/local/lib${libsuff}" - sys_lib_dlsearch_path_spec="/usr/lib${libsuff} /lib${libsuff}" + sys_lib_search_path_spec="/usr/lib$libsuff /lib$libsuff /usr/local/lib$libsuff" + sys_lib_dlsearch_path_spec="/usr/lib$libsuff /lib$libsuff" hardcode_into_libs=yes ;; @@ -10989,13 +11485,33 @@ linux*oldld* | linux*aout* | linux*coff*) dynamic_linker=no ;; +linux*android*) + version_type=none # Android doesn't support versioned libraries. + need_lib_prefix=no + need_version=no + library_names_spec='$libname$release$shared_ext' + soname_spec='$libname$release$shared_ext' + finish_cmds= + shlibpath_var=LD_LIBRARY_PATH + shlibpath_overrides_runpath=yes + + # This implies no fast_install, which is unacceptable. + # Some rework will be needed to allow for fast_install + # before this can be enabled. + hardcode_into_libs=yes + + dynamic_linker='Android linker' + # Don't embed -rpath directories since the linker doesn't support them. + hardcode_libdir_flag_spec='-L$libdir' + ;; + # This must be glibc/ELF. -linux* | k*bsd*-gnu | kopensolaris*-gnu) +linux* | k*bsd*-gnu | kopensolaris*-gnu | gnu*) version_type=linux # correct to gnu/linux during the next big refactor need_lib_prefix=no need_version=no - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' - soname_spec='${libname}${release}${shared_ext}$major' + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$shared_ext' + soname_spec='$libname$release$shared_ext$major' finish_cmds='PATH="\$PATH:/sbin" ldconfig -n $libdir' shlibpath_var=LD_LIBRARY_PATH shlibpath_overrides_runpath=no @@ -11042,11 +11558,15 @@ fi # Add ABI-specific directories to the system library path. sys_lib_dlsearch_path_spec="/lib64 /usr/lib64 /lib /usr/lib" - # Append ld.so.conf contents to the search path + # Ideally, we could use ldconfig to report *all* directores which are + # searched for libraries, however this is still not possible. Aside from not + # being certain /sbin/ldconfig is available, command + # 'ldconfig -N -X -v | grep ^/' on 64bit Fedora does not report /usr/lib64, + # even though it is searched at run-time. Try to do the best guess by + # appending ld.so.conf contents (and includes) to the search path. if test -f /etc/ld.so.conf; then lt_ld_extra=`awk '/^include / { system(sprintf("cd /etc; cat %s 2>/dev/null", \$2)); skip = 1; } { if (!skip) print \$0; skip = 0; }' < /etc/ld.so.conf | $SED -e 's/#.*//;/^[ ]*hwcap[ ]/d;s/[:, ]/ /g;s/=[^=]*$//;s/=[^= ]* / /g;s/"//g;/^$/d' | tr '\n' ' '` sys_lib_dlsearch_path_spec="$sys_lib_dlsearch_path_spec $lt_ld_extra" - fi # We used to test for /lib/ld.so.1 and disable shared libraries on @@ -11063,12 +11583,12 @@ netbsd*) need_lib_prefix=no need_version=no if echo __ELF__ | $CC -E - | $GREP __ELF__ >/dev/null; then - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${shared_ext}$versuffix' + library_names_spec='$libname$release$shared_ext$versuffix $libname$shared_ext$versuffix' finish_cmds='PATH="\$PATH:/sbin" ldconfig -m $libdir' dynamic_linker='NetBSD (a.out) ld.so' else - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major ${libname}${shared_ext}' - soname_spec='${libname}${release}${shared_ext}$major' + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$shared_ext' + soname_spec='$libname$release$shared_ext$major' dynamic_linker='NetBSD ld.elf_so' fi shlibpath_var=LD_LIBRARY_PATH @@ -11078,7 +11598,7 @@ netbsd*) newsos6) version_type=linux # correct to gnu/linux during the next big refactor - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$shared_ext' shlibpath_var=LD_LIBRARY_PATH shlibpath_overrides_runpath=yes ;; @@ -11087,58 +11607,68 @@ newsos6) version_type=qnx need_lib_prefix=no need_version=no - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' - soname_spec='${libname}${release}${shared_ext}$major' + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$shared_ext' + soname_spec='$libname$release$shared_ext$major' shlibpath_var=LD_LIBRARY_PATH shlibpath_overrides_runpath=no hardcode_into_libs=yes dynamic_linker='ldqnx.so' ;; -openbsd*) +openbsd* | bitrig*) version_type=sunos - sys_lib_dlsearch_path_spec="/usr/lib" + sys_lib_dlsearch_path_spec=/usr/lib need_lib_prefix=no - # Some older versions of OpenBSD (3.3 at least) *do* need versioned libs. - case $host_os in - openbsd3.3 | openbsd3.3.*) need_version=yes ;; - *) need_version=no ;; - esac - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${shared_ext}$versuffix' + if test -z "`echo __ELF__ | $CC -E - | $GREP __ELF__`"; then + need_version=no + else + need_version=yes + fi + library_names_spec='$libname$release$shared_ext$versuffix $libname$shared_ext$versuffix' finish_cmds='PATH="\$PATH:/sbin" ldconfig -m $libdir' shlibpath_var=LD_LIBRARY_PATH - if test -z "`echo __ELF__ | $CC -E - | $GREP __ELF__`" || test "$host_os-$host_cpu" = "openbsd2.8-powerpc"; then - case $host_os in - openbsd2.[89] | openbsd2.[89].*) - shlibpath_overrides_runpath=no - ;; - *) - shlibpath_overrides_runpath=yes - ;; - esac - else - shlibpath_overrides_runpath=yes - fi + shlibpath_overrides_runpath=yes ;; os2*) libname_spec='$name' - shrext_cmds=".dll" + version_type=windows + shrext_cmds=.dll + need_version=no need_lib_prefix=no - library_names_spec='$libname${shared_ext} $libname.a' + # OS/2 can only load a DLL with a base name of 8 characters or less. + soname_spec='`test -n "$os2dllname" && libname="$os2dllname"; + v=$($ECHO $release$versuffix | tr -d .-); + n=$($ECHO $libname | cut -b -$((8 - ${#v})) | tr . _); + $ECHO $n$v`$shared_ext' + library_names_spec='${libname}_dll.$libext' dynamic_linker='OS/2 ld.exe' - shlibpath_var=LIBPATH + shlibpath_var=BEGINLIBPATH + sys_lib_search_path_spec="/lib /usr/lib /usr/local/lib" + sys_lib_dlsearch_path_spec=$sys_lib_search_path_spec + postinstall_cmds='base_file=`basename \$file`~ + dlpath=`$SHELL 2>&1 -c '\''. $dir/'\''\$base_file'\''i; $ECHO \$dlname'\''`~ + dldir=$destdir/`dirname \$dlpath`~ + test -d \$dldir || mkdir -p \$dldir~ + $install_prog $dir/$dlname \$dldir/$dlname~ + chmod a+x \$dldir/$dlname~ + if test -n '\''$stripme'\'' && test -n '\''$striplib'\''; then + eval '\''$striplib \$dldir/$dlname'\'' || exit \$?; + fi' + postuninstall_cmds='dldll=`$SHELL 2>&1 -c '\''. $file; $ECHO \$dlname'\''`~ + dlpath=$dir/\$dldll~ + $RM \$dlpath' ;; osf3* | osf4* | osf5*) version_type=osf need_lib_prefix=no need_version=no - soname_spec='${libname}${release}${shared_ext}$major' - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' + soname_spec='$libname$release$shared_ext$major' + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$shared_ext' shlibpath_var=LD_LIBRARY_PATH sys_lib_search_path_spec="/usr/shlib /usr/ccs/lib /usr/lib/cmplrs/cc /usr/lib /usr/local/lib /var/shlib" - sys_lib_dlsearch_path_spec="$sys_lib_search_path_spec" + sys_lib_dlsearch_path_spec=$sys_lib_search_path_spec ;; rdos*) @@ -11149,8 +11679,8 @@ solaris*) version_type=linux # correct to gnu/linux during the next big refactor need_lib_prefix=no need_version=no - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' - soname_spec='${libname}${release}${shared_ext}$major' + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$shared_ext' + soname_spec='$libname$release$shared_ext$major' shlibpath_var=LD_LIBRARY_PATH shlibpath_overrides_runpath=yes hardcode_into_libs=yes @@ -11160,11 +11690,11 @@ solaris*) sunos4*) version_type=sunos - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${shared_ext}$versuffix' + library_names_spec='$libname$release$shared_ext$versuffix $libname$shared_ext$versuffix' finish_cmds='PATH="\$PATH:/usr/etc" ldconfig $libdir' shlibpath_var=LD_LIBRARY_PATH shlibpath_overrides_runpath=yes - if test "$with_gnu_ld" = yes; then + if test yes = "$with_gnu_ld"; then need_lib_prefix=no fi need_version=yes @@ -11172,8 +11702,8 @@ sunos4*) sysv4 | sysv4.3*) version_type=linux # correct to gnu/linux during the next big refactor - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' - soname_spec='${libname}${release}${shared_ext}$major' + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$shared_ext' + soname_spec='$libname$release$shared_ext$major' shlibpath_var=LD_LIBRARY_PATH case $host_vendor in sni) @@ -11194,24 +11724,24 @@ sysv4 | sysv4.3*) ;; sysv4*MP*) - if test -d /usr/nec ;then + if test -d /usr/nec; then version_type=linux # correct to gnu/linux during the next big refactor - library_names_spec='$libname${shared_ext}.$versuffix $libname${shared_ext}.$major $libname${shared_ext}' - soname_spec='$libname${shared_ext}.$major' + library_names_spec='$libname$shared_ext.$versuffix $libname$shared_ext.$major $libname$shared_ext' + soname_spec='$libname$shared_ext.$major' shlibpath_var=LD_LIBRARY_PATH fi ;; sysv5* | sco3.2v5* | sco5v6* | unixware* | OpenUNIX* | sysv4*uw2*) - version_type=freebsd-elf + version_type=sco need_lib_prefix=no need_version=no - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext} $libname${shared_ext}' - soname_spec='${libname}${release}${shared_ext}$major' + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext $libname$shared_ext' + soname_spec='$libname$release$shared_ext$major' shlibpath_var=LD_LIBRARY_PATH shlibpath_overrides_runpath=yes hardcode_into_libs=yes - if test "$with_gnu_ld" = yes; then + if test yes = "$with_gnu_ld"; then sys_lib_search_path_spec='/usr/local/lib /usr/gnu/lib /usr/ccs/lib /usr/lib /lib' else sys_lib_search_path_spec='/usr/ccs/lib /usr/lib' @@ -11229,7 +11759,7 @@ tpf*) version_type=linux # correct to gnu/linux during the next big refactor need_lib_prefix=no need_version=no - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$shared_ext' shlibpath_var=LD_LIBRARY_PATH shlibpath_overrides_runpath=no hardcode_into_libs=yes @@ -11237,8 +11767,8 @@ tpf*) uts4*) version_type=linux # correct to gnu/linux during the next big refactor - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' - soname_spec='${libname}${release}${shared_ext}$major' + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$shared_ext' + soname_spec='$libname$release$shared_ext$major' shlibpath_var=LD_LIBRARY_PATH ;; @@ -11248,20 +11778,35 @@ uts4*) esac { $as_echo "$as_me:${as_lineno-$LINENO}: result: $dynamic_linker" >&5 $as_echo "$dynamic_linker" >&6; } -test "$dynamic_linker" = no && can_build_shared=no +test no = "$dynamic_linker" && can_build_shared=no variables_saved_for_relink="PATH $shlibpath_var $runpath_var" -if test "$GCC" = yes; then +if test yes = "$GCC"; then variables_saved_for_relink="$variables_saved_for_relink GCC_EXEC_PREFIX COMPILER_PATH LIBRARY_PATH" fi -if test "${lt_cv_sys_lib_search_path_spec+set}" = set; then - sys_lib_search_path_spec="$lt_cv_sys_lib_search_path_spec" +if test set = "${lt_cv_sys_lib_search_path_spec+set}"; then + sys_lib_search_path_spec=$lt_cv_sys_lib_search_path_spec fi -if test "${lt_cv_sys_lib_dlsearch_path_spec+set}" = set; then - sys_lib_dlsearch_path_spec="$lt_cv_sys_lib_dlsearch_path_spec" + +if test set = "${lt_cv_sys_lib_dlsearch_path_spec+set}"; then + sys_lib_dlsearch_path_spec=$lt_cv_sys_lib_dlsearch_path_spec fi +# remember unaugmented sys_lib_dlsearch_path content for libtool script decls... +configure_time_dlsearch_path=$sys_lib_dlsearch_path_spec + +# ... but it needs LT_SYS_LIBRARY_PATH munging for other configure-time code +func_munge_path_list sys_lib_dlsearch_path_spec "$LT_SYS_LIBRARY_PATH" + +# to be used as default LT_SYS_LIBRARY_PATH value in generated libtool +configure_time_lt_sys_library_path=$LT_SYS_LIBRARY_PATH + + + + + + @@ -11358,15 +11903,15 @@ $as_echo_n "checking how to hardcode library paths into programs... " >&6; } hardcode_action= if test -n "$hardcode_libdir_flag_spec" || test -n "$runpath_var" || - test "X$hardcode_automatic" = "Xyes" ; then + test yes = "$hardcode_automatic"; then # We can hardcode non-existent directories. - if test "$hardcode_direct" != no && + if test no != "$hardcode_direct" && # If the only mechanism to avoid hardcoding is shlibpath_var, we # have to relink, otherwise we might link with an installed library # when we should be linking with a yet-to-be-installed one - ## test "$_LT_TAGVAR(hardcode_shlibpath_var, )" != no && - test "$hardcode_minus_L" != no; then + ## test no != "$_LT_TAGVAR(hardcode_shlibpath_var, )" && + test no != "$hardcode_minus_L"; then # Linking always hardcodes the temporary library directory. hardcode_action=relink else @@ -11381,12 +11926,12 @@ fi { $as_echo "$as_me:${as_lineno-$LINENO}: result: $hardcode_action" >&5 $as_echo "$hardcode_action" >&6; } -if test "$hardcode_action" = relink || - test "$inherit_rpath" = yes; then +if test relink = "$hardcode_action" || + test yes = "$inherit_rpath"; then # Fast installation is not supported enable_fast_install=no -elif test "$shlibpath_overrides_runpath" = yes || - test "$enable_shared" = no; then +elif test yes = "$shlibpath_overrides_runpath" || + test no = "$enable_shared"; then # Fast installation is not necessary enable_fast_install=needless fi @@ -11396,7 +11941,7 @@ fi - if test "x$enable_dlopen" != xyes; then + if test yes != "$enable_dlopen"; then enable_dlopen=unknown enable_dlopen_self=unknown enable_dlopen_self_static=unknown @@ -11406,23 +11951,23 @@ else case $host_os in beos*) - lt_cv_dlopen="load_add_on" + lt_cv_dlopen=load_add_on lt_cv_dlopen_libs= lt_cv_dlopen_self=yes ;; mingw* | pw32* | cegcc*) - lt_cv_dlopen="LoadLibrary" + lt_cv_dlopen=LoadLibrary lt_cv_dlopen_libs= ;; cygwin*) - lt_cv_dlopen="dlopen" + lt_cv_dlopen=dlopen lt_cv_dlopen_libs= ;; darwin*) - # if libdl is installed we need to link against it + # if libdl is installed we need to link against it { $as_echo "$as_me:${as_lineno-$LINENO}: checking for dlopen in -ldl" >&5 $as_echo_n "checking for dlopen in -ldl... " >&6; } if ${ac_cv_lib_dl_dlopen+:} false; then : @@ -11460,10 +12005,10 @@ fi { $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_cv_lib_dl_dlopen" >&5 $as_echo "$ac_cv_lib_dl_dlopen" >&6; } if test "x$ac_cv_lib_dl_dlopen" = xyes; then : - lt_cv_dlopen="dlopen" lt_cv_dlopen_libs="-ldl" + lt_cv_dlopen=dlopen lt_cv_dlopen_libs=-ldl else - lt_cv_dlopen="dyld" + lt_cv_dlopen=dyld lt_cv_dlopen_libs= lt_cv_dlopen_self=yes @@ -11471,10 +12016,18 @@ fi ;; + tpf*) + # Don't try to run any link tests for TPF. We know it's impossible + # because TPF is a cross-compiler, and we know how we open DSOs. + lt_cv_dlopen=dlopen + lt_cv_dlopen_libs= + lt_cv_dlopen_self=no + ;; + *) ac_fn_c_check_func "$LINENO" "shl_load" "ac_cv_func_shl_load" if test "x$ac_cv_func_shl_load" = xyes; then : - lt_cv_dlopen="shl_load" + lt_cv_dlopen=shl_load else { $as_echo "$as_me:${as_lineno-$LINENO}: checking for shl_load in -ldld" >&5 $as_echo_n "checking for shl_load in -ldld... " >&6; } @@ -11513,11 +12066,11 @@ fi { $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_cv_lib_dld_shl_load" >&5 $as_echo "$ac_cv_lib_dld_shl_load" >&6; } if test "x$ac_cv_lib_dld_shl_load" = xyes; then : - lt_cv_dlopen="shl_load" lt_cv_dlopen_libs="-ldld" + lt_cv_dlopen=shl_load lt_cv_dlopen_libs=-ldld else ac_fn_c_check_func "$LINENO" "dlopen" "ac_cv_func_dlopen" if test "x$ac_cv_func_dlopen" = xyes; then : - lt_cv_dlopen="dlopen" + lt_cv_dlopen=dlopen else { $as_echo "$as_me:${as_lineno-$LINENO}: checking for dlopen in -ldl" >&5 $as_echo_n "checking for dlopen in -ldl... " >&6; } @@ -11556,7 +12109,7 @@ fi { $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_cv_lib_dl_dlopen" >&5 $as_echo "$ac_cv_lib_dl_dlopen" >&6; } if test "x$ac_cv_lib_dl_dlopen" = xyes; then : - lt_cv_dlopen="dlopen" lt_cv_dlopen_libs="-ldl" + lt_cv_dlopen=dlopen lt_cv_dlopen_libs=-ldl else { $as_echo "$as_me:${as_lineno-$LINENO}: checking for dlopen in -lsvld" >&5 $as_echo_n "checking for dlopen in -lsvld... " >&6; } @@ -11595,7 +12148,7 @@ fi { $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_cv_lib_svld_dlopen" >&5 $as_echo "$ac_cv_lib_svld_dlopen" >&6; } if test "x$ac_cv_lib_svld_dlopen" = xyes; then : - lt_cv_dlopen="dlopen" lt_cv_dlopen_libs="-lsvld" + lt_cv_dlopen=dlopen lt_cv_dlopen_libs=-lsvld else { $as_echo "$as_me:${as_lineno-$LINENO}: checking for dld_link in -ldld" >&5 $as_echo_n "checking for dld_link in -ldld... " >&6; } @@ -11634,7 +12187,7 @@ fi { $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_cv_lib_dld_dld_link" >&5 $as_echo "$ac_cv_lib_dld_dld_link" >&6; } if test "x$ac_cv_lib_dld_dld_link" = xyes; then : - lt_cv_dlopen="dld_link" lt_cv_dlopen_libs="-ldld" + lt_cv_dlopen=dld_link lt_cv_dlopen_libs=-ldld fi @@ -11655,21 +12208,21 @@ fi ;; esac - if test "x$lt_cv_dlopen" != xno; then - enable_dlopen=yes - else + if test no = "$lt_cv_dlopen"; then enable_dlopen=no + else + enable_dlopen=yes fi case $lt_cv_dlopen in dlopen) - save_CPPFLAGS="$CPPFLAGS" - test "x$ac_cv_header_dlfcn_h" = xyes && CPPFLAGS="$CPPFLAGS -DHAVE_DLFCN_H" + save_CPPFLAGS=$CPPFLAGS + test yes = "$ac_cv_header_dlfcn_h" && CPPFLAGS="$CPPFLAGS -DHAVE_DLFCN_H" - save_LDFLAGS="$LDFLAGS" + save_LDFLAGS=$LDFLAGS wl=$lt_prog_compiler_wl eval LDFLAGS=\"\$LDFLAGS $export_dynamic_flag_spec\" - save_LIBS="$LIBS" + save_LIBS=$LIBS LIBS="$lt_cv_dlopen_libs $LIBS" { $as_echo "$as_me:${as_lineno-$LINENO}: checking whether a program can dlopen itself" >&5 @@ -11677,7 +12230,7 @@ $as_echo_n "checking whether a program can dlopen itself... " >&6; } if ${lt_cv_dlopen_self+:} false; then : $as_echo_n "(cached) " >&6 else - if test "$cross_compiling" = yes; then : + if test yes = "$cross_compiling"; then : lt_cv_dlopen_self=cross else lt_dlunknown=0; lt_dlno_uscore=1; lt_dlneed_uscore=2 @@ -11724,9 +12277,9 @@ else # endif #endif -/* When -fvisbility=hidden is used, assume the code has been annotated +/* When -fvisibility=hidden is used, assume the code has been annotated correspondingly for the symbols needed. */ -#if defined(__GNUC__) && (((__GNUC__ == 3) && (__GNUC_MINOR__ >= 3)) || (__GNUC__ > 3)) +#if defined __GNUC__ && (((__GNUC__ == 3) && (__GNUC_MINOR__ >= 3)) || (__GNUC__ > 3)) int fnord () __attribute__((visibility("default"))); #endif @@ -11756,7 +12309,7 @@ _LT_EOF (eval $ac_link) 2>&5 ac_status=$? $as_echo "$as_me:${as_lineno-$LINENO}: \$? = $ac_status" >&5 - test $ac_status = 0; } && test -s conftest${ac_exeext} 2>/dev/null; then + test $ac_status = 0; } && test -s "conftest$ac_exeext" 2>/dev/null; then (./conftest; exit; ) >&5 2>/dev/null lt_status=$? case x$lt_status in @@ -11776,14 +12329,14 @@ fi { $as_echo "$as_me:${as_lineno-$LINENO}: result: $lt_cv_dlopen_self" >&5 $as_echo "$lt_cv_dlopen_self" >&6; } - if test "x$lt_cv_dlopen_self" = xyes; then + if test yes = "$lt_cv_dlopen_self"; then wl=$lt_prog_compiler_wl eval LDFLAGS=\"\$LDFLAGS $lt_prog_compiler_static\" { $as_echo "$as_me:${as_lineno-$LINENO}: checking whether a statically linked program can dlopen itself" >&5 $as_echo_n "checking whether a statically linked program can dlopen itself... " >&6; } if ${lt_cv_dlopen_self_static+:} false; then : $as_echo_n "(cached) " >&6 else - if test "$cross_compiling" = yes; then : + if test yes = "$cross_compiling"; then : lt_cv_dlopen_self_static=cross else lt_dlunknown=0; lt_dlno_uscore=1; lt_dlneed_uscore=2 @@ -11830,9 +12383,9 @@ else # endif #endif -/* When -fvisbility=hidden is used, assume the code has been annotated +/* When -fvisibility=hidden is used, assume the code has been annotated correspondingly for the symbols needed. */ -#if defined(__GNUC__) && (((__GNUC__ == 3) && (__GNUC_MINOR__ >= 3)) || (__GNUC__ > 3)) +#if defined __GNUC__ && (((__GNUC__ == 3) && (__GNUC_MINOR__ >= 3)) || (__GNUC__ > 3)) int fnord () __attribute__((visibility("default"))); #endif @@ -11862,7 +12415,7 @@ _LT_EOF (eval $ac_link) 2>&5 ac_status=$? $as_echo "$as_me:${as_lineno-$LINENO}: \$? = $ac_status" >&5 - test $ac_status = 0; } && test -s conftest${ac_exeext} 2>/dev/null; then + test $ac_status = 0; } && test -s "conftest$ac_exeext" 2>/dev/null; then (./conftest; exit; ) >&5 2>/dev/null lt_status=$? case x$lt_status in @@ -11883,9 +12436,9 @@ fi $as_echo "$lt_cv_dlopen_self_static" >&6; } fi - CPPFLAGS="$save_CPPFLAGS" - LDFLAGS="$save_LDFLAGS" - LIBS="$save_LIBS" + CPPFLAGS=$save_CPPFLAGS + LDFLAGS=$save_LDFLAGS + LIBS=$save_LIBS ;; esac @@ -11929,7 +12482,7 @@ else # FIXME - insert some real tests, host_os isn't really good enough case $host_os in darwin*) - if test -n "$STRIP" ; then + if test -n "$STRIP"; then striplib="$STRIP -x" old_striplib="$STRIP -S" { $as_echo "$as_me:${as_lineno-$LINENO}: result: yes" >&5 @@ -11957,7 +12510,7 @@ fi - # Report which library types will actually be built + # Report what library types will actually be built { $as_echo "$as_me:${as_lineno-$LINENO}: checking if libtool supports shared libraries" >&5 $as_echo_n "checking if libtool supports shared libraries... " >&6; } { $as_echo "$as_me:${as_lineno-$LINENO}: result: $can_build_shared" >&5 @@ -11965,13 +12518,13 @@ $as_echo "$can_build_shared" >&6; } { $as_echo "$as_me:${as_lineno-$LINENO}: checking whether to build shared libraries" >&5 $as_echo_n "checking whether to build shared libraries... " >&6; } - test "$can_build_shared" = "no" && enable_shared=no + test no = "$can_build_shared" && enable_shared=no # On AIX, shared libraries and static libraries use the same namespace, and # are all built from PIC. case $host_os in aix3*) - test "$enable_shared" = yes && enable_static=no + test yes = "$enable_shared" && enable_static=no if test -n "$RANLIB"; then archive_cmds="$archive_cmds~\$RANLIB \$lib" postinstall_cmds='$RANLIB $lib' @@ -11979,8 +12532,12 @@ $as_echo_n "checking whether to build shared libraries... " >&6; } ;; aix[4-9]*) - if test "$host_cpu" != ia64 && test "$aix_use_runtimelinking" = no ; then - test "$enable_shared" = yes && enable_static=no + if test ia64 != "$host_cpu"; then + case $enable_shared,$with_aix_soname,$aix_use_runtimelinking in + yes,aix,yes) ;; # shared object as lib.so file only + yes,svr4,*) ;; # shared object as lib.so archive member only + yes,*) enable_static=no ;; # shared object in lib.a archive as well + esac fi ;; esac @@ -11990,7 +12547,7 @@ $as_echo "$enable_shared" >&6; } { $as_echo "$as_me:${as_lineno-$LINENO}: checking whether to build static libraries" >&5 $as_echo_n "checking whether to build static libraries... " >&6; } # Make sure either enable_shared or enable_static is yes. - test "$enable_shared" = yes || enable_static=yes + test yes = "$enable_shared" || enable_static=yes { $as_echo "$as_me:${as_lineno-$LINENO}: result: $enable_static" >&5 $as_echo "$enable_static" >&6; } @@ -12004,11 +12561,11 @@ ac_compile='$CC -c $CFLAGS $CPPFLAGS conftest.$ac_ext >&5' ac_link='$CC -o conftest$ac_exeext $CFLAGS $CPPFLAGS $LDFLAGS conftest.$ac_ext $LIBS >&5' ac_compiler_gnu=$ac_cv_c_compiler_gnu -CC="$lt_save_CC" +CC=$lt_save_CC - if test -n "$CXX" && ( test "X$CXX" != "Xno" && - ( (test "X$CXX" = "Xg++" && `g++ -v >/dev/null 2>&1` ) || - (test "X$CXX" != "Xg++"))) ; then + if test -n "$CXX" && ( test no != "$CXX" && + ( (test g++ = "$CXX" && `g++ -v >/dev/null 2>&1` ) || + (test g++ != "$CXX"))); then ac_ext=cpp ac_cpp='$CXXCPP $CPPFLAGS' ac_compile='$CXX -c $CXXFLAGS $CPPFLAGS conftest.$ac_ext >&5' @@ -12187,7 +12744,7 @@ objext_CXX=$objext # the CXX compiler isn't working. Some variables (like enable_shared) # are currently assumed to apply to all compilers on this platform, # and will be corrupted by setting them based on a non-working compiler. -if test "$_lt_caught_CXX_error" != yes; then +if test yes != "$_lt_caught_CXX_error"; then # Code to be used in simple compile tests lt_simple_compile_test_code="int some_variable = 0;" @@ -12248,46 +12805,39 @@ $RM -r conftest* CFLAGS=$CXXFLAGS compiler=$CC compiler_CXX=$CC - for cc_temp in $compiler""; do - case $cc_temp in - compile | *[\\/]compile | ccache | *[\\/]ccache ) ;; - distcc | *[\\/]distcc | purify | *[\\/]purify ) ;; - \-*) ;; - *) break;; - esac -done -cc_basename=`$ECHO "$cc_temp" | $SED "s%.*/%%; s%^$host_alias-%%"` + func_cc_basename $compiler +cc_basename=$func_cc_basename_result if test -n "$compiler"; then # We don't want -fno-exception when compiling C++ code, so set the # no_builtin_flag separately - if test "$GXX" = yes; then + if test yes = "$GXX"; then lt_prog_compiler_no_builtin_flag_CXX=' -fno-builtin' else lt_prog_compiler_no_builtin_flag_CXX= fi - if test "$GXX" = yes; then + if test yes = "$GXX"; then # Set up default GNU C++ configuration # Check whether --with-gnu-ld was given. if test "${with_gnu_ld+set}" = set; then : - withval=$with_gnu_ld; test "$withval" = no || with_gnu_ld=yes + withval=$with_gnu_ld; test no = "$withval" || with_gnu_ld=yes else with_gnu_ld=no fi ac_prog=ld -if test "$GCC" = yes; then +if test yes = "$GCC"; then # Check if gcc -print-prog-name=ld gives a path. { $as_echo "$as_me:${as_lineno-$LINENO}: checking for ld used by $CC" >&5 $as_echo_n "checking for ld used by $CC... " >&6; } case $host in *-*-mingw*) - # gcc leaves a trailing carriage return which upsets mingw + # gcc leaves a trailing carriage return, which upsets mingw ac_prog=`($CC -print-prog-name=ld) 2>&5 | tr -d '\015'` ;; *) ac_prog=`($CC -print-prog-name=ld) 2>&5` ;; @@ -12301,7 +12851,7 @@ $as_echo_n "checking for ld used by $CC... " >&6; } while $ECHO "$ac_prog" | $GREP "$re_direlt" > /dev/null 2>&1; do ac_prog=`$ECHO $ac_prog| $SED "s%$re_direlt%/%"` done - test -z "$LD" && LD="$ac_prog" + test -z "$LD" && LD=$ac_prog ;; "") # If it fails, then pretend we aren't using GCC. @@ -12312,7 +12862,7 @@ $as_echo_n "checking for ld used by $CC... " >&6; } with_gnu_ld=unknown ;; esac -elif test "$with_gnu_ld" = yes; then +elif test yes = "$with_gnu_ld"; then { $as_echo "$as_me:${as_lineno-$LINENO}: checking for GNU ld" >&5 $as_echo_n "checking for GNU ld... " >&6; } else @@ -12323,32 +12873,32 @@ if ${lt_cv_path_LD+:} false; then : $as_echo_n "(cached) " >&6 else if test -z "$LD"; then - lt_save_ifs="$IFS"; IFS=$PATH_SEPARATOR + lt_save_ifs=$IFS; IFS=$PATH_SEPARATOR for ac_dir in $PATH; do - IFS="$lt_save_ifs" + IFS=$lt_save_ifs test -z "$ac_dir" && ac_dir=. if test -f "$ac_dir/$ac_prog" || test -f "$ac_dir/$ac_prog$ac_exeext"; then - lt_cv_path_LD="$ac_dir/$ac_prog" + lt_cv_path_LD=$ac_dir/$ac_prog # Check to see if the program is GNU ld. I'd rather use --version, # but apparently some variants of GNU ld only accept -v. # Break only if it was the GNU/non-GNU ld that we prefer. case `"$lt_cv_path_LD" -v 2>&1 &5 $as_echo "$LD" >&6; } @@ -12384,22 +12934,22 @@ with_gnu_ld=$lt_cv_prog_gnu_ld # Check if GNU C++ uses GNU ld as the underlying linker, since the # archiving commands below assume that GNU ld is being used. - if test "$with_gnu_ld" = yes; then - archive_cmds_CXX='$CC $pic_flag -shared -nostdlib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-soname $wl$soname -o $lib' - archive_expsym_cmds_CXX='$CC $pic_flag -shared -nostdlib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-soname $wl$soname ${wl}-retain-symbols-file $wl$export_symbols -o $lib' + if test yes = "$with_gnu_ld"; then + archive_cmds_CXX='$CC $pic_flag -shared -nostdlib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags $wl-soname $wl$soname -o $lib' + archive_expsym_cmds_CXX='$CC $pic_flag -shared -nostdlib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags $wl-soname $wl$soname $wl-retain-symbols-file $wl$export_symbols -o $lib' - hardcode_libdir_flag_spec_CXX='${wl}-rpath ${wl}$libdir' - export_dynamic_flag_spec_CXX='${wl}--export-dynamic' + hardcode_libdir_flag_spec_CXX='$wl-rpath $wl$libdir' + export_dynamic_flag_spec_CXX='$wl--export-dynamic' # If archive_cmds runs LD, not CC, wlarc should be empty # XXX I think wlarc can be eliminated in ltcf-cxx, but I need to # investigate it a little bit more. (MM) - wlarc='${wl}' + wlarc='$wl' # ancient GNU ld didn't support --whole-archive et. al. if eval "`$CC -print-prog-name=ld` --help 2>&1" | $GREP 'no-whole-archive' > /dev/null; then - whole_archive_flag_spec_CXX="$wlarc"'--whole-archive$convenience '"$wlarc"'--no-whole-archive' + whole_archive_flag_spec_CXX=$wlarc'--whole-archive$convenience '$wlarc'--no-whole-archive' else whole_archive_flag_spec_CXX= fi @@ -12436,18 +12986,30 @@ $as_echo_n "checking whether the $compiler linker ($LD) supports shared librarie ld_shlibs_CXX=no ;; aix[4-9]*) - if test "$host_cpu" = ia64; then + if test ia64 = "$host_cpu"; then # On IA64, the linker does run time linking by default, so we don't # have to do anything special. aix_use_runtimelinking=no exp_sym_flag='-Bexport' - no_entry_flag="" + no_entry_flag= else aix_use_runtimelinking=no # Test if we are trying to use run time linking or normal # AIX style linking. If -brtl is somewhere in LDFLAGS, we - # need to do runtime linking. + # have runtime linking enabled, and use it for executables. + # For shared libraries, we enable/disable runtime linking + # depending on the kind of the shared library created - + # when "with_aix_soname,aix_use_runtimelinking" is: + # "aix,no" lib.a(lib.so.V) shared, rtl:no, for executables + # "aix,yes" lib.so shared, rtl:yes, for executables + # lib.a static archive + # "both,no" lib.so.V(shr.o) shared, rtl:yes + # lib.a(lib.so.V) shared, rtl:no, for executables + # "both,yes" lib.so.V(shr.o) shared, rtl:yes, for executables + # lib.a(lib.so.V) shared, rtl:no + # "svr4,*" lib.so.V(shr.o) shared, rtl:yes, for executables + # lib.a static archive case $host_os in aix4.[23]|aix4.[23].*|aix[5-9]*) for ld_flag in $LDFLAGS; do case $ld_flag in @@ -12457,6 +13019,13 @@ $as_echo_n "checking whether the $compiler linker ($LD) supports shared librarie ;; esac done + if test svr4,no = "$with_aix_soname,$aix_use_runtimelinking"; then + # With aix-soname=svr4, we create the lib.so.V shared archives only, + # so we don't have lib.a shared libs to link our executables. + # We have to force runtime linking in this case. + aix_use_runtimelinking=yes + LDFLAGS="$LDFLAGS -Wl,-brtl" + fi ;; esac @@ -12475,13 +13044,21 @@ $as_echo_n "checking whether the $compiler linker ($LD) supports shared librarie hardcode_direct_absolute_CXX=yes hardcode_libdir_separator_CXX=':' link_all_deplibs_CXX=yes - file_list_spec_CXX='${wl}-f,' + file_list_spec_CXX='$wl-f,' + case $with_aix_soname,$aix_use_runtimelinking in + aix,*) ;; # no import file + svr4,* | *,yes) # use import file + # The Import File defines what to hardcode. + hardcode_direct_CXX=no + hardcode_direct_absolute_CXX=no + ;; + esac - if test "$GXX" = yes; then + if test yes = "$GXX"; then case $host_os in aix4.[012]|aix4.[012].*) # We only want to do this on AIX 4.2 and lower, the check # below for broken collect2 doesn't work under 4.3+ - collect2name=`${CC} -print-prog-name=collect2` + collect2name=`$CC -print-prog-name=collect2` if test -f "$collect2name" && strings "$collect2name" | $GREP resolve_lib_name >/dev/null then @@ -12499,36 +13076,44 @@ $as_echo_n "checking whether the $compiler linker ($LD) supports shared librarie fi esac shared_flag='-shared' - if test "$aix_use_runtimelinking" = yes; then - shared_flag="$shared_flag "'${wl}-G' + if test yes = "$aix_use_runtimelinking"; then + shared_flag=$shared_flag' $wl-G' fi + # Need to ensure runtime linking is disabled for the traditional + # shared library, or the linker may eventually find shared libraries + # /with/ Import File - we do not want to mix them. + shared_flag_aix='-shared' + shared_flag_svr4='-shared $wl-G' else # not using gcc - if test "$host_cpu" = ia64; then + if test ia64 = "$host_cpu"; then # VisualAge C++, Version 5.5 for AIX 5L for IA-64, Beta 3 Release # chokes on -Wl,-G. The following line is correct: shared_flag='-G' else - if test "$aix_use_runtimelinking" = yes; then - shared_flag='${wl}-G' + if test yes = "$aix_use_runtimelinking"; then + shared_flag='$wl-G' else - shared_flag='${wl}-bM:SRE' + shared_flag='$wl-bM:SRE' fi + shared_flag_aix='$wl-bM:SRE' + shared_flag_svr4='$wl-G' fi fi - export_dynamic_flag_spec_CXX='${wl}-bexpall' + export_dynamic_flag_spec_CXX='$wl-bexpall' # It seems that -bexpall does not export symbols beginning with # underscore (_), so it is better to generate a list of symbols to # export. always_export_symbols_CXX=yes - if test "$aix_use_runtimelinking" = yes; then + if test aix,yes = "$with_aix_soname,$aix_use_runtimelinking"; then # Warning - without using the other runtime loading flags (-brtl), # -berok will link without error, but may produce a broken library. - allow_undefined_flag_CXX='-berok' + # The "-G" linker flag allows undefined symbols. + no_undefined_flag_CXX='-bernotok' # Determine the default libpath from the value encoded in an empty # executable. - if test "${lt_cv_aix_libpath+set}" = set; then + if test set = "${lt_cv_aix_libpath+set}"; then aix_libpath=$lt_cv_aix_libpath else if ${lt_cv_aix_libpath__CXX+:} false; then : @@ -12563,7 +13148,7 @@ fi rm -f core conftest.err conftest.$ac_objext \ conftest$ac_exeext conftest.$ac_ext if test -z "$lt_cv_aix_libpath__CXX"; then - lt_cv_aix_libpath__CXX="/usr/lib:/lib" + lt_cv_aix_libpath__CXX=/usr/lib:/lib fi fi @@ -12571,18 +13156,18 @@ fi aix_libpath=$lt_cv_aix_libpath__CXX fi - hardcode_libdir_flag_spec_CXX='${wl}-blibpath:$libdir:'"$aix_libpath" + hardcode_libdir_flag_spec_CXX='$wl-blibpath:$libdir:'"$aix_libpath" - archive_expsym_cmds_CXX='$CC -o $output_objdir/$soname $libobjs $deplibs '"\${wl}$no_entry_flag"' $compiler_flags `if test "x${allow_undefined_flag}" != "x"; then func_echo_all "${wl}${allow_undefined_flag}"; else :; fi` '"\${wl}$exp_sym_flag:\$export_symbols $shared_flag" + archive_expsym_cmds_CXX='$CC -o $output_objdir/$soname $libobjs $deplibs $wl'$no_entry_flag' $compiler_flags `if test -n "$allow_undefined_flag"; then func_echo_all "$wl$allow_undefined_flag"; else :; fi` $wl'$exp_sym_flag:\$export_symbols' '$shared_flag else - if test "$host_cpu" = ia64; then - hardcode_libdir_flag_spec_CXX='${wl}-R $libdir:/usr/lib:/lib' + if test ia64 = "$host_cpu"; then + hardcode_libdir_flag_spec_CXX='$wl-R $libdir:/usr/lib:/lib' allow_undefined_flag_CXX="-z nodefs" - archive_expsym_cmds_CXX="\$CC $shared_flag"' -o $output_objdir/$soname $libobjs $deplibs '"\${wl}$no_entry_flag"' $compiler_flags ${wl}${allow_undefined_flag} '"\${wl}$exp_sym_flag:\$export_symbols" + archive_expsym_cmds_CXX="\$CC $shared_flag"' -o $output_objdir/$soname $libobjs $deplibs '"\$wl$no_entry_flag"' $compiler_flags $wl$allow_undefined_flag '"\$wl$exp_sym_flag:\$export_symbols" else # Determine the default libpath from the value encoded in an # empty executable. - if test "${lt_cv_aix_libpath+set}" = set; then + if test set = "${lt_cv_aix_libpath+set}"; then aix_libpath=$lt_cv_aix_libpath else if ${lt_cv_aix_libpath__CXX+:} false; then : @@ -12617,7 +13202,7 @@ fi rm -f core conftest.err conftest.$ac_objext \ conftest$ac_exeext conftest.$ac_ext if test -z "$lt_cv_aix_libpath__CXX"; then - lt_cv_aix_libpath__CXX="/usr/lib:/lib" + lt_cv_aix_libpath__CXX=/usr/lib:/lib fi fi @@ -12625,22 +13210,34 @@ fi aix_libpath=$lt_cv_aix_libpath__CXX fi - hardcode_libdir_flag_spec_CXX='${wl}-blibpath:$libdir:'"$aix_libpath" + hardcode_libdir_flag_spec_CXX='$wl-blibpath:$libdir:'"$aix_libpath" # Warning - without using the other run time loading flags, # -berok will link without error, but may produce a broken library. - no_undefined_flag_CXX=' ${wl}-bernotok' - allow_undefined_flag_CXX=' ${wl}-berok' - if test "$with_gnu_ld" = yes; then + no_undefined_flag_CXX=' $wl-bernotok' + allow_undefined_flag_CXX=' $wl-berok' + if test yes = "$with_gnu_ld"; then # We only use this code for GNU lds that support --whole-archive. - whole_archive_flag_spec_CXX='${wl}--whole-archive$convenience ${wl}--no-whole-archive' + whole_archive_flag_spec_CXX='$wl--whole-archive$convenience $wl--no-whole-archive' else # Exported symbols can be pulled into shared objects from archives whole_archive_flag_spec_CXX='$convenience' fi archive_cmds_need_lc_CXX=yes - # This is similar to how AIX traditionally builds its shared - # libraries. - archive_expsym_cmds_CXX="\$CC $shared_flag"' -o $output_objdir/$soname $libobjs $deplibs ${wl}-bnoentry $compiler_flags ${wl}-bE:$export_symbols${allow_undefined_flag}~$AR $AR_FLAGS $output_objdir/$libname$release.a $output_objdir/$soname' + archive_expsym_cmds_CXX='$RM -r $output_objdir/$realname.d~$MKDIR $output_objdir/$realname.d' + # -brtl affects multiple linker settings, -berok does not and is overridden later + compiler_flags_filtered='`func_echo_all "$compiler_flags " | $SED -e "s%-brtl\\([, ]\\)%-berok\\1%g"`' + if test svr4 != "$with_aix_soname"; then + # This is similar to how AIX traditionally builds its shared + # libraries. Need -bnortl late, we may have -brtl in LDFLAGS. + archive_expsym_cmds_CXX="$archive_expsym_cmds_CXX"'~$CC '$shared_flag_aix' -o $output_objdir/$realname.d/$soname $libobjs $deplibs $wl-bnoentry '$compiler_flags_filtered'$wl-bE:$export_symbols$allow_undefined_flag~$AR $AR_FLAGS $output_objdir/$libname$release.a $output_objdir/$realname.d/$soname' + fi + if test aix != "$with_aix_soname"; then + archive_expsym_cmds_CXX="$archive_expsym_cmds_CXX"'~$CC '$shared_flag_svr4' -o $output_objdir/$realname.d/$shared_archive_member_spec.o $libobjs $deplibs $wl-bnoentry '$compiler_flags_filtered'$wl-bE:$export_symbols$allow_undefined_flag~$STRIP -e $output_objdir/$realname.d/$shared_archive_member_spec.o~( func_echo_all "#! $soname($shared_archive_member_spec.o)"; if test shr_64 = "$shared_archive_member_spec"; then func_echo_all "# 64"; else func_echo_all "# 32"; fi; cat $export_symbols ) > $output_objdir/$realname.d/$shared_archive_member_spec.imp~$AR $AR_FLAGS $output_objdir/$soname $output_objdir/$realname.d/$shared_archive_member_spec.o $output_objdir/$realname.d/$shared_archive_member_spec.imp' + else + # used by -dlpreopen to get the symbols + archive_expsym_cmds_CXX="$archive_expsym_cmds_CXX"'~$MV $output_objdir/$realname.d/$soname $output_objdir' + fi + archive_expsym_cmds_CXX="$archive_expsym_cmds_CXX"'~$RM -r $output_objdir/$realname.d' fi fi ;; @@ -12650,7 +13247,7 @@ fi allow_undefined_flag_CXX=unsupported # Joseph Beckenbach says some releases of gcc # support --undefined. This deserves some investigation. FIXME - archive_cmds_CXX='$CC -nostart $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname -o $lib' + archive_cmds_CXX='$CC -nostart $libobjs $deplibs $compiler_flags $wl-soname $wl$soname -o $lib' else ld_shlibs_CXX=no fi @@ -12678,57 +13275,58 @@ fi # Tell ltmain to make .lib files, not .a files. libext=lib # Tell ltmain to make .dll files, not .so files. - shrext_cmds=".dll" + shrext_cmds=.dll # FIXME: Setting linknames here is a bad hack. - archive_cmds_CXX='$CC -o $output_objdir/$soname $libobjs $compiler_flags $deplibs -Wl,-dll~linknames=' - archive_expsym_cmds_CXX='if test "x`$SED 1q $export_symbols`" = xEXPORTS; then - $SED -n -e 's/\\\\\\\(.*\\\\\\\)/-link\\\ -EXPORT:\\\\\\\1/' -e '1\\\!p' < $export_symbols > $output_objdir/$soname.exp; - else - $SED -e 's/\\\\\\\(.*\\\\\\\)/-link\\\ -EXPORT:\\\\\\\1/' < $export_symbols > $output_objdir/$soname.exp; - fi~ - $CC -o $tool_output_objdir$soname $libobjs $compiler_flags $deplibs "@$tool_output_objdir$soname.exp" -Wl,-DLL,-IMPLIB:"$tool_output_objdir$libname.dll.lib"~ - linknames=' + archive_cmds_CXX='$CC -o $output_objdir/$soname $libobjs $compiler_flags $deplibs -Wl,-DLL,-IMPLIB:"$tool_output_objdir$libname.dll.lib"~linknames=' + archive_expsym_cmds_CXX='if test DEF = "`$SED -n -e '\''s/^[ ]*//'\'' -e '\''/^\(;.*\)*$/d'\'' -e '\''s/^\(EXPORTS\|LIBRARY\)\([ ].*\)*$/DEF/p'\'' -e q $export_symbols`" ; then + cp "$export_symbols" "$output_objdir/$soname.def"; + echo "$tool_output_objdir$soname.def" > "$output_objdir/$soname.exp"; + else + $SED -e '\''s/^/-link -EXPORT:/'\'' < $export_symbols > $output_objdir/$soname.exp; + fi~ + $CC -o $tool_output_objdir$soname $libobjs $compiler_flags $deplibs "@$tool_output_objdir$soname.exp" -Wl,-DLL,-IMPLIB:"$tool_output_objdir$libname.dll.lib"~ + linknames=' # The linker will not automatically build a static lib if we build a DLL. # _LT_TAGVAR(old_archive_from_new_cmds, CXX)='true' enable_shared_with_static_runtimes_CXX=yes # Don't use ranlib old_postinstall_cmds_CXX='chmod 644 $oldlib' postlink_cmds_CXX='lt_outputfile="@OUTPUT@"~ - lt_tool_outputfile="@TOOL_OUTPUT@"~ - case $lt_outputfile in - *.exe|*.EXE) ;; - *) - lt_outputfile="$lt_outputfile.exe" - lt_tool_outputfile="$lt_tool_outputfile.exe" - ;; - esac~ - func_to_tool_file "$lt_outputfile"~ - if test "$MANIFEST_TOOL" != ":" && test -f "$lt_outputfile.manifest"; then - $MANIFEST_TOOL -manifest "$lt_tool_outputfile.manifest" -outputresource:"$lt_tool_outputfile" || exit 1; - $RM "$lt_outputfile.manifest"; - fi' + lt_tool_outputfile="@TOOL_OUTPUT@"~ + case $lt_outputfile in + *.exe|*.EXE) ;; + *) + lt_outputfile=$lt_outputfile.exe + lt_tool_outputfile=$lt_tool_outputfile.exe + ;; + esac~ + func_to_tool_file "$lt_outputfile"~ + if test : != "$MANIFEST_TOOL" && test -f "$lt_outputfile.manifest"; then + $MANIFEST_TOOL -manifest "$lt_tool_outputfile.manifest" -outputresource:"$lt_tool_outputfile" || exit 1; + $RM "$lt_outputfile.manifest"; + fi' ;; *) # g++ # _LT_TAGVAR(hardcode_libdir_flag_spec, CXX) is actually meaningless, # as there is no search path for DLLs. hardcode_libdir_flag_spec_CXX='-L$libdir' - export_dynamic_flag_spec_CXX='${wl}--export-all-symbols' + export_dynamic_flag_spec_CXX='$wl--export-all-symbols' allow_undefined_flag_CXX=unsupported always_export_symbols_CXX=no enable_shared_with_static_runtimes_CXX=yes if $LD --help 2>&1 | $GREP 'auto-import' > /dev/null; then - archive_cmds_CXX='$CC -shared -nostdlib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags -o $output_objdir/$soname ${wl}--enable-auto-image-base -Xlinker --out-implib -Xlinker $lib' - # If the export-symbols file already is a .def file (1st line - # is EXPORTS), use it as is; otherwise, prepend... - archive_expsym_cmds_CXX='if test "x`$SED 1q $export_symbols`" = xEXPORTS; then - cp $export_symbols $output_objdir/$soname.def; - else - echo EXPORTS > $output_objdir/$soname.def; - cat $export_symbols >> $output_objdir/$soname.def; - fi~ - $CC -shared -nostdlib $output_objdir/$soname.def $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags -o $output_objdir/$soname ${wl}--enable-auto-image-base -Xlinker --out-implib -Xlinker $lib' + archive_cmds_CXX='$CC -shared -nostdlib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags -o $output_objdir/$soname $wl--enable-auto-image-base -Xlinker --out-implib -Xlinker $lib' + # If the export-symbols file already is a .def file, use it as + # is; otherwise, prepend EXPORTS... + archive_expsym_cmds_CXX='if test DEF = "`$SED -n -e '\''s/^[ ]*//'\'' -e '\''/^\(;.*\)*$/d'\'' -e '\''s/^\(EXPORTS\|LIBRARY\)\([ ].*\)*$/DEF/p'\'' -e q $export_symbols`" ; then + cp $export_symbols $output_objdir/$soname.def; + else + echo EXPORTS > $output_objdir/$soname.def; + cat $export_symbols >> $output_objdir/$soname.def; + fi~ + $CC -shared -nostdlib $output_objdir/$soname.def $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags -o $output_objdir/$soname $wl--enable-auto-image-base -Xlinker --out-implib -Xlinker $lib' else ld_shlibs_CXX=no fi @@ -12742,27 +13340,27 @@ fi hardcode_direct_CXX=no hardcode_automatic_CXX=yes hardcode_shlibpath_var_CXX=unsupported - if test "$lt_cv_ld_force_load" = "yes"; then - whole_archive_flag_spec_CXX='`for conv in $convenience\"\"; do test -n \"$conv\" && new_convenience=\"$new_convenience ${wl}-force_load,$conv\"; done; func_echo_all \"$new_convenience\"`' + if test yes = "$lt_cv_ld_force_load"; then + whole_archive_flag_spec_CXX='`for conv in $convenience\"\"; do test -n \"$conv\" && new_convenience=\"$new_convenience $wl-force_load,$conv\"; done; func_echo_all \"$new_convenience\"`' else whole_archive_flag_spec_CXX='' fi link_all_deplibs_CXX=yes - allow_undefined_flag_CXX="$_lt_dar_allow_undefined" + allow_undefined_flag_CXX=$_lt_dar_allow_undefined case $cc_basename in - ifort*) _lt_dar_can_shared=yes ;; + ifort*|nagfor*) _lt_dar_can_shared=yes ;; *) _lt_dar_can_shared=$GCC ;; esac - if test "$_lt_dar_can_shared" = "yes"; then + if test yes = "$_lt_dar_can_shared"; then output_verbose_link_cmd=func_echo_all - archive_cmds_CXX="\$CC -dynamiclib \$allow_undefined_flag -o \$lib \$libobjs \$deplibs \$compiler_flags -install_name \$rpath/\$soname \$verstring $_lt_dar_single_mod${_lt_dsymutil}" - module_cmds_CXX="\$CC \$allow_undefined_flag -o \$lib -bundle \$libobjs \$deplibs \$compiler_flags${_lt_dsymutil}" - archive_expsym_cmds_CXX="sed 's,^,_,' < \$export_symbols > \$output_objdir/\${libname}-symbols.expsym~\$CC -dynamiclib \$allow_undefined_flag -o \$lib \$libobjs \$deplibs \$compiler_flags -install_name \$rpath/\$soname \$verstring ${_lt_dar_single_mod}${_lt_dar_export_syms}${_lt_dsymutil}" - module_expsym_cmds_CXX="sed -e 's,^,_,' < \$export_symbols > \$output_objdir/\${libname}-symbols.expsym~\$CC \$allow_undefined_flag -o \$lib -bundle \$libobjs \$deplibs \$compiler_flags${_lt_dar_export_syms}${_lt_dsymutil}" - if test "$lt_cv_apple_cc_single_mod" != "yes"; then - archive_cmds_CXX="\$CC -r -keep_private_externs -nostdlib -o \${lib}-master.o \$libobjs~\$CC -dynamiclib \$allow_undefined_flag -o \$lib \${lib}-master.o \$deplibs \$compiler_flags -install_name \$rpath/\$soname \$verstring${_lt_dsymutil}" - archive_expsym_cmds_CXX="sed 's,^,_,' < \$export_symbols > \$output_objdir/\${libname}-symbols.expsym~\$CC -r -keep_private_externs -nostdlib -o \${lib}-master.o \$libobjs~\$CC -dynamiclib \$allow_undefined_flag -o \$lib \${lib}-master.o \$deplibs \$compiler_flags -install_name \$rpath/\$soname \$verstring${_lt_dar_export_syms}${_lt_dsymutil}" + archive_cmds_CXX="\$CC -dynamiclib \$allow_undefined_flag -o \$lib \$libobjs \$deplibs \$compiler_flags -install_name \$rpath/\$soname \$verstring $_lt_dar_single_mod$_lt_dsymutil" + module_cmds_CXX="\$CC \$allow_undefined_flag -o \$lib -bundle \$libobjs \$deplibs \$compiler_flags$_lt_dsymutil" + archive_expsym_cmds_CXX="sed 's|^|_|' < \$export_symbols > \$output_objdir/\$libname-symbols.expsym~\$CC -dynamiclib \$allow_undefined_flag -o \$lib \$libobjs \$deplibs \$compiler_flags -install_name \$rpath/\$soname \$verstring $_lt_dar_single_mod$_lt_dar_export_syms$_lt_dsymutil" + module_expsym_cmds_CXX="sed -e 's|^|_|' < \$export_symbols > \$output_objdir/\$libname-symbols.expsym~\$CC \$allow_undefined_flag -o \$lib -bundle \$libobjs \$deplibs \$compiler_flags$_lt_dar_export_syms$_lt_dsymutil" + if test yes != "$lt_cv_apple_cc_single_mod"; then + archive_cmds_CXX="\$CC -r -keep_private_externs -nostdlib -o \$lib-master.o \$libobjs~\$CC -dynamiclib \$allow_undefined_flag -o \$lib \$lib-master.o \$deplibs \$compiler_flags -install_name \$rpath/\$soname \$verstring$_lt_dsymutil" + archive_expsym_cmds_CXX="sed 's|^|_|' < \$export_symbols > \$output_objdir/\$libname-symbols.expsym~\$CC -r -keep_private_externs -nostdlib -o \$lib-master.o \$libobjs~\$CC -dynamiclib \$allow_undefined_flag -o \$lib \$lib-master.o \$deplibs \$compiler_flags -install_name \$rpath/\$soname \$verstring$_lt_dar_export_syms$_lt_dsymutil" fi else @@ -12771,6 +13369,34 @@ fi ;; + os2*) + hardcode_libdir_flag_spec_CXX='-L$libdir' + hardcode_minus_L_CXX=yes + allow_undefined_flag_CXX=unsupported + shrext_cmds=.dll + archive_cmds_CXX='$ECHO "LIBRARY ${soname%$shared_ext} INITINSTANCE TERMINSTANCE" > $output_objdir/$libname.def~ + $ECHO "DESCRIPTION \"$libname\"" >> $output_objdir/$libname.def~ + $ECHO "DATA MULTIPLE NONSHARED" >> $output_objdir/$libname.def~ + $ECHO EXPORTS >> $output_objdir/$libname.def~ + emxexp $libobjs | $SED /"_DLL_InitTerm"/d >> $output_objdir/$libname.def~ + $CC -Zdll -Zcrtdll -o $output_objdir/$soname $libobjs $deplibs $compiler_flags $output_objdir/$libname.def~ + emximp -o $lib $output_objdir/$libname.def' + archive_expsym_cmds_CXX='$ECHO "LIBRARY ${soname%$shared_ext} INITINSTANCE TERMINSTANCE" > $output_objdir/$libname.def~ + $ECHO "DESCRIPTION \"$libname\"" >> $output_objdir/$libname.def~ + $ECHO "DATA MULTIPLE NONSHARED" >> $output_objdir/$libname.def~ + $ECHO EXPORTS >> $output_objdir/$libname.def~ + prefix_cmds="$SED"~ + if test EXPORTS = "`$SED 1q $export_symbols`"; then + prefix_cmds="$prefix_cmds -e 1d"; + fi~ + prefix_cmds="$prefix_cmds -e \"s/^\(.*\)$/_\1/g\""~ + cat $export_symbols | $prefix_cmds >> $output_objdir/$libname.def~ + $CC -Zdll -Zcrtdll -o $output_objdir/$soname $libobjs $deplibs $compiler_flags $output_objdir/$libname.def~ + emximp -o $lib $output_objdir/$libname.def' + old_archive_From_new_cmds_CXX='emximp -o $output_objdir/${libname}_dll.a $output_objdir/$libname.def' + enable_shared_with_static_runtimes_CXX=yes + ;; + dgux*) case $cc_basename in ec++*) @@ -12805,18 +13431,15 @@ fi ld_shlibs_CXX=yes ;; - gnu*) - ;; - haiku*) - archive_cmds_CXX='$CC -shared $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname -o $lib' + archive_cmds_CXX='$CC -shared $libobjs $deplibs $compiler_flags $wl-soname $wl$soname -o $lib' link_all_deplibs_CXX=yes ;; hpux9*) - hardcode_libdir_flag_spec_CXX='${wl}+b ${wl}$libdir' + hardcode_libdir_flag_spec_CXX='$wl+b $wl$libdir' hardcode_libdir_separator_CXX=: - export_dynamic_flag_spec_CXX='${wl}-E' + export_dynamic_flag_spec_CXX='$wl-E' hardcode_direct_CXX=yes hardcode_minus_L_CXX=yes # Not in the search PATH, # but as the default @@ -12828,7 +13451,7 @@ fi ld_shlibs_CXX=no ;; aCC*) - archive_cmds_CXX='$RM $output_objdir/$soname~$CC -b ${wl}+b ${wl}$install_libdir -o $output_objdir/$soname $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags~test $output_objdir/$soname = $lib || mv $output_objdir/$soname $lib' + archive_cmds_CXX='$RM $output_objdir/$soname~$CC -b $wl+b $wl$install_libdir -o $output_objdir/$soname $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags~test "x$output_objdir/$soname" = "x$lib" || mv $output_objdir/$soname $lib' # Commands to make compiler produce verbose output that lists # what "hidden" libraries, object files and flags are used when # linking a shared library. @@ -12837,11 +13460,11 @@ fi # explicitly linking system object files so we need to strip them # from the output so that they don't get included in the library # dependencies. - output_verbose_link_cmd='templist=`($CC -b $CFLAGS -v conftest.$objext 2>&1) | $EGREP "\-L"`; list=""; for z in $templist; do case $z in conftest.$objext) list="$list $z";; *.$objext);; *) list="$list $z";;esac; done; func_echo_all "$list"' + output_verbose_link_cmd='templist=`($CC -b $CFLAGS -v conftest.$objext 2>&1) | $EGREP "\-L"`; list= ; for z in $templist; do case $z in conftest.$objext) list="$list $z";; *.$objext);; *) list="$list $z";;esac; done; func_echo_all "$list"' ;; *) - if test "$GXX" = yes; then - archive_cmds_CXX='$RM $output_objdir/$soname~$CC -shared -nostdlib $pic_flag ${wl}+b ${wl}$install_libdir -o $output_objdir/$soname $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags~test $output_objdir/$soname = $lib || mv $output_objdir/$soname $lib' + if test yes = "$GXX"; then + archive_cmds_CXX='$RM $output_objdir/$soname~$CC -shared -nostdlib $pic_flag $wl+b $wl$install_libdir -o $output_objdir/$soname $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags~test "x$output_objdir/$soname" = "x$lib" || mv $output_objdir/$soname $lib' else # FIXME: insert proper C++ library support ld_shlibs_CXX=no @@ -12851,15 +13474,15 @@ fi ;; hpux10*|hpux11*) - if test $with_gnu_ld = no; then - hardcode_libdir_flag_spec_CXX='${wl}+b ${wl}$libdir' + if test no = "$with_gnu_ld"; then + hardcode_libdir_flag_spec_CXX='$wl+b $wl$libdir' hardcode_libdir_separator_CXX=: case $host_cpu in hppa*64*|ia64*) ;; *) - export_dynamic_flag_spec_CXX='${wl}-E' + export_dynamic_flag_spec_CXX='$wl-E' ;; esac fi @@ -12885,13 +13508,13 @@ fi aCC*) case $host_cpu in hppa*64*) - archive_cmds_CXX='$CC -b ${wl}+h ${wl}$soname -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags' + archive_cmds_CXX='$CC -b $wl+h $wl$soname -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags' ;; ia64*) - archive_cmds_CXX='$CC -b ${wl}+h ${wl}$soname ${wl}+nodefaultrpath -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags' + archive_cmds_CXX='$CC -b $wl+h $wl$soname $wl+nodefaultrpath -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags' ;; *) - archive_cmds_CXX='$CC -b ${wl}+h ${wl}$soname ${wl}+b ${wl}$install_libdir -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags' + archive_cmds_CXX='$CC -b $wl+h $wl$soname $wl+b $wl$install_libdir -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags' ;; esac # Commands to make compiler produce verbose output that lists @@ -12902,20 +13525,20 @@ fi # explicitly linking system object files so we need to strip them # from the output so that they don't get included in the library # dependencies. - output_verbose_link_cmd='templist=`($CC -b $CFLAGS -v conftest.$objext 2>&1) | $GREP "\-L"`; list=""; for z in $templist; do case $z in conftest.$objext) list="$list $z";; *.$objext);; *) list="$list $z";;esac; done; func_echo_all "$list"' + output_verbose_link_cmd='templist=`($CC -b $CFLAGS -v conftest.$objext 2>&1) | $GREP "\-L"`; list= ; for z in $templist; do case $z in conftest.$objext) list="$list $z";; *.$objext);; *) list="$list $z";;esac; done; func_echo_all "$list"' ;; *) - if test "$GXX" = yes; then - if test $with_gnu_ld = no; then + if test yes = "$GXX"; then + if test no = "$with_gnu_ld"; then case $host_cpu in hppa*64*) - archive_cmds_CXX='$CC -shared -nostdlib -fPIC ${wl}+h ${wl}$soname -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags' + archive_cmds_CXX='$CC -shared -nostdlib -fPIC $wl+h $wl$soname -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags' ;; ia64*) - archive_cmds_CXX='$CC -shared -nostdlib $pic_flag ${wl}+h ${wl}$soname ${wl}+nodefaultrpath -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags' + archive_cmds_CXX='$CC -shared -nostdlib $pic_flag $wl+h $wl$soname $wl+nodefaultrpath -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags' ;; *) - archive_cmds_CXX='$CC -shared -nostdlib $pic_flag ${wl}+h ${wl}$soname ${wl}+b ${wl}$install_libdir -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags' + archive_cmds_CXX='$CC -shared -nostdlib $pic_flag $wl+h $wl$soname $wl+b $wl$install_libdir -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags' ;; esac fi @@ -12930,22 +13553,22 @@ fi interix[3-9]*) hardcode_direct_CXX=no hardcode_shlibpath_var_CXX=no - hardcode_libdir_flag_spec_CXX='${wl}-rpath,$libdir' - export_dynamic_flag_spec_CXX='${wl}-E' + hardcode_libdir_flag_spec_CXX='$wl-rpath,$libdir' + export_dynamic_flag_spec_CXX='$wl-E' # Hack: On Interix 3.x, we cannot compile PIC because of a broken gcc. # Instead, shared libraries are loaded at an image base (0x10000000 by # default) and relocated if they conflict, which is a slow very memory # consuming and fragmenting process. To avoid this, we pick a random, # 256 KiB-aligned image base between 0x50000000 and 0x6FFC0000 at link # time. Moving up from 0x10000000 also allows more sbrk(2) space. - archive_cmds_CXX='$CC -shared $pic_flag $libobjs $deplibs $compiler_flags ${wl}-h,$soname ${wl}--image-base,`expr ${RANDOM-$$} % 4096 / 2 \* 262144 + 1342177280` -o $lib' - archive_expsym_cmds_CXX='sed "s,^,_," $export_symbols >$output_objdir/$soname.expsym~$CC -shared $pic_flag $libobjs $deplibs $compiler_flags ${wl}-h,$soname ${wl}--retain-symbols-file,$output_objdir/$soname.expsym ${wl}--image-base,`expr ${RANDOM-$$} % 4096 / 2 \* 262144 + 1342177280` -o $lib' + archive_cmds_CXX='$CC -shared $pic_flag $libobjs $deplibs $compiler_flags $wl-h,$soname $wl--image-base,`expr ${RANDOM-$$} % 4096 / 2 \* 262144 + 1342177280` -o $lib' + archive_expsym_cmds_CXX='sed "s|^|_|" $export_symbols >$output_objdir/$soname.expsym~$CC -shared $pic_flag $libobjs $deplibs $compiler_flags $wl-h,$soname $wl--retain-symbols-file,$output_objdir/$soname.expsym $wl--image-base,`expr ${RANDOM-$$} % 4096 / 2 \* 262144 + 1342177280` -o $lib' ;; irix5* | irix6*) case $cc_basename in CC*) # SGI C++ - archive_cmds_CXX='$CC -shared -all -multigot $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags -soname $soname `test -n "$verstring" && func_echo_all "-set_version $verstring"` -update_registry ${output_objdir}/so_locations -o $lib' + archive_cmds_CXX='$CC -shared -all -multigot $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags -soname $soname `test -n "$verstring" && func_echo_all "-set_version $verstring"` -update_registry $output_objdir/so_locations -o $lib' # Archives containing C++ object files must be created using # "CC -ar", where "CC" is the IRIX C++ compiler. This is @@ -12954,22 +13577,22 @@ fi old_archive_cmds_CXX='$CC -ar -WR,-u -o $oldlib $oldobjs' ;; *) - if test "$GXX" = yes; then - if test "$with_gnu_ld" = no; then - archive_cmds_CXX='$CC -shared $pic_flag -nostdlib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-soname ${wl}$soname `test -n "$verstring" && func_echo_all "${wl}-set_version ${wl}$verstring"` ${wl}-update_registry ${wl}${output_objdir}/so_locations -o $lib' + if test yes = "$GXX"; then + if test no = "$with_gnu_ld"; then + archive_cmds_CXX='$CC -shared $pic_flag -nostdlib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags $wl-soname $wl$soname `test -n "$verstring" && func_echo_all "$wl-set_version $wl$verstring"` $wl-update_registry $wl$output_objdir/so_locations -o $lib' else - archive_cmds_CXX='$CC -shared $pic_flag -nostdlib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-soname ${wl}$soname `test -n "$verstring" && func_echo_all "${wl}-set_version ${wl}$verstring"` -o $lib' + archive_cmds_CXX='$CC -shared $pic_flag -nostdlib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags $wl-soname $wl$soname `test -n "$verstring" && func_echo_all "$wl-set_version $wl$verstring"` -o $lib' fi fi link_all_deplibs_CXX=yes ;; esac - hardcode_libdir_flag_spec_CXX='${wl}-rpath ${wl}$libdir' + hardcode_libdir_flag_spec_CXX='$wl-rpath $wl$libdir' hardcode_libdir_separator_CXX=: inherit_rpath_CXX=yes ;; - linux* | k*bsd*-gnu | kopensolaris*-gnu) + linux* | k*bsd*-gnu | kopensolaris*-gnu | gnu*) case $cc_basename in KCC*) # Kuck and Associates, Inc. (KAI) C++ Compiler @@ -12977,8 +13600,8 @@ fi # KCC will only create a shared library if the output file # ends with ".so" (or ".sl" for HP-UX), so rename the library # to its proper name (with version) after linking. - archive_cmds_CXX='tempext=`echo $shared_ext | $SED -e '\''s/\([^()0-9A-Za-z{}]\)/\\\\\1/g'\''`; templib=`echo $lib | $SED -e "s/\${tempext}\..*/.so/"`; $CC $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags --soname $soname -o \$templib; mv \$templib $lib' - archive_expsym_cmds_CXX='tempext=`echo $shared_ext | $SED -e '\''s/\([^()0-9A-Za-z{}]\)/\\\\\1/g'\''`; templib=`echo $lib | $SED -e "s/\${tempext}\..*/.so/"`; $CC $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags --soname $soname -o \$templib ${wl}-retain-symbols-file,$export_symbols; mv \$templib $lib' + archive_cmds_CXX='tempext=`echo $shared_ext | $SED -e '\''s/\([^()0-9A-Za-z{}]\)/\\\\\1/g'\''`; templib=`echo $lib | $SED -e "s/\$tempext\..*/.so/"`; $CC $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags --soname $soname -o \$templib; mv \$templib $lib' + archive_expsym_cmds_CXX='tempext=`echo $shared_ext | $SED -e '\''s/\([^()0-9A-Za-z{}]\)/\\\\\1/g'\''`; templib=`echo $lib | $SED -e "s/\$tempext\..*/.so/"`; $CC $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags --soname $soname -o \$templib $wl-retain-symbols-file,$export_symbols; mv \$templib $lib' # Commands to make compiler produce verbose output that lists # what "hidden" libraries, object files and flags are used when # linking a shared library. @@ -12987,10 +13610,10 @@ fi # explicitly linking system object files so we need to strip them # from the output so that they don't get included in the library # dependencies. - output_verbose_link_cmd='templist=`$CC $CFLAGS -v conftest.$objext -o libconftest$shared_ext 2>&1 | $GREP "ld"`; rm -f libconftest$shared_ext; list=""; for z in $templist; do case $z in conftest.$objext) list="$list $z";; *.$objext);; *) list="$list $z";;esac; done; func_echo_all "$list"' + output_verbose_link_cmd='templist=`$CC $CFLAGS -v conftest.$objext -o libconftest$shared_ext 2>&1 | $GREP "ld"`; rm -f libconftest$shared_ext; list= ; for z in $templist; do case $z in conftest.$objext) list="$list $z";; *.$objext);; *) list="$list $z";;esac; done; func_echo_all "$list"' - hardcode_libdir_flag_spec_CXX='${wl}-rpath,$libdir' - export_dynamic_flag_spec_CXX='${wl}--export-dynamic' + hardcode_libdir_flag_spec_CXX='$wl-rpath,$libdir' + export_dynamic_flag_spec_CXX='$wl--export-dynamic' # Archives containing C++ object files must be created using # "CC -Bstatic", where "CC" is the KAI C++ compiler. @@ -13004,59 +13627,59 @@ fi # earlier do not add the objects themselves. case `$CC -V 2>&1` in *"Version 7."*) - archive_cmds_CXX='$CC -shared $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-soname $wl$soname -o $lib' - archive_expsym_cmds_CXX='$CC -shared $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-soname $wl$soname ${wl}-retain-symbols-file $wl$export_symbols -o $lib' + archive_cmds_CXX='$CC -shared $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags $wl-soname $wl$soname -o $lib' + archive_expsym_cmds_CXX='$CC -shared $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags $wl-soname $wl$soname $wl-retain-symbols-file $wl$export_symbols -o $lib' ;; *) # Version 8.0 or newer tmp_idyn= case $host_cpu in ia64*) tmp_idyn=' -i_dynamic';; esac - archive_cmds_CXX='$CC -shared'"$tmp_idyn"' $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname -o $lib' - archive_expsym_cmds_CXX='$CC -shared'"$tmp_idyn"' $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname ${wl}-retain-symbols-file $wl$export_symbols -o $lib' + archive_cmds_CXX='$CC -shared'"$tmp_idyn"' $libobjs $deplibs $compiler_flags $wl-soname $wl$soname -o $lib' + archive_expsym_cmds_CXX='$CC -shared'"$tmp_idyn"' $libobjs $deplibs $compiler_flags $wl-soname $wl$soname $wl-retain-symbols-file $wl$export_symbols -o $lib' ;; esac archive_cmds_need_lc_CXX=no - hardcode_libdir_flag_spec_CXX='${wl}-rpath,$libdir' - export_dynamic_flag_spec_CXX='${wl}--export-dynamic' - whole_archive_flag_spec_CXX='${wl}--whole-archive$convenience ${wl}--no-whole-archive' + hardcode_libdir_flag_spec_CXX='$wl-rpath,$libdir' + export_dynamic_flag_spec_CXX='$wl--export-dynamic' + whole_archive_flag_spec_CXX='$wl--whole-archive$convenience $wl--no-whole-archive' ;; pgCC* | pgcpp*) # Portland Group C++ compiler case `$CC -V` in *pgCC\ [1-5].* | *pgcpp\ [1-5].*) prelink_cmds_CXX='tpldir=Template.dir~ - rm -rf $tpldir~ - $CC --prelink_objects --instantiation_dir $tpldir $objs $libobjs $compile_deplibs~ - compile_command="$compile_command `find $tpldir -name \*.o | sort | $NL2SP`"' + rm -rf $tpldir~ + $CC --prelink_objects --instantiation_dir $tpldir $objs $libobjs $compile_deplibs~ + compile_command="$compile_command `find $tpldir -name \*.o | sort | $NL2SP`"' old_archive_cmds_CXX='tpldir=Template.dir~ - rm -rf $tpldir~ - $CC --prelink_objects --instantiation_dir $tpldir $oldobjs$old_deplibs~ - $AR $AR_FLAGS $oldlib$oldobjs$old_deplibs `find $tpldir -name \*.o | sort | $NL2SP`~ - $RANLIB $oldlib' + rm -rf $tpldir~ + $CC --prelink_objects --instantiation_dir $tpldir $oldobjs$old_deplibs~ + $AR $AR_FLAGS $oldlib$oldobjs$old_deplibs `find $tpldir -name \*.o | sort | $NL2SP`~ + $RANLIB $oldlib' archive_cmds_CXX='tpldir=Template.dir~ - rm -rf $tpldir~ - $CC --prelink_objects --instantiation_dir $tpldir $predep_objects $libobjs $deplibs $convenience $postdep_objects~ - $CC -shared $pic_flag $predep_objects $libobjs $deplibs `find $tpldir -name \*.o | sort | $NL2SP` $postdep_objects $compiler_flags ${wl}-soname ${wl}$soname -o $lib' + rm -rf $tpldir~ + $CC --prelink_objects --instantiation_dir $tpldir $predep_objects $libobjs $deplibs $convenience $postdep_objects~ + $CC -shared $pic_flag $predep_objects $libobjs $deplibs `find $tpldir -name \*.o | sort | $NL2SP` $postdep_objects $compiler_flags $wl-soname $wl$soname -o $lib' archive_expsym_cmds_CXX='tpldir=Template.dir~ - rm -rf $tpldir~ - $CC --prelink_objects --instantiation_dir $tpldir $predep_objects $libobjs $deplibs $convenience $postdep_objects~ - $CC -shared $pic_flag $predep_objects $libobjs $deplibs `find $tpldir -name \*.o | sort | $NL2SP` $postdep_objects $compiler_flags ${wl}-soname ${wl}$soname ${wl}-retain-symbols-file ${wl}$export_symbols -o $lib' + rm -rf $tpldir~ + $CC --prelink_objects --instantiation_dir $tpldir $predep_objects $libobjs $deplibs $convenience $postdep_objects~ + $CC -shared $pic_flag $predep_objects $libobjs $deplibs `find $tpldir -name \*.o | sort | $NL2SP` $postdep_objects $compiler_flags $wl-soname $wl$soname $wl-retain-symbols-file $wl$export_symbols -o $lib' ;; *) # Version 6 and above use weak symbols - archive_cmds_CXX='$CC -shared $pic_flag $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-soname ${wl}$soname -o $lib' - archive_expsym_cmds_CXX='$CC -shared $pic_flag $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-soname ${wl}$soname ${wl}-retain-symbols-file ${wl}$export_symbols -o $lib' + archive_cmds_CXX='$CC -shared $pic_flag $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags $wl-soname $wl$soname -o $lib' + archive_expsym_cmds_CXX='$CC -shared $pic_flag $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags $wl-soname $wl$soname $wl-retain-symbols-file $wl$export_symbols -o $lib' ;; esac - hardcode_libdir_flag_spec_CXX='${wl}--rpath ${wl}$libdir' - export_dynamic_flag_spec_CXX='${wl}--export-dynamic' - whole_archive_flag_spec_CXX='${wl}--whole-archive`for conv in $convenience\"\"; do test -n \"$conv\" && new_convenience=\"$new_convenience,$conv\"; done; func_echo_all \"$new_convenience\"` ${wl}--no-whole-archive' + hardcode_libdir_flag_spec_CXX='$wl--rpath $wl$libdir' + export_dynamic_flag_spec_CXX='$wl--export-dynamic' + whole_archive_flag_spec_CXX='$wl--whole-archive`for conv in $convenience\"\"; do test -n \"$conv\" && new_convenience=\"$new_convenience,$conv\"; done; func_echo_all \"$new_convenience\"` $wl--no-whole-archive' ;; cxx*) # Compaq C++ - archive_cmds_CXX='$CC -shared $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-soname $wl$soname -o $lib' - archive_expsym_cmds_CXX='$CC -shared $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-soname $wl$soname -o $lib ${wl}-retain-symbols-file $wl$export_symbols' + archive_cmds_CXX='$CC -shared $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags $wl-soname $wl$soname -o $lib' + archive_expsym_cmds_CXX='$CC -shared $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags $wl-soname $wl$soname -o $lib $wl-retain-symbols-file $wl$export_symbols' runpath_var=LD_RUN_PATH hardcode_libdir_flag_spec_CXX='-rpath $libdir' @@ -13070,18 +13693,18 @@ fi # explicitly linking system object files so we need to strip them # from the output so that they don't get included in the library # dependencies. - output_verbose_link_cmd='templist=`$CC -shared $CFLAGS -v conftest.$objext 2>&1 | $GREP "ld"`; templist=`func_echo_all "$templist" | $SED "s/\(^.*ld.*\)\( .*ld .*$\)/\1/"`; list=""; for z in $templist; do case $z in conftest.$objext) list="$list $z";; *.$objext);; *) list="$list $z";;esac; done; func_echo_all "X$list" | $Xsed' + output_verbose_link_cmd='templist=`$CC -shared $CFLAGS -v conftest.$objext 2>&1 | $GREP "ld"`; templist=`func_echo_all "$templist" | $SED "s/\(^.*ld.*\)\( .*ld .*$\)/\1/"`; list= ; for z in $templist; do case $z in conftest.$objext) list="$list $z";; *.$objext);; *) list="$list $z";;esac; done; func_echo_all "X$list" | $Xsed' ;; xl* | mpixl* | bgxl*) # IBM XL 8.0 on PPC, with GNU ld - hardcode_libdir_flag_spec_CXX='${wl}-rpath ${wl}$libdir' - export_dynamic_flag_spec_CXX='${wl}--export-dynamic' - archive_cmds_CXX='$CC -qmkshrobj $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname -o $lib' - if test "x$supports_anon_versioning" = xyes; then + hardcode_libdir_flag_spec_CXX='$wl-rpath $wl$libdir' + export_dynamic_flag_spec_CXX='$wl--export-dynamic' + archive_cmds_CXX='$CC -qmkshrobj $libobjs $deplibs $compiler_flags $wl-soname $wl$soname -o $lib' + if test yes = "$supports_anon_versioning"; then archive_expsym_cmds_CXX='echo "{ global:" > $output_objdir/$libname.ver~ - cat $export_symbols | sed -e "s/\(.*\)/\1;/" >> $output_objdir/$libname.ver~ - echo "local: *; };" >> $output_objdir/$libname.ver~ - $CC -qmkshrobj $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname ${wl}-version-script ${wl}$output_objdir/$libname.ver -o $lib' + cat $export_symbols | sed -e "s/\(.*\)/\1;/" >> $output_objdir/$libname.ver~ + echo "local: *; };" >> $output_objdir/$libname.ver~ + $CC -qmkshrobj $libobjs $deplibs $compiler_flags $wl-soname $wl$soname $wl-version-script $wl$output_objdir/$libname.ver -o $lib' fi ;; *) @@ -13089,10 +13712,10 @@ fi *Sun\ C*) # Sun C++ 5.9 no_undefined_flag_CXX=' -zdefs' - archive_cmds_CXX='$CC -G${allow_undefined_flag} -h$soname -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags' - archive_expsym_cmds_CXX='$CC -G${allow_undefined_flag} -h$soname -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-retain-symbols-file ${wl}$export_symbols' + archive_cmds_CXX='$CC -G$allow_undefined_flag -h$soname -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags' + archive_expsym_cmds_CXX='$CC -G$allow_undefined_flag -h$soname -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags $wl-retain-symbols-file $wl$export_symbols' hardcode_libdir_flag_spec_CXX='-R$libdir' - whole_archive_flag_spec_CXX='${wl}--whole-archive`new_convenience=; for conv in $convenience\"\"; do test -z \"$conv\" || new_convenience=\"$new_convenience,$conv\"; done; func_echo_all \"$new_convenience\"` ${wl}--no-whole-archive' + whole_archive_flag_spec_CXX='$wl--whole-archive`new_convenience=; for conv in $convenience\"\"; do test -z \"$conv\" || new_convenience=\"$new_convenience,$conv\"; done; func_echo_all \"$new_convenience\"` $wl--no-whole-archive' compiler_needs_object_CXX=yes # Not sure whether something based on @@ -13150,22 +13773,17 @@ fi ld_shlibs_CXX=yes ;; - openbsd2*) - # C++ shared libraries are fairly broken - ld_shlibs_CXX=no - ;; - - openbsd*) + openbsd* | bitrig*) if test -f /usr/libexec/ld.so; then hardcode_direct_CXX=yes hardcode_shlibpath_var_CXX=no hardcode_direct_absolute_CXX=yes archive_cmds_CXX='$CC -shared $pic_flag $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags -o $lib' - hardcode_libdir_flag_spec_CXX='${wl}-rpath,$libdir' - if test -z "`echo __ELF__ | $CC -E - | grep __ELF__`" || test "$host_os-$host_cpu" = "openbsd2.8-powerpc"; then - archive_expsym_cmds_CXX='$CC -shared $pic_flag $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-retain-symbols-file,$export_symbols -o $lib' - export_dynamic_flag_spec_CXX='${wl}-E' - whole_archive_flag_spec_CXX="$wlarc"'--whole-archive$convenience '"$wlarc"'--no-whole-archive' + hardcode_libdir_flag_spec_CXX='$wl-rpath,$libdir' + if test -z "`echo __ELF__ | $CC -E - | grep __ELF__`"; then + archive_expsym_cmds_CXX='$CC -shared $pic_flag $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags $wl-retain-symbols-file,$export_symbols -o $lib' + export_dynamic_flag_spec_CXX='$wl-E' + whole_archive_flag_spec_CXX=$wlarc'--whole-archive$convenience '$wlarc'--no-whole-archive' fi output_verbose_link_cmd=func_echo_all else @@ -13181,9 +13799,9 @@ fi # KCC will only create a shared library if the output file # ends with ".so" (or ".sl" for HP-UX), so rename the library # to its proper name (with version) after linking. - archive_cmds_CXX='tempext=`echo $shared_ext | $SED -e '\''s/\([^()0-9A-Za-z{}]\)/\\\\\1/g'\''`; templib=`echo "$lib" | $SED -e "s/\${tempext}\..*/.so/"`; $CC $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags --soname $soname -o \$templib; mv \$templib $lib' + archive_cmds_CXX='tempext=`echo $shared_ext | $SED -e '\''s/\([^()0-9A-Za-z{}]\)/\\\\\1/g'\''`; templib=`echo "$lib" | $SED -e "s/\$tempext\..*/.so/"`; $CC $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags --soname $soname -o \$templib; mv \$templib $lib' - hardcode_libdir_flag_spec_CXX='${wl}-rpath,$libdir' + hardcode_libdir_flag_spec_CXX='$wl-rpath,$libdir' hardcode_libdir_separator_CXX=: # Archives containing C++ object files must be created using @@ -13201,17 +13819,17 @@ fi cxx*) case $host in osf3*) - allow_undefined_flag_CXX=' ${wl}-expect_unresolved ${wl}\*' - archive_cmds_CXX='$CC -shared${allow_undefined_flag} $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-soname $soname `test -n "$verstring" && func_echo_all "${wl}-set_version $verstring"` -update_registry ${output_objdir}/so_locations -o $lib' - hardcode_libdir_flag_spec_CXX='${wl}-rpath ${wl}$libdir' + allow_undefined_flag_CXX=' $wl-expect_unresolved $wl\*' + archive_cmds_CXX='$CC -shared$allow_undefined_flag $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags $wl-soname $soname `test -n "$verstring" && func_echo_all "$wl-set_version $verstring"` -update_registry $output_objdir/so_locations -o $lib' + hardcode_libdir_flag_spec_CXX='$wl-rpath $wl$libdir' ;; *) allow_undefined_flag_CXX=' -expect_unresolved \*' - archive_cmds_CXX='$CC -shared${allow_undefined_flag} $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags -msym -soname $soname `test -n "$verstring" && func_echo_all "-set_version $verstring"` -update_registry ${output_objdir}/so_locations -o $lib' + archive_cmds_CXX='$CC -shared$allow_undefined_flag $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags -msym -soname $soname `test -n "$verstring" && func_echo_all "-set_version $verstring"` -update_registry $output_objdir/so_locations -o $lib' archive_expsym_cmds_CXX='for i in `cat $export_symbols`; do printf "%s %s\\n" -exported_symbol "\$i" >> $lib.exp; done~ - echo "-hidden">> $lib.exp~ - $CC -shared$allow_undefined_flag $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags -msym -soname $soname ${wl}-input ${wl}$lib.exp `test -n "$verstring" && $ECHO "-set_version $verstring"` -update_registry ${output_objdir}/so_locations -o $lib~ - $RM $lib.exp' + echo "-hidden">> $lib.exp~ + $CC -shared$allow_undefined_flag $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags -msym -soname $soname $wl-input $wl$lib.exp `test -n "$verstring" && $ECHO "-set_version $verstring"` -update_registry $output_objdir/so_locations -o $lib~ + $RM $lib.exp' hardcode_libdir_flag_spec_CXX='-rpath $libdir' ;; esac @@ -13226,21 +13844,21 @@ fi # explicitly linking system object files so we need to strip them # from the output so that they don't get included in the library # dependencies. - output_verbose_link_cmd='templist=`$CC -shared $CFLAGS -v conftest.$objext 2>&1 | $GREP "ld" | $GREP -v "ld:"`; templist=`func_echo_all "$templist" | $SED "s/\(^.*ld.*\)\( .*ld.*$\)/\1/"`; list=""; for z in $templist; do case $z in conftest.$objext) list="$list $z";; *.$objext);; *) list="$list $z";;esac; done; func_echo_all "$list"' + output_verbose_link_cmd='templist=`$CC -shared $CFLAGS -v conftest.$objext 2>&1 | $GREP "ld" | $GREP -v "ld:"`; templist=`func_echo_all "$templist" | $SED "s/\(^.*ld.*\)\( .*ld.*$\)/\1/"`; list= ; for z in $templist; do case $z in conftest.$objext) list="$list $z";; *.$objext);; *) list="$list $z";;esac; done; func_echo_all "$list"' ;; *) - if test "$GXX" = yes && test "$with_gnu_ld" = no; then - allow_undefined_flag_CXX=' ${wl}-expect_unresolved ${wl}\*' + if test yes,no = "$GXX,$with_gnu_ld"; then + allow_undefined_flag_CXX=' $wl-expect_unresolved $wl\*' case $host in osf3*) - archive_cmds_CXX='$CC -shared -nostdlib ${allow_undefined_flag} $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-soname ${wl}$soname `test -n "$verstring" && func_echo_all "${wl}-set_version ${wl}$verstring"` ${wl}-update_registry ${wl}${output_objdir}/so_locations -o $lib' + archive_cmds_CXX='$CC -shared -nostdlib $allow_undefined_flag $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags $wl-soname $wl$soname `test -n "$verstring" && func_echo_all "$wl-set_version $wl$verstring"` $wl-update_registry $wl$output_objdir/so_locations -o $lib' ;; *) - archive_cmds_CXX='$CC -shared $pic_flag -nostdlib ${allow_undefined_flag} $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-msym ${wl}-soname ${wl}$soname `test -n "$verstring" && func_echo_all "${wl}-set_version ${wl}$verstring"` ${wl}-update_registry ${wl}${output_objdir}/so_locations -o $lib' + archive_cmds_CXX='$CC -shared $pic_flag -nostdlib $allow_undefined_flag $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags $wl-msym $wl-soname $wl$soname `test -n "$verstring" && func_echo_all "$wl-set_version $wl$verstring"` $wl-update_registry $wl$output_objdir/so_locations -o $lib' ;; esac - hardcode_libdir_flag_spec_CXX='${wl}-rpath ${wl}$libdir' + hardcode_libdir_flag_spec_CXX='$wl-rpath $wl$libdir' hardcode_libdir_separator_CXX=: # Commands to make compiler produce verbose output that lists @@ -13286,9 +13904,9 @@ fi # Sun C++ 4.2, 5.x and Centerline C++ archive_cmds_need_lc_CXX=yes no_undefined_flag_CXX=' -zdefs' - archive_cmds_CXX='$CC -G${allow_undefined_flag} -h$soname -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags' + archive_cmds_CXX='$CC -G$allow_undefined_flag -h$soname -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags' archive_expsym_cmds_CXX='echo "{ global:" > $lib.exp~cat $export_symbols | $SED -e "s/\(.*\)/\1;/" >> $lib.exp~echo "local: *; };" >> $lib.exp~ - $CC -G${allow_undefined_flag} ${wl}-M ${wl}$lib.exp -h$soname -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags~$RM $lib.exp' + $CC -G$allow_undefined_flag $wl-M $wl$lib.exp -h$soname -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags~$RM $lib.exp' hardcode_libdir_flag_spec_CXX='-R$libdir' hardcode_shlibpath_var_CXX=no @@ -13296,7 +13914,7 @@ fi solaris2.[0-5] | solaris2.[0-5].*) ;; *) # The compiler driver will combine and reorder linker options, - # but understands `-z linker_flag'. + # but understands '-z linker_flag'. # Supported since Solaris 2.6 (maybe 2.5.1?) whole_archive_flag_spec_CXX='-z allextract$convenience -z defaultextract' ;; @@ -13313,30 +13931,30 @@ fi ;; gcx*) # Green Hills C++ Compiler - archive_cmds_CXX='$CC -shared $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-h $wl$soname -o $lib' + archive_cmds_CXX='$CC -shared $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags $wl-h $wl$soname -o $lib' # The C++ compiler must be used to create the archive. old_archive_cmds_CXX='$CC $LDFLAGS -archive -o $oldlib $oldobjs' ;; *) # GNU C++ compiler with Solaris linker - if test "$GXX" = yes && test "$with_gnu_ld" = no; then - no_undefined_flag_CXX=' ${wl}-z ${wl}defs' + if test yes,no = "$GXX,$with_gnu_ld"; then + no_undefined_flag_CXX=' $wl-z ${wl}defs' if $CC --version | $GREP -v '^2\.7' > /dev/null; then - archive_cmds_CXX='$CC -shared $pic_flag -nostdlib $LDFLAGS $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-h $wl$soname -o $lib' + archive_cmds_CXX='$CC -shared $pic_flag -nostdlib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags $wl-h $wl$soname -o $lib' archive_expsym_cmds_CXX='echo "{ global:" > $lib.exp~cat $export_symbols | $SED -e "s/\(.*\)/\1;/" >> $lib.exp~echo "local: *; };" >> $lib.exp~ - $CC -shared $pic_flag -nostdlib ${wl}-M $wl$lib.exp -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags~$RM $lib.exp' + $CC -shared $pic_flag -nostdlib $wl-M $wl$lib.exp $wl-h $wl$soname -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags~$RM $lib.exp' # Commands to make compiler produce verbose output that lists # what "hidden" libraries, object files and flags are used when # linking a shared library. output_verbose_link_cmd='$CC -shared $CFLAGS -v conftest.$objext 2>&1 | $GREP -v "^Configured with:" | $GREP "\-L"' else - # g++ 2.7 appears to require `-G' NOT `-shared' on this + # g++ 2.7 appears to require '-G' NOT '-shared' on this # platform. - archive_cmds_CXX='$CC -G -nostdlib $LDFLAGS $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-h $wl$soname -o $lib' + archive_cmds_CXX='$CC -G -nostdlib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags $wl-h $wl$soname -o $lib' archive_expsym_cmds_CXX='echo "{ global:" > $lib.exp~cat $export_symbols | $SED -e "s/\(.*\)/\1;/" >> $lib.exp~echo "local: *; };" >> $lib.exp~ - $CC -G -nostdlib ${wl}-M $wl$lib.exp -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags~$RM $lib.exp' + $CC -G -nostdlib $wl-M $wl$lib.exp $wl-h $wl$soname -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags~$RM $lib.exp' # Commands to make compiler produce verbose output that lists # what "hidden" libraries, object files and flags are used when @@ -13344,11 +13962,11 @@ fi output_verbose_link_cmd='$CC -G $CFLAGS -v conftest.$objext 2>&1 | $GREP -v "^Configured with:" | $GREP "\-L"' fi - hardcode_libdir_flag_spec_CXX='${wl}-R $wl$libdir' + hardcode_libdir_flag_spec_CXX='$wl-R $wl$libdir' case $host_os in solaris2.[0-5] | solaris2.[0-5].*) ;; *) - whole_archive_flag_spec_CXX='${wl}-z ${wl}allextract$convenience ${wl}-z ${wl}defaultextract' + whole_archive_flag_spec_CXX='$wl-z ${wl}allextract$convenience $wl-z ${wl}defaultextract' ;; esac fi @@ -13357,52 +13975,52 @@ fi ;; sysv4*uw2* | sysv5OpenUNIX* | sysv5UnixWare7.[01].[10]* | unixware7* | sco3.2v5.0.[024]*) - no_undefined_flag_CXX='${wl}-z,text' + no_undefined_flag_CXX='$wl-z,text' archive_cmds_need_lc_CXX=no hardcode_shlibpath_var_CXX=no runpath_var='LD_RUN_PATH' case $cc_basename in CC*) - archive_cmds_CXX='$CC -G ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' - archive_expsym_cmds_CXX='$CC -G ${wl}-Bexport:$export_symbols ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + archive_cmds_CXX='$CC -G $wl-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + archive_expsym_cmds_CXX='$CC -G $wl-Bexport:$export_symbols $wl-h,$soname -o $lib $libobjs $deplibs $compiler_flags' ;; *) - archive_cmds_CXX='$CC -shared ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' - archive_expsym_cmds_CXX='$CC -shared ${wl}-Bexport:$export_symbols ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + archive_cmds_CXX='$CC -shared $wl-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + archive_expsym_cmds_CXX='$CC -shared $wl-Bexport:$export_symbols $wl-h,$soname -o $lib $libobjs $deplibs $compiler_flags' ;; esac ;; sysv5* | sco3.2v5* | sco5v6*) - # Note: We can NOT use -z defs as we might desire, because we do not + # Note: We CANNOT use -z defs as we might desire, because we do not # link with -lc, and that would cause any symbols used from libc to # always be unresolved, which means just about no library would # ever link correctly. If we're not using GNU ld we use -z text # though, which does catch some bad symbols but isn't as heavy-handed # as -z defs. - no_undefined_flag_CXX='${wl}-z,text' - allow_undefined_flag_CXX='${wl}-z,nodefs' + no_undefined_flag_CXX='$wl-z,text' + allow_undefined_flag_CXX='$wl-z,nodefs' archive_cmds_need_lc_CXX=no hardcode_shlibpath_var_CXX=no - hardcode_libdir_flag_spec_CXX='${wl}-R,$libdir' + hardcode_libdir_flag_spec_CXX='$wl-R,$libdir' hardcode_libdir_separator_CXX=':' link_all_deplibs_CXX=yes - export_dynamic_flag_spec_CXX='${wl}-Bexport' + export_dynamic_flag_spec_CXX='$wl-Bexport' runpath_var='LD_RUN_PATH' case $cc_basename in CC*) - archive_cmds_CXX='$CC -G ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' - archive_expsym_cmds_CXX='$CC -G ${wl}-Bexport:$export_symbols ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + archive_cmds_CXX='$CC -G $wl-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + archive_expsym_cmds_CXX='$CC -G $wl-Bexport:$export_symbols $wl-h,$soname -o $lib $libobjs $deplibs $compiler_flags' old_archive_cmds_CXX='$CC -Tprelink_objects $oldobjs~ - '"$old_archive_cmds_CXX" + '"$old_archive_cmds_CXX" reload_cmds_CXX='$CC -Tprelink_objects $reload_objs~ - '"$reload_cmds_CXX" + '"$reload_cmds_CXX" ;; *) - archive_cmds_CXX='$CC -shared ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' - archive_expsym_cmds_CXX='$CC -shared ${wl}-Bexport:$export_symbols ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + archive_cmds_CXX='$CC -shared $wl-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + archive_expsym_cmds_CXX='$CC -shared $wl-Bexport:$export_symbols $wl-h,$soname -o $lib $libobjs $deplibs $compiler_flags' ;; esac ;; @@ -13434,10 +14052,10 @@ fi { $as_echo "$as_me:${as_lineno-$LINENO}: result: $ld_shlibs_CXX" >&5 $as_echo "$ld_shlibs_CXX" >&6; } - test "$ld_shlibs_CXX" = no && can_build_shared=no + test no = "$ld_shlibs_CXX" && can_build_shared=no - GCC_CXX="$GXX" - LD_CXX="$LD" + GCC_CXX=$GXX + LD_CXX=$LD ## CAVEAT EMPTOR: ## There is no encapsulation within the following macros, do not change @@ -13481,13 +14099,13 @@ if { { eval echo "\"\$as_me\":${as_lineno-$LINENO}: \"$ac_compile\""; } >&5 pre_test_object_deps_done=no for p in `eval "$output_verbose_link_cmd"`; do - case ${prev}${p} in + case $prev$p in -L* | -R* | -l*) # Some compilers place space between "-{L,R}" and the path. # Remove the space. - if test $p = "-L" || - test $p = "-R"; then + if test x-L = "$p" || + test x-R = "$p"; then prev=$p continue fi @@ -13503,16 +14121,16 @@ if { { eval echo "\"\$as_me\":${as_lineno-$LINENO}: \"$ac_compile\""; } >&5 case $p in =*) func_stripname_cnf '=' '' "$p"; p=$lt_sysroot$func_stripname_result ;; esac - if test "$pre_test_object_deps_done" = no; then - case ${prev} in + if test no = "$pre_test_object_deps_done"; then + case $prev in -L | -R) # Internal compiler library paths should come after those # provided the user. The postdeps already come after the # user supplied libs so there is no need to process them. if test -z "$compiler_lib_search_path_CXX"; then - compiler_lib_search_path_CXX="${prev}${p}" + compiler_lib_search_path_CXX=$prev$p else - compiler_lib_search_path_CXX="${compiler_lib_search_path_CXX} ${prev}${p}" + compiler_lib_search_path_CXX="${compiler_lib_search_path_CXX} $prev$p" fi ;; # The "-l" case would never come before the object being @@ -13520,9 +14138,9 @@ if { { eval echo "\"\$as_me\":${as_lineno-$LINENO}: \"$ac_compile\""; } >&5 esac else if test -z "$postdeps_CXX"; then - postdeps_CXX="${prev}${p}" + postdeps_CXX=$prev$p else - postdeps_CXX="${postdeps_CXX} ${prev}${p}" + postdeps_CXX="${postdeps_CXX} $prev$p" fi fi prev= @@ -13537,15 +14155,15 @@ if { { eval echo "\"\$as_me\":${as_lineno-$LINENO}: \"$ac_compile\""; } >&5 continue fi - if test "$pre_test_object_deps_done" = no; then + if test no = "$pre_test_object_deps_done"; then if test -z "$predep_objects_CXX"; then - predep_objects_CXX="$p" + predep_objects_CXX=$p else predep_objects_CXX="$predep_objects_CXX $p" fi else if test -z "$postdep_objects_CXX"; then - postdep_objects_CXX="$p" + postdep_objects_CXX=$p else postdep_objects_CXX="$postdep_objects_CXX $p" fi @@ -13575,51 +14193,6 @@ interix[3-9]*) postdep_objects_CXX= postdeps_CXX= ;; - -linux*) - case `$CC -V 2>&1 | sed 5q` in - *Sun\ C*) - # Sun C++ 5.9 - - # The more standards-conforming stlport4 library is - # incompatible with the Cstd library. Avoid specifying - # it if it's in CXXFLAGS. Ignore libCrun as - # -library=stlport4 depends on it. - case " $CXX $CXXFLAGS " in - *" -library=stlport4 "*) - solaris_use_stlport4=yes - ;; - esac - - if test "$solaris_use_stlport4" != yes; then - postdeps_CXX='-library=Cstd -library=Crun' - fi - ;; - esac - ;; - -solaris*) - case $cc_basename in - CC* | sunCC*) - # The more standards-conforming stlport4 library is - # incompatible with the Cstd library. Avoid specifying - # it if it's in CXXFLAGS. Ignore libCrun as - # -library=stlport4 depends on it. - case " $CXX $CXXFLAGS " in - *" -library=stlport4 "*) - solaris_use_stlport4=yes - ;; - esac - - # Adding this requires a known-good setup of shared libraries for - # Sun compiler versions before 5.6, else PIC objects from an old - # archive will be linked into the output, leading to subtle bugs. - if test "$solaris_use_stlport4" != yes; then - postdeps_CXX='-library=Cstd -library=Crun' - fi - ;; - esac - ;; esac @@ -13628,7 +14201,7 @@ case " $postdeps_CXX " in esac compiler_lib_search_dirs_CXX= if test -n "${compiler_lib_search_path_CXX}"; then - compiler_lib_search_dirs_CXX=`echo " ${compiler_lib_search_path_CXX}" | ${SED} -e 's! -L! !g' -e 's!^ !!'` + compiler_lib_search_dirs_CXX=`echo " ${compiler_lib_search_path_CXX}" | $SED -e 's! -L! !g' -e 's!^ !!'` fi @@ -13667,17 +14240,18 @@ lt_prog_compiler_static_CXX= # C++ specific cases for pic, static, wl, etc. - if test "$GXX" = yes; then + if test yes = "$GXX"; then lt_prog_compiler_wl_CXX='-Wl,' lt_prog_compiler_static_CXX='-static' case $host_os in aix*) # All AIX code is PIC. - if test "$host_cpu" = ia64; then + if test ia64 = "$host_cpu"; then # AIX 5 now supports IA64 processor lt_prog_compiler_static_CXX='-Bstatic' fi + lt_prog_compiler_pic_CXX='-fPIC' ;; amigaos*) @@ -13688,8 +14262,8 @@ lt_prog_compiler_static_CXX= ;; m68k) # FIXME: we need at least 68020 code to build shared libraries, but - # adding the `-m68020' flag to GCC prevents building anything better, - # like `-m68040'. + # adding the '-m68020' flag to GCC prevents building anything better, + # like '-m68040'. lt_prog_compiler_pic_CXX='-m68020 -resident32 -malways-restore-a4' ;; esac @@ -13704,6 +14278,11 @@ lt_prog_compiler_static_CXX= # Although the cygwin gcc ignores -fPIC, still need this for old-style # (--disable-auto-import) libraries lt_prog_compiler_pic_CXX='-DDLL_EXPORT' + case $host_os in + os2*) + lt_prog_compiler_static_CXX='$wl-static' + ;; + esac ;; darwin* | rhapsody*) # PIC is the default on this platform @@ -13753,7 +14332,7 @@ lt_prog_compiler_static_CXX= case $host_os in aix[4-9]*) # All AIX code is PIC. - if test "$host_cpu" = ia64; then + if test ia64 = "$host_cpu"; then # AIX 5 now supports IA64 processor lt_prog_compiler_static_CXX='-Bstatic' else @@ -13793,14 +14372,14 @@ lt_prog_compiler_static_CXX= case $cc_basename in CC*) lt_prog_compiler_wl_CXX='-Wl,' - lt_prog_compiler_static_CXX='${wl}-a ${wl}archive' - if test "$host_cpu" != ia64; then + lt_prog_compiler_static_CXX='$wl-a ${wl}archive' + if test ia64 != "$host_cpu"; then lt_prog_compiler_pic_CXX='+Z' fi ;; aCC*) lt_prog_compiler_wl_CXX='-Wl,' - lt_prog_compiler_static_CXX='${wl}-a ${wl}archive' + lt_prog_compiler_static_CXX='$wl-a ${wl}archive' case $host_cpu in hppa*64*|ia64*) # +Z the default @@ -13829,7 +14408,7 @@ lt_prog_compiler_static_CXX= ;; esac ;; - linux* | k*bsd*-gnu | kopensolaris*-gnu) + linux* | k*bsd*-gnu | kopensolaris*-gnu | gnu*) case $cc_basename in KCC*) # KAI C++ Compiler @@ -13837,7 +14416,7 @@ lt_prog_compiler_static_CXX= lt_prog_compiler_pic_CXX='-fPIC' ;; ecpc* ) - # old Intel C++ for x86_64 which still supported -KPIC. + # old Intel C++ for x86_64, which still supported -KPIC. lt_prog_compiler_wl_CXX='-Wl,' lt_prog_compiler_pic_CXX='-KPIC' lt_prog_compiler_static_CXX='-static' @@ -13982,7 +14561,7 @@ lt_prog_compiler_static_CXX= fi case $host_os in - # For platforms which do not support PIC, -DPIC is meaningless: + # For platforms that do not support PIC, -DPIC is meaningless: *djgpp*) lt_prog_compiler_pic_CXX= ;; @@ -14014,7 +14593,7 @@ else lt_cv_prog_compiler_pic_works_CXX=no ac_outfile=conftest.$ac_objext echo "$lt_simple_compile_test_code" > conftest.$ac_ext - lt_compiler_flag="$lt_prog_compiler_pic_CXX -DPIC" + lt_compiler_flag="$lt_prog_compiler_pic_CXX -DPIC" ## exclude from sc_useless_quotes_in_assignment # Insert the option either (1) after the last *FLAGS variable, or # (2) before a word containing "conftest.", or (3) at the end. # Note that $ac_compile itself does not contain backslashes and begins @@ -14044,7 +14623,7 @@ fi { $as_echo "$as_me:${as_lineno-$LINENO}: result: $lt_cv_prog_compiler_pic_works_CXX" >&5 $as_echo "$lt_cv_prog_compiler_pic_works_CXX" >&6; } -if test x"$lt_cv_prog_compiler_pic_works_CXX" = xyes; then +if test yes = "$lt_cv_prog_compiler_pic_works_CXX"; then case $lt_prog_compiler_pic_CXX in "" | " "*) ;; *) lt_prog_compiler_pic_CXX=" $lt_prog_compiler_pic_CXX" ;; @@ -14070,7 +14649,7 @@ if ${lt_cv_prog_compiler_static_works_CXX+:} false; then : $as_echo_n "(cached) " >&6 else lt_cv_prog_compiler_static_works_CXX=no - save_LDFLAGS="$LDFLAGS" + save_LDFLAGS=$LDFLAGS LDFLAGS="$LDFLAGS $lt_tmp_static_flag" echo "$lt_simple_link_test_code" > conftest.$ac_ext if (eval $ac_link 2>conftest.err) && test -s conftest$ac_exeext; then @@ -14089,13 +14668,13 @@ else fi fi $RM -r conftest* - LDFLAGS="$save_LDFLAGS" + LDFLAGS=$save_LDFLAGS fi { $as_echo "$as_me:${as_lineno-$LINENO}: result: $lt_cv_prog_compiler_static_works_CXX" >&5 $as_echo "$lt_cv_prog_compiler_static_works_CXX" >&6; } -if test x"$lt_cv_prog_compiler_static_works_CXX" = xyes; then +if test yes = "$lt_cv_prog_compiler_static_works_CXX"; then : else lt_prog_compiler_static_CXX= @@ -14209,8 +14788,8 @@ $as_echo "$lt_cv_prog_compiler_c_o_CXX" >&6; } -hard_links="nottested" -if test "$lt_cv_prog_compiler_c_o_CXX" = no && test "$need_locks" != no; then +hard_links=nottested +if test no = "$lt_cv_prog_compiler_c_o_CXX" && test no != "$need_locks"; then # do not overwrite the value of need_locks provided by the user { $as_echo "$as_me:${as_lineno-$LINENO}: checking if we can lock with hard links" >&5 $as_echo_n "checking if we can lock with hard links... " >&6; } @@ -14222,9 +14801,9 @@ $as_echo_n "checking if we can lock with hard links... " >&6; } ln conftest.a conftest.b 2>/dev/null && hard_links=no { $as_echo "$as_me:${as_lineno-$LINENO}: result: $hard_links" >&5 $as_echo "$hard_links" >&6; } - if test "$hard_links" = no; then - { $as_echo "$as_me:${as_lineno-$LINENO}: WARNING: \`$CC' does not support \`-c -o', so \`make -j' may be unsafe" >&5 -$as_echo "$as_me: WARNING: \`$CC' does not support \`-c -o', so \`make -j' may be unsafe" >&2;} + if test no = "$hard_links"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: WARNING: '$CC' does not support '-c -o', so 'make -j' may be unsafe" >&5 +$as_echo "$as_me: WARNING: '$CC' does not support '-c -o', so 'make -j' may be unsafe" >&2;} need_locks=warn fi else @@ -14241,17 +14820,21 @@ $as_echo_n "checking whether the $compiler linker ($LD) supports shared librarie case $host_os in aix[4-9]*) # If we're using GNU nm, then we don't want the "-C" option. - # -C means demangle to AIX nm, but means don't demangle with GNU nm - # Also, AIX nm treats weak defined symbols like other global defined - # symbols, whereas GNU nm marks them as "W". + # -C means demangle to GNU nm, but means don't demangle to AIX nm. + # Without the "-l" option, or with the "-B" option, AIX nm treats + # weak defined symbols like other global defined symbols, whereas + # GNU nm marks them as "W". + # While the 'weak' keyword is ignored in the Export File, we need + # it in the Import File for the 'aix-soname' feature, so we have + # to replace the "-B" option with "-P" for AIX nm. if $NM -V 2>&1 | $GREP 'GNU' > /dev/null; then - export_symbols_cmds_CXX='$NM -Bpg $libobjs $convenience | awk '\''{ if (((\$ 2 == "T") || (\$ 2 == "D") || (\$ 2 == "B") || (\$ 2 == "W")) && (substr(\$ 3,1,1) != ".")) { print \$ 3 } }'\'' | sort -u > $export_symbols' + export_symbols_cmds_CXX='$NM -Bpg $libobjs $convenience | awk '\''{ if (((\$ 2 == "T") || (\$ 2 == "D") || (\$ 2 == "B") || (\$ 2 == "W")) && (substr(\$ 3,1,1) != ".")) { if (\$ 2 == "W") { print \$ 3 " weak" } else { print \$ 3 } } }'\'' | sort -u > $export_symbols' else - export_symbols_cmds_CXX='$NM -BCpg $libobjs $convenience | awk '\''{ if (((\$ 2 == "T") || (\$ 2 == "D") || (\$ 2 == "B")) && (substr(\$ 3,1,1) != ".")) { print \$ 3 } }'\'' | sort -u > $export_symbols' + export_symbols_cmds_CXX='`func_echo_all $NM | $SED -e '\''s/B\([^B]*\)$/P\1/'\''` -PCpgl $libobjs $convenience | awk '\''{ if (((\$ 2 == "T") || (\$ 2 == "D") || (\$ 2 == "B") || (\$ 2 == "W") || (\$ 2 == "V") || (\$ 2 == "Z")) && (substr(\$ 1,1,1) != ".")) { if ((\$ 2 == "W") || (\$ 2 == "V") || (\$ 2 == "Z")) { print \$ 1 " weak" } else { print \$ 1 } } }'\'' | sort -u > $export_symbols' fi ;; pw32*) - export_symbols_cmds_CXX="$ltdll_cmds" + export_symbols_cmds_CXX=$ltdll_cmds ;; cygwin* | mingw* | cegcc*) case $cc_basename in @@ -14271,7 +14854,7 @@ $as_echo_n "checking whether the $compiler linker ($LD) supports shared librarie { $as_echo "$as_me:${as_lineno-$LINENO}: result: $ld_shlibs_CXX" >&5 $as_echo "$ld_shlibs_CXX" >&6; } -test "$ld_shlibs_CXX" = no && can_build_shared=no +test no = "$ld_shlibs_CXX" && can_build_shared=no with_gnu_ld_CXX=$with_gnu_ld @@ -14288,7 +14871,7 @@ x|xyes) # Assume -lc should be added archive_cmds_need_lc_CXX=yes - if test "$enable_shared" = yes && test "$GCC" = yes; then + if test yes,yes = "$GCC,$enable_shared"; then case $archive_cmds_CXX in *'~'*) # FIXME: we may have to deal with multi-command sequences. @@ -14416,7 +14999,7 @@ $as_echo_n "checking dynamic linker characteristics... " >&6; } library_names_spec= libname_spec='lib$name' soname_spec= -shrext_cmds=".so" +shrext_cmds=.so postinstall_cmds= postuninstall_cmds= finish_cmds= @@ -14433,14 +15016,16 @@ hardcode_into_libs=no # flags to be left without arguments need_version=unknown + + case $host_os in aix3*) version_type=linux # correct to gnu/linux during the next big refactor - library_names_spec='${libname}${release}${shared_ext}$versuffix $libname.a' + library_names_spec='$libname$release$shared_ext$versuffix $libname.a' shlibpath_var=LIBPATH # AIX 3 has no versioning support, so we append a major version to the name. - soname_spec='${libname}${release}${shared_ext}$major' + soname_spec='$libname$release$shared_ext$major' ;; aix[4-9]*) @@ -14448,41 +15033,91 @@ aix[4-9]*) need_lib_prefix=no need_version=no hardcode_into_libs=yes - if test "$host_cpu" = ia64; then + if test ia64 = "$host_cpu"; then # AIX 5 supports IA64 - library_names_spec='${libname}${release}${shared_ext}$major ${libname}${release}${shared_ext}$versuffix $libname${shared_ext}' + library_names_spec='$libname$release$shared_ext$major $libname$release$shared_ext$versuffix $libname$shared_ext' shlibpath_var=LD_LIBRARY_PATH else # With GCC up to 2.95.x, collect2 would create an import file # for dependence libraries. The import file would start with - # the line `#! .'. This would cause the generated library to - # depend on `.', always an invalid library. This was fixed in + # the line '#! .'. This would cause the generated library to + # depend on '.', always an invalid library. This was fixed in # development snapshots of GCC prior to 3.0. case $host_os in aix4 | aix4.[01] | aix4.[01].*) if { echo '#if __GNUC__ > 2 || (__GNUC__ == 2 && __GNUC_MINOR__ >= 97)' echo ' yes ' - echo '#endif'; } | ${CC} -E - | $GREP yes > /dev/null; then + echo '#endif'; } | $CC -E - | $GREP yes > /dev/null; then : else can_build_shared=no fi ;; esac - # AIX (on Power*) has no versioning support, so currently we can not hardcode correct + # Using Import Files as archive members, it is possible to support + # filename-based versioning of shared library archives on AIX. While + # this would work for both with and without runtime linking, it will + # prevent static linking of such archives. So we do filename-based + # shared library versioning with .so extension only, which is used + # when both runtime linking and shared linking is enabled. + # Unfortunately, runtime linking may impact performance, so we do + # not want this to be the default eventually. Also, we use the + # versioned .so libs for executables only if there is the -brtl + # linker flag in LDFLAGS as well, or --with-aix-soname=svr4 only. + # To allow for filename-based versioning support, we need to create + # libNAME.so.V as an archive file, containing: + # *) an Import File, referring to the versioned filename of the + # archive as well as the shared archive member, telling the + # bitwidth (32 or 64) of that shared object, and providing the + # list of exported symbols of that shared object, eventually + # decorated with the 'weak' keyword + # *) the shared object with the F_LOADONLY flag set, to really avoid + # it being seen by the linker. + # At run time we better use the real file rather than another symlink, + # but for link time we create the symlink libNAME.so -> libNAME.so.V + + case $with_aix_soname,$aix_use_runtimelinking in + # AIX (on Power*) has no versioning support, so currently we cannot hardcode correct # soname into executable. Probably we can add versioning support to # collect2, so additional links can be useful in future. - if test "$aix_use_runtimelinking" = yes; then + aix,yes) # traditional libtool + dynamic_linker='AIX unversionable lib.so' # If using run time linking (on AIX 4.2 or later) use lib.so # instead of lib.a to let people know that these are not # typical AIX shared libraries. - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' - else + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$shared_ext' + ;; + aix,no) # traditional AIX only + dynamic_linker='AIX lib.a(lib.so.V)' # We preserve .a as extension for shared libraries through AIX4.2 # and later when we are not doing run time linking. - library_names_spec='${libname}${release}.a $libname.a' - soname_spec='${libname}${release}${shared_ext}$major' - fi + library_names_spec='$libname$release.a $libname.a' + soname_spec='$libname$release$shared_ext$major' + ;; + svr4,*) # full svr4 only + dynamic_linker="AIX lib.so.V($shared_archive_member_spec.o)" + library_names_spec='$libname$release$shared_ext$major $libname$shared_ext' + # We do not specify a path in Import Files, so LIBPATH fires. + shlibpath_overrides_runpath=yes + ;; + *,yes) # both, prefer svr4 + dynamic_linker="AIX lib.so.V($shared_archive_member_spec.o), lib.a(lib.so.V)" + library_names_spec='$libname$release$shared_ext$major $libname$shared_ext' + # unpreferred sharedlib libNAME.a needs extra handling + postinstall_cmds='test -n "$linkname" || linkname="$realname"~func_stripname "" ".so" "$linkname"~$install_shared_prog "$dir/$func_stripname_result.$libext" "$destdir/$func_stripname_result.$libext"~test -z "$tstripme" || test -z "$striplib" || $striplib "$destdir/$func_stripname_result.$libext"' + postuninstall_cmds='for n in $library_names $old_library; do :; done~func_stripname "" ".so" "$n"~test "$func_stripname_result" = "$n" || func_append rmfiles " $odir/$func_stripname_result.$libext"' + # We do not specify a path in Import Files, so LIBPATH fires. + shlibpath_overrides_runpath=yes + ;; + *,no) # both, prefer aix + dynamic_linker="AIX lib.a(lib.so.V), lib.so.V($shared_archive_member_spec.o)" + library_names_spec='$libname$release.a $libname.a' + soname_spec='$libname$release$shared_ext$major' + # unpreferred sharedlib libNAME.so.V and symlink libNAME.so need extra handling + postinstall_cmds='test -z "$dlname" || $install_shared_prog $dir/$dlname $destdir/$dlname~test -z "$tstripme" || test -z "$striplib" || $striplib $destdir/$dlname~test -n "$linkname" || linkname=$realname~func_stripname "" ".a" "$linkname"~(cd "$destdir" && $LN_S -f $dlname $func_stripname_result.so)' + postuninstall_cmds='test -z "$dlname" || func_append rmfiles " $odir/$dlname"~for n in $old_library $library_names; do :; done~func_stripname "" ".a" "$n"~func_append rmfiles " $odir/$func_stripname_result.so"' + ;; + esac shlibpath_var=LIBPATH fi ;; @@ -14492,18 +15127,18 @@ amigaos*) powerpc) # Since July 2007 AmigaOS4 officially supports .so libraries. # When compiling the executable, add -use-dynld -Lsobjs: to the compileline. - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$shared_ext' ;; m68k) library_names_spec='$libname.ixlibrary $libname.a' # Create ${libname}_ixlibrary.a entries in /sys/libs. - finish_eval='for lib in `ls $libdir/*.ixlibrary 2>/dev/null`; do libname=`func_echo_all "$lib" | $SED '\''s%^.*/\([^/]*\)\.ixlibrary$%\1%'\''`; test $RM /sys/libs/${libname}_ixlibrary.a; $show "cd /sys/libs && $LN_S $lib ${libname}_ixlibrary.a"; cd /sys/libs && $LN_S $lib ${libname}_ixlibrary.a || exit 1; done' + finish_eval='for lib in `ls $libdir/*.ixlibrary 2>/dev/null`; do libname=`func_echo_all "$lib" | $SED '\''s%^.*/\([^/]*\)\.ixlibrary$%\1%'\''`; $RM /sys/libs/${libname}_ixlibrary.a; $show "cd /sys/libs && $LN_S $lib ${libname}_ixlibrary.a"; cd /sys/libs && $LN_S $lib ${libname}_ixlibrary.a || exit 1; done' ;; esac ;; beos*) - library_names_spec='${libname}${shared_ext}' + library_names_spec='$libname$shared_ext' dynamic_linker="$host_os ld.so" shlibpath_var=LIBRARY_PATH ;; @@ -14511,8 +15146,8 @@ beos*) bsdi[45]*) version_type=linux # correct to gnu/linux during the next big refactor need_version=no - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' - soname_spec='${libname}${release}${shared_ext}$major' + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$shared_ext' + soname_spec='$libname$release$shared_ext$major' finish_cmds='PATH="\$PATH:/sbin" ldconfig $libdir' shlibpath_var=LD_LIBRARY_PATH sys_lib_search_path_spec="/shlib /usr/lib /usr/X11/lib /usr/contrib/lib /lib /usr/local/lib" @@ -14524,7 +15159,7 @@ bsdi[45]*) cygwin* | mingw* | pw32* | cegcc*) version_type=windows - shrext_cmds=".dll" + shrext_cmds=.dll need_version=no need_lib_prefix=no @@ -14533,8 +15168,8 @@ cygwin* | mingw* | pw32* | cegcc*) # gcc library_names_spec='$libname.dll.a' # DLL is installed to $(libdir)/../bin by postinstall_cmds - postinstall_cmds='base_file=`basename \${file}`~ - dlpath=`$SHELL 2>&1 -c '\''. $dir/'\''\${base_file}'\''i; echo \$dlname'\''`~ + postinstall_cmds='base_file=`basename \$file`~ + dlpath=`$SHELL 2>&1 -c '\''. $dir/'\''\$base_file'\''i; echo \$dlname'\''`~ dldir=$destdir/`dirname \$dlpath`~ test -d \$dldir || mkdir -p \$dldir~ $install_prog $dir/$dlname \$dldir/$dlname~ @@ -14550,16 +15185,16 @@ cygwin* | mingw* | pw32* | cegcc*) case $host_os in cygwin*) # Cygwin DLLs use 'cyg' prefix rather than 'lib' - soname_spec='`echo ${libname} | sed -e 's/^lib/cyg/'``echo ${release} | $SED -e 's/[.]/-/g'`${versuffix}${shared_ext}' + soname_spec='`echo $libname | sed -e 's/^lib/cyg/'``echo $release | $SED -e 's/[.]/-/g'`$versuffix$shared_ext' ;; mingw* | cegcc*) # MinGW DLLs use traditional 'lib' prefix - soname_spec='${libname}`echo ${release} | $SED -e 's/[.]/-/g'`${versuffix}${shared_ext}' + soname_spec='$libname`echo $release | $SED -e 's/[.]/-/g'`$versuffix$shared_ext' ;; pw32*) # pw32 DLLs use 'pw' prefix rather than 'lib' - library_names_spec='`echo ${libname} | sed -e 's/^lib/pw/'``echo ${release} | $SED -e 's/[.]/-/g'`${versuffix}${shared_ext}' + library_names_spec='`echo $libname | sed -e 's/^lib/pw/'``echo $release | $SED -e 's/[.]/-/g'`$versuffix$shared_ext' ;; esac dynamic_linker='Win32 ld.exe' @@ -14568,8 +15203,8 @@ cygwin* | mingw* | pw32* | cegcc*) *,cl*) # Native MSVC libname_spec='$name' - soname_spec='${libname}`echo ${release} | $SED -e 's/[.]/-/g'`${versuffix}${shared_ext}' - library_names_spec='${libname}.dll.lib' + soname_spec='$libname`echo $release | $SED -e 's/[.]/-/g'`$versuffix$shared_ext' + library_names_spec='$libname.dll.lib' case $build_os in mingw*) @@ -14596,7 +15231,7 @@ cygwin* | mingw* | pw32* | cegcc*) sys_lib_search_path_spec=`cygpath --path --unix "$sys_lib_search_path_spec" | $SED -e "s/$PATH_SEPARATOR/ /g"` ;; *) - sys_lib_search_path_spec="$LIB" + sys_lib_search_path_spec=$LIB if $ECHO "$sys_lib_search_path_spec" | $GREP ';[c-zC-Z]:/' >/dev/null; then # It is most probably a Windows format PATH. sys_lib_search_path_spec=`$ECHO "$sys_lib_search_path_spec" | $SED -e 's/;/ /g'` @@ -14609,8 +15244,8 @@ cygwin* | mingw* | pw32* | cegcc*) esac # DLL is installed to $(libdir)/../bin by postinstall_cmds - postinstall_cmds='base_file=`basename \${file}`~ - dlpath=`$SHELL 2>&1 -c '\''. $dir/'\''\${base_file}'\''i; echo \$dlname'\''`~ + postinstall_cmds='base_file=`basename \$file`~ + dlpath=`$SHELL 2>&1 -c '\''. $dir/'\''\$base_file'\''i; echo \$dlname'\''`~ dldir=$destdir/`dirname \$dlpath`~ test -d \$dldir || mkdir -p \$dldir~ $install_prog $dir/$dlname \$dldir/$dlname' @@ -14623,7 +15258,7 @@ cygwin* | mingw* | pw32* | cegcc*) *) # Assume MSVC wrapper - library_names_spec='${libname}`echo ${release} | $SED -e 's/[.]/-/g'`${versuffix}${shared_ext} $libname.lib' + library_names_spec='$libname`echo $release | $SED -e 's/[.]/-/g'`$versuffix$shared_ext $libname.lib' dynamic_linker='Win32 ld.exe' ;; esac @@ -14636,8 +15271,8 @@ darwin* | rhapsody*) version_type=darwin need_lib_prefix=no need_version=no - library_names_spec='${libname}${release}${major}$shared_ext ${libname}$shared_ext' - soname_spec='${libname}${release}${major}$shared_ext' + library_names_spec='$libname$release$major$shared_ext $libname$shared_ext' + soname_spec='$libname$release$major$shared_ext' shlibpath_overrides_runpath=yes shlibpath_var=DYLD_LIBRARY_PATH shrext_cmds='`test .$module = .yes && echo .so || echo .dylib`' @@ -14649,8 +15284,8 @@ dgux*) version_type=linux # correct to gnu/linux during the next big refactor need_lib_prefix=no need_version=no - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname$shared_ext' - soname_spec='${libname}${release}${shared_ext}$major' + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$shared_ext' + soname_spec='$libname$release$shared_ext$major' shlibpath_var=LD_LIBRARY_PATH ;; @@ -14668,12 +15303,13 @@ freebsd* | dragonfly*) version_type=freebsd-$objformat case $version_type in freebsd-elf*) - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext} $libname${shared_ext}' + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$shared_ext' + soname_spec='$libname$release$shared_ext$major' need_version=no need_lib_prefix=no ;; freebsd-*) - library_names_spec='${libname}${release}${shared_ext}$versuffix $libname${shared_ext}$versuffix' + library_names_spec='$libname$release$shared_ext$versuffix $libname$shared_ext$versuffix' need_version=yes ;; esac @@ -14698,26 +15334,15 @@ freebsd* | dragonfly*) esac ;; -gnu*) - version_type=linux # correct to gnu/linux during the next big refactor - need_lib_prefix=no - need_version=no - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}${major} ${libname}${shared_ext}' - soname_spec='${libname}${release}${shared_ext}$major' - shlibpath_var=LD_LIBRARY_PATH - shlibpath_overrides_runpath=no - hardcode_into_libs=yes - ;; - haiku*) version_type=linux # correct to gnu/linux during the next big refactor need_lib_prefix=no need_version=no dynamic_linker="$host_os runtime_loader" - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}${major} ${libname}${shared_ext}' - soname_spec='${libname}${release}${shared_ext}$major' + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$shared_ext' + soname_spec='$libname$release$shared_ext$major' shlibpath_var=LIBRARY_PATH - shlibpath_overrides_runpath=yes + shlibpath_overrides_runpath=no sys_lib_dlsearch_path_spec='/boot/home/config/lib /boot/common/lib /boot/system/lib' hardcode_into_libs=yes ;; @@ -14735,14 +15360,15 @@ hpux9* | hpux10* | hpux11*) dynamic_linker="$host_os dld.so" shlibpath_var=LD_LIBRARY_PATH shlibpath_overrides_runpath=yes # Unless +noenvvar is specified. - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' - soname_spec='${libname}${release}${shared_ext}$major' - if test "X$HPUX_IA64_MODE" = X32; then + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$shared_ext' + soname_spec='$libname$release$shared_ext$major' + if test 32 = "$HPUX_IA64_MODE"; then sys_lib_search_path_spec="/usr/lib/hpux32 /usr/local/lib/hpux32 /usr/local/lib" + sys_lib_dlsearch_path_spec=/usr/lib/hpux32 else sys_lib_search_path_spec="/usr/lib/hpux64 /usr/local/lib/hpux64" + sys_lib_dlsearch_path_spec=/usr/lib/hpux64 fi - sys_lib_dlsearch_path_spec=$sys_lib_search_path_spec ;; hppa*64*) shrext_cmds='.sl' @@ -14750,8 +15376,8 @@ hpux9* | hpux10* | hpux11*) dynamic_linker="$host_os dld.sl" shlibpath_var=LD_LIBRARY_PATH # How should we handle SHLIB_PATH shlibpath_overrides_runpath=yes # Unless +noenvvar is specified. - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' - soname_spec='${libname}${release}${shared_ext}$major' + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$shared_ext' + soname_spec='$libname$release$shared_ext$major' sys_lib_search_path_spec="/usr/lib/pa20_64 /usr/ccs/lib/pa20_64" sys_lib_dlsearch_path_spec=$sys_lib_search_path_spec ;; @@ -14760,8 +15386,8 @@ hpux9* | hpux10* | hpux11*) dynamic_linker="$host_os dld.sl" shlibpath_var=SHLIB_PATH shlibpath_overrides_runpath=no # +s is required to enable SHLIB_PATH - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' - soname_spec='${libname}${release}${shared_ext}$major' + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$shared_ext' + soname_spec='$libname$release$shared_ext$major' ;; esac # HP-UX runs *really* slowly unless shared libraries are mode 555, ... @@ -14774,8 +15400,8 @@ interix[3-9]*) version_type=linux # correct to gnu/linux during the next big refactor need_lib_prefix=no need_version=no - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major ${libname}${shared_ext}' - soname_spec='${libname}${release}${shared_ext}$major' + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$shared_ext' + soname_spec='$libname$release$shared_ext$major' dynamic_linker='Interix 3.x ld.so.1 (PE, like ELF)' shlibpath_var=LD_LIBRARY_PATH shlibpath_overrides_runpath=no @@ -14786,7 +15412,7 @@ irix5* | irix6* | nonstopux*) case $host_os in nonstopux*) version_type=nonstopux ;; *) - if test "$lt_cv_prog_gnu_ld" = yes; then + if test yes = "$lt_cv_prog_gnu_ld"; then version_type=linux # correct to gnu/linux during the next big refactor else version_type=irix @@ -14794,8 +15420,8 @@ irix5* | irix6* | nonstopux*) esac need_lib_prefix=no need_version=no - soname_spec='${libname}${release}${shared_ext}$major' - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major ${libname}${release}${shared_ext} $libname${shared_ext}' + soname_spec='$libname$release$shared_ext$major' + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$release$shared_ext $libname$shared_ext' case $host_os in irix5* | nonstopux*) libsuff= shlibsuff= @@ -14814,8 +15440,8 @@ irix5* | irix6* | nonstopux*) esac shlibpath_var=LD_LIBRARY${shlibsuff}_PATH shlibpath_overrides_runpath=no - sys_lib_search_path_spec="/usr/lib${libsuff} /lib${libsuff} /usr/local/lib${libsuff}" - sys_lib_dlsearch_path_spec="/usr/lib${libsuff} /lib${libsuff}" + sys_lib_search_path_spec="/usr/lib$libsuff /lib$libsuff /usr/local/lib$libsuff" + sys_lib_dlsearch_path_spec="/usr/lib$libsuff /lib$libsuff" hardcode_into_libs=yes ;; @@ -14824,13 +15450,33 @@ linux*oldld* | linux*aout* | linux*coff*) dynamic_linker=no ;; +linux*android*) + version_type=none # Android doesn't support versioned libraries. + need_lib_prefix=no + need_version=no + library_names_spec='$libname$release$shared_ext' + soname_spec='$libname$release$shared_ext' + finish_cmds= + shlibpath_var=LD_LIBRARY_PATH + shlibpath_overrides_runpath=yes + + # This implies no fast_install, which is unacceptable. + # Some rework will be needed to allow for fast_install + # before this can be enabled. + hardcode_into_libs=yes + + dynamic_linker='Android linker' + # Don't embed -rpath directories since the linker doesn't support them. + hardcode_libdir_flag_spec_CXX='-L$libdir' + ;; + # This must be glibc/ELF. -linux* | k*bsd*-gnu | kopensolaris*-gnu) +linux* | k*bsd*-gnu | kopensolaris*-gnu | gnu*) version_type=linux # correct to gnu/linux during the next big refactor need_lib_prefix=no need_version=no - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' - soname_spec='${libname}${release}${shared_ext}$major' + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$shared_ext' + soname_spec='$libname$release$shared_ext$major' finish_cmds='PATH="\$PATH:/sbin" ldconfig -n $libdir' shlibpath_var=LD_LIBRARY_PATH shlibpath_overrides_runpath=no @@ -14877,11 +15523,15 @@ fi # Add ABI-specific directories to the system library path. sys_lib_dlsearch_path_spec="/lib64 /usr/lib64 /lib /usr/lib" - # Append ld.so.conf contents to the search path + # Ideally, we could use ldconfig to report *all* directores which are + # searched for libraries, however this is still not possible. Aside from not + # being certain /sbin/ldconfig is available, command + # 'ldconfig -N -X -v | grep ^/' on 64bit Fedora does not report /usr/lib64, + # even though it is searched at run-time. Try to do the best guess by + # appending ld.so.conf contents (and includes) to the search path. if test -f /etc/ld.so.conf; then lt_ld_extra=`awk '/^include / { system(sprintf("cd /etc; cat %s 2>/dev/null", \$2)); skip = 1; } { if (!skip) print \$0; skip = 0; }' < /etc/ld.so.conf | $SED -e 's/#.*//;/^[ ]*hwcap[ ]/d;s/[:, ]/ /g;s/=[^=]*$//;s/=[^= ]* / /g;s/"//g;/^$/d' | tr '\n' ' '` sys_lib_dlsearch_path_spec="$sys_lib_dlsearch_path_spec $lt_ld_extra" - fi # We used to test for /lib/ld.so.1 and disable shared libraries on @@ -14898,12 +15548,12 @@ netbsd*) need_lib_prefix=no need_version=no if echo __ELF__ | $CC -E - | $GREP __ELF__ >/dev/null; then - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${shared_ext}$versuffix' + library_names_spec='$libname$release$shared_ext$versuffix $libname$shared_ext$versuffix' finish_cmds='PATH="\$PATH:/sbin" ldconfig -m $libdir' dynamic_linker='NetBSD (a.out) ld.so' else - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major ${libname}${shared_ext}' - soname_spec='${libname}${release}${shared_ext}$major' + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$shared_ext' + soname_spec='$libname$release$shared_ext$major' dynamic_linker='NetBSD ld.elf_so' fi shlibpath_var=LD_LIBRARY_PATH @@ -14913,7 +15563,7 @@ netbsd*) newsos6) version_type=linux # correct to gnu/linux during the next big refactor - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$shared_ext' shlibpath_var=LD_LIBRARY_PATH shlibpath_overrides_runpath=yes ;; @@ -14922,58 +15572,68 @@ newsos6) version_type=qnx need_lib_prefix=no need_version=no - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' - soname_spec='${libname}${release}${shared_ext}$major' + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$shared_ext' + soname_spec='$libname$release$shared_ext$major' shlibpath_var=LD_LIBRARY_PATH shlibpath_overrides_runpath=no hardcode_into_libs=yes dynamic_linker='ldqnx.so' ;; -openbsd*) +openbsd* | bitrig*) version_type=sunos - sys_lib_dlsearch_path_spec="/usr/lib" + sys_lib_dlsearch_path_spec=/usr/lib need_lib_prefix=no - # Some older versions of OpenBSD (3.3 at least) *do* need versioned libs. - case $host_os in - openbsd3.3 | openbsd3.3.*) need_version=yes ;; - *) need_version=no ;; - esac - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${shared_ext}$versuffix' + if test -z "`echo __ELF__ | $CC -E - | $GREP __ELF__`"; then + need_version=no + else + need_version=yes + fi + library_names_spec='$libname$release$shared_ext$versuffix $libname$shared_ext$versuffix' finish_cmds='PATH="\$PATH:/sbin" ldconfig -m $libdir' shlibpath_var=LD_LIBRARY_PATH - if test -z "`echo __ELF__ | $CC -E - | $GREP __ELF__`" || test "$host_os-$host_cpu" = "openbsd2.8-powerpc"; then - case $host_os in - openbsd2.[89] | openbsd2.[89].*) - shlibpath_overrides_runpath=no - ;; - *) - shlibpath_overrides_runpath=yes - ;; - esac - else - shlibpath_overrides_runpath=yes - fi + shlibpath_overrides_runpath=yes ;; os2*) libname_spec='$name' - shrext_cmds=".dll" + version_type=windows + shrext_cmds=.dll + need_version=no need_lib_prefix=no - library_names_spec='$libname${shared_ext} $libname.a' + # OS/2 can only load a DLL with a base name of 8 characters or less. + soname_spec='`test -n "$os2dllname" && libname="$os2dllname"; + v=$($ECHO $release$versuffix | tr -d .-); + n=$($ECHO $libname | cut -b -$((8 - ${#v})) | tr . _); + $ECHO $n$v`$shared_ext' + library_names_spec='${libname}_dll.$libext' dynamic_linker='OS/2 ld.exe' - shlibpath_var=LIBPATH + shlibpath_var=BEGINLIBPATH + sys_lib_search_path_spec="/lib /usr/lib /usr/local/lib" + sys_lib_dlsearch_path_spec=$sys_lib_search_path_spec + postinstall_cmds='base_file=`basename \$file`~ + dlpath=`$SHELL 2>&1 -c '\''. $dir/'\''\$base_file'\''i; $ECHO \$dlname'\''`~ + dldir=$destdir/`dirname \$dlpath`~ + test -d \$dldir || mkdir -p \$dldir~ + $install_prog $dir/$dlname \$dldir/$dlname~ + chmod a+x \$dldir/$dlname~ + if test -n '\''$stripme'\'' && test -n '\''$striplib'\''; then + eval '\''$striplib \$dldir/$dlname'\'' || exit \$?; + fi' + postuninstall_cmds='dldll=`$SHELL 2>&1 -c '\''. $file; $ECHO \$dlname'\''`~ + dlpath=$dir/\$dldll~ + $RM \$dlpath' ;; osf3* | osf4* | osf5*) version_type=osf need_lib_prefix=no need_version=no - soname_spec='${libname}${release}${shared_ext}$major' - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' + soname_spec='$libname$release$shared_ext$major' + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$shared_ext' shlibpath_var=LD_LIBRARY_PATH sys_lib_search_path_spec="/usr/shlib /usr/ccs/lib /usr/lib/cmplrs/cc /usr/lib /usr/local/lib /var/shlib" - sys_lib_dlsearch_path_spec="$sys_lib_search_path_spec" + sys_lib_dlsearch_path_spec=$sys_lib_search_path_spec ;; rdos*) @@ -14984,8 +15644,8 @@ solaris*) version_type=linux # correct to gnu/linux during the next big refactor need_lib_prefix=no need_version=no - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' - soname_spec='${libname}${release}${shared_ext}$major' + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$shared_ext' + soname_spec='$libname$release$shared_ext$major' shlibpath_var=LD_LIBRARY_PATH shlibpath_overrides_runpath=yes hardcode_into_libs=yes @@ -14995,11 +15655,11 @@ solaris*) sunos4*) version_type=sunos - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${shared_ext}$versuffix' + library_names_spec='$libname$release$shared_ext$versuffix $libname$shared_ext$versuffix' finish_cmds='PATH="\$PATH:/usr/etc" ldconfig $libdir' shlibpath_var=LD_LIBRARY_PATH shlibpath_overrides_runpath=yes - if test "$with_gnu_ld" = yes; then + if test yes = "$with_gnu_ld"; then need_lib_prefix=no fi need_version=yes @@ -15007,8 +15667,8 @@ sunos4*) sysv4 | sysv4.3*) version_type=linux # correct to gnu/linux during the next big refactor - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' - soname_spec='${libname}${release}${shared_ext}$major' + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$shared_ext' + soname_spec='$libname$release$shared_ext$major' shlibpath_var=LD_LIBRARY_PATH case $host_vendor in sni) @@ -15029,24 +15689,24 @@ sysv4 | sysv4.3*) ;; sysv4*MP*) - if test -d /usr/nec ;then + if test -d /usr/nec; then version_type=linux # correct to gnu/linux during the next big refactor - library_names_spec='$libname${shared_ext}.$versuffix $libname${shared_ext}.$major $libname${shared_ext}' - soname_spec='$libname${shared_ext}.$major' + library_names_spec='$libname$shared_ext.$versuffix $libname$shared_ext.$major $libname$shared_ext' + soname_spec='$libname$shared_ext.$major' shlibpath_var=LD_LIBRARY_PATH fi ;; sysv5* | sco3.2v5* | sco5v6* | unixware* | OpenUNIX* | sysv4*uw2*) - version_type=freebsd-elf + version_type=sco need_lib_prefix=no need_version=no - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext} $libname${shared_ext}' - soname_spec='${libname}${release}${shared_ext}$major' + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext $libname$shared_ext' + soname_spec='$libname$release$shared_ext$major' shlibpath_var=LD_LIBRARY_PATH shlibpath_overrides_runpath=yes hardcode_into_libs=yes - if test "$with_gnu_ld" = yes; then + if test yes = "$with_gnu_ld"; then sys_lib_search_path_spec='/usr/local/lib /usr/gnu/lib /usr/ccs/lib /usr/lib /lib' else sys_lib_search_path_spec='/usr/ccs/lib /usr/lib' @@ -15064,7 +15724,7 @@ tpf*) version_type=linux # correct to gnu/linux during the next big refactor need_lib_prefix=no need_version=no - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$shared_ext' shlibpath_var=LD_LIBRARY_PATH shlibpath_overrides_runpath=no hardcode_into_libs=yes @@ -15072,8 +15732,8 @@ tpf*) uts4*) version_type=linux # correct to gnu/linux during the next big refactor - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' - soname_spec='${libname}${release}${shared_ext}$major' + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$shared_ext' + soname_spec='$libname$release$shared_ext$major' shlibpath_var=LD_LIBRARY_PATH ;; @@ -15083,20 +15743,32 @@ uts4*) esac { $as_echo "$as_me:${as_lineno-$LINENO}: result: $dynamic_linker" >&5 $as_echo "$dynamic_linker" >&6; } -test "$dynamic_linker" = no && can_build_shared=no +test no = "$dynamic_linker" && can_build_shared=no variables_saved_for_relink="PATH $shlibpath_var $runpath_var" -if test "$GCC" = yes; then +if test yes = "$GCC"; then variables_saved_for_relink="$variables_saved_for_relink GCC_EXEC_PREFIX COMPILER_PATH LIBRARY_PATH" fi -if test "${lt_cv_sys_lib_search_path_spec+set}" = set; then - sys_lib_search_path_spec="$lt_cv_sys_lib_search_path_spec" +if test set = "${lt_cv_sys_lib_search_path_spec+set}"; then + sys_lib_search_path_spec=$lt_cv_sys_lib_search_path_spec fi -if test "${lt_cv_sys_lib_dlsearch_path_spec+set}" = set; then - sys_lib_dlsearch_path_spec="$lt_cv_sys_lib_dlsearch_path_spec" + +if test set = "${lt_cv_sys_lib_dlsearch_path_spec+set}"; then + sys_lib_dlsearch_path_spec=$lt_cv_sys_lib_dlsearch_path_spec fi +# remember unaugmented sys_lib_dlsearch_path content for libtool script decls... +configure_time_dlsearch_path=$sys_lib_dlsearch_path_spec + +# ... but it needs LT_SYS_LIBRARY_PATH munging for other configure-time code +func_munge_path_list sys_lib_dlsearch_path_spec "$LT_SYS_LIBRARY_PATH" + +# to be used as default LT_SYS_LIBRARY_PATH value in generated libtool +configure_time_lt_sys_library_path=$LT_SYS_LIBRARY_PATH + + + @@ -15139,15 +15811,15 @@ $as_echo_n "checking how to hardcode library paths into programs... " >&6; } hardcode_action_CXX= if test -n "$hardcode_libdir_flag_spec_CXX" || test -n "$runpath_var_CXX" || - test "X$hardcode_automatic_CXX" = "Xyes" ; then + test yes = "$hardcode_automatic_CXX"; then # We can hardcode non-existent directories. - if test "$hardcode_direct_CXX" != no && + if test no != "$hardcode_direct_CXX" && # If the only mechanism to avoid hardcoding is shlibpath_var, we # have to relink, otherwise we might link with an installed library # when we should be linking with a yet-to-be-installed one - ## test "$_LT_TAGVAR(hardcode_shlibpath_var, CXX)" != no && - test "$hardcode_minus_L_CXX" != no; then + ## test no != "$_LT_TAGVAR(hardcode_shlibpath_var, CXX)" && + test no != "$hardcode_minus_L_CXX"; then # Linking always hardcodes the temporary library directory. hardcode_action_CXX=relink else @@ -15162,12 +15834,12 @@ fi { $as_echo "$as_me:${as_lineno-$LINENO}: result: $hardcode_action_CXX" >&5 $as_echo "$hardcode_action_CXX" >&6; } -if test "$hardcode_action_CXX" = relink || - test "$inherit_rpath_CXX" = yes; then +if test relink = "$hardcode_action_CXX" || + test yes = "$inherit_rpath_CXX"; then # Fast installation is not supported enable_fast_install=no -elif test "$shlibpath_overrides_runpath" = yes || - test "$enable_shared" = no; then +elif test yes = "$shlibpath_overrides_runpath" || + test no = "$enable_shared"; then # Fast installation is not necessary enable_fast_install=needless fi @@ -15190,7 +15862,7 @@ fi lt_cv_path_LD=$lt_save_path_LD lt_cv_prog_gnu_ldcxx=$lt_cv_prog_gnu_ld lt_cv_prog_gnu_ld=$lt_save_with_gnu_ld -fi # test "$_lt_caught_CXX_error" != yes +fi # test yes != "$_lt_caught_CXX_error" ac_ext=c ac_cpp='$CPP $CPPFLAGS' @@ -15220,157 +15892,14 @@ ac_compiler_gnu=$ac_cv_c_compiler_gnu # Only expand once: - -# Checks for header files. -for ac_header in float.h -do : - ac_fn_c_check_header_mongrel "$LINENO" "float.h" "ac_cv_header_float_h" "$ac_includes_default" -if test "x$ac_cv_header_float_h" = xyes; then : - cat >>confdefs.h <<_ACEOF -#define HAVE_FLOAT_H 1 -_ACEOF - -fi - -done +ac_ext=cpp +ac_cpp='$CXXCPP $CPPFLAGS' +ac_compile='$CXX -c $CXXFLAGS $CPPFLAGS conftest.$ac_ext >&5' +ac_link='$CXX -o conftest$ac_exeext $CXXFLAGS $CPPFLAGS $LDFLAGS conftest.$ac_ext $LIBS >&5' +ac_compiler_gnu=$ac_cv_cxx_compiler_gnu -# Checks for typedefs, structures, and compiler characteristics. -{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for stdbool.h that conforms to C99" >&5 -$as_echo_n "checking for stdbool.h that conforms to C99... " >&6; } -if ${ac_cv_header_stdbool_h+:} false; then : - $as_echo_n "(cached) " >&6 -else - cat confdefs.h - <<_ACEOF >conftest.$ac_ext -/* end confdefs.h. */ - - #include - #ifndef bool - "error: bool is not defined" - #endif - #ifndef false - "error: false is not defined" - #endif - #if false - "error: false is not 0" - #endif - #ifndef true - "error: true is not defined" - #endif - #if true != 1 - "error: true is not 1" - #endif - #ifndef __bool_true_false_are_defined - "error: __bool_true_false_are_defined is not defined" - #endif - - struct s { _Bool s: 1; _Bool t; } s; - - char a[true == 1 ? 1 : -1]; - char b[false == 0 ? 1 : -1]; - char c[__bool_true_false_are_defined == 1 ? 1 : -1]; - char d[(bool) 0.5 == true ? 1 : -1]; - /* See body of main program for 'e'. */ - char f[(_Bool) 0.0 == false ? 1 : -1]; - char g[true]; - char h[sizeof (_Bool)]; - char i[sizeof s.t]; - enum { j = false, k = true, l = false * true, m = true * 256 }; - /* The following fails for - HP aC++/ANSI C B3910B A.05.55 [Dec 04 2003]. */ - _Bool n[m]; - char o[sizeof n == m * sizeof n[0] ? 1 : -1]; - char p[-1 - (_Bool) 0 < 0 && -1 - (bool) 0 < 0 ? 1 : -1]; - /* Catch a bug in an HP-UX C compiler. See - http://gcc.gnu.org/ml/gcc-patches/2003-12/msg02303.html - http://lists.gnu.org/archive/html/bug-coreutils/2005-11/msg00161.html - */ - _Bool q = true; - _Bool *pq = &q; - -int -main () -{ - - bool e = &s; - *pq |= q; - *pq |= ! q; - /* Refer to every declared value, to avoid compiler optimizations. */ - return (!a + !b + !c + !d + !e + !f + !g + !h + !i + !!j + !k + !!l - + !m + !n + !o + !p + !q + !pq); - - ; - return 0; -} -_ACEOF -if ac_fn_c_try_compile "$LINENO"; then : - ac_cv_header_stdbool_h=yes -else - ac_cv_header_stdbool_h=no -fi -rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext -fi -{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_cv_header_stdbool_h" >&5 -$as_echo "$ac_cv_header_stdbool_h" >&6; } - ac_fn_c_check_type "$LINENO" "_Bool" "ac_cv_type__Bool" "$ac_includes_default" -if test "x$ac_cv_type__Bool" = xyes; then : - -cat >>confdefs.h <<_ACEOF -#define HAVE__BOOL 1 -_ACEOF - - -fi - - -if test $ac_cv_header_stdbool_h = yes; then - -$as_echo "#define HAVE_STDBOOL_H 1" >>confdefs.h - -fi - -{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for inline" >&5 -$as_echo_n "checking for inline... " >&6; } -if ${ac_cv_c_inline+:} false; then : - $as_echo_n "(cached) " >&6 -else - ac_cv_c_inline=no -for ac_kw in inline __inline__ __inline; do - cat confdefs.h - <<_ACEOF >conftest.$ac_ext -/* end confdefs.h. */ -#ifndef __cplusplus -typedef int foo_t; -static $ac_kw foo_t static_foo () {return 0; } -$ac_kw foo_t foo () {return 0; } -#endif - -_ACEOF -if ac_fn_c_try_compile "$LINENO"; then : - ac_cv_c_inline=$ac_kw -fi -rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext - test "$ac_cv_c_inline" != no && break -done - -fi -{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_cv_c_inline" >&5 -$as_echo "$ac_cv_c_inline" >&6; } - -case $ac_cv_c_inline in - inline | yes) ;; - *) - case $ac_cv_c_inline in - no) ac_val=;; - *) ac_val=$ac_cv_c_inline;; - esac - cat >>confdefs.h <<_ACEOF -#ifndef __cplusplus -#define inline $ac_val -#endif -_ACEOF - ;; -esac - +# Checks for long double { $as_echo "$as_me:${as_lineno-$LINENO}: checking for long double" >&5 $as_echo_n "checking for long double... " >&6; } @@ -15397,7 +15926,7 @@ return test_array [0]; return 0; } _ACEOF -if ac_fn_c_try_compile "$LINENO"; then : +if ac_fn_cxx_try_compile "$LINENO"; then : ac_cv_type_long_double=yes else ac_cv_type_long_double=no @@ -15414,300 +15943,6 @@ $as_echo "#define HAVE_LONG_DOUBLE 1" >>confdefs.h fi -# Checks for library functions. -{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for working strtod" >&5 -$as_echo_n "checking for working strtod... " >&6; } -if ${ac_cv_func_strtod+:} false; then : - $as_echo_n "(cached) " >&6 -else - if test "$cross_compiling" = yes; then : - ac_cv_func_strtod=no -else - cat confdefs.h - <<_ACEOF >conftest.$ac_ext -/* end confdefs.h. */ - -$ac_includes_default -#ifndef strtod -double strtod (); -#endif -int -main() -{ - { - /* Some versions of Linux strtod mis-parse strings with leading '+'. */ - char *string = " +69"; - char *term; - double value; - value = strtod (string, &term); - if (value != 69 || term != (string + 4)) - return 1; - } - - { - /* Under Solaris 2.4, strtod returns the wrong value for the - terminating character under some conditions. */ - char *string = "NaN"; - char *term; - strtod (string, &term); - if (term != string && *(term - 1) == 0) - return 1; - } - return 0; -} - -_ACEOF -if ac_fn_c_try_run "$LINENO"; then : - ac_cv_func_strtod=yes -else - ac_cv_func_strtod=no -fi -rm -f core *.core core.conftest.* gmon.out bb.out conftest$ac_exeext \ - conftest.$ac_objext conftest.beam conftest.$ac_ext -fi - -fi -{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_cv_func_strtod" >&5 -$as_echo "$ac_cv_func_strtod" >&6; } -if test $ac_cv_func_strtod = no; then - case " $LIBOBJS " in - *" strtod.$ac_objext "* ) ;; - *) LIBOBJS="$LIBOBJS strtod.$ac_objext" - ;; -esac - -ac_fn_c_check_func "$LINENO" "pow" "ac_cv_func_pow" -if test "x$ac_cv_func_pow" = xyes; then : - -fi - -if test $ac_cv_func_pow = no; then - { $as_echo "$as_me:${as_lineno-$LINENO}: checking for pow in -lm" >&5 -$as_echo_n "checking for pow in -lm... " >&6; } -if ${ac_cv_lib_m_pow+:} false; then : - $as_echo_n "(cached) " >&6 -else - ac_check_lib_save_LIBS=$LIBS -LIBS="-lm $LIBS" -cat confdefs.h - <<_ACEOF >conftest.$ac_ext -/* end confdefs.h. */ - -/* Override any GCC internal prototype to avoid an error. - Use char because int might match the return type of a GCC - builtin and then its argument prototype would still apply. */ -#ifdef __cplusplus -extern "C" -#endif -char pow (); -int -main () -{ -return pow (); - ; - return 0; -} -_ACEOF -if ac_fn_c_try_link "$LINENO"; then : - ac_cv_lib_m_pow=yes -else - ac_cv_lib_m_pow=no -fi -rm -f core conftest.err conftest.$ac_objext \ - conftest$ac_exeext conftest.$ac_ext -LIBS=$ac_check_lib_save_LIBS -fi -{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_cv_lib_m_pow" >&5 -$as_echo "$ac_cv_lib_m_pow" >&6; } -if test "x$ac_cv_lib_m_pow" = xyes; then : - POW_LIB=-lm -else - { $as_echo "$as_me:${as_lineno-$LINENO}: WARNING: cannot find library containing definition of pow" >&5 -$as_echo "$as_me: WARNING: cannot find library containing definition of pow" >&2;} -fi - -fi - -fi - -for ac_func in strtol -do : - ac_fn_c_check_func "$LINENO" "strtol" "ac_cv_func_strtol" -if test "x$ac_cv_func_strtol" = xyes; then : - cat >>confdefs.h <<_ACEOF -#define HAVE_STRTOL 1 -_ACEOF - -fi -done - -{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for library containing floor" >&5 -$as_echo_n "checking for library containing floor... " >&6; } -if ${ac_cv_search_floor+:} false; then : - $as_echo_n "(cached) " >&6 -else - ac_func_search_save_LIBS=$LIBS -cat confdefs.h - <<_ACEOF >conftest.$ac_ext -/* end confdefs.h. */ - -/* Override any GCC internal prototype to avoid an error. - Use char because int might match the return type of a GCC - builtin and then its argument prototype would still apply. */ -#ifdef __cplusplus -extern "C" -#endif -char floor (); -int -main () -{ -return floor (); - ; - return 0; -} -_ACEOF -for ac_lib in '' m; do - if test -z "$ac_lib"; then - ac_res="none required" - else - ac_res=-l$ac_lib - LIBS="-l$ac_lib $ac_func_search_save_LIBS" - fi - if ac_fn_c_try_link "$LINENO"; then : - ac_cv_search_floor=$ac_res -fi -rm -f core conftest.err conftest.$ac_objext \ - conftest$ac_exeext - if ${ac_cv_search_floor+:} false; then : - break -fi -done -if ${ac_cv_search_floor+:} false; then : - -else - ac_cv_search_floor=no -fi -rm conftest.$ac_ext -LIBS=$ac_func_search_save_LIBS -fi -{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_cv_search_floor" >&5 -$as_echo "$ac_cv_search_floor" >&6; } -ac_res=$ac_cv_search_floor -if test "$ac_res" != no; then : - test "$ac_res" = "none required" || LIBS="$ac_res $LIBS" - -fi - -{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for library containing pow" >&5 -$as_echo_n "checking for library containing pow... " >&6; } -if ${ac_cv_search_pow+:} false; then : - $as_echo_n "(cached) " >&6 -else - ac_func_search_save_LIBS=$LIBS -cat confdefs.h - <<_ACEOF >conftest.$ac_ext -/* end confdefs.h. */ - -/* Override any GCC internal prototype to avoid an error. - Use char because int might match the return type of a GCC - builtin and then its argument prototype would still apply. */ -#ifdef __cplusplus -extern "C" -#endif -char pow (); -int -main () -{ -return pow (); - ; - return 0; -} -_ACEOF -for ac_lib in '' m; do - if test -z "$ac_lib"; then - ac_res="none required" - else - ac_res=-l$ac_lib - LIBS="-l$ac_lib $ac_func_search_save_LIBS" - fi - if ac_fn_c_try_link "$LINENO"; then : - ac_cv_search_pow=$ac_res -fi -rm -f core conftest.err conftest.$ac_objext \ - conftest$ac_exeext - if ${ac_cv_search_pow+:} false; then : - break -fi -done -if ${ac_cv_search_pow+:} false; then : - -else - ac_cv_search_pow=no -fi -rm conftest.$ac_ext -LIBS=$ac_func_search_save_LIBS -fi -{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_cv_search_pow" >&5 -$as_echo "$ac_cv_search_pow" >&6; } -ac_res=$ac_cv_search_pow -if test "$ac_res" != no; then : - test "$ac_res" = "none required" || LIBS="$ac_res $LIBS" - -fi - -{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for library containing sqrt" >&5 -$as_echo_n "checking for library containing sqrt... " >&6; } -if ${ac_cv_search_sqrt+:} false; then : - $as_echo_n "(cached) " >&6 -else - ac_func_search_save_LIBS=$LIBS -cat confdefs.h - <<_ACEOF >conftest.$ac_ext -/* end confdefs.h. */ - -/* Override any GCC internal prototype to avoid an error. - Use char because int might match the return type of a GCC - builtin and then its argument prototype would still apply. */ -#ifdef __cplusplus -extern "C" -#endif -char sqrt (); -int -main () -{ -return sqrt (); - ; - return 0; -} -_ACEOF -for ac_lib in '' m; do - if test -z "$ac_lib"; then - ac_res="none required" - else - ac_res=-l$ac_lib - LIBS="-l$ac_lib $ac_func_search_save_LIBS" - fi - if ac_fn_c_try_link "$LINENO"; then : - ac_cv_search_sqrt=$ac_res -fi -rm -f core conftest.err conftest.$ac_objext \ - conftest$ac_exeext - if ${ac_cv_search_sqrt+:} false; then : - break -fi -done -if ${ac_cv_search_sqrt+:} false; then : - -else - ac_cv_search_sqrt=no -fi -rm conftest.$ac_ext -LIBS=$ac_func_search_save_LIBS -fi -{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_cv_search_sqrt" >&5 -$as_echo "$ac_cv_search_sqrt" >&6; } -ac_res=$ac_cv_search_sqrt -if test "$ac_res" != no; then : - test "$ac_res" = "none required" || LIBS="$ac_res $LIBS" - -fi - - # Check endianness { $as_echo "$as_me:${as_lineno-$LINENO}: checking whether byte ordering is bigendian" >&5 $as_echo_n "checking whether byte ordering is bigendian... " >&6; } @@ -15724,7 +15959,7 @@ else typedef int dummy; _ACEOF -if ac_fn_c_try_compile "$LINENO"; then : +if ac_fn_cxx_try_compile "$LINENO"; then : # Check for potential -arch flags. It is not universal unless # there are at least two -arch flags with different values. @@ -15769,7 +16004,7 @@ main () return 0; } _ACEOF -if ac_fn_c_try_compile "$LINENO"; then : +if ac_fn_cxx_try_compile "$LINENO"; then : # It does; now see whether it defined to BIG_ENDIAN or not. cat confdefs.h - <<_ACEOF >conftest.$ac_ext /* end confdefs.h. */ @@ -15787,7 +16022,7 @@ main () return 0; } _ACEOF -if ac_fn_c_try_compile "$LINENO"; then : +if ac_fn_cxx_try_compile "$LINENO"; then : ac_cv_c_bigendian=yes else ac_cv_c_bigendian=no @@ -15813,7 +16048,7 @@ main () return 0; } _ACEOF -if ac_fn_c_try_compile "$LINENO"; then : +if ac_fn_cxx_try_compile "$LINENO"; then : # It does; now see whether it defined to _BIG_ENDIAN or not. cat confdefs.h - <<_ACEOF >conftest.$ac_ext /* end confdefs.h. */ @@ -15830,7 +16065,7 @@ main () return 0; } _ACEOF -if ac_fn_c_try_compile "$LINENO"; then : +if ac_fn_cxx_try_compile "$LINENO"; then : ac_cv_c_bigendian=yes else ac_cv_c_bigendian=no @@ -15869,7 +16104,7 @@ return use_ascii (foo) == use_ebcdic (foo); return 0; } _ACEOF -if ac_fn_c_try_compile "$LINENO"; then : +if ac_fn_cxx_try_compile "$LINENO"; then : if grep BIGenDianSyS conftest.$ac_objext >/dev/null; then ac_cv_c_bigendian=yes fi @@ -15904,7 +16139,7 @@ main () return 0; } _ACEOF -if ac_fn_c_try_run "$LINENO"; then : +if ac_fn_cxx_try_run "$LINENO"; then : ac_cv_c_bigendian=no else ac_cv_c_bigendian=yes @@ -15934,8 +16169,109 @@ $as_echo "#define AC_APPLE_UNIVERSAL_BUILD 1" >>confdefs.h esac -# Check for doxygen. -# Need version 1.8.1.2 or later for greek and math symbols. +# Check flags for C++11 +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking whether C++ compiler accepts -std=c++11" >&5 +$as_echo_n "checking whether C++ compiler accepts -std=c++11... " >&6; } +if ${ax_cv_check_cxxflags___std_cpp11+:} false; then : + $as_echo_n "(cached) " >&6 +else + + ax_check_save_flags=$CXXFLAGS + CXXFLAGS="$CXXFLAGS -std=c++11" + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ + +int +main () +{ + + ; + return 0; +} +_ACEOF +if ac_fn_cxx_try_compile "$LINENO"; then : + ax_cv_check_cxxflags___std_cpp11=yes +else + ax_cv_check_cxxflags___std_cpp11=no +fi +rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext + CXXFLAGS=$ax_check_save_flags +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $ax_cv_check_cxxflags___std_cpp11" >&5 +$as_echo "$ax_cv_check_cxxflags___std_cpp11" >&6; } +if test "x$ax_cv_check_cxxflags___std_cpp11" = xyes; then : + CXXFLAGS="$CXXFLAGS -std=c++11" +else + { $as_echo "$as_me:${as_lineno-$LINENO}: checking whether C++ compiler accepts -std=c++0x" >&5 +$as_echo_n "checking whether C++ compiler accepts -std=c++0x... " >&6; } +if ${ax_cv_check_cxxflags___std_cpp0x+:} false; then : + $as_echo_n "(cached) " >&6 +else + + ax_check_save_flags=$CXXFLAGS + CXXFLAGS="$CXXFLAGS -std=c++0x" + cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ + +int +main () +{ + + ; + return 0; +} +_ACEOF +if ac_fn_cxx_try_compile "$LINENO"; then : + ax_cv_check_cxxflags___std_cpp0x=yes +else + ax_cv_check_cxxflags___std_cpp0x=no +fi +rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext + CXXFLAGS=$ax_check_save_flags +fi +{ $as_echo "$as_me:${as_lineno-$LINENO}: result: $ax_cv_check_cxxflags___std_cpp0x" >&5 +$as_echo "$ax_cv_check_cxxflags___std_cpp0x" >&6; } +if test "x$ax_cv_check_cxxflags___std_cpp0x" = xyes; then : + CXXFLAGS="$CXXFLAGS -std=c++0x" +else + : +fi + +fi + +# Check for C++11 math functions +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for C++11 math functions" >&5 +$as_echo_n "checking for C++11 math functions... " >&6; } +cat confdefs.h - <<_ACEOF >conftest.$ac_ext +/* end confdefs.h. */ +#include +int +main () +{ +int q; + return int(std::hypot(3.0, 4.0) + std::expm1(0.5) + + std::log1p(2.0) + std::asinh(10.0) + + std::atanh(0.8) + std::cbrt(8.0) + + std::fma(1.0, 2.0, 3.0) + std::remquo(100.0, 90.0, &q) + + std::remainder(100.0, 90.0) + std::copysign(1.0, -0.0)) + + std::isfinite(4.0) + std::isnan(0.0); + ; + return 0; +} +_ACEOF +if ac_fn_cxx_try_link "$LINENO"; then : + { $as_echo "$as_me:${as_lineno-$LINENO}: result: yes" >&5 +$as_echo "yes" >&6; }; + CXXFLAGS="$CXXFLAGS -DGEOGRAPHICLIB_CXX11_MATH=1" +else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; }; + CXXFLAGS="$CXXFLAGS -DGEOGRAPHICLIB_CXX11_MATH=0" +fi +rm -f core conftest.err conftest.$ac_objext \ + conftest$ac_exeext conftest.$ac_ext + +# Check for doxygen. Version 1.8.7 or later needed for … for ac_prog in doxygen do # Extract the first word of "$ac_prog", so it can be a program name with args. @@ -15979,7 +16315,7 @@ fi done if test "$DOXYGEN" && test `"$DOXYGEN" --version | - sed 's/^\([0-9]\)\.\([0-9]\)\./\1.0\2./'` '>' 1.08.1.1; then + sed 's/\b\([0-9]\)\b/0\1/g'` '>' 01.08.06.99; then HAVE_DOXYGEN_TRUE= HAVE_DOXYGEN_FALSE='#' else @@ -16123,7 +16459,147 @@ else fi -ac_config_files="$ac_config_files Makefile src/Makefile include/Makefile tools/Makefile doc/Makefile man/Makefile matlab/Makefile python/Makefile cmake/Makefile examples/Makefile" +ac_config_files="$ac_config_files Makefile src/Makefile include/Makefile tools/Makefile doc/Makefile js/Makefile man/Makefile matlab/Makefile python/Makefile cmake/Makefile examples/Makefile" + + + + + + + + + +if test "x$ac_cv_env_PKG_CONFIG_set" != "xset"; then + if test -n "$ac_tool_prefix"; then + # Extract the first word of "${ac_tool_prefix}pkg-config", so it can be a program name with args. +set dummy ${ac_tool_prefix}pkg-config; ac_word=$2 +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for $ac_word" >&5 +$as_echo_n "checking for $ac_word... " >&6; } +if ${ac_cv_path_PKG_CONFIG+:} false; then : + $as_echo_n "(cached) " >&6 +else + case $PKG_CONFIG in + [\\/]* | ?:[\\/]*) + ac_cv_path_PKG_CONFIG="$PKG_CONFIG" # Let the user override the test with a path. + ;; + *) + as_save_IFS=$IFS; IFS=$PATH_SEPARATOR +for as_dir in $PATH +do + IFS=$as_save_IFS + test -z "$as_dir" && as_dir=. + for ac_exec_ext in '' $ac_executable_extensions; do + if as_fn_executable_p "$as_dir/$ac_word$ac_exec_ext"; then + ac_cv_path_PKG_CONFIG="$as_dir/$ac_word$ac_exec_ext" + $as_echo "$as_me:${as_lineno-$LINENO}: found $as_dir/$ac_word$ac_exec_ext" >&5 + break 2 + fi +done + done +IFS=$as_save_IFS + + ;; +esac +fi +PKG_CONFIG=$ac_cv_path_PKG_CONFIG +if test -n "$PKG_CONFIG"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $PKG_CONFIG" >&5 +$as_echo "$PKG_CONFIG" >&6; } +else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } +fi + + +fi +if test -z "$ac_cv_path_PKG_CONFIG"; then + ac_pt_PKG_CONFIG=$PKG_CONFIG + # Extract the first word of "pkg-config", so it can be a program name with args. +set dummy pkg-config; ac_word=$2 +{ $as_echo "$as_me:${as_lineno-$LINENO}: checking for $ac_word" >&5 +$as_echo_n "checking for $ac_word... " >&6; } +if ${ac_cv_path_ac_pt_PKG_CONFIG+:} false; then : + $as_echo_n "(cached) " >&6 +else + case $ac_pt_PKG_CONFIG in + [\\/]* | ?:[\\/]*) + ac_cv_path_ac_pt_PKG_CONFIG="$ac_pt_PKG_CONFIG" # Let the user override the test with a path. + ;; + *) + as_save_IFS=$IFS; IFS=$PATH_SEPARATOR +for as_dir in $PATH +do + IFS=$as_save_IFS + test -z "$as_dir" && as_dir=. + for ac_exec_ext in '' $ac_executable_extensions; do + if as_fn_executable_p "$as_dir/$ac_word$ac_exec_ext"; then + ac_cv_path_ac_pt_PKG_CONFIG="$as_dir/$ac_word$ac_exec_ext" + $as_echo "$as_me:${as_lineno-$LINENO}: found $as_dir/$ac_word$ac_exec_ext" >&5 + break 2 + fi +done + done +IFS=$as_save_IFS + + ;; +esac +fi +ac_pt_PKG_CONFIG=$ac_cv_path_ac_pt_PKG_CONFIG +if test -n "$ac_pt_PKG_CONFIG"; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: $ac_pt_PKG_CONFIG" >&5 +$as_echo "$ac_pt_PKG_CONFIG" >&6; } +else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } +fi + + if test "x$ac_pt_PKG_CONFIG" = x; then + PKG_CONFIG="" + else + case $cross_compiling:$ac_tool_warned in +yes:) +{ $as_echo "$as_me:${as_lineno-$LINENO}: WARNING: using cross tools not prefixed with host triplet" >&5 +$as_echo "$as_me: WARNING: using cross tools not prefixed with host triplet" >&2;} +ac_tool_warned=yes ;; +esac + PKG_CONFIG=$ac_pt_PKG_CONFIG + fi +else + PKG_CONFIG="$ac_cv_path_PKG_CONFIG" +fi + +fi +if test -n "$PKG_CONFIG"; then + _pkg_min_version=0.9.0 + { $as_echo "$as_me:${as_lineno-$LINENO}: checking pkg-config is at least version $_pkg_min_version" >&5 +$as_echo_n "checking pkg-config is at least version $_pkg_min_version... " >&6; } + if $PKG_CONFIG --atleast-pkgconfig-version $_pkg_min_version; then + { $as_echo "$as_me:${as_lineno-$LINENO}: result: yes" >&5 +$as_echo "yes" >&6; } + else + { $as_echo "$as_me:${as_lineno-$LINENO}: result: no" >&5 +$as_echo "no" >&6; } + PKG_CONFIG="" + fi +fi + + + +# Check whether --with-pkgconfigdir was given. +if test "${with_pkgconfigdir+set}" = set; then : + withval=$with_pkgconfigdir; +else + with_pkgconfigdir='${libdir}/pkgconfig' +fi + +pkgconfigdir=$with_pkgconfigdir + + + + + +ac_config_files="$ac_config_files cmake/geographiclib.pc:cmake/project.pc.in" + cat >confcache <<\_ACEOF # This file is a shell script that caches the results of configure @@ -16672,7 +17148,7 @@ cat >>$CONFIG_STATUS <<\_ACEOF || ac_write_fail=1 # report actual input values of CONFIG_FILES etc. instead of their # values after options handling. ac_log=" -This file was extended by GeographicLib $as_me 1.35, which was +This file was extended by GeographicLib $as_me 1.49, which was generated by GNU Autoconf 2.69. Invocation command line was CONFIG_FILES = $CONFIG_FILES @@ -16738,7 +17214,7 @@ _ACEOF cat >>$CONFIG_STATUS <<_ACEOF || ac_write_fail=1 ac_cs_config="`$as_echo "$ac_configure_args" | sed 's/^ //; s/[\\""\`\$]/\\\\&/g'`" ac_cs_version="\\ -GeographicLib config.status 1.35 +GeographicLib config.status 1.49 configured by $0, generated by GNU Autoconf 2.69, with options \\"\$ac_cs_config\\" @@ -16873,6 +17349,7 @@ enable_shared='`$ECHO "$enable_shared" | $SED "$delay_single_quote_subst"`' enable_static='`$ECHO "$enable_static" | $SED "$delay_single_quote_subst"`' pic_mode='`$ECHO "$pic_mode" | $SED "$delay_single_quote_subst"`' enable_fast_install='`$ECHO "$enable_fast_install" | $SED "$delay_single_quote_subst"`' +shared_archive_member_spec='`$ECHO "$shared_archive_member_spec" | $SED "$delay_single_quote_subst"`' SHELL='`$ECHO "$SHELL" | $SED "$delay_single_quote_subst"`' ECHO='`$ECHO "$ECHO" | $SED "$delay_single_quote_subst"`' PATH_SEPARATOR='`$ECHO "$PATH_SEPARATOR" | $SED "$delay_single_quote_subst"`' @@ -16922,10 +17399,13 @@ compiler='`$ECHO "$compiler" | $SED "$delay_single_quote_subst"`' GCC='`$ECHO "$GCC" | $SED "$delay_single_quote_subst"`' lt_cv_sys_global_symbol_pipe='`$ECHO "$lt_cv_sys_global_symbol_pipe" | $SED "$delay_single_quote_subst"`' lt_cv_sys_global_symbol_to_cdecl='`$ECHO "$lt_cv_sys_global_symbol_to_cdecl" | $SED "$delay_single_quote_subst"`' +lt_cv_sys_global_symbol_to_import='`$ECHO "$lt_cv_sys_global_symbol_to_import" | $SED "$delay_single_quote_subst"`' lt_cv_sys_global_symbol_to_c_name_address='`$ECHO "$lt_cv_sys_global_symbol_to_c_name_address" | $SED "$delay_single_quote_subst"`' lt_cv_sys_global_symbol_to_c_name_address_lib_prefix='`$ECHO "$lt_cv_sys_global_symbol_to_c_name_address_lib_prefix" | $SED "$delay_single_quote_subst"`' +lt_cv_nm_interface='`$ECHO "$lt_cv_nm_interface" | $SED "$delay_single_quote_subst"`' nm_file_list_spec='`$ECHO "$nm_file_list_spec" | $SED "$delay_single_quote_subst"`' lt_sysroot='`$ECHO "$lt_sysroot" | $SED "$delay_single_quote_subst"`' +lt_cv_truncate_bin='`$ECHO "$lt_cv_truncate_bin" | $SED "$delay_single_quote_subst"`' objdir='`$ECHO "$objdir" | $SED "$delay_single_quote_subst"`' MAGIC_CMD='`$ECHO "$MAGIC_CMD" | $SED "$delay_single_quote_subst"`' lt_prog_compiler_no_builtin_flag='`$ECHO "$lt_prog_compiler_no_builtin_flag" | $SED "$delay_single_quote_subst"`' @@ -16990,7 +17470,8 @@ finish_cmds='`$ECHO "$finish_cmds" | $SED "$delay_single_quote_subst"`' finish_eval='`$ECHO "$finish_eval" | $SED "$delay_single_quote_subst"`' hardcode_into_libs='`$ECHO "$hardcode_into_libs" | $SED "$delay_single_quote_subst"`' sys_lib_search_path_spec='`$ECHO "$sys_lib_search_path_spec" | $SED "$delay_single_quote_subst"`' -sys_lib_dlsearch_path_spec='`$ECHO "$sys_lib_dlsearch_path_spec" | $SED "$delay_single_quote_subst"`' +configure_time_dlsearch_path='`$ECHO "$configure_time_dlsearch_path" | $SED "$delay_single_quote_subst"`' +configure_time_lt_sys_library_path='`$ECHO "$configure_time_lt_sys_library_path" | $SED "$delay_single_quote_subst"`' hardcode_action='`$ECHO "$hardcode_action" | $SED "$delay_single_quote_subst"`' enable_dlopen='`$ECHO "$enable_dlopen" | $SED "$delay_single_quote_subst"`' enable_dlopen_self='`$ECHO "$enable_dlopen_self" | $SED "$delay_single_quote_subst"`' @@ -17095,9 +17576,12 @@ CFLAGS \ compiler \ lt_cv_sys_global_symbol_pipe \ lt_cv_sys_global_symbol_to_cdecl \ +lt_cv_sys_global_symbol_to_import \ lt_cv_sys_global_symbol_to_c_name_address \ lt_cv_sys_global_symbol_to_c_name_address_lib_prefix \ +lt_cv_nm_interface \ nm_file_list_spec \ +lt_cv_truncate_bin \ lt_prog_compiler_no_builtin_flag \ lt_prog_compiler_pic \ lt_prog_compiler_wl \ @@ -17163,7 +17647,7 @@ postdeps_CXX \ compiler_lib_search_path_CXX; do case \`eval \\\\\$ECHO \\\\""\\\\\$\$var"\\\\"\` in *[\\\\\\\`\\"\\\$]*) - eval "lt_\$var=\\\\\\"\\\`\\\$ECHO \\"\\\$\$var\\" | \\\$SED \\"\\\$sed_quote_subst\\"\\\`\\\\\\"" + eval "lt_\$var=\\\\\\"\\\`\\\$ECHO \\"\\\$\$var\\" | \\\$SED \\"\\\$sed_quote_subst\\"\\\`\\\\\\"" ## exclude from sc_prohibit_nested_quotes ;; *) eval "lt_\$var=\\\\\\"\\\$\$var\\\\\\"" @@ -17190,7 +17674,8 @@ postinstall_cmds \ postuninstall_cmds \ finish_cmds \ sys_lib_search_path_spec \ -sys_lib_dlsearch_path_spec \ +configure_time_dlsearch_path \ +configure_time_lt_sys_library_path \ reload_cmds_CXX \ old_archive_cmds_CXX \ old_archive_from_new_cmds_CXX \ @@ -17204,7 +17689,7 @@ prelink_cmds_CXX \ postlink_cmds_CXX; do case \`eval \\\\\$ECHO \\\\""\\\\\$\$var"\\\\"\` in *[\\\\\\\`\\"\\\$]*) - eval "lt_\$var=\\\\\\"\\\`\\\$ECHO \\"\\\$\$var\\" | \\\$SED -e \\"\\\$double_quote_subst\\" -e \\"\\\$sed_quote_subst\\" -e \\"\\\$delay_variable_subst\\"\\\`\\\\\\"" + eval "lt_\$var=\\\\\\"\\\`\\\$ECHO \\"\\\$\$var\\" | \\\$SED -e \\"\\\$double_quote_subst\\" -e \\"\\\$sed_quote_subst\\" -e \\"\\\$delay_variable_subst\\"\\\`\\\\\\"" ## exclude from sc_prohibit_nested_quotes ;; *) eval "lt_\$var=\\\\\\"\\\$\$var\\\\\\"" @@ -17213,19 +17698,16 @@ postlink_cmds_CXX; do done ac_aux_dir='$ac_aux_dir' -xsi_shell='$xsi_shell' -lt_shell_append='$lt_shell_append' -# See if we are running on zsh, and set the options which allow our +# See if we are running on zsh, and set the options that allow our # commands through without removal of \ escapes INIT. -if test -n "\${ZSH_VERSION+set}" ; then +if test -n "\${ZSH_VERSION+set}"; then setopt NO_GLOB_SUBST fi PACKAGE='$PACKAGE' VERSION='$VERSION' - TIMESTAMP='$TIMESTAMP' RM='$RM' ofile='$ofile' @@ -17250,11 +17732,13 @@ do "include/Makefile") CONFIG_FILES="$CONFIG_FILES include/Makefile" ;; "tools/Makefile") CONFIG_FILES="$CONFIG_FILES tools/Makefile" ;; "doc/Makefile") CONFIG_FILES="$CONFIG_FILES doc/Makefile" ;; + "js/Makefile") CONFIG_FILES="$CONFIG_FILES js/Makefile" ;; "man/Makefile") CONFIG_FILES="$CONFIG_FILES man/Makefile" ;; "matlab/Makefile") CONFIG_FILES="$CONFIG_FILES matlab/Makefile" ;; "python/Makefile") CONFIG_FILES="$CONFIG_FILES python/Makefile" ;; "cmake/Makefile") CONFIG_FILES="$CONFIG_FILES cmake/Makefile" ;; "examples/Makefile") CONFIG_FILES="$CONFIG_FILES examples/Makefile" ;; + "cmake/geographiclib.pc") CONFIG_FILES="$CONFIG_FILES cmake/geographiclib.pc:cmake/project.pc.in" ;; *) as_fn_error $? "invalid argument: \`$ac_config_target'" "$LINENO" 5;; esac @@ -17851,7 +18335,7 @@ $as_echo "$as_me: executing $ac_file commands" >&6;} case $ac_file$ac_mode in "depfiles":C) test x"$AMDEP_TRUE" != x"" || { - # Autoconf 2.62 quotes --file arguments for eval, but not when files + # Older Autoconf quotes --file arguments for eval, but not when files # are listed without --file. Let's play safe and only enable the eval # if we detect the quoting. case $CONFIG_FILES in @@ -17902,7 +18386,7 @@ $as_echo X"$mf" | DEPDIR=`sed -n 's/^DEPDIR = //p' < "$mf"` test -z "$DEPDIR" && continue am__include=`sed -n 's/^am__include = //p' < "$mf"` - test -z "am__include" && continue + test -z "$am__include" && continue am__quote=`sed -n 's/^am__quote = //p' < "$mf"` # Find all dependency output files, they are included files with # $(DEPDIR) in their names. We invoke sed twice because it is the @@ -17945,55 +18429,53 @@ $as_echo X"$file" | ;; "libtool":C) - # See if we are running on zsh, and set the options which allow our + # See if we are running on zsh, and set the options that allow our # commands through without removal of \ escapes. - if test -n "${ZSH_VERSION+set}" ; then + if test -n "${ZSH_VERSION+set}"; then setopt NO_GLOB_SUBST fi - cfgfile="${ofile}T" + cfgfile=${ofile}T trap "$RM \"$cfgfile\"; exit 1" 1 2 15 $RM "$cfgfile" cat <<_LT_EOF >> "$cfgfile" #! $SHELL - -# `$ECHO "$ofile" | sed 's%^.*/%%'` - Provide generalized library-building support services. -# Generated automatically by $as_me ($PACKAGE$TIMESTAMP) $VERSION +# Generated automatically by $as_me ($PACKAGE) $VERSION # Libtool was configured on host `(hostname || uname -n) 2>/dev/null | sed 1q`: # NOTE: Changes made to this file will be lost: look at ltmain.sh. + +# Provide generalized library-building support services. +# Written by Gordon Matzigkeit, 1996 + +# Copyright (C) 2014 Free Software Foundation, Inc. +# This is free software; see the source for copying conditions. There is NO +# warranty; not even for MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + +# GNU Libtool 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 2 of of the License, or +# (at your option) any later version. # -# Copyright (C) 1996, 1997, 1998, 1999, 2000, 2001, 2003, 2004, 2005, -# 2006, 2007, 2008, 2009, 2010, 2011 Free Software -# Foundation, Inc. -# Written by Gordon Matzigkeit, 1996 +# As a special exception to the GNU General Public License, if you +# distribute this file as part of a program or library that is built +# using GNU Libtool, you may include this file under the same +# distribution terms that you use for the rest of that program. # -# This file is part of GNU Libtool. -# -# GNU Libtool 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 2 of -# the License, or (at your option) any later version. -# -# As a special exception to the GNU General Public License, -# if you distribute this file as part of a program or library that -# is built using GNU Libtool, you may include this file under the -# same distribution terms that you use for the rest of that program. -# -# GNU Libtool is distributed in the hope that it will be useful, -# but WITHOUT ANY WARRANTY; without even the implied warranty of +# GNU Libtool 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 GNU Libtool; see the file COPYING. If not, a copy -# can be downloaded from http://www.gnu.org/licenses/gpl.html, or -# obtained by writing to the Free Software Foundation, Inc., -# 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301, USA. +# along with this program. If not, see . # The names of the tagged configurations supported by this script. -available_tags="CXX " +available_tags='CXX ' + +# Configured defaults for sys_lib_dlsearch_path munging. +: \${LT_SYS_LIBRARY_PATH="$configure_time_lt_sys_library_path"} # ### BEGIN LIBTOOL CONFIG @@ -18013,6 +18495,9 @@ pic_mode=$pic_mode # Whether or not to optimize for fast installation. fast_install=$enable_fast_install +# Shared archive member basename,for filename based shared library versioning on AIX. +shared_archive_member_spec=$shared_archive_member_spec + # Shell to use when invoking shell scripts. SHELL=$lt_SHELL @@ -18130,18 +18615,27 @@ global_symbol_pipe=$lt_lt_cv_sys_global_symbol_pipe # Transform the output of nm in a proper C declaration. global_symbol_to_cdecl=$lt_lt_cv_sys_global_symbol_to_cdecl +# Transform the output of nm into a list of symbols to manually relocate. +global_symbol_to_import=$lt_lt_cv_sys_global_symbol_to_import + # Transform the output of nm in a C name address pair. global_symbol_to_c_name_address=$lt_lt_cv_sys_global_symbol_to_c_name_address # Transform the output of nm in a C name address pair when lib prefix is needed. global_symbol_to_c_name_address_lib_prefix=$lt_lt_cv_sys_global_symbol_to_c_name_address_lib_prefix +# The name lister interface. +nm_interface=$lt_lt_cv_nm_interface + # Specify filename containing input files for \$NM. nm_file_list_spec=$lt_nm_file_list_spec -# The root where to search for dependent libraries,and in which our libraries should be installed. +# The root where to search for dependent libraries,and where our libraries should be installed. lt_sysroot=$lt_sysroot +# Command to truncate a binary pipe. +lt_truncate_bin=$lt_lt_cv_truncate_bin + # The name of the directory that contains temporary libtool files. objdir=$objdir @@ -18232,8 +18726,11 @@ hardcode_into_libs=$hardcode_into_libs # Compile-time system search path for libraries. sys_lib_search_path_spec=$lt_sys_lib_search_path_spec -# Run-time system search path for libraries. -sys_lib_dlsearch_path_spec=$lt_sys_lib_dlsearch_path_spec +# Detected run-time system search path for libraries. +sys_lib_dlsearch_path_spec=$lt_configure_time_dlsearch_path + +# Explicit LT_SYS_LIBRARY_PATH set during ./configure time. +configure_time_lt_sys_library_path=$lt_configure_time_lt_sys_library_path # Whether dlopen is supported. dlopen_support=$enable_dlopen @@ -18326,13 +18823,13 @@ hardcode_libdir_flag_spec=$lt_hardcode_libdir_flag_spec # Whether we need a single "-rpath" flag with a separated argument. hardcode_libdir_separator=$lt_hardcode_libdir_separator -# Set to "yes" if using DIR/libNAME\${shared_ext} during linking hardcodes +# Set to "yes" if using DIR/libNAME\$shared_ext during linking hardcodes # DIR into the resulting binary. hardcode_direct=$hardcode_direct -# Set to "yes" if using DIR/libNAME\${shared_ext} during linking hardcodes +# Set to "yes" if using DIR/libNAME\$shared_ext during linking hardcodes # DIR into the resulting binary and the resulting library dependency is -# "absolute",i.e impossible to change by setting \${shlibpath_var} if the +# "absolute",i.e impossible to change by setting \$shlibpath_var if the # library is relocated. hardcode_direct_absolute=$hardcode_direct_absolute @@ -18396,6 +18893,65 @@ compiler_lib_search_path=$lt_compiler_lib_search_path # ### END LIBTOOL CONFIG +_LT_EOF + + cat <<'_LT_EOF' >> "$cfgfile" + +# ### BEGIN FUNCTIONS SHARED WITH CONFIGURE + +# func_munge_path_list VARIABLE PATH +# ----------------------------------- +# VARIABLE is name of variable containing _space_ separated list of +# directories to be munged by the contents of PATH, which is string +# having a format: +# "DIR[:DIR]:" +# string "DIR[ DIR]" will be prepended to VARIABLE +# ":DIR[:DIR]" +# string "DIR[ DIR]" will be appended to VARIABLE +# "DIRP[:DIRP]::[DIRA:]DIRA" +# string "DIRP[ DIRP]" will be prepended to VARIABLE and string +# "DIRA[ DIRA]" will be appended to VARIABLE +# "DIR[:DIR]" +# VARIABLE will be replaced by "DIR[ DIR]" +func_munge_path_list () +{ + case x$2 in + x) + ;; + *:) + eval $1=\"`$ECHO $2 | $SED 's/:/ /g'` \$$1\" + ;; + x:*) + eval $1=\"\$$1 `$ECHO $2 | $SED 's/:/ /g'`\" + ;; + *::*) + eval $1=\"\$$1\ `$ECHO $2 | $SED -e 's/.*:://' -e 's/:/ /g'`\" + eval $1=\"`$ECHO $2 | $SED -e 's/::.*//' -e 's/:/ /g'`\ \$$1\" + ;; + *) + eval $1=\"`$ECHO $2 | $SED 's/:/ /g'`\" + ;; + esac +} + + +# Calculate cc_basename. Skip known compiler wrappers and cross-prefix. +func_cc_basename () +{ + for cc_temp in $*""; do + case $cc_temp in + compile | *[\\/]compile | ccache | *[\\/]ccache ) ;; + distcc | *[\\/]distcc | purify | *[\\/]purify ) ;; + \-*) ;; + *) break;; + esac + done + func_cc_basename_result=`$ECHO "$cc_temp" | $SED "s%.*/%%; s%^$host_alias-%%"` +} + + +# ### END FUNCTIONS SHARED WITH CONFIGURE + _LT_EOF case $host_os in @@ -18404,7 +18960,7 @@ _LT_EOF # AIX sometimes has problems with the GCC collect2 program. For some # reason, if we set the COLLECT_NAMES environment variable, the problems # vanish in a puff of smoke. -if test "X${COLLECT_NAMES+set}" != Xset; then +if test set != "${COLLECT_NAMES+set}"; then COLLECT_NAMES= export COLLECT_NAMES fi @@ -18413,7 +18969,7 @@ _LT_EOF esac -ltmain="$ac_aux_dir/ltmain.sh" +ltmain=$ac_aux_dir/ltmain.sh # We use sed instead of cat because bash on DJGPP gets confused if @@ -18423,165 +18979,6 @@ ltmain="$ac_aux_dir/ltmain.sh" sed '$q' "$ltmain" >> "$cfgfile" \ || (rm -f "$cfgfile"; exit 1) - if test x"$xsi_shell" = xyes; then - sed -e '/^func_dirname ()$/,/^} # func_dirname /c\ -func_dirname ()\ -{\ -\ case ${1} in\ -\ */*) func_dirname_result="${1%/*}${2}" ;;\ -\ * ) func_dirname_result="${3}" ;;\ -\ esac\ -} # Extended-shell func_dirname implementation' "$cfgfile" > $cfgfile.tmp \ - && mv -f "$cfgfile.tmp" "$cfgfile" \ - || (rm -f "$cfgfile" && cp "$cfgfile.tmp" "$cfgfile" && rm -f "$cfgfile.tmp") -test 0 -eq $? || _lt_function_replace_fail=: - - - sed -e '/^func_basename ()$/,/^} # func_basename /c\ -func_basename ()\ -{\ -\ func_basename_result="${1##*/}"\ -} # Extended-shell func_basename implementation' "$cfgfile" > $cfgfile.tmp \ - && mv -f "$cfgfile.tmp" "$cfgfile" \ - || (rm -f "$cfgfile" && cp "$cfgfile.tmp" "$cfgfile" && rm -f "$cfgfile.tmp") -test 0 -eq $? || _lt_function_replace_fail=: - - - sed -e '/^func_dirname_and_basename ()$/,/^} # func_dirname_and_basename /c\ -func_dirname_and_basename ()\ -{\ -\ case ${1} in\ -\ */*) func_dirname_result="${1%/*}${2}" ;;\ -\ * ) func_dirname_result="${3}" ;;\ -\ esac\ -\ func_basename_result="${1##*/}"\ -} # Extended-shell func_dirname_and_basename implementation' "$cfgfile" > $cfgfile.tmp \ - && mv -f "$cfgfile.tmp" "$cfgfile" \ - || (rm -f "$cfgfile" && cp "$cfgfile.tmp" "$cfgfile" && rm -f "$cfgfile.tmp") -test 0 -eq $? || _lt_function_replace_fail=: - - - sed -e '/^func_stripname ()$/,/^} # func_stripname /c\ -func_stripname ()\ -{\ -\ # pdksh 5.2.14 does not do ${X%$Y} correctly if both X and Y are\ -\ # positional parameters, so assign one to ordinary parameter first.\ -\ func_stripname_result=${3}\ -\ func_stripname_result=${func_stripname_result#"${1}"}\ -\ func_stripname_result=${func_stripname_result%"${2}"}\ -} # Extended-shell func_stripname implementation' "$cfgfile" > $cfgfile.tmp \ - && mv -f "$cfgfile.tmp" "$cfgfile" \ - || (rm -f "$cfgfile" && cp "$cfgfile.tmp" "$cfgfile" && rm -f "$cfgfile.tmp") -test 0 -eq $? || _lt_function_replace_fail=: - - - sed -e '/^func_split_long_opt ()$/,/^} # func_split_long_opt /c\ -func_split_long_opt ()\ -{\ -\ func_split_long_opt_name=${1%%=*}\ -\ func_split_long_opt_arg=${1#*=}\ -} # Extended-shell func_split_long_opt implementation' "$cfgfile" > $cfgfile.tmp \ - && mv -f "$cfgfile.tmp" "$cfgfile" \ - || (rm -f "$cfgfile" && cp "$cfgfile.tmp" "$cfgfile" && rm -f "$cfgfile.tmp") -test 0 -eq $? || _lt_function_replace_fail=: - - - sed -e '/^func_split_short_opt ()$/,/^} # func_split_short_opt /c\ -func_split_short_opt ()\ -{\ -\ func_split_short_opt_arg=${1#??}\ -\ func_split_short_opt_name=${1%"$func_split_short_opt_arg"}\ -} # Extended-shell func_split_short_opt implementation' "$cfgfile" > $cfgfile.tmp \ - && mv -f "$cfgfile.tmp" "$cfgfile" \ - || (rm -f "$cfgfile" && cp "$cfgfile.tmp" "$cfgfile" && rm -f "$cfgfile.tmp") -test 0 -eq $? || _lt_function_replace_fail=: - - - sed -e '/^func_lo2o ()$/,/^} # func_lo2o /c\ -func_lo2o ()\ -{\ -\ case ${1} in\ -\ *.lo) func_lo2o_result=${1%.lo}.${objext} ;;\ -\ *) func_lo2o_result=${1} ;;\ -\ esac\ -} # Extended-shell func_lo2o implementation' "$cfgfile" > $cfgfile.tmp \ - && mv -f "$cfgfile.tmp" "$cfgfile" \ - || (rm -f "$cfgfile" && cp "$cfgfile.tmp" "$cfgfile" && rm -f "$cfgfile.tmp") -test 0 -eq $? || _lt_function_replace_fail=: - - - sed -e '/^func_xform ()$/,/^} # func_xform /c\ -func_xform ()\ -{\ - func_xform_result=${1%.*}.lo\ -} # Extended-shell func_xform implementation' "$cfgfile" > $cfgfile.tmp \ - && mv -f "$cfgfile.tmp" "$cfgfile" \ - || (rm -f "$cfgfile" && cp "$cfgfile.tmp" "$cfgfile" && rm -f "$cfgfile.tmp") -test 0 -eq $? || _lt_function_replace_fail=: - - - sed -e '/^func_arith ()$/,/^} # func_arith /c\ -func_arith ()\ -{\ - func_arith_result=$(( $* ))\ -} # Extended-shell func_arith implementation' "$cfgfile" > $cfgfile.tmp \ - && mv -f "$cfgfile.tmp" "$cfgfile" \ - || (rm -f "$cfgfile" && cp "$cfgfile.tmp" "$cfgfile" && rm -f "$cfgfile.tmp") -test 0 -eq $? || _lt_function_replace_fail=: - - - sed -e '/^func_len ()$/,/^} # func_len /c\ -func_len ()\ -{\ - func_len_result=${#1}\ -} # Extended-shell func_len implementation' "$cfgfile" > $cfgfile.tmp \ - && mv -f "$cfgfile.tmp" "$cfgfile" \ - || (rm -f "$cfgfile" && cp "$cfgfile.tmp" "$cfgfile" && rm -f "$cfgfile.tmp") -test 0 -eq $? || _lt_function_replace_fail=: - -fi - -if test x"$lt_shell_append" = xyes; then - sed -e '/^func_append ()$/,/^} # func_append /c\ -func_append ()\ -{\ - eval "${1}+=\\${2}"\ -} # Extended-shell func_append implementation' "$cfgfile" > $cfgfile.tmp \ - && mv -f "$cfgfile.tmp" "$cfgfile" \ - || (rm -f "$cfgfile" && cp "$cfgfile.tmp" "$cfgfile" && rm -f "$cfgfile.tmp") -test 0 -eq $? || _lt_function_replace_fail=: - - - sed -e '/^func_append_quoted ()$/,/^} # func_append_quoted /c\ -func_append_quoted ()\ -{\ -\ func_quote_for_eval "${2}"\ -\ eval "${1}+=\\\\ \\$func_quote_for_eval_result"\ -} # Extended-shell func_append_quoted implementation' "$cfgfile" > $cfgfile.tmp \ - && mv -f "$cfgfile.tmp" "$cfgfile" \ - || (rm -f "$cfgfile" && cp "$cfgfile.tmp" "$cfgfile" && rm -f "$cfgfile.tmp") -test 0 -eq $? || _lt_function_replace_fail=: - - - # Save a `func_append' function call where possible by direct use of '+=' - sed -e 's%func_append \([a-zA-Z_]\{1,\}\) "%\1+="%g' $cfgfile > $cfgfile.tmp \ - && mv -f "$cfgfile.tmp" "$cfgfile" \ - || (rm -f "$cfgfile" && cp "$cfgfile.tmp" "$cfgfile" && rm -f "$cfgfile.tmp") - test 0 -eq $? || _lt_function_replace_fail=: -else - # Save a `func_append' function call even when '+=' is not available - sed -e 's%func_append \([a-zA-Z_]\{1,\}\) "%\1="$\1%g' $cfgfile > $cfgfile.tmp \ - && mv -f "$cfgfile.tmp" "$cfgfile" \ - || (rm -f "$cfgfile" && cp "$cfgfile.tmp" "$cfgfile" && rm -f "$cfgfile.tmp") - test 0 -eq $? || _lt_function_replace_fail=: -fi - -if test x"$_lt_function_replace_fail" = x":"; then - { $as_echo "$as_me:${as_lineno-$LINENO}: WARNING: Unable to substitute extended shell functions in $ofile" >&5 -$as_echo "$as_me: WARNING: Unable to substitute extended shell functions in $ofile" >&2;} -fi - - mv -f "$cfgfile" "$ofile" || (rm -f "$ofile" && cp "$cfgfile" "$ofile" && rm -f "$cfgfile") chmod +x "$ofile" @@ -18668,13 +19065,13 @@ hardcode_libdir_flag_spec=$lt_hardcode_libdir_flag_spec_CXX # Whether we need a single "-rpath" flag with a separated argument. hardcode_libdir_separator=$lt_hardcode_libdir_separator_CXX -# Set to "yes" if using DIR/libNAME\${shared_ext} during linking hardcodes +# Set to "yes" if using DIR/libNAME\$shared_ext during linking hardcodes # DIR into the resulting binary. hardcode_direct=$hardcode_direct_CXX -# Set to "yes" if using DIR/libNAME\${shared_ext} during linking hardcodes +# Set to "yes" if using DIR/libNAME\$shared_ext during linking hardcodes # DIR into the resulting binary and the resulting library dependency is -# "absolute",i.e impossible to change by setting \${shlibpath_var} if the +# "absolute",i.e impossible to change by setting \$shlibpath_var if the # library is relocated. hardcode_direct_absolute=$hardcode_direct_absolute_CXX diff --git a/gtsam/3rdparty/GeographicLib/configure.ac b/gtsam/3rdparty/GeographicLib/configure.ac index c0b539c5c..9ff747bad 100644 --- a/gtsam/3rdparty/GeographicLib/configure.ac +++ b/gtsam/3rdparty/GeographicLib/configure.ac @@ -1,7 +1,7 @@ dnl dnl Copyright (C) 2009, Francesco P. Lovergine -AC_INIT([GeographicLib],[1.35],[charles@karney.com]) +AC_INIT([GeographicLib],[1.49],[charles@karney.com]) AC_CANONICAL_SYSTEM AC_PREREQ(2.61) AC_CONFIG_SRCDIR(src/Geodesic.cpp) @@ -9,14 +9,14 @@ AC_CONFIG_MACRO_DIR(m4) AM_INIT_AUTOMAKE GEOGRAPHICLIB_VERSION_MAJOR=1 -GEOGRAPHICLIB_VERSION_MINOR=35 +GEOGRAPHICLIB_VERSION_MINOR=49 GEOGRAPHICLIB_VERSION_PATCH=0 AC_DEFINE_UNQUOTED([GEOGRAPHICLIB_VERSION_MAJOR], - [$GEOGRAPHICLIB_VERSION_MAJOR],[major version number]) + [$GEOGRAPHICLIB_VERSION_MAJOR],[major version number]) AC_DEFINE_UNQUOTED([GEOGRAPHICLIB_VERSION_MINOR], - [$GEOGRAPHICLIB_VERSION_MINOR],[minor version number]) + [$GEOGRAPHICLIB_VERSION_MINOR],[minor version number]) AC_DEFINE_UNQUOTED([GEOGRAPHICLIB_VERSION_PATCH], - [$GEOGRAPHICLIB_VERSION_PATCH],[patch number]) + [$GEOGRAPHICLIB_VERSION_PATCH],[patch number]) AC_SUBST(GEOGRAPHICLIB_VERSION_MAJOR) AC_SUBST(GEOGRAPHICLIB_VERSION_MINOR) AC_SUBST(GEOGRAPHICLIB_VERSION_PATCH) @@ -34,7 +34,7 @@ dnl Library code modified: REVISION++ dnl Interfaces changed/added/removed: CURRENT++ REVISION=0 dnl Interfaces added: AGE++ dnl Interfaces removed: AGE=0 -LT_CURRENT=11 +LT_CURRENT=18 LT_REVISION=2 LT_AGE=1 AC_SUBST(LT_CURRENT) @@ -47,31 +47,40 @@ AC_PROG_MAKE_SET AC_PROG_INSTALL AC_PROG_CXX AC_PROG_LIBTOOL +AC_LANG_CPLUSPLUS -# Checks for header files. -AC_CHECK_HEADERS([float.h]) - -# Checks for typedefs, structures, and compiler characteristics. -AC_HEADER_STDBOOL -AC_C_INLINE +# Checks for long double AC_TYPE_LONG_DOUBLE -# Checks for library functions. -AC_FUNC_STRTOD -AC_CHECK_FUNCS([strtol]) -AC_SEARCH_LIBS([floor],[m]) -AC_SEARCH_LIBS([pow],[m]) -AC_SEARCH_LIBS([sqrt],[m]) - # Check endianness AC_C_BIGENDIAN -# Check for doxygen. -# Need version 1.8.1.2 or later for greek and math symbols. +# Check flags for C++11 +AX_CHECK_COMPILE_FLAG([-std=c++11], + [CXXFLAGS="$CXXFLAGS -std=c++11"], + [AX_CHECK_COMPILE_FLAG([-std=c++0x], + [CXXFLAGS="$CXXFLAGS -std=c++0x"])]) +# Check for C++11 math functions +AC_MSG_CHECKING([for C++11 math functions]) +AC_LINK_IFELSE([AC_LANG_PROGRAM( + [#include ], + [int q; + return int(std::hypot(3.0, 4.0) + std::expm1(0.5) + + std::log1p(2.0) + std::asinh(10.0) + + std::atanh(0.8) + std::cbrt(8.0) + + std::fma(1.0, 2.0, 3.0) + std::remquo(100.0, 90.0, &q) + + std::remainder(100.0, 90.0) + std::copysign(1.0, -0.0)) + + std::isfinite(4.0) + std::isnan(0.0);])], + [AC_MSG_RESULT([yes]); + CXXFLAGS="$CXXFLAGS -DGEOGRAPHICLIB_CXX11_MATH=1"], + [AC_MSG_RESULT([no]); + CXXFLAGS="$CXXFLAGS -DGEOGRAPHICLIB_CXX11_MATH=0"]) + +# Check for doxygen. Version 1.8.7 or later needed for … AC_CHECK_PROGS([DOXYGEN], [doxygen]) AM_CONDITIONAL([HAVE_DOXYGEN], - [test "$DOXYGEN" && test `"$DOXYGEN" --version | - sed 's/^\([[0-9]]\)\.\([[0-9]]\)\./\1.0\2./'` '>' 1.08.1.1]) + [test "$DOXYGEN" && test `"$DOXYGEN" --version | + sed 's/\b\([[0-9]]\)\b/0\1/g'` '>' 01.08.06.99]) AC_CHECK_PROGS([POD2MAN], [pod2man]) AC_CHECK_PROGS([POD2HTML], [pod2html]) @@ -87,10 +96,17 @@ src/Makefile include/Makefile tools/Makefile doc/Makefile +js/Makefile man/Makefile matlab/Makefile python/Makefile cmake/Makefile examples/Makefile ]) + +PKG_PROG_PKG_CONFIG +PKG_INSTALLDIR + +AC_CONFIG_FILES([cmake/geographiclib.pc:cmake/project.pc.in]) + AC_OUTPUT diff --git a/gtsam/3rdparty/GeographicLib/depcomp b/gtsam/3rdparty/GeographicLib/depcomp index debb6ffa3..fc98710e2 100755 --- a/gtsam/3rdparty/GeographicLib/depcomp +++ b/gtsam/3rdparty/GeographicLib/depcomp @@ -1,9 +1,9 @@ #! /bin/sh # depcomp - compile a program generating dependencies as side-effects -scriptversion=2012-03-27.16; # UTC +scriptversion=2013-05-30.07; # UTC -# Copyright (C) 1999-2012 Free Software Foundation, Inc. +# Copyright (C) 1999-2014 Free Software Foundation, Inc. # 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 @@ -27,9 +27,9 @@ scriptversion=2012-03-27.16; # UTC case $1 in '') - echo "$0: No command. Try '$0 --help' for more information." 1>&2 - exit 1; - ;; + echo "$0: No command. Try '$0 --help' for more information." 1>&2 + exit 1; + ;; -h | --h*) cat <<\EOF Usage: depcomp [--help] [--version] PROGRAM [ARGS] @@ -56,11 +56,65 @@ EOF ;; esac +# Get the directory component of the given path, and save it in the +# global variables '$dir'. Note that this directory component will +# be either empty or ending with a '/' character. This is deliberate. +set_dir_from () +{ + case $1 in + */*) dir=`echo "$1" | sed -e 's|/[^/]*$|/|'`;; + *) dir=;; + esac +} + +# Get the suffix-stripped basename of the given path, and save it the +# global variable '$base'. +set_base_from () +{ + base=`echo "$1" | sed -e 's|^.*/||' -e 's/\.[^.]*$//'` +} + +# If no dependency file was actually created by the compiler invocation, +# we still have to create a dummy depfile, to avoid errors with the +# Makefile "include basename.Plo" scheme. +make_dummy_depfile () +{ + echo "#dummy" > "$depfile" +} + +# Factor out some common post-processing of the generated depfile. +# Requires the auxiliary global variable '$tmpdepfile' to be set. +aix_post_process_depfile () +{ + # If the compiler actually managed to produce a dependency file, + # post-process it. + if test -f "$tmpdepfile"; then + # Each line is of the form 'foo.o: dependency.h'. + # Do two passes, one to just change these to + # $object: dependency.h + # and one to simply output + # dependency.h: + # which is needed to avoid the deleted-header problem. + { sed -e "s,^.*\.[$lower]*:,$object:," < "$tmpdepfile" + sed -e "s,^.*\.[$lower]*:[$tab ]*,," -e 's,$,:,' < "$tmpdepfile" + } > "$depfile" + rm -f "$tmpdepfile" + else + make_dummy_depfile + fi +} + # A tabulation character. tab=' ' # A newline character. nl=' ' +# Character ranges might be problematic outside the C locale. +# These definitions help. +upper=ABCDEFGHIJKLMNOPQRSTUVWXYZ +lower=abcdefghijklmnopqrstuvwxyz +digits=0123456789 +alpha=${upper}${lower} if test -z "$depmode" || test -z "$source" || test -z "$object"; then echo "depcomp: Variables source, object and depmode must be set" 1>&2 @@ -74,6 +128,9 @@ tmpdepfile=${tmpdepfile-`echo "$depfile" | sed 's/\.\([^.]*\)$/.T\1/'`} rm -f "$tmpdepfile" +# Avoid interferences from the environment. +gccflag= dashmflag= + # Some modes work just like other modes, but use different flags. We # parameterize here, but still list the modes in the big case below, # to make depend.m4 easier to write. Note that we *cannot* use a case @@ -85,32 +142,32 @@ if test "$depmode" = hp; then fi if test "$depmode" = dashXmstdout; then - # This is just like dashmstdout with a different argument. - dashmflag=-xM - depmode=dashmstdout + # This is just like dashmstdout with a different argument. + dashmflag=-xM + depmode=dashmstdout fi cygpath_u="cygpath -u -f -" if test "$depmode" = msvcmsys; then - # This is just like msvisualcpp but w/o cygpath translation. - # Just convert the backslash-escaped backslashes to single forward - # slashes to satisfy depend.m4 - cygpath_u='sed s,\\\\,/,g' - depmode=msvisualcpp + # This is just like msvisualcpp but w/o cygpath translation. + # Just convert the backslash-escaped backslashes to single forward + # slashes to satisfy depend.m4 + cygpath_u='sed s,\\\\,/,g' + depmode=msvisualcpp fi if test "$depmode" = msvc7msys; then - # This is just like msvc7 but w/o cygpath translation. - # Just convert the backslash-escaped backslashes to single forward - # slashes to satisfy depend.m4 - cygpath_u='sed s,\\\\,/,g' - depmode=msvc7 + # This is just like msvc7 but w/o cygpath translation. + # Just convert the backslash-escaped backslashes to single forward + # slashes to satisfy depend.m4 + cygpath_u='sed s,\\\\,/,g' + depmode=msvc7 fi if test "$depmode" = xlc; then - # IBM C/C++ Compilers xlc/xlC can output gcc-like dependency informations. - gccflag=-qmakedep=gcc,-MF - depmode=gcc + # IBM C/C++ Compilers xlc/xlC can output gcc-like dependency information. + gccflag=-qmakedep=gcc,-MF + depmode=gcc fi case "$depmode" in @@ -133,8 +190,7 @@ gcc3) done "$@" stat=$? - if test $stat -eq 0; then : - else + if test $stat -ne 0; then rm -f "$tmpdepfile" exit $stat fi @@ -142,13 +198,17 @@ gcc3) ;; gcc) +## Note that this doesn't just cater to obsosete pre-3.x GCC compilers. +## but also to in-use compilers like IMB xlc/xlC and the HP C compiler. +## (see the conditional assignment to $gccflag above). ## There are various ways to get dependency output from gcc. Here's ## why we pick this rather obscure method: ## - Don't want to use -MD because we'd like the dependencies to end ## up in a subdir. Having to rename by hand is ugly. ## (We might end up doing this anyway to support other compilers.) ## - The DEPENDENCIES_OUTPUT environment variable makes gcc act like -## -MM, not -M (despite what the docs say). +## -MM, not -M (despite what the docs say). Also, it might not be +## supported by the other compilers which use the 'gcc' depmode. ## - Using -M directly means running the compiler twice (even worse ## than renaming). if test -z "$gccflag"; then @@ -156,15 +216,14 @@ gcc) fi "$@" -Wp,"$gccflag$tmpdepfile" stat=$? - if test $stat -eq 0; then : - else + if test $stat -ne 0; then rm -f "$tmpdepfile" exit $stat fi rm -f "$depfile" echo "$object : \\" > "$depfile" - alpha=ABCDEFGHIJKLMNOPQRSTUVWXYZabcdefghijklmnopqrstuvwxyz -## The second -e expression handles DOS-style file names with drive letters. + # The second -e expression handles DOS-style file names with drive + # letters. sed -e 's/^[^:]*: / /' \ -e 's/^['$alpha']:\/[^:]*: / /' < "$tmpdepfile" >> "$depfile" ## This next piece of magic avoids the "deleted header file" problem. @@ -173,15 +232,15 @@ gcc) ## typically no way to rebuild the header). We avoid this by adding ## dummy dependencies for each header file. Too bad gcc doesn't do ## this for us directly. - tr ' ' "$nl" < "$tmpdepfile" | ## Some versions of gcc put a space before the ':'. On the theory ## that the space means something, we add a space to the output as ## well. hp depmode also adds that space, but also prefixes the VPATH ## to the object. Take care to not repeat it in the output. ## Some versions of the HPUX 10.20 sed can't process this invocation ## correctly. Breaking it into two sed invocations is a workaround. - sed -e 's/^\\$//' -e '/^$/d' -e "s|.*$object$||" -e '/:$/d' \ - | sed -e 's/$/ :/' >> "$depfile" + tr ' ' "$nl" < "$tmpdepfile" \ + | sed -e 's/^\\$//' -e '/^$/d' -e "s|.*$object$||" -e '/:$/d' \ + | sed -e 's/$/ :/' >> "$depfile" rm -f "$tmpdepfile" ;; @@ -199,8 +258,7 @@ sgi) "$@" -MDupdate "$tmpdepfile" fi stat=$? - if test $stat -eq 0; then : - else + if test $stat -ne 0; then rm -f "$tmpdepfile" exit $stat fi @@ -208,7 +266,6 @@ sgi) if test -f "$tmpdepfile"; then # yes, the sourcefile depend on other files echo "$object : \\" > "$depfile" - # Clip off the initial element (the dependent). Don't try to be # clever and replace this with sed code, as IRIX sed won't handle # lines with more than a fixed number of characters (4096 in @@ -216,19 +273,15 @@ sgi) # the IRIX cc adds comments like '#:fec' to the end of the # dependency line. tr ' ' "$nl" < "$tmpdepfile" \ - | sed -e 's/^.*\.o://' -e 's/#.*$//' -e '/^$/ d' | \ - tr "$nl" ' ' >> "$depfile" + | sed -e 's/^.*\.o://' -e 's/#.*$//' -e '/^$/ d' \ + | tr "$nl" ' ' >> "$depfile" echo >> "$depfile" - # The second pass generates a dummy entry for each header file. tr ' ' "$nl" < "$tmpdepfile" \ - | sed -e 's/^.*\.o://' -e 's/#.*$//' -e '/^$/ d' -e 's/$/:/' \ - >> "$depfile" + | sed -e 's/^.*\.o://' -e 's/#.*$//' -e '/^$/ d' -e 's/$/:/' \ + >> "$depfile" else - # The sourcefile does not contain any dependencies, so just - # store a dummy comment line, to avoid errors with the Makefile - # "include basename.Plo" scheme. - echo "#dummy" > "$depfile" + make_dummy_depfile fi rm -f "$tmpdepfile" ;; @@ -246,9 +299,8 @@ aix) # current directory. Also, the AIX compiler puts '$object:' at the # start of each line; $object doesn't have directory information. # Version 6 uses the directory in both cases. - dir=`echo "$object" | sed -e 's|/[^/]*$|/|'` - test "x$dir" = "x$object" && dir= - base=`echo "$object" | sed -e 's|^.*/||' -e 's/\.o$//' -e 's/\.lo$//'` + set_dir_from "$object" + set_base_from "$object" if test "$libtool" = yes; then tmpdepfile1=$dir$base.u tmpdepfile2=$base.u @@ -261,9 +313,7 @@ aix) "$@" -M fi stat=$? - - if test $stat -eq 0; then : - else + if test $stat -ne 0; then rm -f "$tmpdepfile1" "$tmpdepfile2" "$tmpdepfile3" exit $stat fi @@ -272,65 +322,113 @@ aix) do test -f "$tmpdepfile" && break done - if test -f "$tmpdepfile"; then - # Each line is of the form 'foo.o: dependent.h'. - # Do two passes, one to just change these to - # '$object: dependent.h' and one to simply 'dependent.h:'. - sed -e "s,^.*\.[a-z]*:,$object:," < "$tmpdepfile" > "$depfile" - sed -e 's,^.*\.[a-z]*:['"$tab"' ]*,,' -e 's,$,:,' < "$tmpdepfile" >> "$depfile" - else - # The sourcefile does not contain any dependencies, so just - # store a dummy comment line, to avoid errors with the Makefile - # "include basename.Plo" scheme. - echo "#dummy" > "$depfile" - fi - rm -f "$tmpdepfile" + aix_post_process_depfile ;; -icc) - # Intel's C compiler anf tcc (Tiny C Compiler) understand '-MD -MF file'. - # However on - # $CC -MD -MF foo.d -c -o sub/foo.o sub/foo.c - # ICC 7.0 will fill foo.d with something like - # foo.o: sub/foo.c - # foo.o: sub/foo.h - # which is wrong. We want - # sub/foo.o: sub/foo.c - # sub/foo.o: sub/foo.h - # sub/foo.c: - # sub/foo.h: - # ICC 7.1 will output - # foo.o: sub/foo.c sub/foo.h - # and will wrap long lines using '\': - # foo.o: sub/foo.c ... \ - # sub/foo.h ... \ - # ... - # tcc 0.9.26 (FIXME still under development at the moment of writing) - # will emit a similar output, but also prepend the continuation lines - # with horizontal tabulation characters. +tcc) + # tcc (Tiny C Compiler) understand '-MD -MF file' since version 0.9.26 + # FIXME: That version still under development at the moment of writing. + # Make that this statement remains true also for stable, released + # versions. + # It will wrap lines (doesn't matter whether long or short) with a + # trailing '\', as in: + # + # foo.o : \ + # foo.c \ + # foo.h \ + # + # It will put a trailing '\' even on the last line, and will use leading + # spaces rather than leading tabs (at least since its commit 0394caf7 + # "Emit spaces for -MD"). "$@" -MD -MF "$tmpdepfile" stat=$? - if test $stat -eq 0; then : - else + if test $stat -ne 0; then rm -f "$tmpdepfile" exit $stat fi rm -f "$depfile" - # Each line is of the form 'foo.o: dependent.h', - # or 'foo.o: dep1.h dep2.h \', or ' dep3.h dep4.h \'. + # Each non-empty line is of the form 'foo.o : \' or ' dep.h \'. + # We have to change lines of the first kind to '$object: \'. + sed -e "s|.*:|$object :|" < "$tmpdepfile" > "$depfile" + # And for each line of the second kind, we have to emit a 'dep.h:' + # dummy dependency, to avoid the deleted-header problem. + sed -n -e 's|^ *\(.*\) *\\$|\1:|p' < "$tmpdepfile" >> "$depfile" + rm -f "$tmpdepfile" + ;; + +## The order of this option in the case statement is important, since the +## shell code in configure will try each of these formats in the order +## listed in this file. A plain '-MD' option would be understood by many +## compilers, so we must ensure this comes after the gcc and icc options. +pgcc) + # Portland's C compiler understands '-MD'. + # Will always output deps to 'file.d' where file is the root name of the + # source file under compilation, even if file resides in a subdirectory. + # The object file name does not affect the name of the '.d' file. + # pgcc 10.2 will output + # foo.o: sub/foo.c sub/foo.h + # and will wrap long lines using '\' : + # foo.o: sub/foo.c ... \ + # sub/foo.h ... \ + # ... + set_dir_from "$object" + # Use the source, not the object, to determine the base name, since + # that's sadly what pgcc will do too. + set_base_from "$source" + tmpdepfile=$base.d + + # For projects that build the same source file twice into different object + # files, the pgcc approach of using the *source* file root name can cause + # problems in parallel builds. Use a locking strategy to avoid stomping on + # the same $tmpdepfile. + lockdir=$base.d-lock + trap " + echo '$0: caught signal, cleaning up...' >&2 + rmdir '$lockdir' + exit 1 + " 1 2 13 15 + numtries=100 + i=$numtries + while test $i -gt 0; do + # mkdir is a portable test-and-set. + if mkdir "$lockdir" 2>/dev/null; then + # This process acquired the lock. + "$@" -MD + stat=$? + # Release the lock. + rmdir "$lockdir" + break + else + # If the lock is being held by a different process, wait + # until the winning process is done or we timeout. + while test -d "$lockdir" && test $i -gt 0; do + sleep 1 + i=`expr $i - 1` + done + fi + i=`expr $i - 1` + done + trap - 1 2 13 15 + if test $i -le 0; then + echo "$0: failed to acquire lock after $numtries attempts" >&2 + echo "$0: check lockdir '$lockdir'" >&2 + exit 1 + fi + + if test $stat -ne 0; then + rm -f "$tmpdepfile" + exit $stat + fi + rm -f "$depfile" + # Each line is of the form `foo.o: dependent.h', + # or `foo.o: dep1.h dep2.h \', or ` dep3.h dep4.h \'. # Do two passes, one to just change these to - # '$object: dependent.h' and one to simply 'dependent.h:'. - sed -e "s/^[ $tab][ $tab]*/ /" -e "s,^[^:]*:,$object :," \ - < "$tmpdepfile" > "$depfile" - sed ' - s/[ '"$tab"'][ '"$tab"']*/ /g - s/^ *// - s/ *\\*$// - s/^[^:]*: *// - /^$/d - /:$/d - s/$/ :/ - ' < "$tmpdepfile" >> "$depfile" + # `$object: dependent.h' and one to simply `dependent.h:'. + sed "s,^[^:]*:,$object :," < "$tmpdepfile" > "$depfile" + # Some versions of the HPUX 10.20 sed can't process this invocation + # correctly. Breaking it into two sed invocations is a workaround. + sed 's,^[^:]*: \(.*\)$,\1,;s/^\\$//;/^$/d;/:$/d' < "$tmpdepfile" \ + | sed -e 's/$/ :/' >> "$depfile" rm -f "$tmpdepfile" ;; @@ -341,9 +439,8 @@ hp2) # 'foo.d', which lands next to the object file, wherever that # happens to be. # Much of this is similar to the tru64 case; see comments there. - dir=`echo "$object" | sed -e 's|/[^/]*$|/|'` - test "x$dir" = "x$object" && dir= - base=`echo "$object" | sed -e 's|^.*/||' -e 's/\.o$//' -e 's/\.lo$//'` + set_dir_from "$object" + set_base_from "$object" if test "$libtool" = yes; then tmpdepfile1=$dir$base.d tmpdepfile2=$dir.libs/$base.d @@ -354,8 +451,7 @@ hp2) "$@" +Maked fi stat=$? - if test $stat -eq 0; then : - else + if test $stat -ne 0; then rm -f "$tmpdepfile1" "$tmpdepfile2" exit $stat fi @@ -365,76 +461,61 @@ hp2) test -f "$tmpdepfile" && break done if test -f "$tmpdepfile"; then - sed -e "s,^.*\.[a-z]*:,$object:," "$tmpdepfile" > "$depfile" + sed -e "s,^.*\.[$lower]*:,$object:," "$tmpdepfile" > "$depfile" # Add 'dependent.h:' lines. sed -ne '2,${ - s/^ *// - s/ \\*$// - s/$/:/ - p - }' "$tmpdepfile" >> "$depfile" + s/^ *// + s/ \\*$// + s/$/:/ + p + }' "$tmpdepfile" >> "$depfile" else - echo "#dummy" > "$depfile" + make_dummy_depfile fi rm -f "$tmpdepfile" "$tmpdepfile2" ;; tru64) - # The Tru64 compiler uses -MD to generate dependencies as a side - # effect. 'cc -MD -o foo.o ...' puts the dependencies into 'foo.o.d'. - # At least on Alpha/Redhat 6.1, Compaq CCC V6.2-504 seems to put - # dependencies in 'foo.d' instead, so we check for that too. - # Subdirectories are respected. - dir=`echo "$object" | sed -e 's|/[^/]*$|/|'` - test "x$dir" = "x$object" && dir= - base=`echo "$object" | sed -e 's|^.*/||' -e 's/\.o$//' -e 's/\.lo$//'` + # The Tru64 compiler uses -MD to generate dependencies as a side + # effect. 'cc -MD -o foo.o ...' puts the dependencies into 'foo.o.d'. + # At least on Alpha/Redhat 6.1, Compaq CCC V6.2-504 seems to put + # dependencies in 'foo.d' instead, so we check for that too. + # Subdirectories are respected. + set_dir_from "$object" + set_base_from "$object" - if test "$libtool" = yes; then - # With Tru64 cc, shared objects can also be used to make a - # static library. This mechanism is used in libtool 1.4 series to - # handle both shared and static libraries in a single compilation. - # With libtool 1.4, dependencies were output in $dir.libs/$base.lo.d. - # - # With libtool 1.5 this exception was removed, and libtool now - # generates 2 separate objects for the 2 libraries. These two - # compilations output dependencies in $dir.libs/$base.o.d and - # in $dir$base.o.d. We have to check for both files, because - # one of the two compilations can be disabled. We should prefer - # $dir$base.o.d over $dir.libs/$base.o.d because the latter is - # automatically cleaned when .libs/ is deleted, while ignoring - # the former would cause a distcleancheck panic. - tmpdepfile1=$dir.libs/$base.lo.d # libtool 1.4 - tmpdepfile2=$dir$base.o.d # libtool 1.5 - tmpdepfile3=$dir.libs/$base.o.d # libtool 1.5 - tmpdepfile4=$dir.libs/$base.d # Compaq CCC V6.2-504 - "$@" -Wc,-MD - else - tmpdepfile1=$dir$base.o.d - tmpdepfile2=$dir$base.d - tmpdepfile3=$dir$base.d - tmpdepfile4=$dir$base.d - "$@" -MD - fi + if test "$libtool" = yes; then + # Libtool generates 2 separate objects for the 2 libraries. These + # two compilations output dependencies in $dir.libs/$base.o.d and + # in $dir$base.o.d. We have to check for both files, because + # one of the two compilations can be disabled. We should prefer + # $dir$base.o.d over $dir.libs/$base.o.d because the latter is + # automatically cleaned when .libs/ is deleted, while ignoring + # the former would cause a distcleancheck panic. + tmpdepfile1=$dir$base.o.d # libtool 1.5 + tmpdepfile2=$dir.libs/$base.o.d # Likewise. + tmpdepfile3=$dir.libs/$base.d # Compaq CCC V6.2-504 + "$@" -Wc,-MD + else + tmpdepfile1=$dir$base.d + tmpdepfile2=$dir$base.d + tmpdepfile3=$dir$base.d + "$@" -MD + fi - stat=$? - if test $stat -eq 0; then : - else - rm -f "$tmpdepfile1" "$tmpdepfile2" "$tmpdepfile3" "$tmpdepfile4" - exit $stat - fi + stat=$? + if test $stat -ne 0; then + rm -f "$tmpdepfile1" "$tmpdepfile2" "$tmpdepfile3" + exit $stat + fi - for tmpdepfile in "$tmpdepfile1" "$tmpdepfile2" "$tmpdepfile3" "$tmpdepfile4" - do - test -f "$tmpdepfile" && break - done - if test -f "$tmpdepfile"; then - sed -e "s,^.*\.[a-z]*:,$object:," < "$tmpdepfile" > "$depfile" - sed -e 's,^.*\.[a-z]*:['"$tab"' ]*,,' -e 's,$,:,' < "$tmpdepfile" >> "$depfile" - else - echo "#dummy" > "$depfile" - fi - rm -f "$tmpdepfile" - ;; + for tmpdepfile in "$tmpdepfile1" "$tmpdepfile2" "$tmpdepfile3" + do + test -f "$tmpdepfile" && break + done + # Same post-processing that is required for AIX mode. + aix_post_process_depfile + ;; msvc7) if test "$libtool" = yes; then @@ -445,8 +526,7 @@ msvc7) "$@" $showIncludes > "$tmpdepfile" stat=$? grep -v '^Note: including file: ' "$tmpdepfile" - if test "$stat" = 0; then : - else + if test $stat -ne 0; then rm -f "$tmpdepfile" exit $stat fi @@ -472,6 +552,7 @@ $ { G p }' >> "$depfile" + echo >> "$depfile" # make sure the fragment doesn't end with a backslash rm -f "$tmpdepfile" ;; @@ -523,13 +604,14 @@ dashmstdout) # in the target name. This is to cope with DOS-style filenames: # a dependency such as 'c:/foo/bar' could be seen as target 'c' otherwise. "$@" $dashmflag | - sed 's:^['"$tab"' ]*[^:'"$tab"' ][^:][^:]*\:['"$tab"' ]*:'"$object"'\: :' > "$tmpdepfile" + sed "s|^[$tab ]*[^:$tab ][^:][^:]*:[$tab ]*|$object: |" > "$tmpdepfile" rm -f "$depfile" cat < "$tmpdepfile" > "$depfile" - tr ' ' "$nl" < "$tmpdepfile" | \ -## Some versions of the HPUX 10.20 sed can't process this invocation -## correctly. Breaking it into two sed invocations is a workaround. - sed -e 's/^\\$//' -e '/^$/d' -e '/:$/d' | sed -e 's/$/ :/' >> "$depfile" + # Some versions of the HPUX 10.20 sed can't process this sed invocation + # correctly. Breaking it into two sed invocations is a workaround. + tr ' ' "$nl" < "$tmpdepfile" \ + | sed -e 's/^\\$//' -e '/^$/d' -e '/:$/d' \ + | sed -e 's/$/ :/' >> "$depfile" rm -f "$tmpdepfile" ;; @@ -582,10 +664,12 @@ makedepend) # makedepend may prepend the VPATH from the source file name to the object. # No need to regex-escape $object, excess matching of '.' is harmless. sed "s|^.*\($object *:\)|\1|" "$tmpdepfile" > "$depfile" - sed '1,2d' "$tmpdepfile" | tr ' ' "$nl" | \ -## Some versions of the HPUX 10.20 sed can't process this invocation -## correctly. Breaking it into two sed invocations is a workaround. - sed -e 's/^\\$//' -e '/^$/d' -e '/:$/d' | sed -e 's/$/ :/' >> "$depfile" + # Some versions of the HPUX 10.20 sed can't process the last invocation + # correctly. Breaking it into two sed invocations is a workaround. + sed '1,2d' "$tmpdepfile" \ + | tr ' ' "$nl" \ + | sed -e 's/^\\$//' -e '/^$/d' -e '/:$/d' \ + | sed -e 's/$/ :/' >> "$depfile" rm -f "$tmpdepfile" "$tmpdepfile".bak ;; @@ -621,10 +705,10 @@ cpp) esac done - "$@" -E | - sed -n -e '/^# [0-9][0-9]* "\([^"]*\)".*/ s:: \1 \\:p' \ - -e '/^#line [0-9][0-9]* "\([^"]*\)".*/ s:: \1 \\:p' | - sed '$ s: \\$::' > "$tmpdepfile" + "$@" -E \ + | sed -n -e '/^# [0-9][0-9]* "\([^"]*\)".*/ s:: \1 \\:p' \ + -e '/^#line [0-9][0-9]* "\([^"]*\)".*/ s:: \1 \\:p' \ + | sed '$ s: \\$::' > "$tmpdepfile" rm -f "$depfile" echo "$object : \\" > "$depfile" cat < "$tmpdepfile" >> "$depfile" @@ -656,15 +740,15 @@ msvisualcpp) shift ;; "-Gm"|"/Gm"|"-Gi"|"/Gi"|"-ZI"|"/ZI") - set fnord "$@" - shift - shift - ;; + set fnord "$@" + shift + shift + ;; *) - set fnord "$@" "$arg" - shift - shift - ;; + set fnord "$@" "$arg" + shift + shift + ;; esac done "$@" -E 2>/dev/null | diff --git a/gtsam/3rdparty/GeographicLib/doc/CMakeLists.txt b/gtsam/3rdparty/GeographicLib/doc/CMakeLists.txt index 7390a40fd..6455055ed 100644 --- a/gtsam/3rdparty/GeographicLib/doc/CMakeLists.txt +++ b/gtsam/3rdparty/GeographicLib/doc/CMakeLists.txt @@ -29,38 +29,105 @@ endif () file (MAKE_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}/html-stage) if (DOXYGEN_FOUND) - configure_file (doxyfile.in doxyfile) - configure_file (doxyfile-c.in doxyfile-c) - configure_file (doxyfile-for.in doxyfile-for) - configure_file (doxyfile-net.in doxyfile-net) - file (GLOB SOURCES + set (DOCTARGETS) + + configure_file (GeographicLib.dox.in GeographicLib.dox @ONLY) + configure_file (doxyfile.in doxyfile @ONLY) + file (GLOB CXXSOURCES ../src/[A-Za-z]*.cpp ../include/GeographicLib/[A-Za-z]*.hpp ../tools/[A-Za-z]*.cpp ../examples/[A-Za-z]*.cpp - ../legacy/C/*.[ch] ../legacy/Fortran/*.for ../legacy/Fortran/*.inc - ../dotnet/NETGeographicLib/*.cpp ../dotnet/NETGeographicLib/*.h - ../dotnet/examples/CS/*.cs ../dotnet/examples/ManagedCPP/*.cpp - ../dotnet/examples/VB/*.vb) + ../examples/[A-Za-z]*.hpp) file (GLOB EXTRA_FILES ../maxima/[A-Za-z]*.mac tmseries30.html geodseries30.html ../LICENSE.txt) - file (GLOB FIGURES *.png) + file (GLOB FIGURES *.png *.svg *.gif) file (COPY ${EXTRA_FILES} DESTINATION html-stage) - add_custom_target (doc ALL + add_custom_target (cxxdoc ALL DEPENDS ${CMAKE_CURRENT_BINARY_DIR}/html/index.html) - add_dependencies (doc htmlman) + add_dependencies (cxxdoc htmlman) add_custom_command (OUTPUT ${CMAKE_CURRENT_BINARY_DIR}/html/index.html DEPENDS ${CMAKE_CURRENT_BINARY_DIR}/doxyfile - ${CMAKE_CURRENT_BINARY_DIR}/doxyfile-c - ${CMAKE_CURRENT_BINARY_DIR}/doxyfile-for - ${CMAKE_CURRENT_BINARY_DIR}/doxyfile-net - GeographicLib.dox geodesic-c.dox geodesic-for.dox NETGeographicLib.dox - ${SOURCES} ${EXTRA_FILES} ${FIGURES} ${HTMLMAN} + ${CMAKE_CURRENT_BINARY_DIR}/GeographicLib.dox + ${CXXSOURCES} ${EXTRA_FILES} ${FIGURES} ${HTMLMAN} COMMAND ${CMAKE_COMMAND} -E remove_directory html COMMAND ${CMAKE_COMMAND} -E copy_directory html-stage html COMMAND ${DOXYGEN_EXECUTABLE} doxyfile > doxygen.log + COMMENT "Generating C++ documentation tree") + set (DOCTARGETS ${DOCTARGETS} cxxdoc) + + configure_file (doxyfile-c.in doxyfile-c @ONLY) + file (GLOB CSOURCES ../legacy/C/*.[ch]) + add_custom_target (cdoc ALL + DEPENDS ${CMAKE_CURRENT_BINARY_DIR}/html/C/index.html) + add_dependencies (cdoc cxxdoc) + add_custom_command (OUTPUT ${CMAKE_CURRENT_BINARY_DIR}/html/C/index.html + DEPENDS ${CMAKE_CURRENT_BINARY_DIR}/doxyfile-c geodesic-c.dox ${CSOURCES} COMMAND ${DOXYGEN_EXECUTABLE} doxyfile-c > doxygen-c.log + COMMENT "Generating C documentation tree") + set (DOCTARGETS ${DOCTARGETS} cdoc) + + configure_file (doxyfile-for.in doxyfile-for @ONLY) + file (GLOB FORTRANSOURCES ../legacy/Fortran/*.for ../legacy/Fortran/*.inc) + add_custom_target (fortrandoc ALL + DEPENDS ${CMAKE_CURRENT_BINARY_DIR}/html/Fortran/index.html) + add_dependencies (fortrandoc cxxdoc) + add_custom_command (OUTPUT + ${CMAKE_CURRENT_BINARY_DIR}/html/Fortran/index.html + DEPENDS ${CMAKE_CURRENT_BINARY_DIR}/doxyfile-for + geodesic-for.dox ${FORTRANSOURCES} COMMAND ${DOXYGEN_EXECUTABLE} doxyfile-for > doxygen-for.log + COMMENT "Generating Fortran documentation tree") + set (DOCTARGETS ${DOCTARGETS} fortrandoc) + + configure_file (doxyfile-net.in doxyfile-net @ONLY) + file (GLOB DOTNETSOURCES + ../dotnet/NETGeographicLib/*.cpp ../dotnet/NETGeographicLib/*.h + ../dotnet/examples/CS/*.cs ../dotnet/examples/ManagedCPP/*.cpp + ../dotnet/examples/VB/*.vb) + add_custom_target (dotnetdoc ALL + DEPENDS ${CMAKE_CURRENT_BINARY_DIR}/html/NET/index.html) + add_dependencies (dotnetdoc cxxdoc) + add_custom_command (OUTPUT ${CMAKE_CURRENT_BINARY_DIR}/html/NET/index.html + DEPENDS ${CMAKE_CURRENT_BINARY_DIR}/doxyfile-net + NETGeographicLib.dox ${DOTNETSOURCES} COMMAND ${DOXYGEN_EXECUTABLE} doxyfile-net > doxygen-net.log - COMMENT "Generating html documentation tree") + COMMENT "Generating .NET documentation tree") + set (DOCTARGETS ${DOCTARGETS} dotnetdoc) + + if (JSDOC) + file (GLOB JSSOURCES + ../js/src/*.js ../js/GeographicLib.md ../js/doc/*.md) + add_custom_target (jsdoc ALL + DEPENDS ${CMAKE_CURRENT_BINARY_DIR}/html/js/index.html) + add_dependencies (jsdoc cxxdoc) + add_custom_command (OUTPUT ${CMAKE_CURRENT_BINARY_DIR}/html/js/index.html + DEPENDS ${JSSOURCES} + COMMAND ${JSDOC} --verbose -d html/js + -u ${PROJECT_SOURCE_DIR}/js/doc + -c ${PROJECT_SOURCE_DIR}/js/conf.json + -R ${PROJECT_SOURCE_DIR}/js/GeographicLib.md + ${PROJECT_SOURCE_DIR}/js/src > jsdoc.log + COMMENT "Generating JavaScript documentation tree") + set (DOCTARGETS ${DOCTARGETS} jsdoc) + endif () + + if (SPHINX) + file (GLOB PYTHONSOURCES + ../python/geographiclib/*.py ../python/doc/*.rst ../python/doc/conf.py) + add_custom_target (pythondoc ALL + DEPENDS ${CMAKE_CURRENT_BINARY_DIR}/html/python/index.html) + add_dependencies (pythondoc cxxdoc) + add_custom_command (OUTPUT + ${CMAKE_CURRENT_BINARY_DIR}/html/python/index.html + DEPENDS ${PYTHONSOURCES} + COMMAND ${SPHINX} -v -b html -d python-doctree + ${PROJECT_SOURCE_DIR}/python/doc html/python > pythondoc.log + COMMENT "Generating python documentation tree") + set (DOCTARGETS ${DOCTARGETS} pythondoc) + endif () + + add_custom_target (doc ALL) + add_dependencies (doc ${DOCTARGETS}) + install (DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}/html DESTINATION ${INSTALL_DOC_DIR}) else () @@ -74,10 +141,3 @@ else () ${CMAKE_CURRENT_BINARY_DIR}/html/utilities.html DESTINATION ${INSTALL_DOC_DIR}/html) endif () - -# Finally install the JavaScript files -file (GLOB SCRIPTDRIVERS scripts/[A-Za-z]*.html) -file (GLOB JSSCRIPTS scripts/GeographicLib/[A-Za-z]*.js) -install (FILES ${SCRIPTDRIVERS} DESTINATION ${INSTALL_DOC_DIR}/scripts) -install (FILES ${JSSCRIPTS} - DESTINATION ${INSTALL_DOC_DIR}/scripts/GeographicLib) diff --git a/gtsam/3rdparty/GeographicLib/doc/GeographicLib.dox b/gtsam/3rdparty/GeographicLib/doc/GeographicLib.dox deleted file mode 100644 index 7fd60e992..000000000 --- a/gtsam/3rdparty/GeographicLib/doc/GeographicLib.dox +++ /dev/null @@ -1,5574 +0,0 @@ -// -*- text -*- -/** - * \file GeographicLib.dox - * \brief Documentation for GeographicLib - * - * Written by Charles Karney and licensed under the - * MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ - **********************************************************************/ - -/** -\mainpage GeographicLib library -\author Charles F. F. Karney (charles@karney.com) -\version 1.35 -\date 2014-03-13 - -\section abstract Abstract - -%GeographicLib is a small set of C++ -classes for performing conversions between geographic, UTM, UPS, -MGRS, geocentric, and local cartesian coordinates, for gravity (e.g., -EGM2008), geoid height and geomagnetic field (e.g., WMM2010) -calculations, and for solving geodesic problems. The emphasis is on -returning accurate results with errors close to round-off (about 5--15 -nanometers). New accurate algorithms for \ref geodesic and \ref -transversemercator have been developed for this library. The -functionality of the library can be accessed from user code, from the -\ref utilities provided, or via the \ref other. Also included is a .NET -wrapper library NETGeographicLib -which exposes the functionality to .NET applications. For a sample of -the geodesic capabilities in JavaScript, check out the -online geodesic calculator and -the script for displaying -geodesics in Google Maps - -This library is not a general purpose projection library; use -proj.4 for that. On the other -hand, it does provide the core functionality offered by -GEOTRANS. - -\section download Download - -The main project page is at -- - http://sourceforge.net/projects/geographiclib -. -The code is available for download at -- - GeographicLib-1.35.tar.gz -- - GeographicLib-1.35.zip -. -as either a compressed tar file (tar.gz) or a zip file. (The two -archives have identical contents, except that the zip file has DOS -line endings.) Alternatively you can get the latest release using git -\verbatim - git clone -b r1.35 git://git.code.sf.net/p/geographiclib/code geographiclib -\endverbatim -There are also binary installers for Windows available at -- - GeographicLib-1.35-win32.exe -- - GeographicLib-1.35-win64.exe -. -It is licensed under the -MIT/X11 License; -see LICENSE.txt for the terms. -For more information, see http://geographiclib.sourceforge.net/. - -\section contents Contents - - \ref intro - - \ref install - - \ref start - - \ref utilities - - \ref organization - - \ref other - - \ref geoid - - \ref gravity - - \ref magnetic - - \ref geodesic - - \ref triaxial - - \ref transversemercator - - \ref geocentric - - \ref old - -
-Forward to \ref intro. -
- -**********************************************************************/ -/** -\page intro Introduction - -
-Forward to \ref install. Up to \ref contents. -
- -%GeographicLib offers a C++ interfaces to a small (but important!) set -of geographic transformations. It grew out of a desire to improve on -the geotrans -package for transforming between geographic and MGRS coordinates. At -present, %GeographicLib provides UTM, UPS, MGRS, geocentric, and local -cartesian projections, gravity and geomagnetic models, and classes for -geodesic calculations. - -The goals of %GeographicLib are: - - Accuracy. In most applications the accuracy is close to round-off, - about 5 nm (5 nanometers). Even though in many geographic - applications 1 cm is considered "accurate enough", there is little - penalty in providing much better accuracy. In situations where a - faster approximate algorithm is necessary, %GeographicLib offers an - accurate benchmark to guide the development. - - Completeness. For each of the projections included, an attempt is - made to provide a complete solution. For example, - GeographicLib::Geodesic::Inverse works for anti-podal points. - Similarly, GeographicLib::Geocentric.Reverse will return accurate - geodetic coordinates even for points close to the center of the - earth. - - C++ interface. For the projection methods, this allows encapsulation - of the ellipsoid parameters. - - Emphasis on projections necessary for analyzing military data. - - Uniform treatment of UTM/UPS. The GeographicLib::UTMUPS class treats - UPS as zone 0. This simplifies conversions between UTM and UPS - coordinates, etc. - - Well defined and stable conventions for the conversion between - UTM/UPS to MGRS coordinates. - - Detailed internal documentation on the algorithms. For the most part - %GeographicLib uses published algorithms and references are given. If - changes have been made (usually to improve the numerical accuracy), - these are described in the code. - -Various \ref utilities are provided with the library. These illustrate -the use of the library and are useful in their own right. This library -and the utilities have been tested with g++ 4.4 under Linux, with g++ -4.2 under Mac OS X, and with MS Visual Studio 9 (2008), 10 (2010), 11 -(2012), and 12 (2013) compiled for 32 bit and 64 bit. - -Matlab, JavaScript, and Python interfaces are provided to portions of -%GeographicLib; see \ref other. - -The section \ref geodesic documents the method of solving the geodesic -problem. - -The section \ref transversemercator documents various properties of this -projection. - -The bulk of the testing has used geographically relevant values of the -flattening. Thus, you can expect close to full accuracy for -0.01 ≤ -\e f ≤ 0.01 (but note that GeographicLib::TransverseMercatorExact is -restricted to \e f > 0). However, reasonably accurate results can be -expected if -0.1 ≤ \e f ≤ 0.1. Outside this range, you should -attempt to verify the accuracy of the routines independently. Two types -of problems may occur with larger values of \e f: - - Some classes, specifically GeographicLib::Geodesic, - GeographicLib::GeodesicLine, and GeographicLib::TransverseMercator, - use series expansions using \e f as a small parameter. The accuracy - of these routines will degrade as \e f becomes large. - - Even when exact formulas are used, many of the classes need to invert - the exact formulas (e.g., to invert a projection), typically, using - Newton's method. This usually provides an essentially exact - inversion. However, the choice of starting guess and the exit - conditions have been tuned to cover small values of \e f and the - inversion may be incorrect if \e f is large. - -Undoubtedly, bugs lurk in this code and in the documentation. Please -report any you find to charles@karney.com. - -
-Forward to \ref install. Up to \ref contents. -
-**********************************************************************/ -/** -\page install Installing %GeographicLib - -
-Back to \ref intro. Forward to \ref start. Up to \ref contents. -
- -%GeographicLib has been developed under Linux with the g++ compiler -(versions 4.0 and later) and under Windows with Visual Studio 2005, 2008, -and 2010. Earlier versions were tested also under Darwin and Solaris. It -should compile on a wide range of other systems. First download either - -GeographicLib-1.35.tar.gz or - -GeographicLib-1.35.zip (or - -GeographicLib-1.35-win32.exe or - -GeographicLib-1.35-win64.exe for binary installation under Windows). -Then pick one of the first five options below: -- \ref cmake. This is the preferred installation method as it will work - on the widest range of platforms. However it requires that you have - cmake installed. -- \ref autoconf. This method works for most Unix-like systems, - including Linux and Mac OS X. -- \ref gnu. This is a simple installation method that works with g++ - and GNU make on Linux and many Unix platforms. -- \ref windows. This is a simple installation method that works with - Visual Studio 2005, 2008, and 2010 under Windows. -- \ref windowsbin. Use this installation method if you only need to use - the \ref utilities supplied with %GeographicLib. (This method also - installs the header files and the library for use by Visual Studio 10.) -- \ref qt. How to compile %GeographicLib so that it can be used by Qt - programs. -- \ref maintainer. This describes addition tasks of interest only to - the maintainers of this code. -. -This section documents only how to install the software. If you -wish to use %GeographicLib to evaluate geoid heights or the earth's -gravitational or magnetic fields, then you must also install the -relevant data files. See \ref geoidinst, \ref gravityinst, and \ref -magneticinst for instructions. - -The first two installation methods use two important techniques which -make software maintanence simpler -- Out-of-source builds: This means that you create a separate - directory for compiling the code. In the description here the - directories are called BUILD and are located in the top-level of the - source tree. You might want to use a suffix to denote the type of - build, e.g., BUILD-vc9 for Visual Studio 9, or BUILD-shared for a - build which creates a shared library. The advantages of out-of-source - builds are: - - You don't mess up the source tree, so it's easy to "clean up". - Indeed the source tree might be on a read-only file system. - - Builds for multiple platforms or compilers don't interfere with each - other. -- The library is installed: After compilation, there is a - separate install step which copies the headers, libraries, - tools, and documentation to a "central" location. You may at this - point delete the source and build directories. If you have - administrative privileges, you can install %GeographicLib for the use - of all users (e.g., in /usr/local). Otherwise, you can install it for - your personal use (e.g., in $HOME/packages). - -\section cmake Installation with cmake - -This is the recommended method of installation; however it requires that -cmake be installed on your system. -This permits %GeographicLib to be built either as a shared or a static -library on a wide variety of systems. cmake can also determine the -capabilities of your system and adjust the compilation of the -libraries and examples appropriately. - -cmake is available for most computer platforms. On Linux systems cmake -will typically one of the standard packages and can be installed by a -command like - \verbatim - yum install cmake \endverbatim -(executed as root). The minimum version of cmake supported for building -%GeographicLib is 2.8.4 (which was released on 2011-02-16). (Actually, -a few earlier versions will also work for non-Windows platforms.) - -On other systems, download a binary installer from http://www.cmake.org -click on download, and save and run the appropriate installer. Run the -cmake command with no arguments to get help. Other useful tools are -ccmake and cmake-gui which offer curses and graphical interfaces to -cmake. Building under cmake depends on whether it is targeting an IDE -(interactive development environment) or generating Unix-style -makefiles. The instructions below have been tested with makefiles and -g++ on Linux and with the Visual Studio IDE on Windows. - -Here are the steps to compile and install %GeographicLib: -- Unpack the source, running one of \verbatim - tar xfpz GeographicLib-1.35.tar.gz - unzip -q GeographicLib-1.35.zip \endverbatim - then enter the directory created with one of \verbatim - cd GeographicLib-1.35 \endverbatim -- Create a separate build directory and enter it, for example, \verbatim - mkdir BUILD - cd BUILD \endverbatim -- Run cmake, pointing it to the source directory (..). On Linux, Unix, - and MacOSX systems, the command is \verbatim - cmake .. \endverbatim - For Windows, the command is typically one of \verbatim - cmake -G "Visual Studio 10" -D CMAKE_INSTALL_PREFIX=C:/pkg-vc10/GeographicLib-1.35 .. - cmake -G "Visual Studio 9 2008" -D CMAKE_INSTALL_PREFIX=C:/pkg-vc9/GeographicLib-1.35 .. -\endverbatim - The definitions of CMAKE_INSTALL_PREFIX are optional (see below). The - settings given above are recommended to ensure that packages that use - %GeographicLib use the version compiled with the right compiler. - If you need to rerun cmake, use \verbatim - cmake . \endverbatim - possibly including some options via -D (see the next step). -- cmake allows you to configure how %GeographicLib is built and installed by - supplying options, for example \verbatim - cmake -D CMAKE_INSTALL_PREFIX=/tmp/geographic . \endverbatim - The options you might need to change are - - COMMON_INSTALL_PATH governs the installation - convention. If it is on ON (the Linux default), the installation - is to a common directory, e.g., /usr/local. If it is OFF (the - Windows default), the installation directory contains the package - name, e.g., C:/pkg/GeographicLib-1.35. The installation - directories for the documentation, cmake configuration, python and - matlab interfaces all depend on the variable with deeper paths - relative to CMAKE_INSTALL_PREFIX being used when it's ON: - - documentation: OFF: doc/html; ON: share/doc/GeographicLib/html; - - cmake configuration: OFF cmake; ON: share/cmake/GeographicLib; - - python interface: OFF: python; ON: lib/python/site-packages; - - matlab interface: OFF: matlab; ON: libexec/GeographicLib/matlab; - . - - CMAKE_INSTALL_PREFIX (default: /usr/local - on non-Windows systems, C:/Program Files/GeographicLib - on Windows systems) specifies where the library will be installed. - For windows systems, it is recommended to use a prefix which - includes the compiler version, as shown above (and also, possibly, - whether this is a 64-bit build, e.g., cmake -G "Visual Studio - 10 Win64" -D CMAKE_INSTALL_PREFIX=C:/pkg-vc10-x64/GeographicLib-1.35 - ..). If you just want to try the library to see if it suits - your needs, pick, for example, - CMAKE_INSTALL_PREFIX=/tmp/geographic. - - GEOGRAPHICLIB_DATA (default: - /usr/local/share/GeographicLib for non-Windows systems, - C:/Documents and Settings/All Users/Application - Data/GeographicLib for Windows systems) specifies the default - location for the various datasets for use by GeographicLib::Geoid, - GeographicLib::GravityModel, and GeographicLib::MagneticModel. - See \ref geoidinst, \ref gravityinst, and \ref magneticinst for more - information. - - GEOGRAPHICLIB_LIB_TYPE (allowed values: SHARED, STATIC, or - BOTH), specifies the types of libraries build. The default is - STATIC for Windows and SHARED otherwise. If building %GeographicLib - for sytem-wide use, BOTH is recommended, because this provides users - with the choice of which library to use. - - CMAKE_BUILD_TYPE (default: Release). This - flags only affects non-IDE compile environments (like make + g++). - The default is actually blank, but this is treated as - Release. Choose one of - \verbatim - Debug - Release - RelWithDebInfo - MinSizeRel -\endverbatim - (With IDE compile environments, you get to select the build type in - the IDE.) - - MATLAB_COMPILER (default: OFF). Set this to either - "mex" (for Matlab) or "mkoctfile" (for Octave) to specify the - compiler to use for the Matlab/Octave interface. See \ref matlab - for more information. - - GEOGRAPHICLIB_DOCUMENTATION (default: OFF). If set to - ON, then html documentation is created from the source files, - provided a sufficiently recent version of doxygen can be found. - Otherwise, the html documentation will redirect to the appropriate - version of the online documentation. - - BUILD_NETGEOGRAPHICLIB (default: OFF). If set to ON, - build the managed C++ wrapper library - NETGeographicLib. This only makes - sense for Windows systems. - - GEOGRAPHICLIB_PRECISION specifies the precision to be - used for "real" (i.e., floating point) numbers. 1 means float - (single precision); 2 (the default) means double; 3 means long - double; 4 is reserved for quadruple precision. Nearly all the - testing has been carried out with doubles and that's the - recommended configuration. In particular you should avoid - "installing" the library with a precision different from double. -- Build and install the software. In non-IDE environments, run - \verbatim - make # compile the library and the examples - make test # run some tests - make install # as root, if CMAKE_INSTALL_PREFIX is a system directory -\endverbatim - Possible additional targets are \verbatim - make matlabinterface (only for the Release configuration on Windows) - make dist - make exampleprograms - make netexamples (supported only for Release configuration) \endverbatim - On IDE environments, run your IDE (e.g., Visual Studio), load - GeographicLib.sln, pick the build type (e.g., Release), and select - "Build Solution". If this succeeds, select "RUN_TESTS" to build; - finally, select "INSTALL" to install (RUN_TESTS and INSTALL are in - the CMakePredefinedTargets folder). Alternatively, you run the - Visual Studio compiler from the command line with \verbatim - cmake --build . --config Release --target ALL_BUILD - cmake --build . --config Release --target RUN_TESTS - cmake --build . --config Release --target INSTALL \endverbatim - For maximum flexibility, it's a good idea to build and install both - the Debug and Release versions of the library (in that order). The - installation directories will then contain the release versions of the - tools and both versions (debug and release) of the libraries. - If you use cmake to configure and build your programs, then the right - version of the library (debug vs. release) will automatically be used. -- The headers, library, and utilities are installed in the - include/GeographicLib, lib, and bin directories under - CMAKE_INSTALL_PREFIX. (dll dynamic libraries are - installed in bin.) For documentation, open in a web browser - - PREFIX/share/doc/GeographicLib/html/index.html, if - COMMON_INSTALL_PATH is ON, or - PREFIX/doc/index.html, otherwise. - -\section autoconf Installation using the autoconfigure tools - -The method works on most Unix-like systems including Linux and Mac OS X. -Here are the steps to compile and install %GeographicLib: -- Unpack the source, running \verbatim - tar xfpz GeographicLib-1.35.tar.gz \endverbatim - then enter the directory created \verbatim - cd GeographicLib-1.35 \endverbatim -- Create a separate build directory and enter it, for example, \verbatim - mkdir BUILD - cd BUILD \endverbatim -- Configure the software, specifing the path of the source directory, - with \verbatim - ../configure \endverbatim -- By default %GeographicLib will be installed under /usr/local. - You can change this with, for example \verbatim - ../configure --prefix=/tmp/geographic \endverbatim -- Compile and install the software with \verbatim - make - make install \endverbatim -- The headers, library, and utilities are installed in the - include/GeographicLib, lib, and bin directories under - prefix. This installation method does not compile - the Matlab/Octave interface; however the source for the interface is - installed in libexec/GeographicLib/matlab, see \ref matlab of - instructions on compiling the interface. For documentation, open - - share/doc/GeographicLib/html/index.html in a web browser. - -\section gnu Installation with GNU compiler and Make - -This method requires the standard GNU suite of tools, in particular make -and g++. This builds a static library and the examples. - -Here are the steps to compile and install %GeographicLib: -- Unpack the source, running \verbatim - tar xfpz GeographicLib-1.35.tar.gz \endverbatim - then enter the directory created \verbatim - cd GeographicLib-1.35 \endverbatim -- Edit \verbatim - include/GeographicLib/Config.h \endverbatim - If your C++ compiler does not recognize the long double type - (unlikely), insert \code - #undef HAVE_LONG_DOUBLE \endcode - If your machine using big endian ordering, then insert \code - #define WORDS_BIGENDIAN 1 \endcode -- Build and install the software: \verbatim - make # compile the library and the examples - make install # as root \endverbatim - The installation is in directories under /usr/local. You - can specify a different installation directory with, for example, - \verbatim - make PREFIX=/tmp/geographic install \endverbatim -- The headers, library, and utilities are installed in the - include/GeographicLib, lib, and bin directories under - PREFIX. This installation method does not compile - the Matlab/Octave interface; however the source for the interface is - installed in libexec/GeographicLib/matlab, see \ref matlab of - instructions on compiling the interface. For documentation, open - - share/doc/GeographicLib/html/index.html in a web browser. - -\section windows Installation on Windows - -This method requires Visual Studio 2005, 2008, or 2010. This builds a -static library and the utilities. If you only have Visual Studio 2003, -use cmake to create the necessary solution file, see \ref cmake. (cmake -is needed to build the Matlab interface and to run the tests.) -- Unpack the source, running \verbatim - unzip -q GeographicLib-1.35.zip \endverbatim -- Open GeographicLib-1.35/windows/GeographicLib-vc10.sln in Visual Studio - 2010 (for Visual Studio 2005 and 2008, replace -vc10 by -vc8 or -vc9). -- Pick the build type (e.g., Release), and select "Build Solution". -- The library and the compiled examples are in the windows/Release. -- Copy the library windows/Release/GeographicLib.lib and the - headers in include/GeographicLib somewhere convenient. The - headers should remain in a directory named %GeographicLib. If you - expect to use the Matlab/Octave interface, copy matlab/*.m and - matlab/*.cpp to a directory in your matlab/octave path, see \ref - matlab for instructions on compiling the interface. For documentation, - open - doc/html/index.html in a web - browser. - -The Visual Studio 10 solution also contains projects to build -NETGeographicLib and the C# example project. - -\section windowsbin Using a binary installer for Windows - -Use this method if you only need to use the %GeographicLib utilities. -The header files and static and shared versions of library are also -provided; these can only be used by Visual Studio 2010 (in either -release or debug mode). However, if you plan to use the library, it may -be advisable to build it with the compiler you are using for your own -code using either \ref cmake or \ref windows. - -Download and run - -GeographicLib-1.35-win32.exe or - -GeographicLib-1.35-win64.exe: - - read the MIT/X11 License agreement, - - select whether you want your PATH modified, - - select the installation folder, by default - C:\\pkg-vc10\\GeographicLib-1.35 or C:\\pkg-vc10-x64\\GeographicLib-1.35, - - select the start menu folder, - - and install. - . -(Note that the default installation folder adheres the the convention -given in \ref cmake.) The start menu will now include links to the -documentation for the library and for the utilities (and a link for -uninstalling the library). If you ask for your PATH to be modified, it -will include C:/pkg-vc10/GeographicLib-1.35/bin where the utilities are -installed. The headers and library are installed in the -include/GeographicLib and lib folders. With the 64-bit installer, the -Matlab interface is installed in the matlab folder. Add this to your -path in Matlab to access this interface. The libraries were built using -using Visual Studio 10 in release and debug modes. The utilities were -linked against the release-mode shared library. The Matlab interface -was compiled with Matlab R2013a 64-bit, however it may work with some -other 64-bit versions of Matlab. -NETGeographicLib library dlls (release and -debug) are included with the binary installers; these are linked against -the shared library for %GeographicLib. - -\section qt Building the library for use with Qt - -If Qt is using a standard compiler, then build %GeographicLib with that -same compiler (and optimization flags) as Qt. - -If you are using the mingw compiler on Windows for Qt, then you need to -build %GeographicLib with mingw. You can accomplish this with cmake -under cygwin with, for example, \verbatim - export PATH="`cygpath -m c:/QtSDK/mingw/bin`:$PATH" - mkdir BUILD - cd BUILD - cmake -G "MinGW Makefiles" -D CMAKE_INSTALL_PREFIX=C:/pkg-mingw/GeographicLib .. - mingw32-make - mingw32-make install \endverbatim -If cmake complains that sh mustn't be in your path, invoke cmake with -\verbatim - env PATH="$( echo $PATH | tr : '\n' | - while read d; do test -f "$d/sh.exe" || echo -n "$d:"; done | - sed 's/:$//' )" \ - cmake -G "MinGW Makefiles" -D CMAKE_INSTALL_PREFIX=C:/pkg-mingw/GeographicLib .. -\endverbatim -If cmake is not available, there is a simple project file that compiles -the %GeographicLib library only with the Qt compiler: \verbatim - cd src - qmake GeographicLib.pro # configure the project - make # build the library \endverbatim -The library will be in the src directory (or the src/release or -src/debug directory under Windows). The headers are in -include/GeographicLib. - -\section maintainer Maintainer tasks - -Check the code out of git with \verbatim - git clone -b master git://git.code.sf.net/p/geographiclib/code geographiclib -\endverbatim -Here the "master" branch is checked out. There are three branches in -the git repository: -- master: the main branch for code maintainence. Releases are - tagged on this branch as, e.g., v1.35. -- devel: the development branch; changes made here are merged - into master. -- release: the release branch created by unpacking the source - releases (git is \e not used to merge changes from the other - branches into this branch). This is the \e default branch of the - repository (the branch you get if cloning the repository without - specifying a branch). This differs from the master branch in that - some administrative files are excluded while some intermediate files - are included (in order to aid building on as many platforms as - possible). Releases are tagged on this branch as, e.g., r1.35. -. -The autoconf configuration script and the formatted man pages are not -checked into master branch of the repository. In order to create the -autoconf configuration script, run \verbatim - sh autogen.sh \endverbatim -in the top level directory. Provided you are running on a system with -doxygen, pod2man, and pod2html installed, then you can create the -documentation and the man pages by building the system using cmake or -configure. - -In the case of cmake, you then run \verbatim - make dist \endverbatim -which will copy the man pages from the build directory back into the -source tree and package the resulting source tree for distribution as -\verbatim - GeographicLib-1.35.tar.gz - GeographicLib-1.35.zip \endverbatim -Finally, \verbatim - make package \endverbatim -or building PACKAGE in Visual Studio will create a binary installer for -%GeographicLib. For Windows, this requires in the installation of -NSIS. On Windows, you should -configure %GeographicLib with PACKAGE_DEBUG_LIBS=ON, build both -Release and Debug versions of the library and finally build PACKAGE in -Release mode. This will get the release and debug versions of the -library included in the package. For example, the 64-bit binary -installer is created with \verbatim - cmake -G "Visual Studio 10 Win64" \ - -D GEOGRAPHICLIB_LIB_TYPE=BOTH \ - -D PACKAGE_DEBUG_LIBS=ON \ - -D MATLAB_COMPILER=mex \ - -D BUILD_NETGEOGRAPHICLIB=ON \ - .. - cmake --build . --config Debug --target ALL_BUILD - cmake --build . --config Release --target ALL_BUILD - cmake --build . --config Release --target matlabinterface - cmake --build . --config Release --target PACKAGE \endverbatim - -With configure, run \verbatim - make dist-gzip \endverbatim -which will create the additional files and packages the results ready -for distribution as \verbatim - geographiclib-1.35.tar.gz \endverbatim - -
-Back to \ref intro. Forward to \ref start. Up to \ref contents. -
-**********************************************************************/ -/** -\page start Getting started - -
-Back to \ref install. Forward to \ref utilities. Up to \ref contents. -
- -Much (but not all!) of the useful functionality of %GeographicLib is -available via simple command line utilities. Interfaces to some of them -are available via the web. See \ref utilities for documentation on -these. - -In order to use %GeographicLib from C++ code, you will need to -- Include the header files for the %GeographicLib classes in your code. - E.g., \code - #include \endcode -- Include the GeographicLib:: namespace prefix to the %GeographicLib classes, - or include \code - using namespace GeographicLib; \endcode - in your code. -- Finally compile and link your code. You have two options here. - - Use cmake to build your package. If you are familiar with cmake - this typically will be far the simplest option. - - Set the include paths and linking options "manually". -- Building your code with cmake. In brief, the necessary steps are: - - include in your CMakeLists.txt files \verbatim - find_package (GeographicLib 1.34 REQUIRED) - include_directories (${GeographicLib_INCLUDE_DIRS}) - add_definitions (${GeographicLib_DEFINITIONS}) - add_executable (program source1.cpp source2.cpp) - target_link_libraries (program ${GeographicLib_LIBRARIES}) \endverbatim - (The add_definitions line is only needed for Windows - and can be omitted if you're using cmake version 2.8.11 or later.) - - configure your package, e.g., with \verbatim - mkdir BUILD - cd BUILD - cmake -G "Visual Studio 10" \ - -D CMAKE_PREFIX_PATH=C:/pkg-vc10 \ - -D CMAKE_PREFIX_PATH=C:/pkg-vc10/testgeographic \ - .. \endverbatim - Note that you almost always want to configure and build your code - somewhere other than the source directory (in this case, we use the - BUILD subdirectory). - - build your package. On Linux and MacOS this usually involves just - running make. On Windows, you can load the solution file created by - cmake into Visual Studio; alternatively, you can get cmake to run - build your code with \verbatim - cmake --build . --config Release --target ALL_BUILD \endverbatim - You might also want to install your package (using "make install" or - build the "INSTALL" target with the command above). - . - The most import step is the find_package command. The cmake - documentation describes the locations searched by find_package (the - appropriate rule for %GeographicLib are those for "Config" mode lookups). - In brief, the locations that are searched are (from least specific to - most specific, i.e., in reverse order) are - - under the system paths, i.e., locations such as C:/Program - Files and /usr/local); - - frequently, it's necessary to search within a "package directory" - (or set of directories) for external dependencies; this is given by - a (semicolon separated) list of directories specified by the cmake - variable CMAKE_PREFIX_PATH (illustrated above); - - the package directory for %GeographicLib can be overridden with the - environment variable GeographicLib_DIR (which is the - directory under which %GeographicLib is installed); - - finally, if you need to point to a particular build of %GeographicLib, - define the cmake variable GeographicLib_DIR, which - specifies the directory containing the configuration file - geographiclib-config.cmake (for debugging this be the - top-level build directory, as opposed to installation - directory, for %GeographicLib). - . - Typically, specifying nothing or CMAKE_PREFIX_PATH - suffices. However the two GeographicLib_DIR variables allow - for a specific version to be chosen. On Windows systems (with Visual - Studio), find_package will only find versions of %GeographicLib built with - the right version of the compiler. (If you used a non-cmake method of - installing %GeographicLib, you can try copying cmake/FindGeographicLib.cmake - to somewhere in your CMAKE_MODULE_PATH in order for - find_package to work. However, this method has not been thoroughly - tested.) - - If %GeographicLib is found, then the following cmake variables are set: - - GeographicLib_FOUND = 1 - - GeographicLib_VERSION = 1.35 - - GeographicLib_INCLUDE_DIRS - - GeographicLib_LIBRARIES = one of the following two: - - GeographicLib_SHARED_LIBRARIES = %GeographicLib - - GeographicLib_STATIC_LIBRARIES = GeographicLib_STATIC - - GeographicLib_DEFINITIONS = one of the following two: - - GeographicLib_SHARED_DEFINITIONS = -DGEOGRAPHICLIB_SHARED_LIB=1 - - GeographicLib_STATIC_DEFINITIONS = -DGEOGRAPHICLIB_SHARED_LIB=0 - - GeographicLib_LIBRARY_DIRS - - GeographicLib_BINARY_DIRS - . - Either of GeographicLib_SHARED_LIBRARIES or - GeographicLib_STATIC_LIBRARIES may be empty, if that version - of the library is unavailable. If you require a specific version, - SHARED or STATIC, of the library, add a COMPONENTS clause - to find_package, e.g., - \verbatim - find_package (GeographicLib 1.34 REQUIRED COMPONENTS SHARED) \endverbatim - causes only packages which include the shared library to be found. If - the package includes both versions of the library, then - GeographicLib_LIBRARIES and - GeographicLib_DEFINITIONS are set to the shared versions, - unless you include \verbatim - set (GeographicLib_USE_STATIC_LIBS ON) \endverbatim - before the find_package command. You can check whether - GeographicLib_LIBRARIES refers to the shared or static - library with \verbatim - get_target_property(_LIBTYPE ${GeographicLib_LIBRARIES} TYPE) \endverbatim - which results in _LIBTYPE being set to - SHARED_LIBRARY or STATIC_LIBRARY. - On Windows, cmake takes care of linking to the release or debug - version of the library as appropriate. (This assumes that the Release - and Debug versions of the libraries were built and installed. This is - true for the Windows binary installer for %GeographicLib version 1.34 and - later.) -- Here are the steps to compile and link your code using %GeographicLib - "manually". - - Tell the compiler where to find the header files. With g++ and with - /usr/local specified as the installation directory, - this is accomplished with \verbatim - g++ -c -g -O3 -funroll-loops -I/usr/local/include testprogram.cpp - \endverbatim - With Visual Studio, specify the include directory in the IDE via, - e.g., - \verbatim - C/C++ -> General -> Additional Include Directories = C:\pkg-vc10\GeographicLib\include - \endverbatim - - If using the shared (or static) library with Visual Studio, define - the macro GEOGRAPHICLIB_SHARED_LIB=1 (or - 0), e.g., - \verbatim - C/C++ -> Preprocessor -> Preprocessor Definitions = GEOGRAPHICLIB_SHARED_LIB=1 - \endverbatim - This is only needed for Windows systems when both shared and static - libraries have been installed. (If you configure your package with - cmake, this definition is added automatically.) - - Tell the linker the name, Geographic, and location of the - library. Using g++ as the linker, you would use \verbatim - g++ -g -o testprogram testprogram.o -L/usr/local/lib -lGeographic - \endverbatim - With Visual Studio, you supply this information in the IDE via, - e.g., \verbatim - Linker -> Input -> Additional Dependencies = Geographic-i.lib (for shared library) - Linker -> Input -> Additional Dependencies = Geographic.lib (for static library) - Linker -> General -> Additional Library Directories = C:\pkg-vc10\Geographic\lib - \endverbatim - Note that the library name is Geographic and not - %GeographicLib. For the Debug version of your program on Windows - add "_d" to the library, e.g., Geographic_d-i.lib or - Geographic_d.lib. - - Tell the runtime environment where to find the shared library - (assuming you compiled %Geographic as a shared library). With g++, - this is accomplished by modifying the link line above to read \verbatim - g++ -g -o testprogram testprogram.o -Wl,-rpath=/usr/local/lib \ - -L/usr/local/lib -lGeographic - \endverbatim - (There are two other ways to specify the location of shared libraries - at runtime: (1) define the environment variable - LD_LIBRARY_PATH to be a colon-separated list of - directories to search; (2) as root, specify /usr/local/lib as a - directory searched by ldconfig(8).) On Windows, you need to ensure - that Geographic.dll or Geographic_d.dll is in the same directory as - your executable or else include the directory containing the dll in - your PATH. - -Here is a very simple test code, which uses the GeographicLib::Geodesic -class: -\include example-Geodesic-small.cpp -This example is examples/example-Geodesic-small.cpp. If you -compile, link, and run it according to the instructions above, it should -print out \verbatim - 5551.76 km \endverbatim -Here is a complete CMakeList.txt files you can use to build this test -code using the installed library: \verbatim -project (geodesictest) -cmake_minimum_required (VERSION 2.8.4) - -find_package (GeographicLib 1.34 REQUIRED) - -if (NOT MSVC) - set (CMAKE_INSTALL_RPATH_USE_LINK_PATH TRUE) -endif () - -include_directories (${GeographicLib_INCLUDE_DIRS}) -add_definitions (${GeographicLib_DEFINITIONS}) -add_executable (${PROJECT_NAME} example-Geodesic-small.cpp) -target_link_libraries (${PROJECT_NAME} ${GeographicLib_LIBRARIES}) - -if (MSVC) - get_target_property (_LIBTYPE ${GeographicLib_LIBRARIES} TYPE) - if (_LIBTYPE STREQUAL "SHARED_LIBRARY") - # On Windows systems, copy the shared library to build directory - add_custom_command (TARGET ${PROJECT_NAME} POST_BUILD - COMMAND ${CMAKE_COMMAND} -E - copy $ ${CMAKE_CFG_INTDIR} - COMMENT "Copying shared library for GeographicLib") - endif () -endif () \endverbatim - -The next steps are: - - Learn about and run the \ref utilities. - - Read the section, \ref organization, for an overview of the library. - - Browse the Class List for full documentation - on the classes in the library. - - Look at the example code in the examples directory. Each file - provides a very simple standalone example of using one %GeographicLib - class. These are included in the descriptions of the classes. - - Look at the source code for the utilities in the tools directory for - more examples of using %GeographicLib from C++ code, e.g., - GeodesicProj.cpp is a program to performing various geodesic - projections. - -Here's a list of some of the abbreviations used here with links to the -corresponding Wikipedia articles: - - - WGS84, World Geodetic System 1984. - - - UTM, Universal Transverse Mercator coordinate system. - - - UPS, Universal Polar Stereographic coordinate system. - - - MGRS, Military Grid Reference System. - - - EGM, Earth Gravity Model. - - - WMM, World Magnetic Model. - - - IGRF, International Geomagnetic Reference Field. - -
-Back to \ref install. Forward to \ref utilities. Up to \ref contents. -
-**********************************************************************/ -/** -\page utilities Utility programs - -
-Back to \ref start. Forward to \ref organization. Up to \ref contents. -
- -Various utility programs are provided with %GeographicLib. These should -be installed in a directory included in your PATH (e.g., -/usr/local/bin). These programs are wrapper programs that invoke -the underlying functionality provided by the library. - -The utilities are - - - GeoConvert: convert geographic coordinates using - GeographicLib::GeoCoords. - - - GeodSolve: perform geodesic calculations using - GeographicLib::Geodesic and GeographicLib::GeodesicLine. - - - Planimeter: compute the area of geodesic polygons using - GeographicLib::PolygonArea. - - - TransverseMercatorProj: convert between geographic - and transverse Mercator. This is for testing - GeographicLib::TransverseMercatorExact and - GeographicLib::TransverseMercator. - - - CartConvert: convert geodetic coordinates to geocentric or - local cartesian using GeographicLib::Geocentric and - GeographicLib::LocalCartesian. - - - GeodesicProj: perform projections based on geodesics - using GeographicLib::AzimuthalEquidistant, GeographicLib::Gnomonic, - and GeographicLib::CassiniSoldner. - - - ConicProj: perform conic projections using - GeographicLib::LambertConformalConic and - GeographicLib::AlbersEqualArea. - - - GeoidEval: look up geoid heights using - GeographicLib::Geoid. - - - Gravity: compute the earth's gravitational field using - GeographicLib::GravityModel and GeographicLib::GravityCircle. - - - MagneticField: compute the earth's magnetic field using - GeographicLib::MagneticModel and GeographicLib::MagneticCircle. - . -The documentation for these utilities is in the form of man pages. This -documentation can be accessed by clicking on the utility name in the -list above, running the man command on Unix-like systems, or by invoking -the utility with the --help option. A brief summary of usage is given -by invoking the utility with the -h option. The version of the utility -is given by the --version option. - -The utilities all accept data on standard input, transform it in some -way, and print the results on standard output. This makes the utilities -easy to use within scripts to transform tabular data; however they can -also be used interactively, often with the input supplied via a pipe, -e.g., - - echo 38SMB4488 | GeoConvert -d - -Online versions of four of these utilities are provided: - - GeoConvert - - GeodSolve - - Planimeter - - GeoidEval - -
-Back to \ref start. Forward to \ref organization. Up to \ref contents. -
-**********************************************************************/ -/** -\page organization Code organization - -
-Back to \ref utilities. Forward to \ref other. Up to \ref contents. -
- -Here is a brief description of the relationship between the various -components of %GeographicLib. All of these are defined in the -GeographicLib namespace. - -GeographicLib::TransverseMercator, GeographicLib::PolarStereographic, -GeographicLib::LambertConformalConic, and GeographicLib::AlbersEqualArea -provide the basic projections. The constructors for these classes -specify the ellipsoid and the forward and reverse projections are -implemented as const member functions. TransverseMercator uses -Krüger's series which have been extended to sixth order in the -square of the eccentricity. PolarStereographic, LambertConformalConic, -and AlbersEqualArea use the exact formulas for the projections (e.g., -from Snyder). - -GeographicLib::TransverseMercator::UTM and -GeographicLib::PolarStereographic::UPS are const static instantiations -specific for the WGS84 ellipsoid with the UTM and UPS scale factors. -(These do \e not add the standard false eastings or false northings for -UTM and UPS.) Similarly GeographicLib::LambertConformalConic::Mercator -is a const static instantiation of this projection for a WGS84 ellipsoid -and a standard parallel of 0 (which gives the Mercator projection). -GeographicLib::AlbersEqualArea::CylindricalEqualArea, -AzimuthalEqualAreaNorth, and AzimuthalEqualAreaSouth, likewise provide -special cases of the equal area projection. - -GeographicLib::UTMUPS uses TransverseMercator::UTM and -PolarStereographic::UPS to perform the UTM and UPS -projections. The class offers a uniform interface to UTM and UPS by -treating UPS as UTM zone 0. This class stores no internal state and the -forward and reverse projections are provided via static member -functions. The forward projection offers the ability to override the -standard UTM/UPS choice and the UTM zone. - -GeographicLib::MGRS transforms between UTM/UPS coordinates and MGRS. -UPS coordinates are handled as UTM zone 0. This class stores no -internal state and the forward (UTM/UPS to MGRS) and reverse (MGRS to -UTM/UPS) conversions are provided via static member functions. - -GeographicLib::GeoCoords holds a single geographic location which may be -specified as latitude and longitude, UTM or UPS, or MGRS. Member -functions are provided to convert between coordinate systems and to -provide formatted representations of them. -GeoConvert is a simple command line -utility to provide access to the GeoCoords class. - -GeographicLib::TransverseMercatorExact is a drop in replacement for -TransverseMercator which uses the exact formulas, based on elliptic -functions, for the projection as given by Lee. -TransverseMercatorProj is a -simple command line utility to test to the TransverseMercator and -TransverseMercatorExact. - -GeographicLib::Geodesic and GeographicLib::GeodesicLine perform geodesic -calculations. The constructor for GeographicLib::Geodesic specifies the -ellipsoid and the direct and inverse calculations are implemented as -const member functions. GeographicLib::Geocentric::WGS84 is a const -static instantiation of Geodesic specific for the WGS84 ellipsoid. In -order to perform a series of direct geodesic calculations on a single -line, the GeographicLib::GeodesicLine class can be used. This packages -all the information needed to specify a geodesic. A const member -function returns the coordinates a specified distance from the starting -point. GeodSolve is a simple command -line utility to perform geodesic calculations. -GeographicLib::PolygonArea is a class which compute the area of geodesic -polygons using the Geodesic class and Planimeter is a command line utility for -the same purpose. GeographicLib::AzimuthalEquidistant, -GeographicLib::CassiniSoldner, and GeographicLib::Gnomonic are -projections based on the Geodesic class. GeodesicProj is a command line utility to -exercise these projections. - -GeographicLib::GeodesicExact and GeographicLib::GeodesicLineExact are -drop in replacements for GeographicLib::Geodesic and -GeographicLib::GeodesicLine in which the solution is given in terms of -elliptic integrals (computed by GeographicLib::EllipticFunction). -These classes should be used if the absolute value of the flattening -exceeds 0.02. The -E option to GeodSolve -uses these classes. - -GeographicLib::Geocentric and GeographicLib::LocalCartesian convert between -geodetic and geocentric or a local cartesian system. The constructor for -specifies the ellipsoid and the forward and reverse projections are -implemented as const member functions. GeographicLib::Geocentric::WGS84 is a -const static instantiation of Geocentric specific for the WGS84 ellipsoid. -CartConvert is a simple command line -utility to provide access to these classes. - -GeographicLib::Geoid evaluates geoid heights by interpolation. This is -provided by the operator() member function. -GeoidEval is a simple command line -utility to provide access to this class. This class requires -installation of data files for the various geoid models; see \ref -geoidinst for details. - -GeographicLib::Ellipsoid is a class which performs latitude -conversions and returns various properties of the ellipsoid. - -GeographicLib::GravityModel evaluates the earth's gravitational field -using a particular gravity model. Various member functions return the -gravitational field, the gravity disturbance, the gravity anomaly, and -the geoid height Gravity is a simple -command line utility to provide access to this class. If the field -several points on a circle of latitude are sought then use -GeographicLib::GravityModel::Circle to return a -GeographicLib::GravityCircle object whose member functions performs the -calculations efficiently. (This is particularly important for high -degree models such as EGM2008.) These classes requires installation of -data files for the various gravity models; see \ref gravityinst for -details. - -GeographicLib::MagneticModel evaluates the earth's magnetic field using -a particular magnetic model. The field is provided by the operator() -member function. MagneticField is a -simple command line utility to provide access to this class. If the -field several points on a circle of latitude are sought then use -GeographicLib::MagneticModel::Circle to return a -GeographicLib::MagneticCircle object whose operator() member function -performs the calculation efficiently. (This is particularly important -for high degree models such as emm2010.) These classes requires -installation of data files for the various magnetic models; see \ref -magneticinst for details. - -GeographicLib::Constants, GeographicLib::Math, GeographicLib::Utility, -GeographicLib::DMS, are general utility class which are used -internally by the library; in addition GeographicLib::EllipticFunction -is used by GeographicLib::TransverseMercatorExact, -GeographicLib::Ellipsoid, and GeographicLib::GeodesicExact, and -GeographicLib::GeodesicLineExact; GeographicLib::Accumulator is used -by GeographicLib::PolygonArea, and GeographicLib::SphericalEngine, -GeographicLib::CircularEngine, GeographicLib::SphericalHarmonic, -GeographicLib::SphericalHarmonic1, and -GeographicLib::SphericalHarmonic2 facilitate the summation of -spherical harmonic series which is needed by and -GeographicLib::MagneticModel and GeographicLib::MagneticCircle. One -important definition is GeographicLib::Math::real which is the type -used for real numbers. This allows the library to be easily switched -to using floats, doubles, or long doubles. However all the testing -has been with real set to double and the library should be installed -in this way. - -In general, the constructors for the classes in %GeographicLib check -their arguments and throw GeographicLib::GeographicErr exceptions with a -explanatory message if these are illegal. The member functions, e.g., -the projections implemented by TransverseMercator and -PolarStereographic, the solutions to the geodesic problem, etc., -typically do not check their arguments; the calling program -should ensure that the arguments are legitimate. However, the functions -implemented by UTMUPS, MGRS, and GeoCoords do check their arguments and -may throw GeographicLib::GeographicErr exceptions. Similarly Geoid may -throw exceptions on file errors. If a function does throw an exception, -then the function arguments used for return values will not have been -altered. - -%GeographicLib attempts to act sensibly with NaNs. NaNs in constructors -typically throw errors (an exception is GeodesicLine). However, calling -the class functions with NaNs as arguments is not an error; NaNs are -returned as appropriate. "INV" is treated as an invalid zone -designation by UTMUPS. "INVALID" is the corresponding invalid MGRS -string. (Similary "nan" is the equivalent invalid Geohash.) NaNs allow -the projection of polylines which are separated by NaNs; in this format -they can be easily plotted in Matlab. - -A note about portability. For the most part, the code uses standard C++ -and should be able to be deployed on any system with a modern C++ -compiler. System dependencies come into - - GeographicLib::Math -- GeographicLib needs to define functions such - as atanh for systems that lack them. The system dependence will - disappear with the adoption of C++11 because the needed functions are - part of that standard. - - use of long double -- the type is used only for testing. On systems - which lack this data type the cmake and autoconf configuration - methods should detect its absence and omit the code that depends on - it. - - GeographicLib::Geoid, GeographicLib::GravityModel, and - GeographicLib::MagneticModel -- these class uses system-dependent - default paths for looking up the respective datasets. It also relies - on getenv to find the value of the environment variables. - - GeographicLib::Utility::readarray reads numerical data from binary - files. This assumes that floating point numbers are in IEEE format. - It attempts to handled the "endianness" of the target platform using - the WORDS_BIGENDIAN macro (which sets the compile-time constant - GeographicLib::Math::bigendian). - -An attempt is made to maintain backward compatibility with -%GeographicLib (especially at the level of your source code). Sometimes -it's necessary to take actions that depend on what version of -%GeographicLib is being used; for example, you may want to use a new -feature of %GeographicLib, but want your code still to work with older -versions. In that case, you can test the values of the macros -GEOGRAPHICLIB_VERSION_MAJOR, GEOGRAPHICLIB_VERSION_MINOR, and -GEOGRAPHICLIB_VERSION_PATCH; these expand to numbers (and the last one -is usually 0); these macros appeared starting in version 1.31. There's -also a macro GEOGRAPHICLIB_VERSION_STRING which expands to, e.g., -"1.35"; this macro has been defined since version 1.9. - -
-Back to \ref utilities. Forward to \ref other. Up to \ref contents. -
-**********************************************************************/ -/** -\page other Implementations in other languages - -
-Back to \ref organization. Forward to \ref geoid. Up to \ref contents. -
- -Implementations of subsets of %GeographicLib are available in other languages -- \ref c-fortran -- \ref java. -- \ref javascript. -- \ref python. -- \ref matlab. -- \ref maxima. -- \ref dotnet. - -\section c-fortran C and Fortran implementation - -The directories legacy/C and legacy/Fortran -contain implementations of GeographicLib::Geodesic, -GeographicLib::GeodesicLine, and GeographicLib::PolygonArea in C and -Fortran respectively. These are intended for use in old codes written -in these languages and should work any reasonably modern compiler. -These implementations are entirely self-contained and do not depend on -the rest of %GeographicLib. Sample main programs to solve the direct -and inverse geodesic problems and to compute polygonal areas are -provided. - -For documentation, see - - C library for geodesics, - - Fortran library for geodesics. - -\section java Java implementation - -The directory java contains implementations of -GeographicLib::Geodesic, GeographicLib::GeodesicLine, and -GeographicLib::PolygonArea in Java. This implementation is entirely -self-contained and does not depend on the rest of %GeographicLib. -Sample main programs to solve the direct and inverse geodesic problems -and to compute polygonal areas are provided. - -For documentation, see - - Java library for geodesics. - -\section javascript JavaScript implementation - -The directory doc/scripts/GeographicLib contains the classes -- GeographicLib::Math -- GeographicLib::Accumulator -- GeographicLib::Geodesic -- GeographicLib::GeodesicLine -- GeographicLib::PolygonArea -- GeographicLib::DMS -. -translated into JavaScript. See Interface.js for a simple JavaScript -interface to these routines (documented near the top of the file). -Examples of using this interface are -- a geodesic calculator showing - the solution of direct and inverse geodesic problem, finding - intermediate points on a geodesic line, and computing the area of a - geodesic polygon. -- displaying geodesics in Google - Maps which shows the geodesic, the geodesic circle, and various - geodesic envelopes. -. -These examples include a "stripped" version of the JavaScript code, \code - \endcode -which loads faster. - -\section python Python implementation - -A python implementation of the geodesic routines from GeographicLib -are provided in the python/geographiclib directory (which is installed -as PREFIX/lib/python/site-packages/geographiclib, if -COMMON_INSTALL_PATH is ON, and as PREFIX/python/geographiclib, -otherwise). This contains implementations of the classes -- GeographicLib::Math -- GeographicLib::Accumulator -- GeographicLib::Geodesic -- GeographicLib::GeodesicLine -- GeographicLib::PolygonArea -. -You can also download the python interface independent of the rest of -%GeographicLib from -- - http://pypi.python.org/pypi/geographiclib -. -and then unpack the .tar.gz or .zip file. - -You can "install" these routines, so that they are in python's default -path with, for example \verbatim - cd geographiclib-1.16 - python setup.py install -\endverbatim -(this will require root privileges). Or else you can set the path -within python using \code ->>> import sys ->>> sys.path.append("/usr/local/lib/python/site-packages") -\endcode - -An example of using this interface is \code ->>> from geographiclib.geodesic import Geodesic ->>> # The geodesic inverse problem -... Geodesic.WGS84.Inverse(-41.32, 174.81, 40.96, -5.50) ->>> # The geodesic direct problem -... Geodesic.WGS84.Direct(40.6, -73.8, 45, 10000e3) ->>> # How to obtain several points along a geodesic -... line = Geodesic.WGS84.Line(40.6, -73.8, 45) ->>> line.Position( 5000e3) ->>> line.Position(10000e3) ->>> # Computing the area of a geodesic polygon -... def p(lat,lon): return {'lat': lat, 'lon': lon} -... ->>> Geodesic.WGS84.Area([p(0, 0), p(0, 90), p(90, 0)]) ->>> # Introductory help -... help(Geodesic) -\endcode - -Another illustrative exercise is finding the point midway between JFK -Airport to Singapore Changi Airport -\code -from geographiclib.geodesic import Geodesic - -# Coordinates of airports -lat1, lon1 = 40.640, -73.779 # JFK -lat2, lon2 = 1.359, 103.989 # SIN - -# Compute path from 1 to 2 -g = Geodesic.WGS84.Inverse(lat1, lon1, lat2, lon2) - -# Compute midpoint starting at 1 -h = Geodesic.WGS84.Direct(lat1, lon1, g['azi1'], g['s12']/2) -print(h['lat2'], h['lon2']); -\endcode - -(Note: The initial version of setup.py was provided by Andrew MacIntyre -of the Australian Communications and Media Authority.) - -\section matlab Matlab and Octave implementations - -The matlab directory contains - - Native Matlab implementations of the geodesic routines. To use - these, start Matlab or Octave and run one of (for example) \verbatim - addpath /usr/local/libexec/GeographicLib/matlab - addpath 'C:/pkg-vc10-x64/GeographicLib-1.35/libexec/GeographicLib/matlab' - \endverbatim - The available functions are: - - geoddoc: briefly descibe the routines - - geodreckon: solve the direct geodesic problem - - geoddistance: solve the inverse geodesic problem - - geodarea: compute the area of ellipsoidal polygons - . - Use the help function to get documentation, e.g., \code - help geoddistance \endcode - to obtain documentation. These functions are also available as a - standalone package from - - Matlab File Exchange using the link - - - http://www.mathworks.com/matlabcentral/fileexchange/39108 - - Native Matlab implementations of projections which are related to - geodesics. These are - - geodproj: briefly descibe the routines - - eqdazim_fwd, eqdazim_inv: azimuthal equidistant - - cassini_fwd, cassini_inv: Cassini-Soldner - - tranmerc_fwd, tranmerc_inv: transverse Mercator - - gnomonic_fwd, gnomonic_inv: ellipsoidal gnomonic - - utm_fwd, utm_inv: universal transverse Mercator - . - These functions are also available as a package from - - Matlab File Exchange using the link - - - http://www.mathworks.com/matlabcentral/fileexchange/39366 - . - (This requires that the previous package also be installed.) - - Interface code so that some %GeographicLib classes can be accessed - from Matlab or Octave. The rest of this section describes how to - compile and use these interfaces. - -There are two ways of compiling the interface code: (1) using cmake and -(2) invoking the compiler from Matlab. - - Using cmake: Before running cmake, configure MATLAB on - Windows to use the same compiler that you're going to use for compiling - %GeographicLib. For example \verbatim - mex.bat -setup - - Please choose your compiler for building MEX-files: - Would you like mex to locate installed compilers [y]/n? y - Select a compiler: - [1] Microsoft Visual C++ 2012 in C:\Program Files (x86)\Microsoft Visual Studio 11.0 - [2] Microsoft Visual C++ 2010 in C:\Program Files (x86)\Microsoft Visual Studio 10.0 - - [0] None - - Compiler: 2 - etc. \endverbatim - (This will require that mex.bat is in your PATH. With Linux, use - mex -setup.) Then configure cmake with, for example - \verbatim - cmake -G "Visual Studio 10" -D MATLAB_COMPILER=mex .. - cmake --build . --config Release --target matlabinterface \endverbatim - (Note that only the Release configuration is supported for Matlab.) - If you are running a 64-bit version of Matlab, be sure to select a - 64-bit generator with cmake, e.g., "Visual Studio 10 Win64". Finally - compile %GeographicLib with Visual Studio. (The binary installer for - 64-bit Windows includes the compiled interface built with Visual - Studio 10 and Matlab R2013a 64-bit).
- On Linux systems, you can compile the interface for use with octave - instead by using \verbatim - cmake -D MATLAB_COMPILER=mkoctfile .. - make matlabinterface \endverbatim - - Invoking the compiler from Matlab or Octave: Start Matlab or - Octave and run, e.g., \code - mex -setup - cd 'C:/pkg-vc10-x64/GeographicLib-1.35/matlab' - help geographiclibinterface - geographiclibinterface('C:/pkg-vc10/GeographicLib-1.35'); - addpath(pwd); - \endcode - The first command allows you to select the compiler to use (which - should be the same as that used to compile %GeographicLib). - -To use the interface routines for %GeographicLib, run one of (for -example) \verbatim - addpath /usr/local/libexec/GeographicLib/matlab - addpath 'C:/pkg-vc10-x64/GeographicLib-1.35/libexec/GeographicLib/matlab' -\endverbatim -in Octave or Matlab. The available functions are: - - geodesicdirect: solve direct geodesic problem - (see GeographicLib::Geodesic::Direct) - - geodesicinverse: solve inverse geodesic problem - (see GeographicLib::Geodesic::Inverse) - - geodesicline: compute points along a geodesic - (see GeographicLib::GeodesicLine::Position) - - polygonarea: compute area of a geodesic polygon - (see GeographicLib::PolygonArea) - - utmupsforward: convert geographic coordinates to UTM/UPS - (see GeographicLib::UTMUPS::Forward) - - utmupsreverse: convert UTM/UPS coordinates to geographic - (see GeographicLib::UTMUPS::Reverse) - - mgrsforward: convert UTM/UPS coordinates to MGRS - (see GeographicLib::MGRS::Forward) - - mgrsreverse: convert MGRS coordinates to UTM/UPS - (see GeographicLib::MGRS::Reverse) - - geoidheight: compute geoid height - (see GeographicLib::Geoid::operator()()) - - geocentricforward: convert geographic coordinates to geocentric - (see GeographicLib::Geocentric::Forward) - - geocentricreverse: convert geocentric coordinates to geographic - (see GeographicLib::Geocentric::Reverse) - - localcartesianforward: convert geographic coordinates to local cartesian - (see GeographicLib::LocalCartesian::Forward) - - localcartesianreverse: convert local cartesian coordinates to geographic - (see GeographicLib::LocalCartesian::Reverse) - . -These routines just offer a simple interface to the corresponding C++ -class. Use the help function to get documentation, e.g., \code - help geodesicdirect \endcode -Unfortunately, the help function does not work for compiled functions in -Octave; in this case, just list the .m file, e.g., \code - type geodesicdirect \endcode -Other useful functions, e.g., to convert from geographic -coordinates to MGRS can easily be written with Matlab code. - -Note that geoidheight, when compiled with Visual Studio 2008 causes -Matlab to crash. (The problem does not occur with Visual Studio 2005 or -Visual Studio 2010.) - -\section maxima Maxima routines - -Maxima is a free computer algebra system which can be downloaded from -http://maxima.sf.net. Maxima was used to generate the series used by -GeographicLib::TransverseMercator ( -tmseries.mac) and GeographicLib::Geodesic ( -geod.mac) and to generate accurate data for testing -( tm.mac and -geodesic.mac). The latter uses Maxima's bigfloat arithmetic -together with series extended to high order or solutions in terms of -elliptic integrals ( ellint.mac). These files -contain brief instructions on how to use them. - -\section dotnet .NET wrapper - -This is a comprehensive wrapper library, written and maintained by Scott -Heiman, which exposes all of the functionality of %GeographicLib to the -.NET family of languages. For documentation, see - - NETGeographicLib .NET wrapper library. - -
-Back to \ref organization. Forward to \ref geoid. Up to \ref contents. -
-**********************************************************************/ -/** -\page geoid Geoid height - -
-Back to \ref other. Forward to \ref gravity. Up to \ref contents. -
- -The gravitational equipotential surface approximately coinciding with -mean sea level is called the geoid. The GeographicLib::Geoid class and -the GeoidEval utility evaluate the height -of the geoid above the WGS84 ellipsoid. This can be used to convert -heights above mean sea level to heights above the WGS84 ellipsoid. -Because the normal to the ellipsoid differs from the normal to the geoid -(the direction of a plumb line) there is a slight ambiguity in the -measurement of heights; however for heights up to 10 km this ambiguity -is only 1 mm. - -The geoid is usually approximated by an "earth gravity model" (EGM). -The models published by the NGA are: -- EGM84: - http://earth-info.nga.mil/GandG/wgs84/gravitymod/wgs84_180/wgs84_180.html -- EGM96: - http://earth-info.nga.mil/GandG/wgs84/gravitymod/egm96/egm96.html -- EGM2008: - http://earth-info.nga.mil/GandG/wgs84/gravitymod/egm2008 -. -GeographicLib::Geoid offers a uniform way to handle all 3 geoids at a -variety of grid resolutions. (In contrast, the software tools that NGA -offers are different for each geoid, and the interpolation programs are -different for each grid resolution. In addition these tools are written -in Fortran with is nowadays difficult to integrate with other software.) - -Unlike other components of %GeographicLib, there is a appreciable error -in the results obtained (at best, the RMS error is 1 mm). However the -class provides methods to report the maximum and RMS errors in the -results. The class also returns the gradient of the geoid. This can be -used to estimate the direction of a plumb line relative to the WGS84 -ellipsoid. - -The GeographicLib::GravityModel class calculates geoid heights using the -underlying gravity model. This is slower then GeographicLib::Geoid but -considerably more accurate. This class also can accurately compute all -the components of the acceleration due to gravity (and hence the -direction of plumb line). - -Go to - - \ref geoidinst - - \ref geoidformat - - \ref geoidinterp - - \ref geoidcache - - \ref testgeoid - -\section geoidinst Installing the geoid datasets - -The geoid heights are computed using interpolation into a rectangular -grid. The grids are read from data files which have been are computed -using the NGA synthesis programs in the case of the EGM84 and EGM96 -models and using the NGA binary gridded data files in the case of -EGM2008. These data files are available for download: -
- - - - - - - - - - - - - - - -
Available geoid data files
name geoid grid - size\n(MB) -
Download Links (size, MB)
tar fileWindows\n installerzip file
egm84-30 - EGM84 -
30'
-
0.6
-
- - link (0.5)
-
- - link (0.8)
-
- - link (0.5)
-
egm84-15 - EGM84 -
15'
-
2.1
-
- - link (1.5)
-
- - link (1.9)
-
- - link (2.0)
-
egm96-15 - EGM96 -
15'
-
2.1
-
- - link (1.5)
-
- - link (1.9)
-
- - link (2.0)
-
egm96-5 - EGM96 -
5'
-
19
-
- - link (11)
-
- - link (11)
-
- - link (17)
-
egm2008-5 - EGM2008 -
5'
-
19
-
- - link (11)
-
- - link (11)
-
- - link (17)
-
egm2008-2_5 - EGM2008 -
2.5'
-
75
-
- - link (35)
-
- - link (33)
-
- - link (65)
-
egm2008-1 - EGM2008 -
1'
-
470
-
- - link (170)
-
- - link (130)
-
- - link (390)
-
-
-The "size" column is the size of the uncompressed data and it also -gives the memory requirements for caching the entire dataset using the -GeographicLib::Geoid::CacheAll method. -At a minimum you should install egm96-5 and either egm2008-1 or -egm2008-2_5. Many applications use the EGM96 geoid, however the use of -EGM2008 is growing. (EGM84 is rarely used now.) - -For Linux and Unix systems, %GeographicLib provides a shell script -geographiclib-get-geoids (typically installed in /usr/local/sbin) which -automates the process of downloading and installing the geoid data. For -example -\verbatim - geographiclib-get-geoids best # to install egm84-15, egm96-5, egm2008-1 - geographiclib-get-geoids -h # for help -\endverbatim -This script should be run as a user with write access to the -installation directory, which is typically -/usr/local/share/GeographicLib (this can be overridden with the -p -flag), and the data will then be placed in the "geoids" subdirectory. - -Windows users should download and run the Windows installers. These -will prompt for an installation directory with the default being one of -\verbatim - C:/Documents and Settings/All Users/Application Data/GeographicLib - C:/ProgramData/GeographicLib -\endverbatim -(which you probably should not change) and the data is installed in the -"geoids" sub-directory. (The second directory name is an alternate name -that Windows 7 uses for the "Application Data" directory.) - -Otherwise download \e either the tar.bz2 file \e or the zip file (they -have the same contents). If possible use the tar.bz2 files, since these -are compressed about 2 times better than the zip file. To unpack these, -run, for example -\verbatim - mkdir -p /usr/local/share/GeographicLib - tar xofjC egm96-5.tar.bz2 /usr/local/share/GeographicLib - tar xofjC egm2008-2_5.tar.bz2 /usr/local/share/GeographicLib - etc. -\endverbatim -and, again, the data will be placed in the "geoids" subdirectory. - -However you install the geoid data, all the datasets should -be installed in the same directory. GeographicLib::Geoid and -GeoidEval uses a compile time default to -locate the datasets. This is -- /usr/local/share/GeographicLib/geoids, for non-Windows systems -- C:/Documents and Settings/All Users/Application Data/GeographicLib/geoids, - for Windows systems -. -consistent with the examples above. This may be overridden at run-time -by defining the GEOID_PATH or the GEOGRAPHICLIB_DATA environment variables; -see GeographicLib::Geoid::DefaultGeoidPath() for details. Finally, the -path may be set using the optional second argument to the -GeographicLib::Geoid constructor or with the "-d" flag to -GeoidEval. Supplying the "-h" flag to -GeoidEval reports the default geoid path -for that utility. The "-v" flag causes GeoidEval to report the full -path name of the data file it uses. - -\section geoidformat The format of the geoid data files - -The gridded data used by the GeographicLib::Geoid class is stored in -16-bit PGM files. Thus the data for egm96-5 might be stored in the file -- /usr/local/share/GeographicLib/geoids/egm96-5.pgm -. -PGM simple graphic format with the following properties -- it is well documented - here; -- there are no separate "little-endian" and "big-endian" versions; -- it uses 1 or 2 bytes per pixel; -- pixels can be randomly accessed; -- comments can be added to the file header; -- it is sufficiently simple that it can be easily read without using the - libnetpbm - library (and thus we avoid adding a software dependency to - %GeographicLib). -. -The major drawback of this format is that since there are only 65535 -possible pixel values, the height must be quantized to 3 mm. However, -the resulting quantization error (up to 1.5 mm) is typically smaller -than the linear interpolation errors. The comments in the header for -egm96-5 are -\verbatim - # Geoid file in PGM format for the GeographicLib::Geoid class - # Description WGS84 EGM96, 5-minute grid - # URL http://earth-info.nga.mil/GandG/wgs84/gravitymod/egm96/egm96.html - # DateTime 2009-08-29 18:45:03 - # MaxBilinearError 0.140 - # RMSBilinearError 0.005 - # MaxCubicError 0.003 - # RMSCubicError 0.001 - # Offset -108 - # Scale 0.003 - # Origin 90N 0E - # AREA_OR_POINT Point - # Vertical_Datum WGS84 -\endverbatim -Of these lines, the Scale and Offset lines are required and define the -conversion from pixel value to height (in meters) using \e height = -\e offset + \e scale \e pixel. The Geoid constructor also reads the -Description, DateTime, and error lines (if present) and stores the -resulting data so that it can be returned by -GeographicLib::Geoid::Description, GeographicLib::Geoid::DateTime, -GeographicLib::Geoid::MaxError, and GeographicLib::Geoid::RMSError -methods. The other lines serve as additional documentation but are not -used by this class. Accompanying egm96-5.pgm (and similarly with the -other geoid data files) are two files egm96-5.wld and -egm96-5.pgm.aux.xml. The first is an ESRI "world" file and the second -supplies complete projection metadata for use by -GDAL. Neither of these files is read -by GeographicLib::Geoid. - -You can use gdal_translate to convert the data files to a standard -GeoTiff, e.g., with -\verbatim - gdal_translate -ot Float32 -scale 0 65000 -108 87 egm96-5.pgm egm96-5.tif -\endverbatim -The arguments to -scale here are specific to the Offset and Scale -parameters used in the pgm file (note 65000 * 0.003 - 108 = 87). You -can check these by running GeoidEval with -the "-v" option. - -Here is a sample script which uses GDAL to create a 1-degree -squared grid of geoid heights at 3" resolution (matching DTED1) by -bilinear interpolation. -\verbatim - #! /bin/sh - lat=37 - lon=067 - res=3 # resolution in seconds - TEMP=`mktemp junkXXXXXXXXXX` # temporary file for GDAL - gdalwarp -q -te `echo $lon $lat $res | awk '{ - lon = $1; lat = $2; res = $3; - printf "%.14f %.14f %.14f %.14f", - lon -0.5*res/3600, lat -0.5*res/3600, - lon+1+0.5*res/3600, lat+1+0.5*res/3600; - }'` -ts $((3600/res+1)) $((3600/res+1)) -r bilinear egm96-5.tif $TEMP - gdal_translate -quiet \ - -mo AREA_OR_POINT=Point \ - -mo Description="WGS84 EGM96, $res-second grid" \ - -mo Vertical_Datum=WGS84 \ - -mo Tie_Point_Location=pixel_corner \ - $TEMP e$lon-n$lat.tif - rm -f $TEMP -\endverbatim - -Because the pgm files are uncompressed, they can take up a lot of disk -space. Some compressed formats compress in tiles and so might be -compatible with the requirement that the data can be randomly accessed. -In particular gdal_translate can be used to convert the pgm files to -compressed tiff files with -\verbatim -gdal_translate -co COMPRESS=LZW -co PREDICTOR=2 \ - -co TILED=YES -co BLOCKXSIZE=256 -co BLOCKYSIZE=256 \ - egmyy-g.pgm egmyy-g.tif -\endverbatim -The resulting files sizes are -\verbatim - pgm tif - egm84-30 0.6 MB 0.5 MB - egm84-15 2.1 MB 1.4 MB - egm96-15 2.1 MB 1.5 MB - egm96-5 19 MB 8.5 MB - egm2008-5 19 MB 9.8 MB - egm2008-2_5 75 MB 28 MB - egm2008-1 470 MB 97 MB -\endverbatim -Currently, there are no plans for %GeographicLib to support this -compressed format. - -\section geoidinterp Interpolating the geoid data - -GeographicLib::Geoid evaluates the geoid height using bilinear or cubic -interpolation. The gradient of the geoid height is obtained by -differentiating the interpolated height and referencing the result to -distance on the WGS84 ellipsoid. - -WARNING: Although GeographicLib::Geoid computes the gradient of -the geoid height, this is subject to large quantization errors as a -result of the way that the geoid data is stored. This is particularly -acute for fine grids, at high latitudes, and for the easterly gradient. -If you need to compute the direction of the acceleration due to gravity -accurately, you should use GeographicLib::GravityModel::Gravity. - -The bilinear interpolation is based on the values at the 4 corners of -the enclosing cell. The interpolated height is a continuous function of -position; however the gradient has discontinuities are cell boundaries. -The quantization of the data files exacerbates the errors in the -gradients. - -The cubic interpolation is a least-squares fit to the values on a -12-point stencil with weights as follows: -\verbatim - . 1 1 . - 1 2 2 1 - 1 2 2 1 - . 1 1 . -\endverbatim -The cubic is constrained to be independent of longitude when evaluating -the height at one of the poles. Cubic interpolation is considerably -more accurate than bilinear interpolation; however, in this -implementation there are small discontinuities in the heights are cell -boundaries. The over-constrained cubic fit slightly reduces the -quantization errors on average. - -The algorithm for the least squares fit is taken from, F. H. Lesh, -Multi-dimensional least-squares polynomial curve fitting, CACM 2, 29-30 -(1959). This algorithm is not part of GeographicLib::Geoid; instead it is -implemented as -Maxima -code which is used to precompute the matrices to convert the function -values on the stencil into the coefficients from the cubic polynomial. -This code is included as a comment in Geoid.cpp. - -The interpolation methods are quick and give good accuracy. Here is a -summary of the combined quantization and interpolation errors for the -heights. -
- - - - - - - - - - - - -
Interpolation and quantization errors for geoid heights
name - geoid - grid -
bilinear error
cubic error
max
rms
-
max
rms
-
egm84-30 EGM84
30'
-
1.546 m
70 mm
-
0.274 m
14 mm
-
egm84-15 EGM84
15'
-
0.413 m
18 mm
-
0.021 m
1.2 mm
-
egm96-15 EGM96
15'
-
1.152 m
40 mm
-
0.169 m
7.0 mm
-
egm96-5 EGM96
5'
-
0.140 m
4.6 mm
-
0.0032 m
0.7 mm
-
egm2008-5 EGM2008
5'
-
0.478 m
12 mm
-
0.294 m
4.5 mm
-
egm2008-2_5EGM2008
2.5'
-
0.135 m
3.2 mm
-
0.031 m
0.8 mm
-
egm2008-1 EGM2008
1'
-
0.025 m
0.8 mm
-
0.0022 m
0.7 mm
-
-The errors are with respect to the specific NGA earth gravity model -(not to any "real" geoid). The RMS values are obtained using 5 million -uniformly distributed random points. The maximum values are obtained by -evaluating the errors using a different grid with points at the -centers of the original grid. (The RMS difference between EGM96 and -EGM2008 is about 0.5 m. The RMS difference between EGM84 and EGM96 is -about 1.5 m.) - -The errors in the table above include the quantization errors that arise -because the height data that GeographicLib::Geoid uses are quantized to -3 mm. If, instead, GeographicLib::Geoid were to use data files without -such quantization artifacts, the overall error would be reduced but -only modestly as shown in the following table, where only the -changed rows are included and where the changed entries are given in -bold: -
- - - - - - - - -
Interpolation (only!) errors for geoid heights
name - geoid - grid -
bilinear error
cubic error
max
rms
-
max
rms
-
egm96-5 EGM96
5'
-
0.140 m
4.6 mm
-
0.0026 m
0.1 mm
-
egm2008-2_5EGM2008
2.5'
-
0.135 m
3.2 mm
-
0.031 m
0.4 mm
-
egm2008-1 EGM2008
1'
-
0.025 m
0.6 mm
-
0.0010 m
0.011 mm
-
- -\section geoidcache Caching the geoid data - -A simple way of calling Geoid is as follows -\code - #include - #include - ... - GeographicLib::Geoid g("egm96-5"); - double lat, lon; - while (std::cin >> lat >> lon) - std::cout << g(lat, lon) << "\n"; - ... -\endcode - -The first call to g(lat, lon) causes the data for the stencil points (4 -points for bilinear interpolation and 12 for cubic interpolation) to be -read and the interpolated value returned. A simple 0th-order caching -scheme is provided by default, so that, if the second and subsequent -points falls within the same grid cell, the data values are not reread -from the file. This is adequate for most interactive use and also -minimizes disk accesses for the case when a continuous track is being -followed. - -If a large quantity of geoid calculations are needed, the calculation -can be sped up by preloading the data for a rectangular block with -GeographicLib::Geoid::CacheArea or the entire dataset with -GeographicLib::Geoid::CacheAll. If the requested points lie within the -cached area, the cached data values are used; otherwise the data is read -from disk as before. Caching all the data is a reasonable choice for -the 5' grids and coarser. Caching all the data for the 1' grid will -require 0.5 GB of RAM and should only be used on systems with sufficient -memory. - -The use of caching does not affect the values returned. Because of the -caching and the random file access, this class is \e not normally thread -safe; i.e., a single instantiation cannot be safely used by multiple -threads. If multiple threads need to calculate geoid heights, there are -two alternatives: - - they should all construct thread-local instantiations. - - GeographicLib::Geoid should be constructed with \e threadsafe = true. - This causes all the data to be read at the time of construction (and - if this fails, an exception is thrown), the data file to be closed - and the single-cell caching to be turned off. The resulting object - may then be shared safely between threads. - -\section testgeoid Test data for geoids - -A test set for the geoid models is available at - - - GeoidHeights.dat.gz - . -This is about 11 MB (compressed). This test set consists of a set of -500000 geographic coordinates together with the corresponding geoid -heights according to various earth gravity models. - -Each line of the test set gives 6 space delimited numbers - - latitude (degrees, exact) - - longitude (degrees, exact) - - EGM84 height (meters, accurate to 1 μm) - - EGM96 height (meters, accurate to 1 μm) - - EGM2008 height (meters, accurate to 1 μm) - . -The latitude and longitude are all multiples of 10−6 -deg and should be regarded as exact. The geoid heights are computed -using the harmonic NGA synthesis programs, where the programs were -compiled (with gfortran) and run under Linux. In the case of the -EGM2008 program, a SAVE statement needed to be added to -subroutine latf, in order for the program to compile -correctly with a stack-based compiler. Similarly the EGM96 code -requires a SAVE statement in subroutine -legfdn. - -
-Back to \ref other. Forward to \ref gravity. Up to \ref contents. -
-**********************************************************************/ -/** -\page gravity Gravity models - -
-Back to \ref geoid. Forward to \ref magnetic. Up to \ref contents. -
- -%GeographicLib can compute the earth's gravitational field with an -earth gravity model using the GeographicLib::GravityModel and -GeographicLib::GravityCircle classes and with the -Gravity utility. These models expand the -gravitational potential of the earth as sum of spherical harmonics. The -models also specify a reference ellipsoid, relative to which geoid -heights and gravity disturbances are measured. - -The supported models are - - egm84, the - - Earth Gravity Model 1984, which includes terms up to degree 180. - - egm96, the - - Earth Gravity Model 1996, which includes terms up to degree 360. - - egm2008, the - - Earth Gravity Model 2008, which includes terms up to degree 2190. - - wgs84, the - - WGS84 Reference Ellipsoid. This is just reproduces the normal - gravitational field for the reference ellipsoid. Usually - GeographicLib::NormalGravity::WGS84 should be used instead. - -See - - W. A. Heiskanen and H. Moritz, Physical Geodesy (Freeman, San - Francisco, 1967). - . -for more information. - -Acknowledgment: I would like to thank Mathieu Peyréga for -sharing EGM_Geoid_CalculatorClass from his Geo library with me. His -implementation was the first I could easily understand and he and I -together worked through some of the issues with overflow and underflow -the occur while performing high-degree spherical harmonic sums. - -Go to - - \ref gravityinst - - \ref gravityformat - - \ref gravitynga - - \ref gravitygeoid - - \ref gravityatmos - - \ref gravityparallel - -\section gravityinst Installing the gravity models - -These gravity models are available for download: -
- - - - - - - - - - - - -
Available gravity models
name max\n degree - size\n(kB) -
Download Links (size, kB)
tar fileWindows\n installerzip file
egm84 -
180
-
27
-
- - link (26)
-
- - link (55)
-
- - link (26)
-
egm96 -
360
-
2100
-
- - link (2100)
-
- - link (2300)
-
- - link (2100)
-
egm2008 -
2190
-
76000
-
- - link (75000)
-
- - link (72000)
-
- - link (73000)
-
wgs84 -
20
-
1
-
- - link (1)
-
- - link (30)
-
- - link (1)
-
-
-The "size" column is the size of the uncompressed data. - -For Linux and Unix systems, %GeographicLib provides a shell script -geographiclib-get-gravity (typically installed in /usr/local/sbin) -which automates the process of downloading and installing the gravity -models. For example -\verbatim - geographiclib-get-gravity all # to install egm84, egm96, egm2008, wgs84 - geographiclib-get-gravity -h # for help -\endverbatim -This script should be run as a user with write access to the -installation directory, which is typically -/usr/local/share/GeographicLib (this can be overridden with the -p -flag), and the data will then be placed in the "gravity" subdirectory. - -Windows users should download and run the Windows installers. These -will prompt for an installation directory with the default being one of -\verbatim - C:/Documents and Settings/All Users/Application Data/GeographicLib - C:/ProgramData/GeographicLib -\endverbatim -(which you probably should not change) and the data is installed in the -"gravity" sub-directory. (The second directory name is an alternate name -that Windows 7 uses for the "Application Data" directory.) - -Otherwise download \e either the tar.bz2 file \e or the zip file (they -have the same contents). To unpack these, run, for example -\verbatim - mkdir -p /usr/local/share/GeographicLib - tar xofjC egm96.tar.bz2 /usr/local/share/GeographicLib - tar xofjC egm2008.tar.bz2 /usr/local/share/GeographicLib - etc. -\endverbatim -and, again, the data will be placed in the "gravity" subdirectory. - -However you install the gravity models, all the datasets should be -installed in the same directory. GeographicLib::GravityModel and -Gravity uses a compile time default to -locate the datasets. This is -- /usr/local/share/GeographicLib/gravity, for non-Windows systems -- C:/Documents and Settings/All Users/Application Data/GeographicLib/gravity, - for Windows systems -. -consistent with the examples above. This may be overridden at run-time -by defining the GRAVITY_PATH or the GEOGRAPHICLIB_DATA environment -variables; see GeographicLib::GravityModel::DefaultGravityPath() for -details. Finally, the path may be set using the optional second -argument to the GeographicLib::GravityModel constructor or with the "-d" -flag to -Gravity. Supplying the "-h" flag to -Gravity reports the default path for -gravity models for that utility. The "-v" flag causes Gravity to report -the full path name of the data file it uses. - -\section gravityformat The format of the gravity model files - -The constructor for GeographicLib::GravityModel reads a file called -NAME.egm which specifies various properties for the gravity model. It -then opens a binary file NAME.egm.cof to obtain the coefficients of the -spherical harmonic sum. - -The first line of the .egm file must consist of "EGMF-v" where EGMF -stands for "Earth Gravity Model Format" and v is the version number of -the format (currently "1"). - -The rest of the File is read a line at a time. A # character and -everything after it are discarded. If the result is just white space it -is discarded. The remaining lines are of the form "KEY WHITESPACE -VALUE". In general, the KEY and the VALUE are case-sensitive. - -GeographicLib::GravityModel only pays attention to the following -keywords - - keywords that affect the field calculation, namely: - - ModelRadius (required), the normalizing radius for the model - in meters. - - ReferenceRadius (required), the major radius \e a for the - reference ellipsoid meters. - - ModelMass (required), the mass constant \e GM for the model - in meters3/seconds2. - - ReferenceMass (required), the mass constant \e GM for the - reference ellipsoid in meters3/seconds2. - - AngularVelocity (required), the angular velocity ω for - the model \e and the reference ellipsoid in rad - seconds−1. - - Flattening, the flattening of the reference ellipsoid; this - can be given a fraction, e.g., 1/298.257223563. One of - Flattening and DynamicalFormFactor is required. - - DynamicalFormFactor, the dynamical form factor - J2 for the reference ellipsoid. One of - Flattening and DynamicalFormFactor is required. - - HeightOffset (default 0), the constant height offset - (meters) added to obtain the geoid height. - - CorrectionMultiplier (default 1), the multiplier for the - "zeta-to-N" correction terms for the geoid height to convert them - to meters. - - Normalization (default full), the normalization used for the - associated Legendre functions (full or schmidt). - - ID (required), 8 printable characters which serve as a - signature for the .egm.cof file (they must appear as the first 8 - bytes of this file). - . - The parameters ModelRadius, ModelMass, and - AngularVelocity apply to the gravity model, while - ReferenceRadius, ReferenceMass, AngularVelocity, - and either Flattening or DynamicalFormFactor - characterize the reference ellipsoid. AngularVelocity - (because it can be measured precisely) is the same for the gravity - model and the reference ellipsoid. ModelRadius is merely a - scaling parameter for the gravity model and there's no requirement - that it be close to the major radius of the earth (although that's - typically how it is chosen). ModelMass and - ReferenceMass need not be the same and, indeed, they are - slightly difference for egm2008. As a result the disturbing - potential \e T has a 1/\e r dependence at large distances. - - keywords that store data that the user can query: - - Name, the name of the model. - - Description, a more descriptive name of the model. - - ReleaseDate, when the model was created. - - keywords that are examined to verify that their values are valid: - - ByteOrder (default little), the order of bytes in the - .egm.cof file. Only little endian is supported at present. - . -Other keywords are ignored. - -The coefficient file NAME.egm.cof is a binary file in little endian -order. The first 8 bytes of this file must match the ID given in -NAME.egm. This is followed by 2 sets of spherical harmonic -coefficients. The first of these gives the gravity potential and the -second gives the zeta-to-N corrections to the geoid height. The format -for each set of coefficients is: - - \e N, the maximum degree of the sum stored as a 4-byte signed integer. - This must satisfy \e N ≥ −1. - - \e M, the maximum order of the sum stored as a 4-byte signed integer. - This must satisfy \e N ≥ \e M ≥ −1. - - \e C\e nm, the coefficients of the cosine coefficients of - the sum in column (i.e., \e m) major order. There are (\e M + 1) - (2\e N - \e M + 2) / 2 elements which are stored as IEEE doubles (8 - bytes). For example for \e N = \e M = 3, there are 10 coefficients - arranged as - C00, - C10, - C20, - C30, - C11, - C21, - C31, - C22, - C32, - C33. - - \e S\e nm, the coefficients of the sine coefficients of - the sum in column (i.e., \e m) major order starting at \e m = 1. - There are \e M (2\e N - \e M + 1) / 2 elements which are stored as - IEEE doubles (8 bytes). For example for \e N = \e M = 3, there are 6 - coefficients arranged as - S11, - S21, - S31, - S22, - S32, - S33. - . -Although the coefficient file is in little endian order, %GeographicLib -can read it on big endian machines. It can only be read on machines -which store doubles in IEEE format. - -As an illustration, here is egm2008.egm: -\verbatim -EGMF-1 -# An Earth Gravity Model (Format 1) file. For documentation on the -# format of this file see -# http://geographiclib.sf.net/html/gravity.html#gravityformat -Name egm2008 -Publisher National Geospatial Intelligence Agency -Description Earth Gravity Model 2008 -URL http://earth-info.nga.mil/GandG/wgs84/gravitymod/egm2008 -ReleaseDate 2008-06-01 -ConversionDate 2011-11-19 -DataVersion 1 -ModelRadius 6378136.3 -ModelMass 3986004.415e8 -AngularVelocity 7292115e-11 -ReferenceRadius 6378137 -ReferenceMass 3986004.418e8 -Flattening 1/298.257223563 -HeightOffset -0.41 - -# Gravitational and correction coefficients taken from -# EGM2008_to2190_TideFree and Zeta-to-N_to2160_egm2008 from -# the egm2008 distribution. -ID EGM2008A -\endverbatim - -\section gravitynga Comments on the NGA harmonic synthesis code - -GeographicLib::GravityModel attempts to reproduce the results of NGA's -harmonic synthesis code for EGM2008, hsynth_WGS84.f. Listed here are -issues that I encountered using the NGA code: - -# A compiler which allocates local variables on the stack produces an - executable with just returns NaNs. The problem here is a missing - SAVE statement in subroutine latf. - -# Because the model and references masses for egm2008 differ (by about - 1 part in 109), there should be a 1/\e r contribution to - the disturbing potential \e T. However, this term is set to zero in - hsynth_WGS84 (effectively altering the normal potential). This - shifts the surface \e W = U0 outward by about 5 mm. - Note too that the reference ellipsoid is no longer a level surface of - the effective normal potential. - -# Subroutine radgrav computes the ellipsoidal coordinate - β incorrectly. This leads to small errors in the deflection - of the vertical, ξ and η, when the height above the - ellipsoid, \e h, is non-zero (about 10−7 arcsec at - \e h = 400 km). - -# There are several expressions which will return inaccurate results - due to cancellation. For example, subroutine grs - computes the flattening using \e f = 1 - sqrt(1 - - e2). Much better is to use \e f = - e2/(1 + sqrt(1 - e2)). The - expressions for \e q and \e q' in grs and - radgrav suffer from similar problems. The resulting - errors are tiny (about 50 pm in the geoid height); however, given - that's there's essentially no cost to using more accurate - expressions, it's preferable to do so. - -# hsynth_WGS84 returns an "undefined" value for \e xi and \e eta at the - poles. Better would be to return the value obtained by taking the - limit \e lat -> +/- 90°. - . -Issues 1--4 have been reported to the authors of hsynth_WGS84. -Issue 1 is peculiar to Fortran and is not encountered in C++ code and -GeographicLib::GravityModel corrects issues 3--5. On issue 2, -GeographicLib::GravityModel neglects the 1/\e r term in \e T in -GeographicLib::GravityModel::GeoidHeight and -GeographicLib::GravityModel::SphericalAnomaly in order to produce -results which match NGA's for these quantities. On the other hand, -GeographicLib::GravityModel::Disturbance and -GeographicLib::GravityModel::T do include this term. - -\section gravitygeoid Details of the geoid height and anomaly calculations - -Ideally, the geoid represents a surface of constant gravitational -potential which approximates mean sea level. In reality some -approximations are taken in determining this surface. The steps taking -by GeographicLib::GravityModel in computing the geoid height are -described here (in the context of EGM2008). This mimics NGA's code -hsynth_WGS84 closely because most users of EGM2008 use the gridded data -generated by this code (e.g., GeographicLib::Geoid) and it is desirable -to use a consistent definition of the geoid height. - - The model potential is band limited; the minimum wavelength that is - represented is 360°/2160 = 10' (i.e., about 10NM or - 18.5km). The maximum degree for the spherical harmonic sum is 2190; - however the model was derived using ellipsoidal harmonics of degree - and order 2160 and the degree was increased to 2190 in order to - capture the ellipsoidal harmonics faithfully with spherical - harmonics. - - The 1/\e r term is omitted from the \e T (this is issue 2 in \ref - gravitynga). This moves the equipotential surface by about 5mm. - - The surface \e W = U0 is determined by Bruns' - formula, which is roughly equivalent to a single iteration of - Newton's method. The RMS error in this approximation is about 1.5mm - with a maximum error of about 10 mm. - - The model potential is only valid above the earth's surface. A - correction therefore needs to be included where the geoid lies - beneath the terrain. This is NGA's "zeta-to-N" correction, which is - represented by a spherical harmonic sum of degree and order 2160 (and - so it misses short wavelength terrain variations). In addition, it - entails estimating the isostatic equilibrium of the earth's crust. - The correction lies in the range [-5.05 m, 0.05 m], however for 99.9% - of the earth's surface the correction is less than 10 mm in - magnitude. - - The resulting surface lies above the observed mean sea level, - so -0.41m is added to the geoid height. (Better would be to change - the potential used to define the geoid; but this would only change - the result by about 2mm.) - . -A useful discussion of the problems with defining a geoid is given by -Dru A. Smith in - -There is no such thing as "The" EGM96 geoid: Subtle points on the use of -a global geopotential model, IGeS Bulletin No. 8, International -Geoid Service, Milan, Italy, pp. 17--28 (1998). - -GeographicLib::GravityModel::GeoidHeight reproduces the results of the -several NGA codes for harmonic synthesis with the following maximum -discrepancies: - - egm84 = 1.1mm. This is probably due to inconsistent parameters for the - reference ellipsoid in the NGA code. (In particular, the value of - mass constant excludes the atmosphere; however, it's not clear - whether the other parameters have been correspondingly adjusted.) - Note that geoid heights predicted by egm84 differ from those of more - recent gravity models by about 1 meter. - - egm96 = 23nm. - - egm2008 = 78pm. After addressing some of the issues alluded to in - issue 4 in \ref gravitynga, the maximum discrepancy becomes 23pm. - -The formula for the gravity anomaly vector involves computing gravity -and normal gravity at two different points (with the displacement -between the points unknown ab initio). Since the gravity anomaly -is already a small quantity it is sometimes acceptable to employ -approximations that change the quantities by \e O(\e f). The NGA code -uses the spherical approximation described by Heiskanen and Moritz, -Sec. 2-14 and GeographicLib::GravityModel::SphericalAnomaly uses the -same approximation for compatibility. In this approximation, the -gravity disturbance delta = grad \e T is calculated. -Here, \e T once again excludes the 1/\e r term (this is issue 2 in \ref -gravitynga and is consistent with the computation of the geoid height). -Note that delta compares the gravity and the normal gravity at -the \e same point; the gravity anomaly vector is then found by -estimating the gradient of the normal gravity in the limit that the -earth is spherically symmetric. delta is expressed in \e -spherical coordinates as \e deltax, \e deltay, \e deltaz where, for -example, \e deltaz is the \e radial component of delta (not the -component perpendicular to the ellipsoid) and \e deltay is similarly -slightly different from the usual northerly component. The components -of the anomaly are then given by - - gravity anomaly, \e Dg01 = \e deltaz - 2T/\e R, where \e R - distance to the center of the earth; - - northerly component of the deflection of the vertical, \e xi = - - deltay/\e gamma, where \e gamma is the magnitude of the normal - gravity; - - easterly component of the deflection of the vertical, \e eta = - - deltax/\e gamma. - . -GeographicLib::NormalGravity computes the normal gravity accurately and -avoids issue 3 of \ref gravitynga. Thus while -GeographicLib::GravityModel::SphericalAnomaly reproduces the results for -\e xi and \e eta at \e h = 0, there is a slight discrepancy if \e h is -non-zero. - -\section gravityatmos The effect of the mass of the atmosphere - -All of the supported models use WGS84 for the reference ellipsoid. This -has (see - -TR8350.2, table 3.1) - - \e a = 6378137 m - - \e f = 1/298.257223563 - - ω = 7292115 × 10−11 rad - s−1 - - \e GM = 3986004.418 × 108 m3 - s−2. - . -The value of \e GM includes the mass of the atmosphere and so strictly -only applies above the earth's atmosphere. Near the surface of the -earth, the value of \e g will be less (in absolute value) than the value -predicted by these models by about δ\e g = (4πG/\e -g) \e A = 8.552 × 10−11 \e A m2/kg, -where \e G is the gravitational constant, \e g is the earth's gravity, -and \e A is the pressure of the atmosphere. At sea level we have \e A = -101.3 kPa, and δ\e g = 8.7 × 10−6 m -s−2, approximately. (In other words the effect is -about 1 part in a million; by way of comparison, buoyancy effects -are about 100 times larger.) - -\section gravityparallel Geoid heights on a multi-processor system - -The egm2008 model includes many terms (over 2 million spherical -harmonics). For that reason computations using this model may be slow; -for example it takes about 78 ms to compute the geoid height at a single -point. There are two ways to speed up this computation: - - Use a GeographicLib::GravityCircle to compute the geoid height at - several points on a circle of latitude. This reduces the cost per - point to about 92 μs (a reduction by a factor of over 800). - - Compute the values on several circles of latitude in parallel. One - of the simplest ways of doing this is with - OpenMP; on an 8-processor system, - this can speed up the computation by another factor of 8. - . -Both of these techniques are illustrated by the following code, -which computes a table of geoid heights on -a regular grid and writes on the result in a -.gtx -file. On an 8-processor Intel 2.66 GHz machine using OpenMP -(-DHAVE_OPENMP=1), it takes about 40 minutes of elapsed time to compute -the geoid height for EGM2008 on a 1' gride. (Without these -optimizations, the computation would have taken about 200 days!) -\include GeoidToGTX.cpp - -This example, examples/GeoidToGTX.cpp, is built if cmake -is configured with -D GEOGRAPHICLIB_EXAMPLES=ON. cmake -will add in support for OpenMP, if it is available. - -
-Back to \ref geoid. Forward to \ref magnetic. Up to \ref contents. -
-**********************************************************************/ -/** -\page magnetic Magnetic models - -
-Back to \ref gravity. Forward to \ref geodesic. Up to \ref contents. -
- -%GeographicLib can compute the earth's magnetic field by a magnetic -model using the GeographicLib::MagneticModel and -GeographicLib::MagneticCircle classes and with the -MagneticField utility. These models -expand the internal magnetic potential of the earth as sum of spherical -harmonics. They neglect magnetic fields due to the ionosphere, the -magnetosphere, nearby magnetized materials, electric machinery, etc. -Users of GeographicLib::MagneticModel are advised to read the -"Health -Warning" this is provided with igrf11. Although the advice is -specific to igrf11, many of the comments apply to all magnetic field -models. - -The supported models are - - wmm2010, the - World - Magnetic Model 2010, which approximates the main magnetic field - for the period 2010--2015. - - igrf11, the - International - Geomagnetic Reference Field (11th generation), which approximates - the main magnetic field for the period 1900--2015. - - emm2010, the - Enhanced - Magnetic Model 2010, which approximates the main and crustal - magnetic fields for the period 2010--2015. - -Go to - - \ref magneticinst - - \ref magneticformat - -\section magneticinst Installing the magnetic field models - -These magnetic models are available for download: -
- - - - - - - - - - - -
Available magnetic models
name max\n degree - time\n interval - size\n(kB) -
Download Links (size, kB)
tar fileWindows\n installerzip file
wmm2010 -
12
-
2010--2015
-
3
-
- - link (2)
-
- - link (300)
-
- - link (2)
-
igrf11 -
13
-
1900--2015
-
25
-
- - link (7)
-
- - link (310)
-
- - link (8)
-
emm2010 -
739
-
2010--2015
-
4400
-
- - link (3700)
-
- - link (3000)
-
- - link (4100)
-
-
-The "size" column is the size of the uncompressed data. - -For Linux and Unix systems, %GeographicLib provides a shell script -geographiclib-get-magnetic (typically installed in /usr/local/sbin) -which automates the process of downloading and installing the magnetic -models. For example -\verbatim - geographiclib-get-magnetic all # to install wmm2010, igrf11, emm2010 - geographiclib-get-magnetic -h # for help -\endverbatim -This script should be run as a user with write access to the -installation directory, which is typically -/usr/local/share/GeographicLib (this can be overridden with the -p -flag), and the data will then be placed in the "magnetic" subdirectory. - -Windows users should download and run the Windows installers. These -will prompt for an installation directory with the default being one of -\verbatim - C:/Documents and Settings/All Users/Application Data/GeographicLib - C:/ProgramData/GeographicLib -\endverbatim -(which you probably should not change) and the data is installed in the -"magnetic" sub-directory. (The second directory name is an alternate name -that Windows 7 uses for the "Application Data" directory.) - -Otherwise download \e either the tar.bz2 file \e or the zip file (they -have the same contents). To unpack these, run, for example -\verbatim - mkdir -p /usr/local/share/GeographicLib - tar xofjC wmm2010.tar.bz2 /usr/local/share/GeographicLib - tar xofjC emm2010.tar.bz2 /usr/local/share/GeographicLib - etc. -\endverbatim -and, again, the data will be placed in the "magnetic" subdirectory. - -However you install the magnetic models, all the datasets should be -installed in the same directory. GeographicLib::MagneticModel and -MagneticField uses a compile time -default to locate the datasets. This is -- /usr/local/share/GeographicLib/magnetic, for non-Windows systems -- C:/Documents and Settings/All Users/Application Data/GeographicLib/magnetic, - for Windows systems -. -consistent with the examples above. This may be overridden at run-time -by defining the MAGNETIC_PATH or the GEOGRAPHIC_DATA environment -variables; see GeographicLib::MagneticModel::DefaultMagneticPath() for -details. Finally, the path may be set using the optional second -argument to the GeographicLib::MagneticModel constructor or with the -"-d" flag to MagneticField. -Supplying the "-h" flag to -MagneticField reports the default -path for magnetic models for that utility. The "-v" flag causes -MagneticField to report the full path name of the data file it uses. - -\section magneticformat The format of the magnetic model files - -The constructor for GeographicLib::MagneticModel reads a file called -NAME.wmm which specifies various properties for the magnetic model. It -then opens a binary file NAME.wmm.cof to obtain the coefficients of the -spherical harmonic sum. - -The first line of the .wmm file must consist of "WMMF-v" where WMMF -stands for "World Magnetic Model Format" and v is the version number of -the format (currently "1"). - -The rest of the File is read a line at a time. A # character and -everything after it are discarded. If the result is just white space it -is discarded. The remaining lines are of the form "KEY WHITESPACE -VALUE". In general, the KEY and the VALUE are case-sensitive. - -GeographicLib::MagneticModel only pays attention to the following -keywords - - keywords that affect the field calculation, namely: - - Radius (required), the normalizing radius of the model in - meters. - - NumModels (default 1), the number of models. WMM2010 - consists of a single model giving the magnetic field and its time - variation at 2010. IGRF11 consists of 23 models for 1900 thru 2010 - at 5 year intervals. The time variation is given only for the last - model to allow extrapolation beyond 2010. For dates prior to 2010, - linear interpolation is used. - - Epoch (required), the time origin (in fractional years) for - the first model. - - DeltaEpoch (default 1), the interval between models in years - (only relevant for NumModels > 1). - - Normalization (default schmidt), the normalization used for - the associated Legendre functions (schmidt or full). - - ID (required), 8 printable characters which serve as a - signature for the .wmm.cof file (they must appear as the first 8 - bytes of this file). - - keywords that store data that the user can query: - - Name, the name of the model. - - Description, a more descriptive name of the model. - - ReleaseDate, when the model was created. - - MinTime, the minimum date at which the model should be used. - - MaxTime, the maximum date at which the model should be used. - - MinHeight, the minimum height above the ellipsoid for which - the model should be used. - - MaxHeight, the maximum height above the ellipsoid for which - the model should be used. - . - GeographicLib::MagneticModel does not enforce the restrictions - implied by last four quantities. However, - MagneticField issues a warning if - these limits are exceeded. - - keywords that are examined to verify that their values are valid: - - Type (default linear), the type of the model. "linear" - means that the time variation is piece-wise linear (either using - interpolation between the field at two dates or using the field and - its first derivative with respect to time). This is the only type - of model supported at present. - - ByteOrder (default little), the order of bytes in the - .wmm.cof file. Only little endian is supported at present. - . -Other keywords are ignored. - -The coefficient file NAME.wmm.cof is a binary file in little endian -order. The first 8 bytes of this file must match the ID given in -NAME.wmm. This is followed by NumModels + 1 sets of spherical harmonic -coefficients. The first NumModels of these model the magnetic field at -Epoch + \e i * DeltaEpoch for 0 ≤ \e i < NumModels. The last set of -coefficients model the rate of change of the magnetic field at Epoch + -(NumModels − 1) * DeltaEpoch. The format for each set of coefficients -is: - - \e N, the maximum degree of the sum stored as a 4-byte signed integer. - This must satisfy \e N ≥ −1. - - \e M, the maximum order of the sum stored as a 4-byte signed integer. - This must satisfy \e N ≥ \e M ≥ −1. - - \e C\e nm, the coefficients of the cosine coefficients of - the sum in column (i.e., \e m) major order. There are (\e M + 1) - (2\e N − \e M + 2) / 2 elements which are stored as IEEE doubles (8 - bytes). For example for \e N = \e M = 3, there are 10 coefficients - arranged as - C00, - C10, - C20, - C30, - C11, - C21, - C31, - C22, - C32, - C33. - - \e S\e nm, the coefficients of the sine coefficients of - the sum in column (i.e., \e m) major order starting at \e m = 1. - There are \e M (2\e N − \e M + 1) / 2 elements which are stored as - IEEE doubles (8 bytes). For example for \e N = \e M = 3, there are 6 - coefficients arranged as - S11, - S21, - S31, - S22, - S32, - S33. - . -Although the coefficient file is in little endian order, %GeographicLib -can read it on big endian machines. It can only be read on machines -which store doubles in IEEE format. - -As an illustration, here is igrf11.wmm: -\verbatim -WMMF-1 -# A World Magnetic Model (Format 1) file. For documentation on the -# format of this file see -# http://geographiclib.sf.net/html/magnetic.html#magneticformat -Name igrf11 -Description International Geomagnetic Reference Field 11th Generation -URL http://ngdc.noaa.gov/IAGA/vmod/igrf.html -Publisher National Oceanic and Atmospheric Administration -ReleaseDate 2009-12-15 -DataCutOff 2009-10-01 -ConversionDate 2011-11-04 -DataVersion 1 -Radius 6371200 -NumModels 23 -Epoch 1900 -DeltaEpoch 5 -MinTime 1900 -MaxTime 2015 -MinHeight -1000 -MaxHeight 600000 - -# The coefficients are stored in a file obtained by appending ".cof" to -# the name of this file. The coefficients were obtained from IGRF11.COF -# in the geomag70 distribution. -ID IGRF11-A -\endverbatim - -
-Back to \ref gravity. Forward to \ref geodesic. Up to \ref contents. -
-**********************************************************************/ -/** -\page geodesic Geodesics on an ellipsoid of revolution - -
-Back to \ref magnetic. Forward to \ref triaxial. Up to \ref contents. -
- -GeographicLib::Geodesic and GeographicLib::GeodesicLine provide accurate -solutions to the direct and inverse geodesic problems. The -GeodSolve utility provides an interface -to these classes. GeographicLib::AzimuthalEquidistant implements the -azimuthal equidistant projection in terms of geodesics. -GeographicLib::CassiniSoldner implements a transverse cylindrical -equidistant projection in terms of geodesics. The GeodesicProj utility provides an -interface to these projections. - -The algorithms used by GeographicLib::Geodesic and -GeographicLib::GeodesicLine are based on a Taylor expansion of the -geodesic integrals valid when the flattening \e f is small. -GeographicLib::GeodesicExact and GeographicLib::GeodesicLineExact -evaluate the integrals exactly (in terms of incomplete elliptic -integrals). For the WGS84 ellipsoid, the series solutions are about -2--3 times faster and 2--3 times more accurate (because it's easier to -control round-off errors with series solutions); thus -GeographicLib::Geodesic and GeographicLib::GeodesicLine are -recommended for most geodetic applications. However, in applications -where the absolute value of \e f is greater than about 0.02, the exact -classes should be used. - -Go to - - \ref testgeod - - \ref geodseries - - \ref geodellip - - \ref meridian - - \ref geodshort - . -For some background information on geodesics on triaxial ellipsoids, see -\ref triaxial. - -References - - F. W. Bessel, - The calculation - of longitude and latitude from geodesic measurements (1825), - Astron. Nachr. 331(8), 852-861 (2010); - translated by C. F. F. Karney and R. E. Deakin. Preprint: - arXiv:0908.1824. - - F. R. Helmert, - - Mathematical and Physical Theories of Higher Geodesy, Part 1 (1880), - Aeronautical Chart and Information Center (St. Louis, 1964), - Chaps. 5--7. - - J. Danielsen, - The Area under the Geodesic, - Survey Review 30(232), 61--66 (1989). - - C. F. F. Karney, - - Algorithms for geodesics, - J. Geodesy 87(1), 43--55 (Jan. 2013); - DOI: - 10.1007/s00190-012-0578-z; - addenda: - geod-addenda.html; - resource page: - geod.html. - - A collection of some papers on geodesics is available at - http://geographiclib.sourceforge.net/geodesic-papers/biblio.html - - The wikipedia page, - - Geodesics on an ellipsoid. - -\section testgeod Test data for geodesics - -A test set a geodesics is available at - - - GeodTest.dat.gz - . -This is about 39 MB (compressed). This consists of a set of geodesics -for the WGS84 ellipsoid. A subset of this (consisting of 1/50 of the -members — about 690 kB, compressed) is available at - - - GeodTest-short.dat.gz - -Each line of the test set gives 10 space delimited numbers - - latitude for point 1, \e lat1 (degrees, exact) - - longitude for point 1, \e lon1 (degrees, always 0) - - azimuth for point 1, \e azi1 (clockwise from north in degrees, exact) - - latitude for point 2, \e lat2 (degrees, accurate to - 10−18 deg) - - longitude for point 2, \e lon2 (degrees, accurate to - 10−18 deg) - - azimuth for point 2, \e azi2 (degrees, accurate to - 10−18 deg) - - geodesic distance from point 1 to point 2, \e s12 (meters, exact) - - arc distance on the auxiliary sphere, \e a12 (degrees, accurate to - 10−18 deg) - - reduced length of the geodesic, \e m12 (meters, accurate to 0.1 pm) - - the area under the geodesic, \e S12 (m2, accurate to - 1 mm2) - . -These are computed using as direct geodesic calculations with the given -\e lat1, \e lon1, \e azi1, and \e s12. The distance \e s12 always -corresponds to an arc length \e a12 ≤ 180°, so the given -geodesics give the shortest paths from point 1 to point 2. For -simplicity and without loss of generality, \e lat1 is chosen in -[0°, 90°], \e lon1 is taken to be zero, \e azi1 is -chosen in [0°, 180°]. Furthermore, \e lat1 and \e -azi1 are taken to be multiples of 10−12 deg and \e s12 -is a multiple of 0.1 μm in [0 m, 20003931.4586254 m]. This results \e -lon2 in [0°, 180°] and \e azi2 in [0°, 180°]. - -The direct calculation uses an expansion of the geodesic equations -accurate to f30 (approximately 1 part in 1050) -and is computed with with -Maxima's -bfloats and fpprec set to 100 (so the errors in the data are probably -1/2 of the values quoted above). - -The contents of the file are as follows: - - 100000 entries randomly distributed - - 50000 entries which are nearly antipodal - - 50000 entries with short distances - - 50000 entries with one end near a pole - - 50000 entries with both ends near opposite poles - - 50000 entries which are nearly meridional - - 50000 entries which are nearly equatorial - - 50000 entries running between vertices (\e azi1 = \e azi2 = 90°) - - 50000 entries ending close to vertices - . -(a total of 500000 entries). The values for \e s12 for the geodesics -running between vertices are truncated to a multiple of 0.1 pm and this -is used to determine point 2. - -This data can be fed to the GeodSolve -utility as follows - - Direct from point 1: -\verbatim - gunzip -c GeodTest.dat.gz | cut -d' ' -f1,2,3,7 | ./GeodSolve -\endverbatim - This should yield columns 4, 5, 6, and 9 of the test set. - - Direct from point 2: -\verbatim - gunzip -c GeodTest.dat.gz | cut -d' ' -f4,5,6,7 | - sed "s/ \([^ ]*$\)/ -\1/" | ./GeodSolve -\endverbatim - (The sed command negates the distance.) This should yield columns 1, - 2, and 3, and the negative of column 9 of the test set. - - Inverse between points 1 and 2: -\verbatim - gunzip -c GeodTest.dat.gz | cut -d' ' -f1,2,4,5 | ./GeodSolve -i -\endverbatim - This should yield columns 3, 6, 7, and 9 of the test set. - . -Add, e.g., "-p 6", to the call to GeodSolve to change the precision of -the output. Adding "-f" causes GeodSolve to print 12 fields specifying -the geodesic; these include the 10 fields in the test set plus the -geodesic scales \e M12 and \e M21 which are inserted between \e m12 and -\e S12. - -Code for computing arbitrarily accurate geodesics in maxima is available -in geodesic.mac (this depends on - ellint.mac and uses the series computed by - geod.mac). This solve both the direct and -inverse geodesic problems and offers the ability to solve the problems -either using series expansions (similar to GeographicLib::Geodesic) or -in terms of elliptic integrals (similar to -GeographicLib::GeodesicExact). - -\section geodseries Expansions for geodesics - -We give here the series expansions for the various geodesic integrals -valid to order f10. In this release of the code, we -use a 6th-order expansions. This is sufficient to maintain accuracy -for doubles for the SRMmax ellipsoid (\e a = 6400 km, \e f = 1/150). -However, the preprocessor macro GEOGRAPHICLIB_GEODESIC_ORDER can be -used to select any order up to 8. (If using long doubles, with a -64-bit fraction, the default order is 7.) The series expanded to -order f30 are given in -geodseries30.html. - -In the formulas below ^ indicates exponentiation (\e f^3 = -f3) and / indicates real division (3/5 = 0.6). The -equations need to be converted to Horner form, but are here left in -expanded form so that they can be easily truncated to lower order. -These expansions were obtained using the Maxima code, -geod.mac. - -In the expansions below, we have - - \f$ \alpha \f$ is the azimuth - - \f$ \alpha_0 \f$ is the azimuth at the equator crossing - - \f$ \lambda \f$ is the longitude measured from the equator crossing - - \f$ \sigma \f$ is the spherical arc length - - \f$ \omega = \tan^{-1}(\sin\alpha_0\tan\sigma) \f$ is the spherical longitude - - \f$ a \f$ is the equatorial radius - - \f$ b \f$ is the polar semi-axis - - \f$ f \f$ is the flattening - - \f$ e^2 = f(2 - f) \f$ - - \f$ e'^2 = e^2/(1-e^2) \f$ - - \f$ k^2 = e'^2 \cos^2\alpha_0 = 4 \epsilon / (1 - \epsilon)^2 \f$ - - \f$ n = f / (2 - f) \f$ - - \f$ c^2 = a^2/2 + b^2/2 (\tanh^{-1}e)/e \f$ - - \e ep2 = \f$ e'^2 \f$ - - \e k2 = \f$ k^2 \f$ - - \e eps = \f$ \epsilon \f$ - -The formula for distance is -\f[ - \frac sb = I_1(\sigma) -\f] -where -\f[ -\begin{aligned} - I_1(\sigma) &= A_1\bigl(\sigma + B_1(\sigma)\bigr) \\ - B_1(\sigma) &= \sum_{j=1} C_{1j} \sin 2j\sigma -\end{aligned} -\f] -and -\verbatim -A1 = (1 + 1/4 * eps^2 - + 1/64 * eps^4 - + 1/256 * eps^6 - + 25/16384 * eps^8 - + 49/65536 * eps^10) / (1 - eps); -\endverbatim -\verbatim -C1[1] = - 1/2 * eps - + 3/16 * eps^3 - - 1/32 * eps^5 - + 19/2048 * eps^7 - - 3/4096 * eps^9; -C1[2] = - 1/16 * eps^2 - + 1/32 * eps^4 - - 9/2048 * eps^6 - + 7/4096 * eps^8 - + 1/65536 * eps^10; -C1[3] = - 1/48 * eps^3 - + 3/256 * eps^5 - - 3/2048 * eps^7 - + 17/24576 * eps^9; -C1[4] = - 5/512 * eps^4 - + 3/512 * eps^6 - - 11/16384 * eps^8 - + 3/8192 * eps^10; -C1[5] = - 7/1280 * eps^5 - + 7/2048 * eps^7 - - 3/8192 * eps^9; -C1[6] = - 7/2048 * eps^6 - + 9/4096 * eps^8 - - 117/524288 * eps^10; -C1[7] = - 33/14336 * eps^7 - + 99/65536 * eps^9; -C1[8] = - 429/262144 * eps^8 - + 143/131072 * eps^10; -C1[9] = - 715/589824 * eps^9; -C1[10] = - 2431/2621440 * eps^10; -\endverbatim - -The function \f$ \tau(\sigma) = s/(b A_1) = \sigma + B_1(\sigma) \f$ -may be inverted by series reversion giving -\f[ - \sigma(\tau) = \tau + \sum_{j=1} C'_{1j} \sin 2j\sigma -\f] -where -\verbatim -C1'[1] = + 1/2 * eps - - 9/32 * eps^3 - + 205/1536 * eps^5 - - 4879/73728 * eps^7 - + 9039/327680 * eps^9; -C1'[2] = + 5/16 * eps^2 - - 37/96 * eps^4 - + 1335/4096 * eps^6 - - 86171/368640 * eps^8 - + 4119073/28311552 * eps^10; -C1'[3] = + 29/96 * eps^3 - - 75/128 * eps^5 - + 2901/4096 * eps^7 - - 443327/655360 * eps^9; -C1'[4] = + 539/1536 * eps^4 - - 2391/2560 * eps^6 - + 1082857/737280 * eps^8 - - 2722891/1548288 * eps^10; -C1'[5] = + 3467/7680 * eps^5 - - 28223/18432 * eps^7 - + 1361343/458752 * eps^9; -C1'[6] = + 38081/61440 * eps^6 - - 733437/286720 * eps^8 - + 10820079/1835008 * eps^10; -C1'[7] = + 459485/516096 * eps^7 - - 709743/163840 * eps^9; -C1'[8] = + 109167851/82575360 * eps^8 - - 550835669/74317824 * eps^10; -C1'[9] = + 83141299/41287680 * eps^9; -C1'[10] = + 9303339907/2972712960 * eps^10; -\endverbatim - -The reduced length is given by -\f[ -\begin{aligned} - \frac mb &= \sqrt{1 + k^2 \sin^2\sigma_2} \cos\sigma_1 \sin\sigma_2 \\ - &\quad {}-\sqrt{1 + k^2 \sin^2\sigma_1} \sin\sigma_1 \cos\sigma_2 \\ - &\quad {}-\cos\sigma_1 \cos\sigma_2 \bigl(J(\sigma_2) - J(\sigma_1)\bigr) -\end{aligned} -\f] -where -\f[ -\begin{aligned} - J(\sigma) &= I_1(\sigma) - I_2(\sigma) \\ - I_2(\sigma) &= A_2\bigl(\sigma + B_2(\sigma)\bigr) \\ - B_2(\sigma) &= \sum_{j=1} C_{2j} \sin 2j\sigma -\end{aligned} -\f] -\verbatim -A2 = (1 + 1/4 * eps^2 - + 9/64 * eps^4 - + 25/256 * eps^6 - + 1225/16384 * eps^8 - + 3969/65536 * eps^10) * (1 - eps); -\endverbatim -\verbatim -C2[1] = + 1/2 * eps - + 1/16 * eps^3 - + 1/32 * eps^5 - + 41/2048 * eps^7 - + 59/4096 * eps^9; -C2[2] = + 3/16 * eps^2 - + 1/32 * eps^4 - + 35/2048 * eps^6 - + 47/4096 * eps^8 - + 557/65536 * eps^10; -C2[3] = + 5/48 * eps^3 - + 5/256 * eps^5 - + 23/2048 * eps^7 - + 191/24576 * eps^9; -C2[4] = + 35/512 * eps^4 - + 7/512 * eps^6 - + 133/16384 * eps^8 - + 47/8192 * eps^10; -C2[5] = + 63/1280 * eps^5 - + 21/2048 * eps^7 - + 51/8192 * eps^9; -C2[6] = + 77/2048 * eps^6 - + 33/4096 * eps^8 - + 2607/524288 * eps^10; -C2[7] = + 429/14336 * eps^7 - + 429/65536 * eps^9; -C2[8] = + 6435/262144 * eps^8 - + 715/131072 * eps^10; -C2[9] = + 12155/589824 * eps^9; -C2[10] = + 46189/2621440 * eps^10; -\endverbatim - -The longitude is given in terms of the spherical longitude by -\f[ -\lambda = \omega - f \sin\alpha_0 I_3(\sigma) -\f] -where -\f[ -\begin{aligned} - I_3(\sigma) &= A_3\bigl(\sigma + B_3(\sigma)\bigr) \\ - B_3(\sigma) &= \sum_{j=1} C_{3j} \sin 2j\sigma -\end{aligned} -\f] -and -\verbatim -A3 = 1 - (1/2 - 1/2*n) * eps - - (1/4 + 1/8*n - 3/8*n^2) * eps^2 - - (1/16 + 3/16*n + 1/16*n^2 - 5/16*n^3) * eps^3 - - (3/64 + 1/32*n + 5/32*n^2 + 5/128*n^3 - 35/128*n^4) * eps^4 - - (3/128 + 5/128*n + 5/256*n^2 + 35/256*n^3 + 7/256*n^4) * eps^5 - - (5/256 + 15/1024*n + 35/1024*n^2 + 7/512*n^3) * eps^6 - - (25/2048 + 35/2048*n + 21/2048*n^2) * eps^7 - - (175/16384 + 35/4096*n) * eps^8 - - 245/32768 * eps^9; -\endverbatim -\verbatim -C3[1] = + (1/4 - 1/4*n) * eps - + (1/8 - 1/8*n^2) * eps^2 - + (3/64 + 3/64*n - 1/64*n^2 - 5/64*n^3) * eps^3 - + (5/128 + 1/64*n + 1/64*n^2 - 1/64*n^3 - 7/128*n^4) * eps^4 - + (3/128 + 11/512*n + 3/512*n^2 + 1/256*n^3 - 7/512*n^4) * eps^5 - + (21/1024 + 5/512*n + 13/1024*n^2 + 1/512*n^3) * eps^6 - + (243/16384 + 189/16384*n + 83/16384*n^2) * eps^7 - + (435/32768 + 109/16384*n) * eps^8 - + 345/32768 * eps^9; -C3[2] = + (1/16 - 3/32*n + 1/32*n^2) * eps^2 - + (3/64 - 1/32*n - 3/64*n^2 + 1/32*n^3) * eps^3 - + (3/128 + 1/128*n - 9/256*n^2 - 3/128*n^3 + 7/256*n^4) * eps^4 - + (5/256 + 1/256*n - 1/128*n^2 - 7/256*n^3 - 3/256*n^4) * eps^5 - + (27/2048 + 69/8192*n - 39/8192*n^2 - 47/4096*n^3) * eps^6 - + (187/16384 + 39/8192*n + 31/16384*n^2) * eps^7 - + (287/32768 + 47/8192*n) * eps^8 - + 255/32768 * eps^9; -C3[3] = + (5/192 - 3/64*n + 5/192*n^2 - 1/192*n^3) * eps^3 - + (3/128 - 5/192*n - 1/64*n^2 + 5/192*n^3 - 1/128*n^4) * eps^4 - + (7/512 - 1/384*n - 77/3072*n^2 + 5/3072*n^3 + 65/3072*n^4) * eps^5 - + (3/256 - 1/1024*n - 71/6144*n^2 - 47/3072*n^3) * eps^6 - + (139/16384 + 143/49152*n - 383/49152*n^2) * eps^7 - + (243/32768 + 95/49152*n) * eps^8 - + 581/98304 * eps^9; -C3[4] = + (7/512 - 7/256*n + 5/256*n^2 - 7/1024*n^3 + 1/1024*n^4) * eps^4 - + (7/512 - 5/256*n - 7/2048*n^2 + 9/512*n^3 - 21/2048*n^4) * eps^5 - + (9/1024 - 43/8192*n - 129/8192*n^2 + 39/4096*n^3) * eps^6 - + (127/16384 - 23/8192*n - 165/16384*n^2) * eps^7 - + (193/32768 + 3/8192*n) * eps^8 - + 171/32768 * eps^9; -C3[5] = + (21/2560 - 9/512*n + 15/1024*n^2 - 7/1024*n^3 + 9/5120*n^4) * eps^5 - + (9/1024 - 15/1024*n + 3/2048*n^2 + 57/5120*n^3) * eps^6 - + (99/16384 - 91/16384*n - 781/81920*n^2) * eps^7 - + (179/32768 - 55/16384*n) * eps^8 - + 141/32768 * eps^9; -C3[6] = + (11/2048 - 99/8192*n + 275/24576*n^2 - 77/12288*n^3) * eps^6 - + (99/16384 - 275/24576*n + 55/16384*n^2) * eps^7 - + (143/32768 - 253/49152*n) * eps^8 - + 33/8192 * eps^9; -C3[7] = + (429/114688 - 143/16384*n + 143/16384*n^2) * eps^7 - + (143/32768 - 143/16384*n) * eps^8 - + 429/131072 * eps^9; -C3[8] = + (715/262144 - 429/65536*n) * eps^8 - + 429/131072 * eps^9; -C3[9] = + 2431/1179648 * eps^9; -\endverbatim - -The formula for area between the geodesic and the equator is given in -Sec. 6 of -Algorithms for geodesics in terms of \e S, -\f[ -S = c^2 \alpha + e^2 a^2 \cos\alpha_0 \sin\alpha_0 I_4(\sigma) -\f] -where -\f[ -I_4(\sigma) = \sum_{j=0} C_{4j} \cos(2j+1)\sigma -\f] -In the paper, this was expanded in \f$ e'^2 \f$ and \f$ k^2 \f$. -However, the series converges faster for eccentric ellipsoids if the -expansion is in \f$ n \f$ and \f$ \epsilon \f$. The series to order -\f$ f^{10} \f$ becomes -\verbatim -C4[0] = + (2/3 - 4/15*n + 8/105*n^2 + 4/315*n^3 + 16/3465*n^4 + 20/9009*n^5 + 8/6435*n^6 + 28/36465*n^7 + 32/62985*n^8 + 4/11305*n^9) - - (1/5 - 16/35*n + 32/105*n^2 - 16/385*n^3 - 64/15015*n^4 - 16/15015*n^5 - 32/85085*n^6 - 112/692835*n^7 - 128/1616615*n^8) * eps - - (2/105 + 32/315*n - 1088/3465*n^2 + 1184/5005*n^3 - 128/3465*n^4 - 3232/765765*n^5 - 1856/1616615*n^6 - 6304/14549535*n^7) * eps^2 - + (11/315 - 368/3465*n - 32/6435*n^2 + 976/4095*n^3 - 154048/765765*n^4 + 368/11115*n^5 + 5216/1322685*n^6) * eps^3 - + (4/1155 + 1088/45045*n - 128/1287*n^2 + 64/3927*n^3 + 2877184/14549535*n^4 - 370112/2078505*n^5) * eps^4 - + (97/15015 - 464/45045*n + 4192/153153*n^2 - 88240/969969*n^3 + 31168/1322685*n^4) * eps^5 - + (10/9009 + 4192/765765*n - 188096/14549535*n^2 + 23392/855855*n^3) * eps^6 - + (193/85085 - 6832/2078505*n + 106976/14549535*n^2) * eps^7 - + (632/1322685 + 3456/1616615*n) * eps^8 - + 107/101745 * eps^9; -C4[1] = + (1/45 - 16/315*n + 32/945*n^2 - 16/3465*n^3 - 64/135135*n^4 - 16/135135*n^5 - 32/765765*n^6 - 112/6235515*n^7 - 128/14549535*n^8) * eps - - (2/105 - 64/945*n + 128/1485*n^2 - 1984/45045*n^3 + 256/45045*n^4 + 64/109395*n^5 + 128/855855*n^6 + 2368/43648605*n^7) * eps^2 - - (1/105 - 16/2079*n - 5792/135135*n^2 + 3568/45045*n^3 - 103744/2297295*n^4 + 264464/43648605*n^5 + 544/855855*n^6) * eps^3 - + (4/1155 - 2944/135135*n + 256/9009*n^2 + 17536/765765*n^3 - 3053056/43648605*n^4 + 1923968/43648605*n^5) * eps^4 - + (1/9009 + 16/19305*n - 2656/153153*n^2 + 65072/2078505*n^3 + 526912/43648605*n^4) * eps^5 - + (10/9009 - 1472/459459*n + 106112/43648605*n^2 - 204352/14549535*n^3) * eps^6 - + (349/2297295 + 28144/43648605*n - 32288/8729721*n^2) * eps^7 - + (632/1322685 - 44288/43648605*n) * eps^8 - + 43/479655 * eps^9; -C4[2] = + (4/525 - 32/1575*n + 64/3465*n^2 - 32/5005*n^3 + 128/225225*n^4 + 32/765765*n^5 + 64/8083075*n^6 + 32/14549535*n^7) * eps^2 - - (8/1575 - 128/5775*n + 256/6825*n^2 - 6784/225225*n^3 + 4608/425425*n^4 - 128/124355*n^5 - 5888/72747675*n^6) * eps^3 - - (8/1925 - 1856/225225*n - 128/17325*n^2 + 42176/1276275*n^3 - 2434816/72747675*n^4 + 195136/14549535*n^5) * eps^4 - + (8/10725 - 128/17325*n + 64256/3828825*n^2 - 128/25935*n^3 - 266752/10392525*n^4) * eps^5 - - (4/25025 + 928/3828825*n + 292288/72747675*n^2 - 106528/6613425*n^3) * eps^6 - + (464/1276275 - 17152/10392525*n + 83456/72747675*n^2) * eps^7 - + (1168/72747675 + 128/1865325*n) * eps^8 - + 208/1119195 * eps^9; -C4[3] = + (8/2205 - 256/24255*n + 512/45045*n^2 - 256/45045*n^3 + 1024/765765*n^4 - 256/2909907*n^5 - 512/101846745*n^6) * eps^3 - - (16/8085 - 1024/105105*n + 2048/105105*n^2 - 1024/51051*n^3 + 4096/373065*n^4 - 1024/357357*n^5) * eps^4 - - (136/63063 - 256/45045*n + 512/1072071*n^2 + 494336/33948915*n^3 - 44032/1996995*n^4) * eps^5 - + (64/315315 - 16384/5360355*n + 966656/101846745*n^2 - 868352/101846745*n^3) * eps^6 - - (16/97461 + 14848/101846745*n + 74752/101846745*n^2) * eps^7 - + (5024/33948915 - 96256/101846745*n) * eps^8 - - 1744/101846745 * eps^9; -C4[4] = + (64/31185 - 512/81081*n + 1024/135135*n^2 - 512/109395*n^3 + 2048/1247103*n^4 - 2560/8729721*n^5) * eps^4 - - (128/135135 - 2048/405405*n + 77824/6891885*n^2 - 198656/14549535*n^3 + 8192/855855*n^4) * eps^5 - - (512/405405 - 2048/530145*n + 299008/130945815*n^2 + 280576/43648605*n^3) * eps^6 - + (128/2297295 - 2048/1438965*n + 241664/43648605*n^2) * eps^7 - - (17536/130945815 + 1024/43648605*n) * eps^8 - + 2944/43648605 * eps^9; -C4[5] = + (128/99099 - 2048/495495*n + 4096/765765*n^2 - 6144/1616615*n^3 + 8192/4849845*n^4) * eps^5 - - (256/495495 - 8192/2807805*n + 376832/53348295*n^2 - 8192/855855*n^3) * eps^6 - - (6784/8423415 - 432128/160044885*n + 397312/160044885*n^2) * eps^7 - + (512/53348295 - 16384/22863555*n) * eps^8 - - 16768/160044885 * eps^9; -C4[6] = + (512/585585 - 4096/1422135*n + 8192/2078505*n^2 - 4096/1322685*n^3) * eps^6 - - (1024/3318315 - 16384/9006855*n + 98304/21015995*n^2) * eps^7 - - (103424/189143955 - 8192/4203199*n) * eps^8 - - 1024/189143955 * eps^9; -C4[7] = + (1024/1640925 - 65536/31177575*n + 131072/43648605*n^2) * eps^7 - - (2048/10392525 - 262144/218243025*n) * eps^8 - - 84992/218243025 * eps^9; -C4[8] = + (16384/35334585 - 131072/82447365*n) * eps^8 - - 32768/247342095 * eps^9; -C4[9] = + 32768/92147055 * eps^9; -\endverbatim - -\section geodellip Geodesics in terms of elliptic integrals - -GeographicLib::GeodesicExact and GeographicLib::GeodesicLineExact solve -the geodesic problem using elliptic integrals. The formulation of -geodesic in terms of incomplete elliptic integrals is given in - - C. F. F. Karney, - Geodesics - on an ellipsoid of revolution, - Feb. 2011; preprint - arxiv:1102.1215v1. - . -It is most convenient to use the form derived for a prolate ellipsoid in -Appendix D. For an oblate ellipsoid this results in elliptic integrals -with an imaginary modulus. However, the integrals themselves are real -and the algorithms used to compute the elliptic integrals handles the -case of an imaginary modulus using real arithmetic. - -The key relations used by %GeographicLib are -\f[ - \begin{aligned} - \frac sb &= E(\sigma, ik), \\ - \lambda &= (1 - f) \sin\alpha_0 G(\sigma, \cos^2\alpha_0, ik) \\ - &= \chi - - \frac{e'^2}{\sqrt{1+e'^2}}\sin\alpha_0 H(\sigma, -e'^2, ik), \\ - J(\sigma) &= k^2 D(\sigma, ik), - \end{aligned} -\f] -where \f$ \chi \f$ is a modified spherical longitude given by -\f[ -\tan\chi = \sqrt{\frac{1+e'^2}{1+k^2\sin^2\sigma}}\tan\omega, -\f] -and -\f[ - \begin{aligned} - D(\phi,k) &= \int_0^\phi - \frac{\sin^2\theta}{\sqrt{1 - k^2\sin^2\theta}}\,d\theta\\ - &=\frac{F(\phi, k) - E(\phi, k)}{k^2},\\ - G(\phi,\alpha^2,k) &= \int_0^\phi - \frac{\sqrt{1 - k^2\sin^2\theta}}{1 - \alpha^2\sin^2\theta}\,d\theta\\ - &=\frac{k^2}{\alpha^2}F(\phi, k) - +\biggl(1-\frac{k^2}{\alpha^2}\biggr)\Pi(\phi, \alpha^2, k),\\ - H(\phi, \alpha^2, k) - &= \int_0^\phi - \frac{\cos^2\theta}{(1-\alpha^2\sin^2\theta)\sqrt{1-k^2\sin^2\theta}} - \,d\theta \\ - &= - \frac1{\alpha^2} F(\phi, k) + - \biggl(1 - \frac1{\alpha^2}\biggr) \Pi(\phi, \alpha^2, k), - \end{aligned} -\f] -and \f$F(\phi, k)\f$, \f$E(\phi, k)\f$, \f$D(\phi, k)\f$, and -\f$\Pi(\phi, \alpha^2, k)\f$, are incomplete elliptic integrals (see -http://dlmf.nist.gov/19.2.ii). The formula for \f$ s \f$ and the -first expression for \f$ \lambda \f$ are given by Legendre (1811) and -are the most common representation of geodesics in terms of elliptic -integrals. The second (equivalent) expression for \f$ \lambda \f$, -which was given by Cayley (1870), is useful in that the elliptic -integral is relegated to a small correction term. This form allows -the longitude to be computed more accurately and is used in -%GeographicLib. (The equivalence of the two expressions for \f$ -\lambda \f$ follows from http://dlmf.nist.gov/19.7.E8.) - -Nominally, GeographicLib::GeodesicExact and -GeographicLib::GeodesicLineExact will give "exact" results for any value -of the flattening. However, the geographic latitude is a distorted -measure of distance from the equator with very eccentric ellipsoids and -this introducing an irreducible representational error in the algorithms -in this case. It is therefore recommended to restrict the use of these -classes to \e b/\e a ∈ [0.01, 100] or \e f ∈ [-99, 0.99]. -Note that GeographicLib::GeodesicExact still uses a series expansion for -the area \e S12. However the series is taken out to 30th order and -gives accurate results for \e b/\e a ∈ [1/2, 2]; the accuracy is -about 8 decimal digits for \e b/\e a ∈ [1/4, 4]. Additional work -planned for this aspect of the geodesic problem: -- formulate the area integral \e S12 in terms of elliptic integrals; -- generate accurate test geodesics for highly eccentric ellipsoids so - that the roundoff errors can be quantified. - -Thomas (1952) and Rollins (2010) use a different independent variable -for geodesics, \f$\theta\f$ instead of \f$\sigma\f$, where \f$ -\tan\theta = \sqrt{1 + k^2} \tan\sigma \f$. The corresponding -expressions for \f$ s \f$ and \f$ \lambda \f$ are given here for -completeness: -\f[ -\begin{aligned} -\frac sb &= \sqrt{1-k'^2} \Pi(\theta, k'^2, k'), \\ -\lambda &= (1-f) \sqrt{1-k'^2} \sin\alpha_0 \Pi(\theta, k'^2/e^2, k'), -\end{aligned} -\f] -where \f$ k' = k/\sqrt{1 + k^2} \f$. The expression for \f$ s \f$ -can be written in terms of elliptic integrals of the second kind and -Cayley's technique can be used to subtract out the leading order -behavior of \f$ \lambda \f$ to give -\f[ -\begin{aligned} -\frac sb &=\frac1{\sqrt{1-k'^2}} - \biggl( E(\theta, k') - - \frac{k'^2 \sin\theta \cos\theta}{\sqrt{1-k'^2\sin^2\theta}} \biggr), \\ -\lambda &= \psi + (1-f) \sqrt{1-k'^2} \sin\alpha_0 -\bigl( F(\theta, k') - \Pi(\theta, e^2, k') \bigr), -\end{aligned} -\f] -where -\f[ -\begin{aligned} -\tan\psi &= \sqrt{\frac{1+k^2\sin^2\sigma}{1+e'^2}}\tan\omega \\ - &= \sqrt{\frac{1-e^2}{1+k^2\cos^2\theta}}\sin\alpha_0\tan\theta. -\end{aligned} -\f] -The tangents of the three "longitude-like" angles are in geometric -progression, \f$ \tan\chi/\tan\omega = \tan\omega/\tan\psi \f$. - -\section meridian Parameters for the meridian - -The formulas for \f$ s \f$ given in the previous section are the same as -those for the distance along a meridian for an ellipsoid with equatorial -radius \f$ a \sqrt{1 - e^2 \sin^2\alpha_0} \f$ and polar semi-axis \f$ b -\f$. Here is a list of possible ways of expressing the meridian -distance in terms of elliptic integrals using the notation: -- \f$ a \f$, equatorial axis, -- \f$ b \f$, polar axis, -- \f$ e = \sqrt{(a^2 - b^2)/a^2} \f$, eccentricity, -- \f$ e' = \sqrt{(a^2 - b^2)/b^2} \f$, second eccentricity, -- \f$ \phi = \mathrm{am}(u, e) \f$, the geographic latitude, -- \f$ \phi' = \mathrm{am}(v', ie') = \pi/2 - \phi \f$, - the geographic colatitude, -- \f$ \beta = \mathrm{am}(v, ie') \f$, the parametric latitude - (\f$ \tan^2\beta = (1 - e^2) \tan^2\phi \f$), -- \f$ \beta' = \mathrm{am}(u', e) = \pi/2 - \beta \f$, - the parametric colatitude, -- \f$ M \f$, the length of a quarter meridian (equator to pole), -- \f$ y \f$, the distance along the meridian (measured from the equator). -- \f$ y' = M -y \f$, the distance along the meridian (measured from the pole). -. -The eccentricities \f$ (e, e') \f$ are real (resp. imaginary) for -oblate (resp. prolate) ellipsoids. The elliptic variables \f$(u, -u')\f$ and \f$(v, v')\f$ are defined by -- \f$ u = F(\phi, e) ,\quad u' = F(\beta', e) \f$ -- \f$ v = F(\beta, ie') ,\quad v' = F(\phi', ie') \f$, -. -and are linearly related by -- \f$ u + u' = K(e) ,\quad v + v' = K(ie') \f$ -- \f$ v = \sqrt{1-e^2} u ,\quad u = \sqrt{1+e'^2} v \f$. -. -The cartesian coordinates for the meridian \f$ (x, y) \f$ are given by -\f[ -\begin{aligned} - x &= a \cos\beta = a \cos\phi / \sqrt{1 - e^2 \sin^2\phi} \\ - &= a \sin\beta' = (a^2/b) \sin\phi' / \sqrt{1 + e'^2 \sin^2\phi'} \\ - &= a \,\mathrm{cn}(v, ie) = a \,\mathrm{cd}(u, e) \\ - &= a \,\mathrm{sn}(u', e) = (a^2/b) \,\mathrm{sd}(v', ie'), -\end{aligned} -\f] -\f[ -\begin{aligned} - z &= b \sin\beta = (b^2/a) \sin\phi / \sqrt{1 - e^2 \sin^2\phi} \\ - &= b \cos\beta' = b \cos\phi' / \sqrt{1 + e'^2 \sin^2\phi'} \\ - &= b \,\mathrm{sn}(v, ie) = (b^2/a) \,\mathrm{sd}(u, e) \\ - &= b \,\mathrm{cn}(u', e) = b \,\mathrm{cd}(v', ie'). -\end{aligned} -\f] -The distance along the meridian can be expressed variously as -\f[ -\begin{aligned} - y &= b \int \sqrt{1 + e'^2 \sin^2\beta}\, d\beta - = b E(\beta, ie') \\ - &= \frac{b^2}a \int \frac1{(1 - e^2 \sin^2\phi)^{3/2}}\, d\phi - = \frac{b^2}a \Pi(\phi, e^2, e) \\ - &= a \biggl(E(\phi, e) - - \frac{e^2\sin\phi \cos\phi}{\sqrt{1 - e^2\sin^2\phi}}\biggr) \\ - &= b \int \mathrm{dn}^2(v, ie')\, dv - = \frac{b^2}a \int \mathrm{nd}^2(u, e)\, du - = \cal E(v, ie'), -\end{aligned} -\f] -\f[ -\begin{aligned} - y' &= a \int \sqrt{1 - e^2 \sin^2\beta'}\, d\beta' - = a E(\beta', e) \\ - &= \frac{a^2}b \int \frac1{(1 + e'^2 \sin^2\phi')^{3/2}}\, d\phi' - = \frac{a^2}b \Pi(\phi', -e'^2, ie') \\ - &= b \biggl(E(\phi', ie') + - \frac{e'^2\sin\phi' \cos\phi'}{\sqrt{1 + e'^2\sin^2\phi'}}\biggr) \\ - &= a \int \mathrm{dn}^2(u', e)\, du' - = \frac{a^2}b \int \mathrm{nd}^2(v', ie')\, dv' - = \cal E(u', e), -\end{aligned} -\f] -with the quarter meridian distance given by -\f[ - M = aE(e) = bE(ie') = (b^2/a)\Pi(e^2,e) = (a^2/b)\Pi(-e'^2,ie'). -\f] -(Here \f$ E, F, \Pi \f$ are elliptic integrals defined in -http://dlmf.nist.gov/19.2.ii. \f$ \cal E, \mathrm{am}, \mathrm{sn}, -\mathrm{cn}, \mathrm{sd}, \mathrm{cd}, \mathrm{dn}, \mathrm{nd} \f$ are -Jacobi elliptic functions defined in http://dlmf.nist.gov/22.2 and -http://dlmf.nist.gov/22.16.) - -There are several considerations in the choice of independent variable -for evaluate the meridian distance -- The use of an imaginary modulus (namely, \f$ ie' \f$, above) is of no - practical concern. The integrals are real in this case and modern - methods (%GeographicLib uses the method given in - http://dlmf.nist.gov/19.36.i) for computing integrals handles this - case using just real arithmetic. -- If the "natural" origin is the equator, choose one of \f$ \phi, \beta, - u, v \f$ (this might be preferred in geodesy). If it's the pole, - choose one of the complementary quantities \f$ \phi', \beta', u', v' - \f$ (this might be preferred by mathematicians). -- Applying these formulas to the geodesic problems, \f$ \beta \f$ - becomes the arc length, \f$ \sigma \f$, on the auxiliary sphere. This - is the traditional method of solution used by Legendre (1806), Oriani - (1806), Bessel (1825), Helmert (1880), Rainsford (1955), Thomas - (1970), Vincenty (1975), Rapp (1993), and so on. Many of the - solutions in terms of elliptic functions use one of the elliptic - variables (\f$ u \f$ or \f$ v \f$), see, for example, Jacobi (1855), - Halphen (1888), Forsyth (1896). In the context of geodesics \f$ - \phi \f$ becomes Thomas' variable \f$ \theta \f$; this is used by - Thomas (1952) and Rollins (2010) in their formulation of the - geodesic problem (see the previous section). -- For highly eccentric ellipsoids the variation of the meridian with - respect to \f$ \beta \f$ is considerably "better behaved" than other - choices (see the figure below). The choice of \f$ \phi \f$ is - probably a poor one in this case. -. -%GeographicLib uses the geodesic generalization of -\f$ y = b E(\beta, ie') \f$, namely \f$ s = b E(\sigma, ik) \f$. See -\ref geodellip. - -\image html meridian-measures.png "Comparison of meridian measures" - -\section geodshort Short geodesics - -Here we describe Bowring's method for solving the inverse geodesic -problem in the limit of short geodesics and contrast it with the great -circle solution using Bessel's auxiliary sphere. References: - - B. R. Bowring, The Direct and Inverse Problems for Short Geodesic - Lines on the Ellipsoid, Surveying and Mapping 41(2), 135--141 (1981). - - R. H. Rapp, - - Geometric Geodesy, Part I, Ohio State Univ. (1991), Sec. 6.5. - -Bowring considers the conformal mapping of the ellipsoid to a sphere of -radius \f$ R \f$ such that circles of latitude and meridians are -preserved (and hence the azimuth of a line is preserved). Let \f$ -(\phi, \lambda) \f$ and \f$ (\phi', \lambda') \f$ be the latitude and -longitude on the ellipsoid and sphere respectively. Define isometric -latitudes for the sphere and the ellipsoid as -\f[ -\begin{aligned} - \psi' &= \sinh^{-1} \tan \phi', \\ - \psi &= \sinh^{-1} \tan \phi - e \tanh^{-1}(e \sin\phi). -\end{aligned} -\f] -The most general conformal mapping satisfying Bowring's conditions is -\f[ -\psi' = A \psi + K, \quad \lambda' = A \lambda, -\f] -where \f$ A \f$ and \f$ K \f$ are constants. (In fact a constant can be -added to the equation for \f$ \lambda' \f$, but this does affect the -analysis.) The scale of this mapping is -\f[ -m(\phi) = \frac{AR}{\nu}\frac{\cos\phi'}{\cos\phi}, -\f] -where \f$ \nu = a/\sqrt{1 - e^2\sin^2\phi} \f$ is the transverse radius -of curvature. (Note that in Bowring's Eq. (10), \f$ \phi \f$ should be -replaced by \f$ \phi' \f$.) The mapping from the ellipsoid to the sphere -depends on three parameters \f$ R, A, K \f$. These will be selected to -satisfy certain conditions at some representative latitude \f$ \phi_0 -\f$. Two possible choices are given below. - -\subsection bowring Bowring's method - -Bowring (1981) requires that -\f[ -m(\phi_0) = 1,\quad -\left.\frac{dm(\phi)}{d\phi}\right|_{\phi=\phi_0} = 0,\quad -\left.\frac{d^2m(\phi)}{d\phi^2}\right|_{\phi=\phi_0} = 0, -\f] -i.e, \f$m\approx 1\f$ in the vicinity of \f$\phi = \phi_0\f$. -This gives -\f[ -\begin{aligned} -R &= \frac{\sqrt{1 + e'^2}}{B^2} a, \\ -A &= \sqrt{1 + e'^2 \cos^4\phi_0}, \\ -\tan\phi'_0 &= \frac1B \tan\phi_0, -\end{aligned} -\f] -where \f$ e' = e/\sqrt{1-e^2} \f$ is the second eccentricity, \f$ B = -\sqrt{1+e'^2\cos^2\phi_0} \f$, and \f$ K \f$ is defined implicitly by -the equation for \f$\phi'_0\f$. The radius \f$ R \f$ is the (Gaussian) -mean radius of curvature of the ellipsoid at \f$\phi_0\f$ (so near -\f$\phi_0\f$ the ellipsoid can be deformed to fit the sphere snugly). -The third derivative of \f$ m \f$ is given by -\f[ -\left.\frac{d^3m(\phi)}{d\phi^3}\right|_{\phi=\phi_0} = -\frac{-2e'^2\sin2\phi_0}{B^4}. -\f] - -The method for solving the inverse problem between two nearby points \f$ -(\phi_1, \lambda_1) \f$ and \f$ (\phi_2, \lambda_2) \f$ is as follows: -Set \f$\phi_0 = (\phi_1 + \phi_2)/2\f$. Compute \f$ R, A, \phi'_0 \f$, -and hence find \f$ (\phi'_1, \lambda'_1) \f$ and \f$ (\phi'_2, -\lambda'_2) \f$. Finally, solve for the great circle on a sphere of -radius \f$ R \f$; the resulting distance and azimuths are good -approximations for the corresponding quantities for the ellipsoidal -geodesic. - -Consistent with the accuracy of this method, we can compute -\f$\phi'_1\f$ and \f$\phi'_2\f$ using a Taylor expansion about -\f$\phi_0\f$. This also avoids numerical errors that arise from -subtracting nearly equal quantities when using the equation for -\f$\phi'\f$ directly. Write \f$\Delta \phi = \phi - \phi_0\f$ and -\f$\Delta \phi' = \phi' - \phi'_0\f$; then we have -\f[ -\Delta\phi' \approx -\frac{\Delta\phi}B \biggl[1 + -\frac{\Delta\phi}{B^2}\frac{e'^2}2 - \biggl(3\sin\phi_0\cos\phi_0 + - \frac{\Delta\phi}{B^2} - \bigl(B^2 - \sin^2\phi_0(2 - 3 e'^2 \cos^2\phi_0)\bigr)\biggr)\biggr], -\f] -where the error is \f$O(f\Delta\phi^4)\f$. -This is essentially Bowring's method. Significant differences between -this result, "Bowring (improved)", compared to Bowring's paper, "Bowring -(original)", are: - - Bowring elects to use \f$\phi_0 = \phi_1\f$. This simplifies the - calculations somewhat but increases the error by about a factor of - 4. - - Bowring's expression for \f$ \Delta\phi' \f$ is only accurate in the - limit \f$ e' \rightarrow 0 \f$. - . -In fact, arguably, the highest order \f$O(f\Delta\phi^3)\f$ terms should -be dropped altogether. Their inclusion does result in a better estimate -for the distance. However, if your goal is to generate both accurate -distances \e and accurate azimuths, then \f$\Delta\phi\f$ needs to be -restricted sufficiently to allow these terms to be dropped to give the -"Bowring (truncated)" method. - -With highly eccentric ellipsoids, the parametric latitude \f$ \beta \f$ -is a better behaved independent variable to use. In this case, \f$ -\phi_0 \f$ is naturally defined using \f$\beta_0 = (\beta_1 + -\beta_2)/2\f$ and in terms of \f$\Delta\beta = \beta - \beta_0\f$, we -have -\f[ -\Delta\phi' \approx -\frac{\Delta\beta}{B'} \biggl[1 + -\frac{\Delta\beta}{B'^2}\frac{e'^2}2 - \biggl(\sin\beta_0\cos\beta_0 + - \frac{\Delta\beta}{3B'^2} - \bigl( \cos^2\beta_0 - \sin^2\beta_0 B'^2\bigr) -\biggr)\biggr], -\f] -where \f$B' = \sqrt{1+e'^2\sin^2\beta_0} = \sqrt{1+e'^2}/B\f$, and the -error once again is \f$O(f\Delta\phi^4)\f$. This is the "Bowring -(using \f$\beta\f$)" method. - -\subsection auxsphere Bessel's auxiliary sphere - -%GeographicLib's uses the auxiliary sphere method of Legendre, Bessel, -and Helmert. For short geodesics, this is equivalent to picking -\f$ R, A, K \f$ so that -\f[ -m(\phi_0) = 1,\quad -\left.\frac{dm(\phi)}{d\phi}\right|_{\phi=\phi_0} = 0,\quad -\tan\phi'_0 = (1 - f) \tan\phi_0. -\f] -Bowring's requirement that the second derivative of \f$m\f$ vanish has -been replaced by the last relation which states that \f$\phi'_0 = -\beta_0\f$, the parametric latitude corresponding to \f$\phi_0\f$. This -gives -\f[ -\begin{aligned} -R &= B'(1-f)a, \\ -A &= \frac1{B'(1-f)}, \\ -\left.\frac{d^2m(\phi)}{d\phi^2}\right|_{\phi=\phi_0} &= --e^2B'^2\sin^2\phi_0. -\end{aligned} -\f] - -Similar to Bowring's method, we can compute \f$\phi'_1\f$ and -\f$\phi'_2\f$ using a Taylor expansion about \f$\beta_0\f$. This results -in the simple expression -\f[ -\Delta\phi' \approx \Delta\beta, -\f] -where the error is \f$O(f\Delta\beta^2)\f$. - -\subsection shorterr Estimating the accuracy - -In assessing the accuracy of these methods we use two metrics: - - The absolute error in the distance. - - The consistency of the predicted azimuths. Imagine starting - ellipsoidal geodesics at \f$ (\phi_1, \lambda_1) \f$ and \f$ (\phi_2, - \lambda_2) \f$ with the predicted azimuths. What is the distance - between them when they are extended a distance \f$ a \f$ beyond the - second point? - . -(The second metric is much more stringent.) We may now compare the -methods by asking for a bound to the length of a geodesic which ensures -that the one or other of the errors fall below 1 mm (an "engineering" -definition of accurate) or 1 nm (1 nanometer, about the round-off -limit). - -
- - - - - - - - - - - - - - - -
Maximum distance that can be used in various methods for -computing short geodesics while keeping the errors within prescribed -bounds
method -
distance metric
azimuth metric
1 mm error1 nm error1 mm error1 nm error
Bowring (original) -
87 km
-
870 m
-
35 km
-
350 m
-
Bowring (improved) -
180 km
-
1.8 km
-
58 km
-
580 m
-
Bowring (truncated) -
52 km
-
520 m
-
52 km
-
520 m
-
Bowring (using \f$\beta\f$) -
380 km
-
24 km
-
60 km
-
600 m
-
Bessel's aux. sphere -
42 km
-
420 m
-
1.7 km
-
1.7 m
-
-
- -For example, if you're only interested in measuring distances and an -accuracy of 1 mm is sufficient, then Bowring's improved method can be -used for distances up to 180 km. On the other hand, %GeographicLib uses -Bessel's auxiliary sphere and we require both the distance and the -azimuth to be accurate, so the great circle approximation can only be -used for distances less than 1.7 m. The reason that %GeographicLib does -not use Bowring's method is that the information necessary for auxiliary -sphere method is already available as part of the general solution and, -as much as possible, we allow all geodesics to be computed by the -general method. - -
-Back to \ref magnetic. Forward to \ref triaxial. Up to \ref contents. -
-**********************************************************************/ -/** -\page triaxial Geodesics on a triaxial ellipsoid - -
-Back to \ref geodesic. Forward to \ref transversemercator. Up to -\ref contents. -
- -Jacobi (1839) showed that the problem of geodesics on a triaxial -ellipsoid (with 3 unequal axes) can be reduced to quadrature. Despite -this, the detailed behavior of the geodesics is not very well known. In -this section, I briefly give Jacobi's solution and illustrate the -behavior of the geodesics and outline an algorithm for the solution of -the inverse problem. - -See also - - The wikipedia page, - - Geodesics on a triaxial ellipsoid. - -Go to - - \ref triaxial-coords - - \ref triaxial-jacobi - - \ref triaxial-survey - - \ref triaxial-stab - - \ref triaxial-inverse - -NOTES - -# A triaxial ellipsoid approximates the earth only slightly better - than an ellipsoid of revolution. If you are really considering - measuring distances on the earth using a triaxial ellipsoid, you - should also be worrying about the shape of the geoid, which - essentially makes the geodesic problem a hopeless mess; see, for - example, Waters - (2011). - -# There is nothing new in this section. It is just an exercise in - exploring Jacobi's solution. My interest here is in generating long - geodesics with the correct long-time behavior. Arnold gives a - nice qualitative description of the solution in Mathematical - Methods of Classical Mechanics (2nd edition, Springer, 1989), - pp. 264--266. - -# Possible reasons this problem might, nevertheless, be of interest - are: - - It is the first example of a dynamical system which has a - non-trivial constant of motion. As such, Jacobi's paper generated - a lot of excitement and was followed by many papers elaborating - his solution. In particular, the unstable behavior of one of the - closed geodesics of the ellipsoid, is an early example of a system - with a positive Lyapunov exponent (one of the essential - ingredients for chaotic behavior in dynamical systems). - - Knowledge of ellipsoidal coordinates (used by Jacobi) might be - useful in other areas of geodesy. - - Geodesics which pass through the pole on an ellipsoid of revolution - represent a degenerate class (they are all closed and all pass - through the opposite pole). It is of interest to see how this - degeneracy is broken with a surface with a more general shape. - -# My interest in this problem was piqued by Jean-Marc Baillard. I put - him onto Jacobi's solution without having looked at it in detail - myself; and he quickly implemented the solution for an HP-41 - calculator(!) which is posted - here. - -# I do not give full citations of the papers here. You can find these - in the - - Online Geodesic Bibliography; this includes links to online - versions of the papers. - -# An alternative to exploring geodesics using Jacobi's solution is to - integrate the equations for the geodesics directly. This is the - approach taken by - - Oliver Knill and Michael Teodorescu. However it is difficult to - ensure that the long time behavior is correctly modeled with such an - approach. - -# At this point, I have no plans to add the solution of triaxial - geodesic problem to %GeographicLib. - -# If you only want to learn about geodesics on a biaxial ellipsoid (an - ellipsoid of revolution), then see \ref geodesic or the paper - - C. F. F. Karney, - - Algorithms for geodesics, - J. Geodesy 87(1), 43--55 (Jan. 2013); - DOI: - 10.1007/s00190-012-0578-z; - addenda: - geod-addenda.html. - -\section triaxial-coords Triaxial coordinate systems - -Consider the ellipsoid defined by -\f[ - f = \frac{x^2}{a^2} + \frac{y^2}{b^2} + \frac{z^2}{c^2} = 1, -\f] -where, without loss of generality, \f$ a \ge b \ge c \gt 0\f$. A -point on the surface is specified by a latitude and longitude. The \e -geographical latitude and longitude \f$(\phi, \lambda)\f$ are defined by -\f[ - \frac{\nabla f}{\left| \nabla f\right|} = \left( -\begin{array}{c} \cos\phi \cos\lambda \\ \cos\phi \sin\lambda \\ \sin\phi -\end{array}\right). -\f] -The \e parametric latitude and longitude \f$(\phi', \lambda')\f$ are -defined by -\f[ -\begin{aligned} - x &= a \cos\phi' \cos\lambda', \\ - y &= b \cos\phi' \sin\lambda', \\ - z &= c \sin\phi'. -\end{aligned} -\f] -Jacobi employed the \e ellipsoidal latitude and longitude \f$(\beta, -\omega)\f$ defined by -\f[ -\begin{aligned} - x &= a \cos\omega - \frac{\sqrt{a^2 - b^2\sin^2\beta - c^2\cos^2\beta}} - {\sqrt{a^2 - c^2}}, \\ - y &= b \cos\beta \sin\omega, \\ - z &= c \sin\beta - \frac{\sqrt{a^2\sin^2\omega + b^2\cos^2\omega - c^2}} - {\sqrt{a^2 - c^2}}. -\end{aligned} -\f] -Grid lines of constant \f$\beta\f$ and \f$\omega\f$ are given in Fig. 1. - -
-Geodesic grid on a triaxial ellipsoid -Fig. 1 -
\n -Fig. 1: -The ellipsoidal grid. The blue (resp. green) lines are lines of constant -\f$\beta\f$ (resp. \f$\omega\f$); the grid spacing is 10°. Also -shown in red are two of the principal sections of the ellipsoid, defined -by \f$x = 0\f$ and \f$z = 0\f$. The third principal section, \f$y = -0\f$, is covered by the lines \f$\beta = \pm 90^\circ\f$ and \f$\omega = -90^\circ \pm 90^\circ\f$. These lines meet at four umbilical points (two -of which are visible in this figure) where the principal radii of -curvature are equal. The parameters of the ellipsoid are \f$a = -1.01\f$, \f$b = 1\f$, \f$c = 0.8\f$, and it is viewed in an orthographic -projection from a point above \f$\phi = 40^\circ\f$, \f$\lambda = -30^\circ\f$. These parameters were chosen to accentuate the ellipsoidal -effects on geodesics (relative to those on the earth) while still -allowing the connection to an ellipsoid of revolution to be made. - -The grid lines of the ellipsoid coordinates are "lines of curvature" on -the ellipsoid, i.e., they are parallel to the direction of principal -curvature (Monge, 1796). They are also intersections of the ellipsoid -with confocal systems of hyperboloids of one and two sheets (Dupin, -1813). Finally they are geodesic ellipses and hyperbolas defined using -two adjacent umbilical points. For example, the lines of constant -\f$\beta\f$ in Fig. 1 can be generated with the familiar string -construction for ellipses with the ends of the string pinned to the two -umbilical points. - -Inter-conversions between these three latitudes and longitudes and the -cartesian coordinates are simple algebraic exercises. - -\section triaxial-jacobi Jacobi's solution - -Solving the geodesic problem for an ellipsoid of revolution is, from the -mathematical point of view, trivial; because of symmetry, geodesics have -a constant of the motion (analogous to the angular momentum) which was -found by Clairaut (1733). By 1806 (with the work of Legendre, Oriani, -et al.), there was a complete understanding of the qualitative behavior -of geodesics on an ellipsoid of revolution. - -On the other hand, geodesics on a triaxial ellipsoid have no obvious -constant of the motion and thus represented a challenging "unsolved" -problem in the first half of the nineteenth century. Jacobi discovered -that the geodesic equations are separable if they are expressed in -ellipsoidal coordinates. You can get an idea of the importance Jacobi -attached to his discovery from the - -letter he wrote to his friend and neighbor Bessel: -
The day before yesterday, I reduced to quadrature the -problem of geodesic lines on an ellipsoid with three unequal -axes. They are the simplest formulas in the world, Abelian -integrals, which become the well known elliptic integrals if 2 axes are -set equal.\n -Königsberg, 28th Dec. '38. -
- -On the same day he wrote a similar letter to the editor of Compte Rendus -and his result was published in J. Crelle in (1839) with a French -translation (from German) appearing in J. Liouville in (1841). - -Here is the solution, exactly as given by Jacobi - here -(with minor changes in notation): -\f[ -\begin{aligned} -\delta &= \int \frac -{\sqrt{b^2\sin^2\beta + c^2\cos^2\beta}\,d\beta} -{\sqrt{a^2 - b^2\sin^2\beta - c^2\cos^2\beta} - \sqrt{(b^2-c^2)\cos^2\beta - \gamma}}\\ -&\quad - -\int \frac -{\sqrt{a^2\sin^2\omega + b^2\cos^2\omega}\,d\omega} -{\sqrt{a^2\sin^2\omega + b^2\cos^2\omega - c^2} - \sqrt{(a^2-b^2)\sin^2\omega + \gamma}} -\end{aligned} -\f] -As Jacobi notes "a function of the angle \f$\beta\f$ equals a -function of the angle \f$\omega\f$. These two functions are just -Abelian integrals..." Two constants \f$\delta\f$ and \f$\gamma\f$ -appear in the solution. Typically \f$\delta\f$ is zero if the lower -limits of the integrals are taken to be the starting point of the geodesic -and the direction of the geodesics is determined by \f$\gamma\f$. -However for geodesics that start at an umbilical points, we have \f$\gamma -= 0\f$ and \f$\delta\f$ determines the direction at the umbilical point. -Incidentally the constant \f$\gamma\f$ may be expressed as -\f[ -\gamma = (b^2-c^2)\cos^2\beta\sin^2\alpha-(a^2-b^2)\sin^2\omega\cos^2\alpha -\f] -where \f$\alpha\f$ is the angle the geodesic makes with lines of -constant \f$\omega\f$. In the limit \f$a\rightarrow b\f$, this reduces -to \f$\cos\beta\sin\alpha = \text{const.}\f$, the familiar Clairaut -relation. A nice derivation of Jacobi's result is given by Darboux -(1894) -§§583--584 where he gives the solution found by Liouville -(1846) for general quadratic surfaces. In this formulation, the -distance along the geodesic, \f$s\f$, is also found using -\f[ -\begin{aligned} -\frac{ds}{(b^2-c^2)\cos^2\beta + (a^2-b^2)\sin^2\omega} -&= \frac -{\sqrt{b^2\sin^2\beta + c^2\cos^2\beta}\,d\beta} -{\sqrt{a^2 - b^2\sin^2\beta - c^2\cos^2\beta} - \sqrt{(b^2-c^2)\cos^2\beta - \gamma}}\\ -&= \frac -{\sqrt{a^2\sin^2\omega + b^2\cos^2\omega}\,d\omega} -{\sqrt{a^2\sin^2\omega + b^2\cos^2\omega - c^2} - \sqrt{(a^2-b^2)\sin^2\omega + \gamma}} -\end{aligned} -\f] -An alternative expression for the distance is -\f[ -\begin{aligned} -ds -&= \frac -{\sqrt{b^2\sin^2\beta + c^2\cos^2\beta} - \sqrt{(b^2-c^2)\cos^2\beta - \gamma}\,d\beta} -{\sqrt{a^2 - b^2\sin^2\beta - c^2\cos^2\beta}}\\ -&\quad {}+ \frac -{\sqrt{a^2\sin^2\omega + b^2\cos^2\omega} - \sqrt{(a^2-b^2)\sin^2\omega + \gamma}\,d\omega} -{\sqrt{a^2\sin^2\omega + b^2\cos^2\omega - c^2}} -\end{aligned} -\f] - -Jacobi's solution is a convenient way to compute geodesics on an -ellipsoid. Care must be taken with the signs of the square roots (which -are determined by the initial azimuth of the geodesic). Also if -\f$\gamma \gt 0\f$ (resp. \f$\gamma \lt 0\f$), then the \f$\beta\f$ -(resp. \f$\omega\f$) integrand diverges. The integrand can be -transformed into a finite one by a change of variable, e.g., -\f$\sin\beta = \sin\sigma \sqrt{1 - \gamma/(b^2-c^2)}\f$. The resulting -integrals are periodic, so the behavior of an arbitrarily long geodesic -is entirely captured by tabulating the integrals over a single period. - -The situation is more complicated if \f$\gamma = 0\f$ (corresponding to -umbilical geodesics). Both integrands have simple poles at the umbilical -points. However, this behavior may be subtracted from the integrands to -yield (for example) the sum of a term involving -\f$\tanh^{-1}\sin\beta\f$ and a finite integral. Since both integrals -contain similar logarithmic singularities they can be equated (thus -fixing the ratio \f$\cos\beta/\sin\omega\f$ at the umbilical point) and -connection formulas can be found which allow the geodesic to be followed -through the umbilical point. The study of umbilical geodesics was of -special interest to a group of Irish mathematicians in the 1840's and -1850's, including Michael and William Roberts (twins!), Hart, Graves, -and Salmon. - -\section triaxial-survey Survey of triaxial geodesics - -Before delving into the nature of geodesics on a triaxial geodesic, it -is worth reviewing geodesics on an ellipsoid of revolution. There are -two classes of simple closed geodesics (i.e., geodesics which close on -themselves without intersection): the equator and all the meridians. -All other geodesics oscillate between two equal and opposite circles of -latitude; but after completing a full oscillation in latitude these fall -slightly short (for an oblate ellipsoid) of completing a full circuit in -longitude. - -Turning to the triaxial case, we find that there are only 3 simple -closed geodesics, the three principal sections of the ellipsoid given by -\f$x = 0\f$, \f$y = 0\f$, and \f$z = 0\f$. To survey the other -geodesics, it is convenient to consider geodesics which intersect the -middle principal section, \f$y = 0\f$, at right angles. Such geodesics -are shown in Figs. 2--6, where I use the same ellipsoid parameters as in -Fig. 1 and the same viewing direction. In addition, the three principal -ellipses are shown in red in each of these figures. - -If the starting point is \f$\beta_1 \in (-90^\circ, 90^\circ)\f$, -\f$\omega_1 = 0\f$, and \f$\alpha_1 = 90^\circ\f$, then the geodesic -encircles the ellipsoid in a "circumpolar" sense. The geodesic -oscillates north and south of the equator; on each oscillation it -completes slightly less that a full circuit around the ellipsoid -resulting in the geodesic filling the area bounded by the two latitude -lines \f$\beta = \pm \beta_1\f$. Two examples are given in -Figs. 2 and 3. Figure 2 shows practically the same behavior as for an -oblate ellipsoid of revolution (because \f$a \approx b\f$). However, if -the starting point is at a higher latitude (Fig. 3) the distortions -resulting from \f$a \ne b\f$ are evident. - -
-Example of a circumpolar geodesic on a
-triaxial ellipsoid -Fig. 2 -
\n -Fig. 2: -Example of a circumpolar geodesic on a triaxial ellipsoid. The starting -point of this geodesic is \f$\beta_1 = 45.1^\circ\f$, \f$\omega_1 = -0^\circ\f$, and \f$\alpha_1 = 90^\circ\f$. - -
-Another example of a circumpolar geodesic on a
-triaxial ellipsoid -Fig. 3 -
\n -Fig. 3: -Another example of a circumpolar geodesic on a triaxial ellipsoid. The -starting point of this geodesic is \f$\beta_1 = 87.48^\circ\f$, \f$\omega_1 = -0^\circ\f$, and \f$\alpha_1 = 90^\circ\f$. - -If the starting point is \f$\beta_1 = 90^\circ\f$, \f$\omega_1 \in -(0^\circ, 180^\circ)\f$, and \f$\alpha_1 = 180^\circ\f$, then the geodesic -encircles the ellipsoid in a "transpolar" sense. The geodesic -oscillates east and west of the ellipse \f$x = 0\f$; on each oscillation -it completes slightly more that a full circuit around the ellipsoid -resulting in the geodesic filling the area bounded by the two longitude -lines \f$\omega = \omega_1\f$ and \f$\omega = 180^\circ - \omega_1\f$. -If \f$a = b\f$, all meridians are geodesics; the effect of \f$a \ne b\f$ -causes such geodesics to oscillate east and west. Two examples are -given in Figs. 4 and 5. - -
-Example of a transpolar geodesic on a
-triaxial ellipsoid -Fig. 4 -
\n -Fig. 4: -Example of a transpolar geodesic on a triaxial ellipsoid. The -starting point of this geodesic is \f$\beta_1 = 90^\circ\f$, \f$\omega_1 = -39.9^\circ\f$, and \f$\alpha_1 = 180^\circ\f$. - -
-Another example of a transpolar geodesic on a
-triaxial ellipsoid -Fig. 5 -
\n -Fig. 5: -Another example of a transpolar geodesic on a triaxial ellipsoid. The -starting point of this geodesic is \f$\beta_1 = 90^\circ\f$, \f$\omega_1 = -9.966^\circ\f$, and \f$\alpha_1 = 180^\circ\f$. - -If the starting point is \f$\beta_1 = 90^\circ\f$, \f$\omega_1 = -0^\circ\f$ (an umbilical point), and \f$\alpha_1 = 135^\circ\f$ (the -geodesic leaves the ellipse \f$y = 0\f$ at right angles), then the -geodesic repeatedly intersects the opposite umbilical point and returns to -its starting point. However on each circuit the angle at which it -intersects \f$y = 0\f$ becomes closer to \f$0^\circ\f$ or -\f$180^\circ\f$ so that asymptotically the geodesic lies on the ellipse -\f$y = 0\f$. This is shown in Fig. 6. Note that a single geodesic does -not fill an area on the ellipsoid. - -
-Example of an umbilical geodesic on a
-triaxial ellipsoid -Fig. 6 -
\n -Fig. 6: -Example of an umbilical geodesic on a triaxial ellipsoid. The -starting point of this geodesic is \f$\beta_1 = 90^\circ\f$, \f$\omega_1 = -0^\circ\f$, and \f$\alpha_1 = 135^\circ\f$ and the geodesics is followed -forwards and backwards until it lies close to the plane \f$y = 0\f$ in -both directions. - -Umbilical geodesics enjoy several interesting properties. - - Through any point on the ellipsoid, there are two umbilical geodesics. - - The geodesic distance between opposite umbilical points is the same - regardless of the initial direction of the geodesic. - - Whereas the closed geodesics on the ellipses \f$x = 0\f$ and \f$z = - 0\f$ are stable (an geodesic initially close to and nearly parallel to - the ellipse remains close to the ellipse), the closed geodesic on the - ellipse \f$y = 0\f$, which goes through all 4 umbilical points, is \e - unstable. If it is perturbed, it will swing out of the plane \f$y = - 0\f$ and flip around before returning to close to the plane. (This - behavior may repeat depending on the nature of the initial - perturbation.). - -\section triaxial-stab The stability of closed geodesics - -The stability of the three simple closed geodesics can be determined by -examining the properties of Jacobi's solution. In particular the -unstable behavior of umbilical geodesics was shown by Hart (1849). -However an alternative approach is to use the equations that Gauss -(1828) gives for a perturbed geodesic -\f[ -\frac {d^2m}{ds^2} + Km = 0 -\f] -where \f$m\f$ is the distance of perturbed geodesic from a reference -geodesic and \f$K\f$ is the Gaussian curvature of the surface. If the -reference geodesic is closed, then this is a linear homogeneous -differential equation with periodic coefficients. In fact it's a -special case of Hill's equation which can be treated using Floquet -theory, see DLMF, §28.29. -Using the notation of §3 of - Algorithms for -geodesics, the stability is determined by computing the reduced -length \f$m_{12}\f$ and the geodesic scales \f$M_{12}, M_{21}\f$ over -half the perimeter of the ellipse and determining the eigenvalues -\f$\lambda_{1,2}\f$ of -\f[ -{\cal M} = \left(\begin{array}{cc} -M_{12} & m_{12}\\ --\frac{1 - M_{12}M_{21}}{m_{12}} & M_{21} -\end{array}\right). -\f] -Because \f$\mathrm{det}\,{\cal M} = 1\f$, the eigenvalues are determined -by \f$\mathrm{tr}\,{\cal M}\f$. In particular if -\f$\left|\mathrm{tr}\,{\cal M}\right| < 2\f$, we have -\f$\left|\lambda_{1,2}\right| = 1\f$ and the solution is stable; if -\f$\left|\mathrm{tr}\,{\cal M}\right| > 2\f$, one of -\f$\left|\lambda_{1,2}\right|\f$ is larger than unity and the solution -is (exponentially) unstable. In the transition case, -\f$\left|\mathrm{tr}\,{\cal M}\right| = 2\f$, the solution is stable -provided that the off-diagonal elements of \f${\cal M}\f$ are zero; -otherwise the solution is linearly unstable. - -The exponential instability of the geodesic on the ellipse \f$y = 0\f$ -is confirmed by this analysis and results from the resonance between the -natural frequency of the equation for \f$m\f$ and the driving frequency -when \f$b\f$ lies in \f$(c, a)\f$. If \f$b\f$ is equal to either of the -other axes (and the triaxial ellipsoid degenerates to an ellipsoid of -revolution), then the solution is linearly unstable. (For example, a -geodesic is which is close to a meridian on an oblate ellipsoid, slowly -moves away from that meridian.) - -\section triaxial-inverse The inverse problem - -In order to solve the inverse geodesic problem, it helps to have an -understanding of the properties of all the geodesics emanating from a -single point \f$(\beta_1, \omega_1)\f$. - - If the point is an umbilical point, all the lines meet at the - opposite umbilical point. - - Otherwise, the first envelope of the geodesics is a 4-pointed - astroid. The cusps of the astroid lie on either \f$\beta = - - \beta_1\f$ or \f$\omega = \omega_1 + \pi\f$; see - Sinclair - (2003). - - All geodesics intersect (or, in the case of \f$\alpha_1 = 0\f$ or - \f$\pi\f$, touch) the line \f$\omega = \omega_1 + \pi\f$. - - All geodesics intersect (or, in the case of \f$\alpha_1 = - \pm\pi/2\f$, touch) the line \f$\beta = -\beta_1\f$. - - Two geodesics with azimuths \f$\pm\alpha_1\f$ first intersect on - \f$\omega = \omega_1 + \pi\f$ and their lengths to the point of - intersection are equal. - - Two geodesics with azimuths \f$\alpha_1\f$ and \f$\pi-\alpha_1\f$ - first intersect on \f$\beta = -\beta_1\f$ and their lengths to the - point of intersection are equal. - . -(These assertions follow directly from the equations for the geodesics; -some of them are somewhat surprising given the asymmetries of the -ellipsoid.) Consider now terminating the geodesics from \f$(\beta_1, -\omega_1)\f$ at the point where they first intersect (or touch) the line -\f$\beta = -\beta_1\f$. To focus the discussion, take \f$\beta_1 \le -0\f$. - - The geodesics completely fill the portion of the ellipsoid satisfying - \f$\beta \le -\beta_1\f$. - - None of geodesics intersect any other geodesics. - - Any initial portion of these geodesics is a shortest path. - - Each geodesic intersects the line \f$\beta = \beta_2\f$, where - \f$\beta_1 < \beta_2 < -\beta_1\f$, exactly once. - - For a given \f$\beta_2\f$, this defines a continuous monotonic - mapping of the circle of azimuths \f$\alpha_1\f$ to the circle of - longitudes \f$\omega_2\f$. - - If \f$\beta_2 = \pm \beta_1\f$, then the previous two assertions need - to be modified similarly to the case for an ellipsoid of revolution. - -These properties show that the inverse problem can be solved using -techniques similar to those employed for an ellipsoid of revolution (see -§4 of - Algorithms for -geodesics). - - If the points are opposite umbilical points, an arbitrary - \f$\alpha_1\f$ may be chosen. - - If the points are neighboring umbilical points, the shortest path - lies on the ellipse \f$y = 0\f$. - - If only one point is an umbilicial point, the azimuth at the - non-umbilical point is found using the generalization of Clairaut's - equation (given above) with \f$\gamma = 0\f$. - - Treat the cases where the geodesic might follow a line of constant - \f$\beta\f$. There are two such cases: (a) the points lie on the - ellipse \f$z = 0\f$ on a general ellipsoid and (b) the points lie on - an ellipse whose major axis is the \f$x\f$ axis on a prolate ellipsoid - (\f$a = b > c\f$). Determine the reduced length \f$m_{12}\f$ for the - geodesic which is the shorter path along the ellipse. If \f$m_{12} - \ge 0\f$, then this is the shortest path on the ellipsoid; otherwise - proceed to the general case (next). - - Swap the points, if necessary, so that the first point is the one - closest to a pole. Estimate \f$\alpha_1\f$ (by some means) and solve - the \e hybrid problem, i.e., determine the longitude \f$\omega_2\f$ - corresponding to the first intersection of the geodesic with \f$\beta - = \beta_2\f$. Adjust \f$\alpha_1\f$ so that the value of - \f$\omega_2\f$ matches the given \f$\omega_2\f$ (there is a single - root). If a sufficiently close solution can be found, Newton's - method can be employed since the necessary derivative can be - expressed in terms of the reduced length \f$m_{12}\f$. - -The shortest path found by this method is unique unless: - - The length of the geodesic vanishes \f$s_{12}=0\f$, in which case any - constant can be added to the azimuths. - - The points are opposite umbilical points. In this case, - \f$\alpha_1\f$ can take on any value and \f$\alpha_2\f$ needs to be - adjusted to maintain the value of \f$\tan\alpha_1 / \tan\alpha_2\f$. - Note that \f$\alpha\f$ increases by \f$\pm 90^\circ\f$ as the - geodesic passes through an umbilical point, depending on whether the - geodesic is considered as passing to the right or left of the point. - Here \f$\alpha_2\f$ is the \e forward azimuth at the second umbilical - point, i.e., its azimuth immediately \e after passage through the - umbilical point. - - \f$\beta_1 + \beta_2 = 0\f$ and \f$\cos\alpha_1\f$ and - \f$\cos\alpha_2\f$ have opposite signs. In this case, there another - shortest geodesic with azimuths \f$\pi - \alpha_1\f$ and - \f$\pi - \alpha_2\f$. - -
-Back to \ref geodesic. Forward to \ref transversemercator. Up to -\ref contents. -
-**********************************************************************/ -/** -\page transversemercator Transverse Mercator projection - -
-Back to \ref triaxial. Forward to \ref geocentric. Up to \ref contents. -
- -GeographicLib::TransverseMercator and -GeographicLib::TransverseMercatorExact provide accurate implementations -of the transverse Mercator projection. The - TransverseMercatorProj -utility provides an interface to these classes. - -Go to - - \ref testmerc - - \ref tmseries - - \ref tmfigures - -References - - L. Krüger, - Konforme - Abbildung des Erdellipsoids in der Ebene (Conformal mapping of - the ellipsoidal earth to the plane), Royal Prussian Geodetic Institute, - New Series 52, 172 pp. (1912). - - L. P. Lee, - Conformal Projections Based on Elliptic Functions, - (B. V. Gutsell, Toronto, 1976), 128pp., - ISBN: 0919870163 - (Also appeared as: - Monograph 16, Suppl. No. 1 to Canadian Cartographer, Vol 13). - Part V, pp. 67--101, - Conformal - Projections Based On Jacobian Elliptic Functions. - - C. F. F. Karney, - - Transverse Mercator with an accuracy of a few nanometers, - J. Geodesy 85(8), 475--485 (Aug. 2011); - preprint: - arXiv:1002.1417; - resource page: - tm.html. - . -The algorithm for GeographicLib::TransverseMercator is based on -Krüger (1912); that for GeographicLib::TransverseMercatorExact is -based on Lee (1976). - -See tm-grid.kmz, for an -illustration of the exact transverse Mercator grid in Google Earth. - -\section testmerc Test data for the transverse Mercator projection - -A test set for the transverse Mercator projection is available at - - - TMcoords.dat.gz - . -This is about 17 MB (compressed). This test set consists of a set of -geographic coordinates together with the corresponding transverse -Mercator coordinates. The WGS84 ellipsoid is used, with central -meridian 0°, central scale factor 0.9996 (the UTM value), -false easting = false northing = 0 m. - -Each line of the test set gives 6 space delimited numbers - - latitude (degrees, exact) - - longitude (degrees, exact — see below) - - easting (meters, accurate to 0.1 pm) - - northing (meters, accurate to 0.1 pm) - - meridian convergence (degrees, accurate to 10−18 deg) - - scale (accurate to 10−20) - . -The latitude and longitude are all multiples of 10−12 -deg and should be regarded as exact, except that longitude = -82.63627282416406551 should be interpreted as exactly 90 (1 - \e e) -degrees. These results are computed using Lee's formulas with -Maxima's -bfloats and fpprec set to 80 (so the errors in the data are probably 1/2 -of the values quoted above). The Maxima code, -tm.mac and ellint.mac, -was used to prepare this data set is included in the distribution; you -will need to have Maxima installed to use this code. The comments at -the top of tm.mac illustrate how to run it. - -The contents of the file are as follows: - - 250000 entries randomly distributed in lat in [0°, 90°], lon - in [0°, 90°]; - - 1000 entries randomly distributed on lat in [0°, 90°], lon = - 0°; - - 1000 entries randomly distributed on lat = 0°, lon in [0°, - 90°]; - - 1000 entries randomly distributed on lat in [0°, 90°], lon = - 90°; - - 1000 entries close to lat = 90° with lon in [0°, 90°]; - - 1000 entries close to lat = 0°, lon = 0° with lat ≥ - 0°, lon ≥ 0°; - - 1000 entries close to lat = 0°, lon = 90° with lat ≥ - 0°, lon ≤ 90°; - - 2000 entries close to lat = 0°, lon = 90° (1 − \e e) - with lat ≥ 0°; - - 25000 entries randomly distributed in lat in [−89°, - 0°], lon in [90° (1 − \e e), 90°]; - - 1000 entries randomly distributed on lat in [−89°, 0°], - lon = 90°; - - 1000 entries randomly distributed on lat in [−89°, 0°], - lon = 90° (1 − \e e); - - 1000 entries close to lat = 0°, lon = 90° (lat < 0°, lon - ≤ 90°); - - 1000 entries close to lat = 0°, lon = 90° (1 − \e e) - (lat < 0°, lon ≤ 90° (1 − \e e)); - . -(a total of 287000 entries). The entries for lat < 0° and -lon in [90° (1 − \e e), 90°] use the "extended" -domain for the transverse Mercator projection explained in Sec. 5 of -arXiv:1002.1417. The first -258000 entries have lat ≥ 0° and are suitable for testing -implementations following the standard convention. - -\section tmseries Series approximation for transverse Mercator - -Krüger (1912) gives a 4th-order approximation to the transverse -Mercator projection. This is accurate to about 200 nm (200 -nanometers) within the UTM domain. Here we present the series -extended to 10th order. By default, GeographicLib::TransverseMercator -uses the 6th-order approximation. The preprocessor macro -GEOGRAPHICLIB_TRANSVERSEMERCATOR_ORDER can be used to select an order -from 4 thru 8. The series expanded to order n30 are -given in tmseries30.html. - -In the formulas below ^ indicates exponentiation (\e n^3 = \e n*\e n*\e -n) and / indicates real division (3/5 = 0.6). The equations need to be -converted to Horner form, but are here left in expanded form so that -they can be easily truncated to lower order in \e n. Some of the -integers here are not representable as 32-bit integers and will need to -be included as double literals. - -\e A in Krüger, p. 12, eq. (5) -\verbatim - A = a/(n + 1) * (1 + 1/4 * n^2 - + 1/64 * n^4 - + 1/256 * n^6 - + 25/16384 * n^8 - + 49/65536 * n^10); -\endverbatim - -γ in Krüger, p. 21, eq. (41) -\verbatim -alpha[1] = 1/2 * n - - 2/3 * n^2 - + 5/16 * n^3 - + 41/180 * n^4 - - 127/288 * n^5 - + 7891/37800 * n^6 - + 72161/387072 * n^7 - - 18975107/50803200 * n^8 - + 60193001/290304000 * n^9 - + 134592031/1026432000 * n^10; -alpha[2] = 13/48 * n^2 - - 3/5 * n^3 - + 557/1440 * n^4 - + 281/630 * n^5 - - 1983433/1935360 * n^6 - + 13769/28800 * n^7 - + 148003883/174182400 * n^8 - - 705286231/465696000 * n^9 - + 1703267974087/3218890752000 * n^10; -alpha[3] = 61/240 * n^3 - - 103/140 * n^4 - + 15061/26880 * n^5 - + 167603/181440 * n^6 - - 67102379/29030400 * n^7 - + 79682431/79833600 * n^8 - + 6304945039/2128896000 * n^9 - - 6601904925257/1307674368000 * n^10; -alpha[4] = 49561/161280 * n^4 - - 179/168 * n^5 - + 6601661/7257600 * n^6 - + 97445/49896 * n^7 - - 40176129013/7664025600 * n^8 - + 138471097/66528000 * n^9 - + 48087451385201/5230697472000 * n^10; -alpha[5] = 34729/80640 * n^5 - - 3418889/1995840 * n^6 - + 14644087/9123840 * n^7 - + 2605413599/622702080 * n^8 - - 31015475399/2583060480 * n^9 - + 5820486440369/1307674368000 * n^10; -alpha[6] = 212378941/319334400 * n^6 - - 30705481/10378368 * n^7 - + 175214326799/58118860800 * n^8 - + 870492877/96096000 * n^9 - - 1328004581729009/47823519744000 * n^10; -alpha[7] = 1522256789/1383782400 * n^7 - - 16759934899/3113510400 * n^8 - + 1315149374443/221405184000 * n^9 - + 71809987837451/3629463552000 * n^10; -alpha[8] = 1424729850961/743921418240 * n^8 - - 256783708069/25204608000 * n^9 - + 2468749292989891/203249958912000 * n^10; -alpha[9] = 21091646195357/6080126976000 * n^9 - - 67196182138355857/3379030566912000 * n^10; -alpha[10]= 77911515623232821/12014330904576000 * n^10; -\endverbatim - -β in Krüger, p. 18, eq. (26*) -\verbatim - beta[1] = 1/2 * n - - 2/3 * n^2 - + 37/96 * n^3 - - 1/360 * n^4 - - 81/512 * n^5 - + 96199/604800 * n^6 - - 5406467/38707200 * n^7 - + 7944359/67737600 * n^8 - - 7378753979/97542144000 * n^9 - + 25123531261/804722688000 * n^10; - beta[2] = 1/48 * n^2 - + 1/15 * n^3 - - 437/1440 * n^4 - + 46/105 * n^5 - - 1118711/3870720 * n^6 - + 51841/1209600 * n^7 - + 24749483/348364800 * n^8 - - 115295683/1397088000 * n^9 - + 5487737251099/51502252032000 * n^10; - beta[3] = 17/480 * n^3 - - 37/840 * n^4 - - 209/4480 * n^5 - + 5569/90720 * n^6 - + 9261899/58060800 * n^7 - - 6457463/17740800 * n^8 - + 2473691167/9289728000 * n^9 - - 852549456029/20922789888000 * n^10; - beta[4] = 4397/161280 * n^4 - - 11/504 * n^5 - - 830251/7257600 * n^6 - + 466511/2494800 * n^7 - + 324154477/7664025600 * n^8 - - 937932223/3891888000 * n^9 - - 89112264211/5230697472000 * n^10; - beta[5] = 4583/161280 * n^5 - - 108847/3991680 * n^6 - - 8005831/63866880 * n^7 - + 22894433/124540416 * n^8 - + 112731569449/557941063680 * n^9 - - 5391039814733/10461394944000 * n^10; - beta[6] = 20648693/638668800 * n^6 - - 16363163/518918400 * n^7 - - 2204645983/12915302400 * n^8 - + 4543317553/18162144000 * n^9 - + 54894890298749/167382319104000 * n^10; - beta[7] = 219941297/5535129600 * n^7 - - 497323811/12454041600 * n^8 - - 79431132943/332107776000 * n^9 - + 4346429528407/12703122432000 * n^10; - beta[8] = 191773887257/3719607091200 * n^8 - - 17822319343/336825216000 * n^9 - - 497155444501631/1422749712384000 * n^10; - beta[9] = 11025641854267/158083301376000 * n^9 - - 492293158444691/6758061133824000 * n^10; - beta[10]= 7028504530429621/72085985427456000 * n^10; -\endverbatim - -The high-order expansions for α and β were produced by the -Maxima program tmseries.mac (included in the -distribution). To run, start Maxima and enter -\verbatim - load("tmseries.mac")$ -\endverbatim -Further instructions are included at the top of the file. - -\section tmfigures Figures from paper on transverse Mercator projection - -This section gives color versions of the figures in - - C. F. F. Karney, - - Transverse Mercator with an accuracy of a few nanometers, - J. Geodesy 85(8), 475--485 (Aug. 2011); - preprint: - arXiv:1002.1417; - resource page: - tm.html. - -\b NOTE: -The numbering of the figures matches that in the paper cited above. The -figures in this section are relatively small in order to allow them to -be displayed quickly. Vector versions of these figures are available in - tm-figs.pdf. This allows you to magnify the -figures to show the details more clearly. - -\image html gauss-schreiber-graticule-a.png "Fig. 1(a)" -Fig. 1(a): -The graticule for the spherical transverse Mercator projection. -The equator lies on \e y = 0. -Compare this with Lee, Fig. 1 (right), which shows the graticule for -half a sphere, but note that in his notation \e x and \e y have switched -meanings. The graticule for the ellipsoid differs from that for a -sphere only in that the latitude lines have shifted slightly. (The -conformal transformation from an ellipsoid to a sphere merely relabels -the lines of latitude.) This projection places the point latitude = -0°, longitude = 90° at infinity. - -\image html gauss-krueger-graticule-a.png "Fig. 1(b)" -Fig. 1(b): -The graticule for the Gauss-Krüger transverse Mercator projection. -The equator lies on \e y = 0 for longitude < 81°; beyond -this, it arcs up to meet \e y = 1. Compare this with Lee, Fig. 45 -(upper), which shows the graticule for the International Ellipsoid. Lee, -Fig. 46, shows the graticule for the entire ellipsoid. This projection -(like the Thompson projection) projects the ellipsoid to a finite area. - -\image html thompson-tm-graticule-a.png "Fig. 1(c)" -Fig. 1(c): -The graticule for the Thompson transverse Mercator projection. The -equator lies on \e y = 0 for longitude < 81°; at longitude = -81°, it turns by 120° and heads for \e y = 1. -Compare this with Lee, Fig. 43, which shows the graticule for the -International Ellipsoid. Lee, Fig. 44, shows the graticule for the -entire ellipsoid. This projection (like the Gauss-Krüger -projection) projects the ellipsoid to a finite area. - -\image html gauss-krueger-error.png "Fig. 2" -Fig. 2: -The truncation error for the series for the Gauss-Krüger transverse -Mercator projection. The blue curves show the truncation error for the -order of the series \e J = 2 (top) thru \e J = 12 (bottom). The red -curves show the combined truncation and round-off errors for - - float and \e J = 4 (top) - - double and \e J = 6 (middle) - - long double and \e J = 8 (bottom) - -\image html gauss-krueger-graticule.png "Fig. 3(a)" -Fig. 3(a): -The graticule for the extended domain. The blue lines show -latitude and longitude at multiples of 10°. The green lines -show 1° intervals for longitude in [80°, 90°] and latitude in -[−5°, 10°]. - -\image html gauss-krueger-convergence-scale.png "Fig. 3(b)" -Fig. 3(b): -The convergence and scale for the Gauss-Krüger -transverse Mercator projection in the extended domain. The blue lines -emanating from the top left corner (the north pole) are lines of -constant convergence. Convergence = 0° is given by the -dog-legged line joining the points (0,1), (0,0), (1.71,0), -(1.71,−∞). -Convergence = 90° is given by the line y = 1. The other -lines show multiples of 10° between 0° and -90°. The other blue, the green and the black lines show -scale = 1 thru 2 at intervals of 0.1, 2 thru 15 at intervals of 1, and -15 thru 35 at intervals of 5. Multiples of 5 are shown in black, -multiples of 1 are shown in blue, and the rest are shown in green. -Scale = 1 is given by the line segment (0,0) to (0,1). The red line -shows the equator between lon = 81° and 90°. The -scale and convergence at the branch point are 1/\e e = 10 and -0°, respectively. - -\image html thompson-tm-graticule.png "Fig. 3(c)" -Fig. 3(c): -The graticule for the Thompson transverse Mercator -projection for the extended domain. The range of the projection is the -rectangular region shown - - 0 ≤ \e u ≤ K(e2), - 0 ≤ \e v ≤ K(1 − e2) - . -The coloring of the lines is the same as Fig. 3(a), except that latitude -lines extended down to −10° and a red line has been added -showing the line \e y = 0 for \e x > 1.71 in the Gauss-Krüger -projection (Fig. 3(a)). The extended Thompson projection figure has -reflection symmetry on all the four sides of Fig. 3(c). - -
-Back to \ref triaxial. Forward to \ref geocentric. Up to \ref contents. -
-**********************************************************************/ -/** -\page geocentric Geocentric coordinates - -
-Back to \ref transversemercator. Forward to \ref old. Up to \ref contents. -
- -The implementation of GeographicLib::Geocentric::Reverse is adapted from - - H. Vermeille, - - Direct transformation from geocentric coordinates to geodetic - coordinates, J. Geodesy 76, 451--454 (2002). - -This provides a closed-form solution but can't directly be applied close to -the center of the earth. Several changes have been made to remove this -restriction and to improve the numerical accuracy. Now the method is -accurate for all inputs (even if \e h is infinite). The changes are -described in Appendix B of - - C. F. F. Karney, - Geodesics - on an ellipsoid of revolution, - Feb. 2011; preprint - arxiv:1102.1215v1. - -The problems encountered near the center of the ellipsoid are: - - There's a potential division by zero in the definition of \e s. The - equations are easily reformulated to avoid this problem. - - t3 may be negative. This is OK; we just take the - real root. - - The solution for \e t may be complex. However this leads to 3 real roots - for u/\e r. It's then just a matter of picking the one that computes - the geodetic result which minimizes |\e h| and which avoids large - round-off errors. - - Some of the equations result in a large loss of accuracy due to - subtracting nearly equal quantities. E.g., \e k= sqrt(\e u + \e v + - w2) − \e w is inaccurate if \e u + \e v is small; - we can fix this by writing \e k = (\e u + \e v)/(sqrt(\e u + \e v + - w2) + \e w). - -The error is computed as follows. Write a version of -Geocentric::WGS84.Forward which uses long doubles (including using long -doubles for the WGS84 parameters). Generate random (long double) -geodetic coordinates (\e lat0, \e lon0, \e h0) and use the "long double" -WGS84.Forward to obtain the corresponding (long double) geocentric -coordinates (\e x0, \e y0, \e z0). [We restrict \e h0 so that -\e h0 ≥ − \e a (1 − e2) / sqrt(1 − -e2 sin2\e lat0), which ensures that (\e -lat0, \e lon0, \e h0) is the principal geodetic inverse of (\e x0, \e -y0, \e z0).] Because the forward calculation is numerically stable and -because long doubles (on Linux systems using g++) provide 11 bits -additional accuracy (about 3.3 decimal digits), we regard this set of -test data as exact. - -Apply the double version of WGS84.Reverse to (\e x0, \e y0, \e z0) to -compute the approximate geodetic coordinates (\e lat1, \e lon1, \e h1). -Convert (\e lat1 − \e lat0, \e lon1 − \e lon0) to a -distance, \e ds, on the surface of the ellipsoid and define \e err = -hypot(\e ds, \e h1 − \e h0). For |\e h0| < 5000 km, we have \e -err < 7 nm (7 nanometers). - -This methodology is not very useful very far from the globe, because the -absolute errors in the approximate geodetic height become large, or -within 50 km of the center of the earth, because of errors in computing -the approximate geodetic latitude. To illustrate the second issue, the -maximum value of \e err for \e h0 < 0 is about 80 mm. The error is -maximum close to the circle given by geocentric coordinates satisfying -hypot(\e x, \e y) = \e a e2 (= 42.7 km), \e z = 0. -(This is the center of meridional curvature for \e lat = 0.) The -geodetic latitude for these points is \e lat = 0. However, if we move 1 -nm towards the center of the earth, the geodetic latitude becomes 0.04", -a distance of 1.4 m from the equator. If, instead, we move 1 nm up, the -geodetic latitude becomes 7.45", a distance of 229 m from the equator. -In light of this, Reverse does quite well in this vicinity. - -To obtain a practical measure of the error for the general case we define -- errh = |\e h1 − \e h0| / max(1, \e h0 / \e a) -- for \e h0 > 0, errout = \e ds -- for \e h0 < 0, apply the long double version of WGS84.Forward to (\e - lat1, \e lon1, \e h1) to give (\e x1, \e y1, \e z1) and compute - errin = hypot(\e x1 − \e x0, \e y1 − \e - y0, \e z1 − \e z0). -. -We then find errh < 8 nm, errout < 4 nm, -and errin < 7 nm. (1 nm = 1 nanometer.) - -The testing has been confined to the WGS84 ellipsoid. The method will work -for all ellipsoids used in terrestrial geodesy. However, the central region, -which leads to multiple real roots for the cubic equation in Reverse, pokes -outside the ellipsoid (at the poles) for ellipsoids with \e e > 1/sqrt(2). -Reverse has not been analyzed for this case. Similarly ellipsoids which are -very nearly spherical near yield inaccurate results due to underflow; in the -other hand, the case of the sphere, \e f = 0, is treated specially and gives -accurate results. - -Other comparable methods are K. M. Borkowski, - Transformation -of geocentric to geodetic coordinates without approximations, -Astrophys. Space Sci. 139, 1--4 (1987) -( erratum) -and T. Fukushima, - Fast transform from -geocentric to geodetic coordinates, J. Geodesy 73, 603--610 (1999). -However the choice of independent variables in these methods leads -to a loss of accuracy for points near the equatorial plane. - -
-Back to \ref transversemercator. Forward to \ref old. Up to \ref contents. - -
-**********************************************************************/ -/** -\page old Old versions - -
-Back to \ref geocentric. Up to \ref contents. -
- -List of versions in reverse chronological order together with a brief -list of changes. (Note: Old versions of the library use a year-month -style of numbering. Now, the library uses a major and minor version -number.) Recent versions of %GeographicLib are available at - -http://sourceforge.net/projects/geographiclib/files/distrib/. -Older versions are in - -http://sourceforge.net/projects/geographiclib/files/distrib/archive/. - -The corresponding documentation for these versions is obtained by -clicking on the “Version m.nn” links below. Some of -the links in the documentaion of older versions may be out of date (in -particular the links for the source code will not work if the code has -been migrated to the archive subdirectory). All the releases are -available as tags “rm.nn” in the the "release" branch -of the git repository for %GeographicLib. - - - Version 1.35 - (released 2014-03-13) - - Fix blunder in GeographicLib::UTMUPS::EncodeEPSG (found by Ben - Adler). - - Matlab wrapper routines geodesic{direct,inverse,line} switch to - "exact" routes if |f| > 0.02. - - GeodSolve.cgi allows ellipsoid to be set (and uses the -E option - for GeodSolve). - - Set title in HTML versions of man pages for the \ref utilities. - - Changes in cmake support: - - add _d to names of executables in debug mode of Visual Studio; - - add support for Android (cmake-only), thanks to Pullan Yu; - - check CPACK version numbers supplied on command line; - - configured version of project-config.cmake.in is - project-config.cmake (instead of geographiclib-config.cmake), to - prevent find_package incorrectly using this file; - - fix tests with multi-line output; - - this release includes a file, pom.xml, which is used by an - experimental build system (based on maven) at SRI. - - - Version 1.34 - (released 2013-12-11) - - Many changes in cmake support: - - minimum version of cmake needed increased to 2.8.4 (which was - released in 2011-02); - - allow building both shared and static librarys with -D - GEOGRAPHICLIB_LIB_TYPE=BOTH; - - both shared and static libraries (Release plus Debug) included in - binary installer; - - find_package uses COMPONENTS and GeographicLib_USE_STATIC_LIBS to - select the library to use; - - find_package version checking allows nmake and Visual Studio - generators to interoperate on Windows; - - find_package (%GeographicLib ...) requires that %GeographicLib be - capitalized correctly; - - on Unix/Linux, don't include the version number in directory for - the cmake configuration files; - - defaults for GEOGRAPHICLIB_DOCUMENTATION and - BUILD_NETGEOGRAPHICLIB are now OFF; - - the GEOGRAPHICLIB_EXAMPLES configuration parameter is no longer - used; cmake always configures to build the examples, but they are - not built by default (instead build targets: exampleprograms and - netexamples); - - matlab-all target renamed to matlabinterface; - - the configuration parameters PACKAGE_PATH and INSTALL_PATH are - now deprecated (use CMAKE_INSTALL_PREFIX instead); - - on Linux, the installed package is relocatable; - - on MacOSX, the installed utilities can find the shared library. - - Use a more precise value for GeographicLib::OSGB::CentralScale(). - - Add Arc routines to python interface. - - The Geod utility has been removed; the same functionality lives on - with GeodSolve (introduced in - version 1.30). - - - Version 1.33 - (released 2013-10-08) - - Add NETGeographic .NET wrapper library - (courtesy of Scott Heiman). - - Make inspector functions in GeographicLib::Ellipsoid const. - - Add Accumulator.cpp to instantiate GeographicLib::Accumulator. - - Defer some of the initialization of GeographicLib::OSGB to when it - is first called. - - Fix bug in autoconf builds under MacOS. - - - Version 1.32 - (released 2013-07-12) - - Generalize C interface for polygon areas to allow vertices to be - specified incrementally. - - Fix way flags for C++11 support are determined. - - - Version 1.31 - (released 2013-07-01) - - Changes breaking binary compatibility (source compatibility is - maintained): - - overloaded versions of GeographicLib::DMS::Encode, - GeographicLib::EllipticFunction::EllipticFunction, and - GeographicLib::GeoCoords::DMSRepresentation, have been eliminated - by the use of optional arguments; - - correct the declaration of first arg to - GeographicLib::UTMUPS::DecodeEPSG. - - FIX BUG in GeographicLib::GravityCircle constructor (found by - Mathieu Peyréga) which caused bogus results for the gravity - disturbance and gravity anomaly vectors. (This only affected - calculations using GravityCircle. GravityModel calculations did - not suffer from this bug.) - - Improvements to the build: - - add macros GEOGRAPHICLIB_VERSION_{MAJOR,MINOR,PATCH} to Config.h; - - fix documentation for new version of perlpod; - - improving setting of runtime path for Unix-like systems with cmake; - - install PDB files when compiling with Visual Studio to aid - debugging; - - Windows binary release now uses Matlab R2013a (64-bit) and - uses the -largeArrayDims option. - - fixes to the way the Matlab interface routines are built (thanks - to Phil Miller and Chris F.). - - Changes to the geodesic routines: - - add \ref java of the geodesic routines (thanks to Skip Breidbach - for the maven support); - - FIX BUG: avoid altering input args in Fortran implementation; - - more systematic treatment of very short geodesic; - - fixes to python port so that they work with version 3.x, in - addition to 2.x (courtesy of Amato); - - accumulate the perimeter and area of polygons via a double-wide - accumulator in Fortran, C, and Matlab implementations (this is - already included in the other implementations); - - port GeographicLib::PolygonArea::AddEdge and - GeographicLib::PolygonArea::TestEdge to JavaScript and python - interfaces; - - include documentation on \ref geodshort. - - Unix scripts for downloading datasets, - geographiclib-get-{geoids,gravity,magnetic}, skip already download - models by default, unless the -f flag is given. - - FIX BUGS: meridian convergence and scale returned by - GeographicLib::TransverseMercatorExact was wrong at a pole. - - Improve efficiency of GeographicLib::MGRS::Forward by avoiding the - calculation of the latitude if possible (adapting an idea of Craig - Rollins). - - Fixes to the way the Matlab interface routines are built (thanks to - Phil Miller and Chris F.). - - - Version 1.30 - (released 2013-02-27) - - Changes to geodesic routines: - - FIX BUG in fail-safe mechanisms in GeographicLib::Geodesic::Inverse; - - the command line utility Geod is now called - GeodSolve; - - allow addition of polygon edges in GeographicLib::PolygonArea; - - add full Maxima implementation of geodesic algorithms. - - - Version 1.29 - (released 2013-01-16) - - Changes to allow compilation with libc++ (courtesy of Kal Conley). - - Add description of \ref triaxial to documentation. - - Update journal reference for "Algorithms for geodesics". - - - Version 1.28 - (released 2012-12-11) - - Changes to geodesic routines: - - compute longitude difference exactly; - - hence FIX BUG in area calculations for polygons with vertices very - close to the prime meridian; - - FIX BUG is geoddistance.m where the value of m12 was wrong for - meridional geodesics; - - add Matlab implementations of the geodesic projections; - - remove unneeded special code for geodesics which start at a pole; - - include polygon area routine in C and Fortran implementations; - - add doxygen documentation for C and Fortran libraries. - - - Version 1.27 - (released 2012-11-29) - - Changes to geodesic routines: - - add native Matlab implementations: geoddistance.m, geodreckon.m, - geodarea.m; - - add C and Fortran implementations; - - improve the solution of the direct problem so that the series - solution is accurate to round off for |f| < 1/50; - - tighten up the convergence criteria for solution of the inverse - problem; - - no longer signal failures of convergence with NaNs (a slightly - less accurate answer is returned instead). - - Fix GeographicLib::DMS::Decode double rounding BUG. - - On MacOSX platforms with the cmake configuration, universal - binaries are built. - - - Version 1.26 - (released 2012-10-22) - - Replace the series used for geodesic areas by one with better - convergence (this only makes an appreciable difference if - |f| > 1/150). - - - Version 1.25 - (released 2012-10-16) - - Changes to geodesic calculations: - - restart Newton's method in Geodesic::Inverse when it goes awry; - - back up Newton's method with the bisection method; - - GeographicLib::Geodesic::Inverse now converges for any value of \e f; - - add GeographicLib::GeodesicExact and - GeographicLib::GeodesicLineExact which are formulated in terms - of elliptic integrals and thus yield accurate results even for - very eccentric ellipsoids. - - the -E option to Geod invokes these - exact classes. - - Add functionality to GeographicLib::EllipticFunction: - - add all the traditional elliptic integrals; - - remove restrictions on argument range for incomplete elliptic integrals; - - allow imaginary modulus for elliptic integrals and elliptic functions; - - make interface to the symmetric elliptic integrals public. - - Allow GeographicLib::Ellipsoid to be copied. - - Changes to the build tools: - - cmake uses folders in Visual Studio to reduce clutter; - - allow precision of reals to be set in cmake; - - fail gracefully in the absence of pod documentation tools; - - remove support for maintainer tasks in Makefile.mk. - - - Version 1.24 - (released 2012-09-22) - - Allow the specification of the hemisphere in UTM coordinates in - order to provide continuity across the equator: - - add GeographicLib::UTMUPS::Transfer; - - add GeographicLib::GeoCoords::UTMUPSRepresentation(bool, int) and - GeographicLib::GeoCoords::AltUTMUPSRepresentation(bool, int); - - use the hemisphere letter in, e.g., - GeoConvert -u -z 31N. - - Add GeographicLib::UTMUPS::DecodeEPSG and - GeographicLib::UTMUPS::EncodeEPSG. - - cmake changes: - - restore support for cmake 2.4.x; - - explicitly check version of doxygen. - - Fix building under cygwin. - - Document restrictions on \e f in \ref intro. - - Fix python interface to work with version 2.6.x. - - - Version 1.23 - (released 2012-07-17) - - Documentation changes: - - remove html documentation from distribution and use web links if - doxygen is not available; - - use doxygen tags to document exceptions; - - begin migrating the documentation to using Greek letters where - appropriate (requires doxygen 1.8.1.2 or later). - - Add GeographicLib::Math::AngNormalize and - GeographicLib::Math::AngNormalize2; the allowed range for longitudes - and azimuths widened to [−540°, 540°). - - GeographicLib::DMS::Decode understands more unicode symbols. - - GeographicLib::Geohash uses geohash code "nan" to stand for not a - number. - - Add GeographicLib::Ellipsoid::NormalCurvatureRadius. - - Various fixes in GeographicLib::LambertConformalConic, - GeographicLib::TransverseMercator, - GeographicLib::PolarStereographic, and GeographicLib::Ellipsoid to - handle reverse projections of points near infinity. - - Fix programming blunder in GeographicLib::LambertConformalConic::Forward - (incorrect results were returned if the tangent latitude was - negative). - - - Version 1.22 - (released 2012-05-27) - - Add GeographicLib::Geohash and GeographicLib::Ellipsoid classes. - - FIX BUG in GeographicLib::AlbersEqualArea for very prolate - ellipsoids (b2 > 2 a2). - - cmake changes: - - optionally use PACKAGE_PATH and INSTALL_PATH to determine - CMAKE_INSTALL_PREFIX; - - use COMMON_INSTALL_PATH to determine layout of installation - directories; - - as a consequence, the installation paths for the documentation, - and python and matlab interfaces are shortened for Windows; - - zip source distribution now uses DOS line endings; - - the tests work in debug mode for Windows; - - default setting of GEOGRAPHICLIB_DATA does not depend on - CMAKE_INSTALL_PREFIX; - - add a cmake configuration for build tree. - - - Version 1.21 - (released 2012-04-25) - - Support colon-separated DMS output: - - GeographicLib::DMS::Encode and - GeographicLib::GeoCoords::DMSRepresentation generalized; - - GeoConvert and - Geod now accept a -: option. - - GeoidEval does not print the gradient - of the geoid height by default (because it's subject to large - errors); give the -g option to get the gradient printed. - - Work around optimization BUG in GeographicLib::Geodesic::Inverse - with tdm mingw g++ version 4.6.1. - - autoconf fixed to ensure that that out-of-sources builds work; - document this as the preferred method of using autoconf. - - cmake tweaks: - - simplify the configuration of doxygen; - - allow the Matlab compiler to be specified with the - MATLAB_COMPILER option. - - - Version 1.20 - (released 2012-03-23) - - cmake tweaks: - - improve find_package's matching of compiler versions; - - CMAKE_INSTALL_PREFIX set from CMAKE_PREFIX_PATH if available; - - add "x64" to the package name for the 64-bit binary installer; - - fix cmake warning with Visual Studio Express. - - Fix GeographicLib::SphericalEngine to deal with aggessive iterator - checking by Visual Studio. - - Fix transcription BUG is Geodesic.js. - - - Version 1.19 - (released 2012-03-13) - - Slight improvement in GeographicLib::Geodesic::Inverse for very - short lines. - - Fix argument checking tests in GeographicLib::MGRS::Forward. - - Add --comment-delimiter and --line-separator options to the \ref - utilities. - - Add installer for 64-bit Windows; the compiled Matlab interface is - supplied with the Windows 64-bit installer only. - - - Version 1.18 - (released 2012-02-18) - - Improve documentation on configuration with cmake. - - cmake's find_package ensures that the compiler versions match on Windows. - - Improve documentation on compiling Matlab interface. - - Binary installer for Windows installs under C:/pkg-vc10 by default. - - - Version 1.17 - (released 2012-01-21) - - Work around optimization BUG in GeographicLib::Geodesic::Inverse - with g++ version 4.4.0 (mingw). - - Fix BUG in argument checking with GeographicLib::OSGB::GridReference. - - Fix missing include file in GeographicLib::SphericalHarmonic2. - - Add simple examples of usage for each class. - - Add internal documentation to the cmake configuration files. - - - Version 1.16 - (released 2011-12-07) - - Add calculation of the earth's gravitational field: - - add GeographicLib::NormalGravity GeographicLib::GravityModel and - GeographicLib::GravityCircle classes; - - add command line utility - Gravity; - - add \ref gravity; - - add GeographicLib::Constants::WGS84_GM(), - GeographicLib::Constants::WGS84_omega(), and similarly for GRS80. - - Build uses GEOGRAPHICLIB_DATA to specify a common parent directory - for geoid, gravity, and magnetic data (instead of - GEOGRAPHICLIB_GEOID_PATH, etc.); similarly, - GeoidEval, - Gravity, and - MagneticField, look at the - environment variable GEOGRAPHICLIB_DATA to locate the data. - - Spherical harmonic software changes: - - capitalize enums GeographicLib::SphericalHarmonic::FULL and - GeographicLib::SphericalHarmonic::SCHMIDT (the lower case names - are retained but deprecated); - - optimize the sum by using a static table of square roots which is - updated by GeographicLib::SphericalEngine::RootTable; - - avoid overflow for high degree models. - - Magnetic software fixes: - - fix documentation BUG in GeographicLib::MagneticModel::Circle; - - make GeographicLib::MagneticModel constructor explicit; - - provide default GeographicLib::MagneticCircle constructor; - - add additional inspector functions to - GeographicLib::MagneticCircle; - - add -c option to MagneticField; - - default height to zero in - MagneticField. - - - Version 1.15 - (released 2011-11-08) - - Add calculation of the earth's magnetic field: - - add GeographicLib::MagneticModel and GeographicLib::MagneticCircle - classes; - - add command line utility - MagneticField; - - add \ref magnetic; - - add \ref magneticinst; - - add \ref magneticformat; - - add classes GeographicLib::SphericalEngine, - GeographicLib::CircularEngine, GeographicLib::SphericalHarmonic, - GeographicLib::SphericalHarmonic1, and - GeographicLib::SphericalHarmonic2. which sum spherical harmonic - series. - - Add GeographicLib::Utility class to support I/O and date - manipulation. - - Cmake configuration includes a _d suffix on the library built in - debug mode. - - For the Python package, include manifest and readme files; don't - install setup.py for non-Windows systems. - - Include Doxygen tag file in distribution as doc/html/Geographic.tag. - - - Version 1.14 - (released 2011-09-30) - - Ensure that geographiclib-config.cmake is relocatable. - - Allow more unicode symbols to be used in GeographicLib::DMS::Decode. - - Modify GeoidEval so that it can be - used to convert the height datum for LIDAR data. - - Modest speed-up of Geodesic::Inverse. - - Changes in python interface: - - FIX BUG in transcription of Geodesic::Inverse; - - include setup.py for easy installation; - - python only distribution is available at - http://pypi.python.org/pypi/geographiclib - - Supply a minimal Qt qmake project file for library - src/Geographic.pro. - - - Version 1.13 - (released 2011-08-13) - - Changes to I/O: - - allow : (colon) to be used as a DMS separator in - GeographicLib::DMS::Decode(const std::string&, flag&); - - also accept Unicode symbols for degrees, minutes, and seconds - (coded as UTF-8); - - provide optional \e swaplatlong argument to various - GeographicLib::DMS and GeographicLib::GeoCoords functions to make - longitude precede latitude; - - GeoConvert now has a -w option to - make longitude precede latitude on input and output; - - include a JavaScript version of GeographicLib::DMS. - - Slight improvement in starting guess for solution of geographic - latitude in terms of conformal latitude in TransverseMercator, - TransverseMercatorExact, and LambertConformalConic. - - For most classes, get rid of const member variables so that the - default copy assignment works. - - Put GeographicLib::Math and GeographicLib::Accumulator in their own - header files. - - Remove unused "fast" GeographicLib::Accumulator method. - - Reorganize the \ref python. - - Withdraw some deprecated routines. - - cmake changes: - - include FindGeographic.cmake in distribution; - - building with cmake creates and installs - geographiclib-config.cmake; - - better support for building a shared library under Windows. - - - Version 1.12 - (released 2011-07-21) - - Change license to MIT/X11. - - Add GeographicLib::PolygonArea class and equivalent Matlab function. - - Provide JavaScript and Python implementations of geodesic routines. - - Fix Windows installer to include runtime dlls for Matlab. - - Fix (innocuous) unassigned variable in Geodesic::GenInverse. - - Geodesic routines in Matlab return a12 as first column of aux return - value (incompatible change). - - A couple of code changes to enable compilation with Visual - Studio 2003. - - - Version 1.11 - (released 2011-06-27) - - Changes to Planimeter: - - add -l flag to Planimeter for polyline - calculations; - - trim precision of area to 3 decimal places; - - FIX BUG with pole crossing edges (due to compiler optimization). - - Geod no longer reports the reduced - length by default; however the -f flag still reports this and in - addition gives the geodesic scales and the geodesic area. - - FIX BUGS (compiler-specific) in inverse geodesic calculations. - - FIX BUG: accommodate tellg() returning −1 at end of string. - - Change way flattening of the ellipsoid is specified: - - constructors take \e f argument which is taken to be the - flattening if \e f < 1 and the inverse flattening otherwise - (this is a compatible change for spheres and oblate ellipsoids, but it - is an INCOMPATIBLE change for prolate ellipsoids); - - the -e arguments to the \ref utilities are handled similarly; in - addition, simple fractions, e.g., 1/297, can be used for the - flattening; - - introduce GeographicLib::Constants::WGS84_f() for the WGS84 - flattening (and deprecate Constants::WGS84_r() for the inverse - flattening); - - most classes have a Flattening() member function; - - InverseFlattening() has been deprecated (and now returns inf for a - sphere, instead of 0). - - - Version 1.10 - (released 2011-06-11) - - Improvements to Matlab/Octave interface: - - add {geocentric,localcartesian}{forward,reverse}; - - make geographiclibinterface more general; - - install the source for the interface; - - cmake compiles the interface if ENABLE_MATLAB=ON; - - include compiled interface with Windows binary installer. - - Fix various configuration issues - - autoconf did not install Config.h; - - cmake installed in man/man1 instead of share/man/man1; - - cmake did not set the rpath on the tools. - - - Version 1.9 - (released 2011-05-28) - - FIX BUG in area returned by - Planimeter for pole encircling polygons. - - FIX BUG in error message reported when DMS::Decode reads the string - "5d.". - - FIX BUG in AlbersEqualArea::Reverse (lon0 not being used). - - Ensure that all exceptions thrown in the \ref utilities are caught. - - Avoid using catch within GeographicLib::DMS. - - Move GeographicLib::Accumulator class from Planimeter.cpp to - Constants.hpp. - - Add GeographicLib::Math::sq. - - Simplify \ref geoidinst - - add geographiclib-get-geoids for Unix-like systems; - - add installers for Windows. - - Provide cmake support: - - build binary installer for Windows; - - include regression tests; - - add --input-string, --input-file, --output-file options to the - \ref utilities to support tests. - - Rename utility EquidistantTest as - GeodesicProj and TransverseMercatorTest as - TransverseMercatorProj. - - Add ConicProj. - - Reverse the initial sense of the -s option for - Planimeter. - - Migrate source from subversion to - - git. - - - Version 1.8 - (released 2011-02-22) - - Optionally return rotation matrix from GeographicLib::Geocentric and - GeographicLib::LocalCartesian. - - For the \ref utilities, supply man pages, -h prints the synopsis, - --help prints the man page, --version prints the version. - - Use accurate summation in Planimeter. - - Add 64-bit targets for Visual Studio 2010. - - Use templates for defining math functions and some constants. - - GeographicLib::Geoid updates - - Add GeographicLib::Geoid::DefaultGeoidPath and - GeographicLib::Geoid::DefaultGeoidName; - - GeoidEval uses environment variable - GEOID_NAME as the default geoid; - - Add --msltohae and --haetomsl as - GeoidEval options (and don't - document the single hyphen versions). - - Remove documentation that duplicates papers on transverse Mercator - and geodesics. - - - Version 1.7 - (released 2010-12-21) - - FIX BUG in scale returned by GeographicLib::LambertConformalConic::Reverse. - - Add GeographicLib::AlbersEqualArea projection. - - Library created by Visual Studio is Geographic.lib instead of - GeographicLib.lib (compatible with makefiles). - - Make classes NaN aware. - - Use cell arrays for MGRS strings in Matlab. - - Add solution/project files for Visual Studio 2010 (32-bit only). - - Use C++11 static_assert and math functions, if available. - - - Version 1.6 - (released 2010-11-23) - - FIX BUG introduced in GeographicLib::Geoid in version 1.5 (found by - Dave Edwards). - - - Version 1.5 - (released 2010-11-19) - - Improve area calculations for small polygons. - - Add -s and -r flags to Planimeter. - - Improve the accuracy of GeographicLib::LambertConformalConic using - divided differences. - - FIX BUG in meridian convergence returned by - LambertConformalConic::Forward. - - Add optional threadsafe parameter to GeographicLib::Geoid - constructor. WARNING: This changes may break binary compatibility - with previous versions of %GeographicLib. However, the library is - source compatible. - - Add GeographicLib::OSGB. - - Matlab and Octave interfaces to GeographicLib::UTMUPS, - GeographicLib::MGRS, GeographicLib::Geoid, GeographicLib::Geodesic - provided. - - Minor changes - - explicitly turn on optimization in Visual Studio 2008 projects; - - add missing dependencies in some Makefiles; - - move pi() and degree() from GeographicLib::Constants to - GeographicLib::Math; - - introduce GeographicLib::Math::extended type to aid testing; - - add GeographicLib::Math::epi() and GeographicLib::Math::edegree(). - - fixes to compile under cygwin; - - tweak expression used to find latitude from conformal latitude. - - - Version 1.4 - (released 2010-09-12) - - Changes to GeographicLib::Geodesic and GeographicLib::GeodesicLine: - - FIX BUG in Geodesic::Inverse with prolate ellipsoids; - - add area computations to Geodesic::Direct and Geodesic::Inverse; - - add geodesic areas to geodesic test set; - - make GeodesicLine constructor public; - - change longitude series in Geodesic into Helmert-like form; - - ensure that equatorial geodesics have cos(alpha0) = 0 identically; - - generalize interface for Geodesic and GeodesicLine; - - split GeodesicLine and Geodesic into different files; - - signal convergence failure in Geodesic::Inverse with NaNs; - - deprecate one function in Geodesic and two functions in - GeodesicLine; - - deprecate -n option for Geod. - . - WARNING: These changes may break binary compatibility with previous - versions of %GeographicLib. However, the library is source - compatible (with the proviso that GeographicLib/GeodesicLine.hpp may - now need to be included). - - Add the Planimeter utility for - computing the areas of geodesic polygons. - - Improve iterative solution of GeographicLib::Gnomonic::Reverse. - - Add GeographicLib::Geoid::ConvertHeight. - - Add -msltohae, -haetomsl, and -z options to - GeoidEval. - - Constructors check that minor radius is positive. - - Add overloaded Forward and Reverse functions to the projection - classes which don't return the convergence (or azimuth) and scale. - - Document function parameters and return values consistently. - - - Version 1.3 - (released 2010-07-21) - - Add GeographicLib::Gnomonic, the ellipsoid generalization of the - gnomonic projection. - - Add -g and -e options to - EquidistantTest. - - Use fixed-point notation for output from - CartConvert, - EquidistantTest, - TransverseMercatorTest. - - PolarStereographic: - - Improved conversion to conformal coordinates; - - Fix bug with scale at opposite pole; - - Complain if latitude out of range in SetScale. - - Add GeographicLib::Math::NaN(). - - Add long double version of hypot for Windows. - - Add EllipticFunction::E(real). - - Update references to Geotrans in MGRS documentation. - - Speed up tmseries.mac. - - - Version 1.2 - (released 2010-05-21) - - FIX BUGS in GeographicLib::Geodesic, - - wrong azimuth returned by Direct if point 2 is on a pole; - - Inverse sometimes fails with very close points. - - Improve calculation of scale in GeographicLib::CassiniSoldner, - - add GeographicLib::GeodesicLine::Scale, - GeographicLib::GeodesicLine::EquatorialAzimuth, and - GeographicLib::GeodesicLine::EquatorialArc; - - break friend connection between CassiniSoldner and Geodesic. - - Add GeographicLib::DMS::DecodeAngle and - GeographicLib::DMS::DecodeAzimuth. Extend - GeographicLib::DMS::Decode and GeographicLib::DMS::Encode to deal - with distances. - - Code and documentation changes in GeographicLib::Geodesic and - GeographicLib::Geocentric for consistency with - the forthcoming paper on geodesics. - - Increase order of series using in GeographicLib::Geodesic to 6 (full - accuracy maintained for ellipsoid flattening < 0.01). - - Macro __NO_LONG_DOUBLE_MATH to disable use of long double. - - Correct declaration of GeographicLib::Math::isfinite to return a bool. - - Changes in the \ref utilities, - - improve error reporting when parsing command line arguments; - - accept latitudes and longitudes in decimal degrees or degrees, - minutes, and seconds, with optional hemisphere designators; - - GeoConvert -z accepts zone or - zone+hemisphere; - - GeoidEval accepts any of the input - formats used by GeoConvert; - - CartConvert allows the ellipsoid - to be specified with -e. - - - Version 1.1 - (released 2010-02-09) - - FIX BUG (introduced in 2009-03) in EllipticFunction::E(sn,cn,dn). - - Increase accuracy of scale calculation in TransverseMercator and - TransverseMercatorExact. - - Code and documentation changes for consistency with - arXiv:1002.1417 - - - Version 1.0 - (released 2010-01-07) - - Add autoconf configuration files. - - BUG FIX: Improve initial guess for Newton's method in - PolarStereographic::Reverse. (Previously this failed to converge - when the co-latitude exceeded about 130 deg.) - - Constructors for TransverseMercator, TransverseMercatorExact, - PolarStereographic, Geocentric, and Geodesic now check for obvious - problems with their arguments and throw an exception if necessary. - - Most classes now include inspector functions such as MajorRadius() - so that you can determine how instances were constructed. - - Add GeographicLib::LambertConformalConic class. - - Add GeographicLib::PolarStereographic::SetScale to allow the - latitude of true scale to be specified. - - Add solution and project files for Visual Studio 2008. - - Add GeographicLib::GeographicErr for exceptions. - - GeographicLib::Geoid changes: - - BUG FIX: fix typo in GeographicLib::Geoid::Cache which could cause - a segmentation fault in some cases when the cached area spanned - the prime meridian. - - Include sufficient edge data to allow heights to be returned for - cached area without disk reads; - - Add inspector functions to query the extent of the cache. - - - Version 2009-11 - (released 2009-11-03) - - Allow specification of "closest UTM zone" in GeographicLib::UTMUPS - and GeoConvert (via -t option). - - Utilities now complain is there are too many tokens on input lines. - - Include real-to-real versions of GeographicLib::DMS::Decode and - GeographicLib::DMS::Encode. - - More house-cleaning changes: - - Ensure that functions which return results through reference - arguments do not alter the arguments when an exception is thrown. - - Improve accuracy of GeographicLib::MGRS::Forward. - - Include more information in some error messages. - - Improve accuracy of inverse hyperbolic functions. - - Fix the way GeographicLib::Math functions handle different precisions. - - - Version 2009-10 - (released 2009-10-18) - - Change web site to http://geographiclib.sourceforge.net - - Several house-cleaning changes: - - Change from the a flat directory structure to a more easily - maintained one. - - Introduce Math class for common mathematical functions (in - Constants.hpp). - - Use Math::real as the type for all real quantities. By default this - is typedef'ed to double; and the library should be installed this - way. - - Eliminate const reference members of AzimuthalEquidistant, - CassiniSoldner and LocalCartesian so that they may be copied. - - Make several constructors explicit. Disallow some constructors. - Disallow copy constructor/assignment for Geoid. - - Document least squares formulas in Geoid.cpp. - - Use unsigned long long for files positions of geoid files in Geoid. - - Introduce optional mgrslimits argument in UTMUPS::Forward and - UTMUPS::Reverse to enforce stricter MGRS limits on eastings and - northings. - - Add 64-bit targets in Visual Studio project files. - - - Version 2009-09 - (released 2009-09-01) - - Add GeographicLib::Geoid and - GeoidEval utility. - - - Version 2009-08 - (released 2009-08-14) - - Add GeographicLib::CassiniSoldner class and - EquidistantTest utility. - - Fix bug in GeographicLib::Geodesic::Inverse where NaNs were - sometimes returned. - - INCOMPATIBLE CHANGE: AzimuthalEquidistant now returns the reciprocal - of the azimuthal scale instead of the reduced length. - - Add -n option to GeoConvert. - - - Version 2009-07 - (released 2009-07-16) - - Speed up the series inversion code in tmseries.mac and geod.mac. - - Reference Borkowski in section on \ref geocentric. - - - Version 2009-06 - (released 2009-06-01) - - Add routines to decode and encode zone+hemisphere to GeographicLib::UTMUPS. - - Clean up code in GeographicLib::Geodesic. - - - Version 2009-05 - (released 2009-05-01) - - Improvements to GeographicLib::Geodesic: - - more economical series expansions, - - return reduced length (as does the - Geod utility), - - improved calculation of starting point for inverse method, - - use reduced length to give derivative for Newton's method. - - Add GeographicLib::AzimuthalEquidistant class. - - Make GeographicLib::Geocentric, GeographicLib::TransverseMercator, - and GeographicLib::PolarStereographic classes work with prolate - ellipsoids. - - CartConvert checks its inputs more - carefully. - - Remove reference to defunct Constants.cpp from GeographicLib.vcproj. - - - Version 2009-04 - (released 2009-04-01) - - Use compile-time constants to select the order of series in - GeographicLib::TransverseMercator. - - 2x unroll of Clenshaw summation to avoid data shuffling. - - Simplification of GeographicLib::EllipticFunction::E. - - Use STATIC_ASSERT for compile-time checking of constants. - - Improvements to GeographicLib::Geodesic: - - compile-time option to change order of series used, - - post Maxima code for generating the series, - - tune the order of series for double, - - improvements in the selection of starting points for Newton's - method, - - accept and return spherical arc lengths, - - works with both oblate and prolate ellipsoids, - - add -a, -e, -b options to the Geod - utility. - - - Version 2009-03 - (released 2009-03-01) - - Add GeographicLib::Geodesic and the - Geod utility. - - Declare when no exceptions are thrown by functions. - - Minor changes to GeographicLib::DMS class. - - Use invf = 0 to mean a sphere in constructors to some classes. - - The makefile creates a library and includes an install target. - - Rename GeographicLib::ECEF to GeographicLib::Geocentric, ECEFConvert - to CartConvert. - - Use inline functions to define constant doubles in Constants.hpp. - - - Version 2009-02 - (released 2009-01-30) - - Fix documentation of constructors (flattening -> inverse - flattening). - - Use std versions of math functions. - - Add GeographicLib::ECEF and GeographicLib::LocalCartesian classes - and the ECEFConvert utility. - - Gather the documentation on the \ref utilities onto one page. - - - Version 2009-01 - (released 2009-01-12) - - First proper release of library. - - More robust GeographicLib::TransverseMercatorExact: - - Introduce \e extendp version of constructor, - - Test against extended test data, - - Optimize starting positions for Newton's method, - - Fix behavior near all singularities, - - Fix order dependence in C++ start-up code, - - Improved method of computing scale and convergence. - - Documentation on transverse Mercator projection. - - Add GeographicLib::MGRS, GeographicLib::UTMUPS, etc. - - - Version 2008-09 - - Ad hoc posting of information on the transverse Mercator projection. - -
-Back to \ref geocentric. Up to \ref contents. -
-**********************************************************************/ diff --git a/gtsam/3rdparty/GeographicLib/doc/GeographicLib.dox.in b/gtsam/3rdparty/GeographicLib/doc/GeographicLib.dox.in new file mode 100644 index 000000000..f9ba9975b --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/doc/GeographicLib.dox.in @@ -0,0 +1,9147 @@ +// -*- text -*- +/** + * \file GeographicLib.dox + * \brief Documentation for GeographicLib + * + * Written by Charles Karney and licensed under the + * MIT/X11 License. For more information, see + * https://geographiclib.sourceforge.io/ + **********************************************************************/ +namespace GeographicLib { +/** +\mainpage GeographicLib library +\author Charles F. F. Karney (charles@karney.com) +\version @PROJECT_VERSION@ +\date 2017-10-05 + +The documentation for other versions is available at +https://geographiclib.sourceforge.io/m.nn/ for versions numbers +m.nn ≥ 1.0. + +\section abstract Abstract + +GeographicLib is a small set of C++ +classes for performing conversions between geographic, UTM, UPS, +MGRS, geocentric, and local cartesian coordinates, for gravity (e.g., +EGM2008), geoid height and geomagnetic field (e.g., WMM2015) +calculations, and for solving geodesic problems. The emphasis is on +returning accurate results with errors close to round-off (about 5--15 +nanometers). Accurate algorithms for \ref geodesic and \ref +transversemercator have been developed for this library. The +functionality of the library can be accessed from user code, from the +\ref utilities provided, or via the \ref other. Also included is a .NET +wrapper library NETGeographicLib +which exposes the functionality to .NET applications. For a sample of +the geodesic capabilities in JavaScript, check out the +online geodesic calculator and +the script for displaying +geodesics in Google Maps + +This library is not a general purpose projection library nor does +it perform datum conversions; instead use +proj.4. On the other +hand, it does provide the core functionality offered by +GEOTRANS. + +\section download Download + +The main project page is at +- https://sourceforge.net/projects/geographiclib +. +The code is available for download at +- + GeographicLib-@PROJECT_VERSION@.tar.gz +- + GeographicLib-@PROJECT_VERSION@.zip +. +as either a compressed tar file (tar.gz) or a zip file. (The two +archives have identical contents, except that the zip file has DOS +line endings.) Alternatively you can get the latest release using git +\verbatim + git clone git://git.code.sourceforge.net/p/geographiclib/code geographiclib +\endverbatim +Each release is tagged, e.g., with r@PROJECT_VERSION@. There are also +binary installers available for some platforms. See \ref binaryinst. + +GeographicLib is licensed under the +MIT/X11 License; +see LICENSE.txt for the terms. + +For more information on GeographicLib, see +- https://geographiclib.sourceforge.io/. + +\section citint Citing GeographicLib + +When citing GeographicLib, use (adjust the version number and date as +appropriate) +- C. F. F. Karney, GeographicLib, Version @PROJECT_VERSION@ (2017-mm-dd), + https://geographiclib.sourceforge.io/@PROJECT_VERSION@ + +\section contents Contents + - \ref intro + - \ref install + - \ref start + - \ref utilities + - \ref organization + - \ref other + - \ref geoid + - \ref gravity + - \ref normalgravity + - \ref magnetic + - \ref geodesic + - \ref nearest + - \ref triaxial + - \ref jacobi + - \ref rhumb + - \ref greatellipse + - \ref transversemercator + - \ref geocentric + - \ref auxlat + - \ref highprec + - \ref changes + +
+Forward to \ref intro. +
+ +**********************************************************************/ +/** +\page intro Introduction + +
+Forward to \ref install. Up to \ref contents. +
+ +GeographicLib offers a C++ interfaces to a small (but important!) set +of geographic transformations. It grew out of a desire to improve on +the geotrans +package for transforming between geographic and MGRS coordinates. At +present, GeographicLib provides UTM, UPS, MGRS, geocentric, and local +cartesian projections, gravity and geomagnetic models, and classes for +geodesic calculations. + +The goals of GeographicLib are: + - Accuracy. In most applications the accuracy is close to round-off, + about 5 nm (5 nanometers). Even though in many geographic + applications 1 cm is considered "accurate enough", there is little + penalty in providing much better accuracy. In situations where a + faster approximate algorithm is necessary, GeographicLib offers an + accurate benchmark to guide the development. + - Completeness. For each of the projections included, an attempt is + made to provide a complete solution. For example, + Geodesic::Inverse works for anti-podal points. + Similarly, Geocentric.Reverse will return accurate + geodetic coordinates even for points close to the center of the + earth. + - C++ interface. For the projection methods, this allows encapsulation + of the ellipsoid parameters. + - Emphasis on projections necessary for analyzing military data. + - Uniform treatment of UTM/UPS. The UTMUPS class treats + UPS as zone 0. This simplifies conversions between UTM and UPS + coordinates, etc. + - Well defined and stable conventions for the conversion between + UTM/UPS to MGRS coordinates. + - Detailed internal documentation on the algorithms. For the most part + GeographicLib uses published algorithms and references are given. If + changes have been made (usually to improve the numerical accuracy), + these are described in the code. + +Various \ref utilities are provided with the library. These illustrate +the use of the library and are useful in their own right. This library +and the utilities have been tested with g++ 5.3.1 under Linux, with +Apple LLVM 7.0.2 under Mac OS X, and with MS Visual Studio 10 (2010), 11 +(2012), 12 (2013), 14 (2015), and 15 (2017) compiled for 32 bit and 64 +bit on Windows. + +MATLAB, JavaScript, and Python interfaces are provided to portions of +GeographicLib; see \ref other. + +The section \ref geodesic documents the method of solving the geodesic +problem. + +The section \ref transversemercator documents various properties of this +projection. + +The bulk of the testing has used geographically relevant values of the +flattening. Thus, you can expect close to full accuracy for −0.01 +≤ \e f ≤ 0.01 (but note that TransverseMercatorExact is restricted +to \e f > 0). However, reasonably accurate results can be expected if +−0.1 ≤ \e f ≤ 0.1. Outside this range, you should attempt +to verify the accuracy of the routines independently. Two types of +problems may occur with larger values of f: + - Some classes, specifically Geodesic, GeodesicLine, and + TransverseMercator, use series expansions using \e f as a small + parameter. The accuracy of these routines will degrade as \e f + becomes large. + - Even when exact formulas are used, many of the classes need to invert + the exact formulas (e.g., to invert a projection), typically, using + Newton's method. This usually provides an essentially exact + inversion. However, the choice of starting guess and the exit + conditions have been tuned to cover small values of \e f and the + inversion may be incorrect if \e f is large. + +Undoubtedly, bugs lurk in this code and in the documentation. Please +report any you find to charles@karney.com. + +
+Forward to \ref install. Up to \ref contents. +
+ +**********************************************************************/ +/** +\page install Installing GeographicLib + +
+Back to \ref intro. Forward to \ref start. Up to \ref contents. +
+ +GeographicLib has been developed under Linux with the g++ compiler +(versions 4.0 and later), under Mac OS X with Xcode (version 8.2), and +under Windows with Visual Studio 2010 and later. Earlier versions were +tested also under Visual Studio 2005 and 2008 and under Solaris. It +should compile on a wide range of other systems. First download either + +GeographicLib-@PROJECT_VERSION@.tar.gz or + +GeographicLib-@PROJECT_VERSION@.zip (or + +GeographicLib-@PROJECT_VERSION@-win32.exe or + +GeographicLib-@PROJECT_VERSION@-win64.exe +for binary installation under Windows). +Then pick one of the first five options below: +- \ref cmake. This is the preferred installation method as it will work + on the widest range of platforms. However it requires that you have + cmake installed. +- \ref autoconf. This method works for most Unix-like systems, + including Linux and Mac OS X. +- \ref gnu. This is a simple installation method that works with g++ + and GNU make on Linux and many Unix platforms. +- \ref windows. This is a simple installation method that works with + Visual Studio 2008 and 2010 under Windows. +- \ref binaryinst. Use this installation method if you only need to use + the \ref utilities supplied with GeographicLib. (This method also + installs the header files and the library for use by Visual Studio 14 + 2015.) +- \ref qt. How to compile GeographicLib so that it can be used by Qt + programs. +- \ref maintainer. This describes addition tasks of interest only to + the maintainers of this code. +. +This section documents only how to install the software. If you +wish to use GeographicLib to evaluate geoid heights or the earth's +gravitational or magnetic fields, then you must also install the +relevant data files. See \ref geoidinst, \ref gravityinst, and \ref +magneticinst for instructions. + +The first two installation methods use two important techniques which +make software maintenance simpler +- Out-of-source builds: This means that you create a separate + directory for compiling the code. In the description here the + directories are called BUILD and are located in the top-level of the + source tree. You might want to use a suffix to denote the type of + build, e.g., BUILD-vc11 for Visual Studio 11, or BUILD-shared for a + build which creates a shared library. The advantages of out-of-source + builds are: + - You don't mess up the source tree, so it's easy to "clean up". + Indeed the source tree might be on a read-only file system. + - Builds for multiple platforms or compilers don't interfere with each + other. +- The library is installed: After compilation, there is a + separate install step which copies the headers, libraries, + tools, and documentation to a "central" location. You may at this + point delete the source and build directories. If you have + administrative privileges, you can install GeographicLib for the use + of all users (e.g., in /usr/local). Otherwise, you can install it for + your personal use (e.g., in $HOME/packages). + +\section cmake Installation with cmake + +This is the recommended method of installation; however it requires that +cmake be installed on your system. +This permits GeographicLib to be built either as a shared or a static +library on a wide variety of systems. cmake can also determine the +capabilities of your system and adjust the compilation of the +libraries and examples appropriately. + +cmake is available for most computer platforms. On Linux systems cmake +will typically one of the standard packages and can be installed by a +command like + \verbatim + yum install cmake \endverbatim +(executed as root). The minimum version of cmake supported for building +GeographicLib is 2.8.4 (which was released on 2011-02-16). (Actually, +a few earlier versions will also work for non-Windows platforms.) + +On other systems, download a binary installer from https://www.cmake.org +click on download, and save and run the appropriate installer. Run the +cmake command with no arguments to get help. Other useful tools are +ccmake and cmake-gui which offer curses and graphical interfaces to +cmake. Building under cmake depends on whether it is targeting an IDE +(interactive development environment) or generating Unix-style +makefiles. The instructions below have been tested with makefiles and +g++ on Linux and with the Visual Studio IDE on Windows. It is known to +work also for Visual Studio 2017 Build Tools. + +Here are the steps to compile and install GeographicLib: +- Unpack the source, running one of \verbatim + tar xfpz GeographicLib-@PROJECT_VERSION@.tar.gz + unzip -q GeographicLib-@PROJECT_VERSION@.zip \endverbatim + then enter the directory created with \verbatim + cd GeographicLib-@PROJECT_VERSION@ \endverbatim +- Create a separate build directory and enter it, for example, \verbatim + mkdir BUILD + cd BUILD \endverbatim +- Run cmake, pointing it to the source directory (..). On Linux, Unix, + and MacOSX systems, the command is \verbatim + cmake .. \endverbatim + For Windows, the command is typically something like \verbatim + cmake -G "Visual Studio 11" -D CMAKE_INSTALL_PREFIX=C:/pkg-vc10/GeographicLib-@PROJECT_VERSION@ .. + cmake -G "Visual Studio 12" -A x64 -D CMAKE_INSTALL_PREFIX=C:/pkg-vc11-x64/GeographicLib-@PROJECT_VERSION@ ..\endverbatim + The definitions of CMAKE_INSTALL_PREFIX are optional (see below). The + settings given above are recommended to ensure that packages that use + GeographicLib use the version compiled with the right compiler. + If you need to rerun cmake, use \verbatim + cmake . \endverbatim + possibly including some options via -D (see the next step). +- cmake allows you to configure how GeographicLib is built and installed by + supplying options, for example \verbatim + cmake -D CMAKE_INSTALL_PREFIX=/tmp/geographic . \endverbatim + The options you might need to change are + - COMMON_INSTALL_PATH governs the installation + convention. If it is on ON (the Linux default), the installation + is to a common directory, e.g., /usr/local. If it is OFF (the + Windows default), the installation directory contains the package + name, e.g., C:/pkg/GeographicLib-@PROJECT_VERSION@. The installation + directories for the documentation, cmake configuration, Python and + MATLAB interfaces all depend on the variable with deeper paths + relative to CMAKE_INSTALL_PREFIX being used when it's ON: + - cmake configuration: OFF cmake; ON: lib/cmake/GeographicLib; + - documentation: OFF: doc/html; ON: share/doc/GeographicLib/html; + - JavaScript interface: OFF: node_modules; ON: lib/node_modules; + - Python interface: OFF: python; ON: lib/python/site-packages; + - MATLAB interface: OFF: matlab; ON: share/matlab. + . + - CMAKE_INSTALL_PREFIX (default: /usr/local + on non-Windows systems, C:/Program Files/GeographicLib + on Windows systems) specifies where the library will be installed. + For windows systems, it is recommended to use a prefix which + includes the compiler version, as shown above. If you just want to + try the library to see if it suits your needs, pick, for example, + CMAKE_INSTALL_PREFIX=/tmp/geographic. + - GEOGRAPHICLIB_DATA (default: + /usr/local/share/GeographicLib for non-Windows systems, + C:/ProgramData/GeographicLib for Windows systems) specifies the default + location for the various datasets for use by Geoid, + GravityModel, and MagneticModel. + See \ref geoidinst, \ref gravityinst, and \ref magneticinst for more + information. + - GEOGRAPHICLIB_LIB_TYPE (allowed values: SHARED, STATIC, or + BOTH), specifies the types of libraries build. The default is + STATIC for Windows and SHARED otherwise. If building GeographicLib + for system-wide use, BOTH is recommended, because this provides users + with the choice of which library to use. + - CMAKE_BUILD_TYPE (default: Release). This + flags only affects non-IDE compile environments (like make + g++). + The default is actually blank, but this is treated as + Release. Choose one of + \verbatim + Debug + Release + RelWithDebInfo + MinSizeRel +\endverbatim + (With IDE compile environments, you get to select the build type in + the IDE.) + - GEOGRAPHICLIB_DOCUMENTATION (default: OFF). If set to + ON, then html documentation is created from the source files, + provided a sufficiently recent version of doxygen can be found. + Otherwise, the html documentation will redirect to the appropriate + version of the online documentation. + - BUILD_NETGEOGRAPHICLIB (default: OFF). If set to ON, + build the managed C++ wrapper library + NETGeographicLib. This only makes + sense for Windows systems. + - GEOGRAPHICLIB_PRECISION specifies the precision to be + used for "real" (i.e., floating point) numbers. Here are the + possible values + -# float (24-bit precision); typically this is far to inaccurate + for geodetic applications. + -# double precision (53-bit precision, the default). + -# long double (64-bit precision); this does not apply for Visual + Studio (long double is the same as double with that compiler). + -# quad precision (113-bit precision). + -# arbitrary precision. + . + See \ref highprec for addition information about the last two + values. Nearly all the testing has been carried out with doubles + and that's the recommended configuration. In particular you should + avoid "installing" the library with a precision different from + double. + - USE_BOOST_FOR_EXAMPLES (default: OFF). If set to ON, + then the Boost library is searched for in order to build the + NearestNeighbor example. + - APPLE_MULTIPLE_ARCHITECTURES (default: OFF). If set to + ON, build for i386 and x86_64 and Mac OS X systems. Otherwise, + build for the default architecture. + - CONVERT_WARNINGS_TO_ERRORS (default: OFF). If set to + ON, then compiler warnings are treated as errors. (This happens + also if you are a "developer", i.e., if the file + tests/CMakeLists.txt is present.) +- Build and install the software. In non-IDE environments, run + \verbatim + make # compile the library and utilities + make test # run some tests + make install # as root, if CMAKE_INSTALL_PREFIX is a system directory +\endverbatim + Possible additional targets are \verbatim + make dist + make exampleprograms + make netexamples (supported only for Release configuration) \endverbatim + On IDE environments, run your IDE (e.g., Visual Studio), load + GeographicLib.sln, pick the build type (e.g., Release), and select + "Build Solution". If this succeeds, select "RUN_TESTS" to build; + finally, select "INSTALL" to install (RUN_TESTS and INSTALL are in + the CMakePredefinedTargets folder). Alternatively (for example, if + you are using the Visual Studio 2017 Build Tools), you run the Visual + Studio compiler from the command line with \verbatim + cmake --build . --config Release --target ALL_BUILD + cmake --build . --config Release --target RUN_TESTS + cmake --build . --config Release --target INSTALL \endverbatim + For maximum flexibility, it's a good idea to build and install both + the Debug and Release versions of the library (in that order). The + installation directories will then contain the release versions of the + tools and both versions (debug and release) of the libraries. + If you use cmake to configure and build your programs, then the right + version of the library (debug vs. release) will automatically be used. +- The headers, library, and utilities are installed in the + include/GeographicLib, lib, and bin directories under + CMAKE_INSTALL_PREFIX. (dll dynamic libraries are + installed in bin.) For documentation, open in a web browser + + PREFIX/share/doc/GeographicLib/html/index.html, if + COMMON_INSTALL_PATH is ON, or + PREFIX/doc/index.html, otherwise. + +\section autoconf Installation using the autoconfigure tools + +The method works on most Unix-like systems including Linux and Mac OS X. +Here are the steps to compile and install GeographicLib: +- Unpack the source, running \verbatim + tar xfpz GeographicLib-@PROJECT_VERSION@.tar.gz \endverbatim + then enter the directory created \verbatim + cd GeographicLib-@PROJECT_VERSION@ \endverbatim +- Create a separate build directory and enter it, for example, \verbatim + mkdir BUILD + cd BUILD \endverbatim +- Configure the software, specifying the path of the source directory, + with \verbatim + ../configure \endverbatim +- By default GeographicLib will be installed under /usr/local. + You can change this with, for example \verbatim + ../configure --prefix=/tmp/geographic \endverbatim +- Compile and install the software with \verbatim + make + make install \endverbatim +- The headers, library, and utilities are installed in the + include/GeographicLib, lib, and bin directories under + prefix. For documentation, open + share/doc/GeographicLib/html/index.html in a web browser. + +\section gnu Installation with GNU compiler and Make + +This method requires the standard GNU suite of tools, in particular make +and g++. This builds a static library and the examples. + +Here are the steps to compile and install GeographicLib: +- Unpack the source, running \verbatim + tar xfpz GeographicLib-@PROJECT_VERSION@.tar.gz \endverbatim + then enter the directory created \verbatim + cd GeographicLib-@PROJECT_VERSION@ \endverbatim +- Edit \verbatim + include/GeographicLib/Config.h \endverbatim + If your C++ compiler does not recognize the long double type + (unlikely), insert \code + #undef GEOGRAPHICLIB_HAVE_LONG_DOUBLE \endcode + If your machine using big endian ordering, then insert \code + #define GEOGRAPHICLIB_WORDS_BIGENDIAN 1 \endcode +- Build and install the software: \verbatim + make # compile the library and the examples + make install # as root \endverbatim + The installation is in directories under /usr/local. You + can specify a different installation directory with, for example, + \verbatim + make PREFIX=/tmp/geographic install \endverbatim +- The headers, library, and utilities are installed in the + include/GeographicLib, lib, and bin directories under + PREFIX. For documentation, open + share/doc/GeographicLib/html/index.html in a web browser. + +\section windows Installation on Windows + +This method requires Visual Studio 2008 or 2010. This builds a static +library and the utilities. If you have some other version of Visual +Studio, use cmake to create the necessary solution file, see \ref cmake. +(cmake is needed to run the tests.) +- Unpack the source, running \verbatim + unzip -q GeographicLib-@PROJECT_VERSION@.zip \endverbatim +- Open GeographicLib-@PROJECT_VERSION@/windows/GeographicLib-vc10.sln in + Visual Studio 2010 (for Visual Studio 2008, replace -vc10 by -vc9; for + Visual Studio Express 2010, replace -vc10 by -vc10x). +- Pick the build type (e.g., Release), and select "Build Solution". +- The library and the compiled examples are in the windows/Release. +- Copy the library windows/Release/GeographicLib.lib and the headers in + include/GeographicLib somewhere convenient. The headers should remain + in a directory named GeographicLib. For documentation, open + doc/html/index.html in a web browser. + +The Visual Studio 10 solution also contains projects to build +NETGeographicLib and the C# example project. + +\section binaryinst Using a binary installer + +Binary installers are available for some platforms + +\subsection binaryinstwin Windows + +Use this method if you only need to use the GeographicLib utilities. +The header files and static and shared versions of library are also +provided; these can only be used by Visual Studio 14 2015 (in either +release or debug mode). However, if you plan to use the library, it may +be advisable to build it with the compiler you are using for your own +code using either \ref cmake or \ref windows. + +Download and run + +GeographicLib-@PROJECT_VERSION@-win32.exe or + +GeographicLib-@PROJECT_VERSION@-win64.exe: + - read the MIT/X11 License agreement, + - select whether you want your PATH modified, + - select the installation folder, by default + C:\\pkg-vc12-win32\\GeographicLib-@PROJECT_VERSION@ or + C:\\pkg-vc12-x64\\GeographicLib-@PROJECT_VERSION@, + - select the start menu folder, + - and install. + . +(Note that the default installation folder adheres the the convention +given in \ref cmake.) The start menu will now include links to the +documentation for the library and for the utilities (and a link for +uninstalling the library). If you ask for your PATH to be modified, it +will include C:/pkg-vc12-{win32,x64}/GeographicLib-@PROJECT_VERSION@/bin +where the utilities are installed. The headers and library are +installed in the include/GeographicLib and lib folders. The libraries +were built using using Visual Studio 14 2015 in release and debug modes. +The utilities were linked against the release-mode shared library. + +NETGeographicLib library dlls (release and +debug) are included with the binary installers; these are linked against +the shared library for GeographicLib. + +\subsection binaryinstosx MacOSX + +You can install using Homebrew. Follow the directions on +https://brew.sh/ for installing this package manager. Then type +\verbatim +brew install geographiclib \endverbatim +Now links to GeographicLib are installed under /usr/local. + +\subsection binaryinstlin Linux + +Some Linux distributions, Fedora, Debian, and Ubuntu, offer +GeographicLib as a standard package. Typically these will be one or two +versions behind the latest. + +\section qt Building the library for use with Qt + +If Qt is using a standard compiler, then build GeographicLib with that +same compiler (and optimization flags) as Qt. + +If you are using the mingw compiler on Windows for Qt, then you need to +build GeographicLib with mingw. You can accomplish this with cmake +under cygwin with, for example, \verbatim + export PATH="`cygpath -m c:/QtSDK/mingw/bin`:$PATH" + mkdir BUILD + cd BUILD + cmake -G "MinGW Makefiles" -D CMAKE_INSTALL_PREFIX=C:/pkg-mingw/GeographicLib .. + mingw32-make + mingw32-make install \endverbatim +If cmake complains that sh mustn't be in your path, invoke cmake with +\verbatim + env PATH="$( echo $PATH | tr : '\n' | + while read d; do test -f "$d/sh.exe" || echo -n "$d:"; done | + sed 's/:$//' )" \ + cmake -G "MinGW Makefiles" -D CMAKE_INSTALL_PREFIX=C:/pkg-mingw/GeographicLib .. +\endverbatim + +\section maintainer Maintainer tasks + +Check the code out of git with \verbatim + git clone -b master git://git.code.sourceforge.net/p/geographiclib/code geographiclib +\endverbatim +Here the "master" branch is checked out. There are three branches in +the git repository: +- master: the main branch for code maintenance. Releases are + tagged on this branch as, e.g., v@PROJECT_VERSION@. +- devel: the development branch; changes made here are merged + into master. +- release: the release branch created by unpacking the source + releases (git is \e not used to merge changes from the other + branches into this branch). This is the \e default branch of the + repository (the branch you get if cloning the repository without + specifying a branch). This differs from the master branch in that + some administrative files are excluded while some intermediate files + are included (in order to aid building on as many platforms as + possible). Releases are tagged on this branch as, e.g., + r@PROJECT_VERSION@. +. +The autoconf configuration script and the formatted man pages are not +checked into master branch of the repository. In order to create the +autoconf configuration script, run \verbatim + sh autogen.sh \endverbatim +in the top level directory. Provided you are running on a system with +doxygen, pod2man, and pod2html installed, then you can create the +documentation and the man pages by building the system using cmake or +configure. + +In the case of cmake, you then run \verbatim + make dist \endverbatim +which will copy the man pages from the build directory back into the +source tree and package the resulting source tree for distribution as +\verbatim + GeographicLib-@PROJECT_VERSION@.tar.gz + GeographicLib-@PROJECT_VERSION@.zip \endverbatim +Finally, \verbatim + make package \endverbatim +or building PACKAGE in Visual Studio will create a binary installer for +GeographicLib. For Windows, this requires in the installation of +NSIS. On Windows, you should +configure GeographicLib with PACKAGE_DEBUG_LIBS=ON, build both +Release and Debug versions of the library and finally build PACKAGE in +Release mode. This will get the release and debug versions of the +library included in the package. For example, the 64-bit binary +installer is created with \verbatim + cmake -G "Visual Studio 12" -A x64 \ + -D GEOGRAPHICLIB_LIB_TYPE=BOTH \ + -D PACKAGE_DEBUG_LIBS=ON \ + -D BUILD_NETGEOGRAPHICLIB=ON \ + .. + cmake --build . --config Debug --target ALL_BUILD + cmake --build . --config Release --target ALL_BUILD + cmake --build . --config Release --target matlabinterface + cmake --build . --config Release --target PACKAGE \endverbatim + +With configure, run \verbatim + make dist-gzip \endverbatim +which will create the additional files and packages the results ready +for distribution as \verbatim + geographiclib-@PROJECT_VERSION@.tar.gz \endverbatim + +Prior to making a release, the script +tests/test-distribution.sh is run on a Fedora system. This +checked that the library compiles correctly is multiple configurations. +In addition it creates a directory and scripts for checking the +compilation on Windows. + +The following Fedora packages are required by +tests/test-distribution.sh +- cmake +- automake +- autoconf-archive +- libtool +- gcc-c++ +- gcc-gfortran +- ccache +- doxygen +- boost-devel +- octave +- python2-sphinx +- nodejs +- maven +. +The following npm packages need to be installed \verbatim + npm install -g mocha jsdoc \endverbatim +A recent version of mpreal.h needs to be downloaded from +https://bitbucket.org/advanpix/mpreal and installed +in the include/ directory. For all the tests to be run, +the following datasets need to be installed +- geoid models: egm96-5 +- magnetic models: wmm2010 emm2015 +- gravity models: egm2008 grs80 + +
+Back to \ref intro. Forward to \ref start. Up to \ref contents. +
+ +**********************************************************************/ +/** +\page start Getting started + +
+Back to \ref install. Forward to \ref utilities. Up to \ref contents. +
+ +Much (but not all!) of the useful functionality of GeographicLib is +available via simple command line utilities. Interfaces to some of them +are available via the web. See \ref utilities for documentation on +these. + +In order to use GeographicLib from C++ code, you will need to +- Include the header files for the GeographicLib classes in your code. + E.g., \code + #include \endcode +- Include the GeographicLib:: namespace prefix to the GeographicLib classes, + or include \code + using namespace GeographicLib; \endcode + in your code. +- Finally compile and link your code. You have two options here. + - Use cmake to build your package. If you are familiar with cmake + this typically will be far the simplest option. + - Set the include paths and linking options "manually". +- Building your code with cmake. In brief, the necessary steps are: + - include in your CMakeLists.txt files \verbatim + find_package (GeographicLib 1.34 REQUIRED) + include_directories (${GeographicLib_INCLUDE_DIRS}) + add_definitions (${GeographicLib_DEFINITIONS}) + add_executable (program source1.cpp source2.cpp) + target_link_libraries (program ${GeographicLib_LIBRARIES}) \endverbatim + If you're using cmake version 2.8.11 or later, you can omit the + include_directories and add_definitions + lines. + - configure your package, e.g., with \verbatim + mkdir BUILD + cd BUILD + cmake -G "Visual Studio 12" -A x64 \ + -D CMAKE_PREFIX_PATH=C:/pkg-vc10-x64 \ + -D CMAKE_INSTALL_PREFIX=C:/pkg-vc10-x64/testgeographic \ + .. \endverbatim + Note that you almost always want to configure and build your code + somewhere other than the source directory (in this case, we use the + BUILD subdirectory). Also, on Windows, make sure that the version + of Visual Sudio (12 in the example above) architecture (x64 in the + example above) matches that used to build GeographicLib. + - build your package. On Linux and MacOS this usually involves just + running make. On Windows, you can load the solution file created by + cmake into Visual Studio; alternatively, you can get cmake to run + build your code with \verbatim + cmake --build . --config Release --target ALL_BUILD \endverbatim + You might also want to install your package (using "make install" or + build the "INSTALL" target with the command above). + . + The most import step is the find_package command. The cmake + documentation describes the locations searched by find_package (the + appropriate rule for GeographicLib are those for "Config" mode lookups). + In brief, the locations that are searched are (from least specific to + most specific, i.e., in reverse order) are + - under the system paths, i.e., locations such as C:/Program + Files and /usr/local); + - frequently, it's necessary to search within a "package directory" + (or set of directories) for external dependencies; this is given by + a (semicolon separated) list of directories specified by the cmake + variable CMAKE_PREFIX_PATH (illustrated above); + - the package directory for GeographicLib can be overridden with the + environment variable GeographicLib_DIR (which is the + directory under which GeographicLib is installed); + - finally, if you need to point to a particular build of GeographicLib, + define the cmake variable GeographicLib_DIR, which + specifies the absolute path of the directory containing the + configuration file geographiclib-config.cmake (for + debugging this may be the top-level build directory, as + opposed to installation directory, for GeographicLib). + . + Typically, specifying nothing or CMAKE_PREFIX_PATH + suffices. However the two GeographicLib_DIR variables allow + for a specific version to be chosen. On Windows systems (with Visual + Studio), find_package will only find versions of GeographicLib built with + the right version of the compiler. (If you used a non-cmake method of + installing GeographicLib, you can try copying cmake/FindGeographicLib.cmake + to somewhere in your CMAKE_MODULE_PATH in order for + find_package to work. However, this method has not been thoroughly + tested.) + + If GeographicLib is not found, check the values of + GeographicLib_CONSIDERED_CONFIGS and + GeographicLib_CONSIDERED_VERSIONS; these list the + configuration files and corresponding versions which were considered + by find_package. + + If GeographicLib is found, then the following cmake variables are set: + - GeographicLib_FOUND = 1 + - GeographicLib_VERSION = @PROJECT_VERSION@ + - GeographicLib_INCLUDE_DIRS + - GeographicLib_LIBRARIES = one of the following two: + - GeographicLib_SHARED_LIBRARIES = GeographicLib + - GeographicLib_STATIC_LIBRARIES = GeographicLib_STATIC + - GeographicLib_DEFINITIONS = one of the following two: + - GeographicLib_SHARED_DEFINITIONS = -DGEOGRAPHICLIB_SHARED_LIB=1 + - GeographicLib_STATIC_DEFINITIONS = -DGEOGRAPHICLIB_SHARED_LIB=0 + - GeographicLib_LIBRARY_DIRS + - GeographicLib_BINARY_DIRS + - GEOGRAPHICLIB_DATA = value of this compile-time parameter + . + Either of GeographicLib_SHARED_LIBRARIES or + GeographicLib_STATIC_LIBRARIES may be empty, if that version + of the library is unavailable. If you require a specific version, + SHARED or STATIC, of the library, add a COMPONENTS clause + to find_package, e.g., + \verbatim + find_package (GeographicLib 1.34 REQUIRED COMPONENTS SHARED) \endverbatim + causes only packages which include the shared library to be found. If + the package includes both versions of the library, then + GeographicLib_LIBRARIES and + GeographicLib_DEFINITIONS are set to the shared versions, + unless you include \verbatim + set (GeographicLib_USE_STATIC_LIBS ON) \endverbatim + before the find_package command. You can check whether + GeographicLib_LIBRARIES refers to the shared or static + library with \verbatim + get_target_property(_LIBTYPE ${GeographicLib_LIBRARIES} TYPE) \endverbatim + which results in _LIBTYPE being set to + SHARED_LIBRARY or STATIC_LIBRARY. + On Windows, cmake takes care of linking to the release or debug + version of the library as appropriate. (This assumes that the Release + and Debug versions of the libraries were built and installed. This is + true for the Windows binary installer for GeographicLib version 1.34 and + later.) +- Here are the steps to compile and link your code using GeographicLib + "manually". + - Tell the compiler where to find the header files. With g++ and with + /usr/local specified as the installation directory, + this is accomplished with \verbatim + g++ -c -g -O3 -I/usr/local/include testprogram.cpp + \endverbatim + With Visual Studio, specify the include directory in the IDE via, + e.g., + \verbatim + C/C++ -> General -> Additional Include Directories = C:\pkg-vc10\GeographicLib\include + \endverbatim + - If using the shared (or static) library with Visual Studio, define + the macro GEOGRAPHICLIB_SHARED_LIB=1 (or + 0), e.g., + \verbatim + C/C++ -> Preprocessor -> Preprocessor Definitions = GEOGRAPHICLIB_SHARED_LIB=1 + \endverbatim + This is only needed for Windows systems when both shared and static + libraries have been installed. (If you configure your package with + cmake, this definition is added automatically.) + - Tell the linker the name, Geographic, and location of the + library. Using g++ as the linker, you would use \verbatim + g++ -g -o testprogram testprogram.o -L/usr/local/lib -lGeographic + \endverbatim + With Visual Studio, you supply this information in the IDE via, + e.g., \verbatim + Linker -> Input -> Additional Dependencies = Geographic-i.lib (for shared library) + Linker -> Input -> Additional Dependencies = Geographic.lib (for static library) + Linker -> General -> Additional Library Directories = C:\pkg-vc10\Geographic\lib + \endverbatim + Note that the library name is Geographic and not + GeographicLib. For the Debug version of your program on Windows + add "_d" to the library, e.g., Geographic_d-i.lib or + Geographic_d.lib. + - Tell the runtime environment where to find the shared library + (assuming you compiled %Geographic as a shared library). With g++, + this is accomplished by modifying the link line above to read \verbatim + g++ -g -o testprogram testprogram.o -Wl,-rpath=/usr/local/lib \ + -L/usr/local/lib -lGeographic + \endverbatim + (There are two other ways to specify the location of shared libraries + at runtime: (1) define the environment variable + LD_LIBRARY_PATH to be a colon-separated list of + directories to search; (2) as root, specify /usr/local/lib as a + directory searched by ldconfig(8).) On Windows, you need to ensure + that Geographic.dll or Geographic_d.dll is in the same directory as + your executable or else include the directory containing the dll in + your PATH. + - You can also use the pkg-config utility to specify compile and link + flags. This requires that pkg-config be installed and that it's + configured to search, e.g., /usr/local/lib/pgkconfig; if not, define + the environment variable PKG_CONFIG_PATH to include + this directory. The compile and link steps under Linux would + typically be + \verbatim + g++ -c -g -O3 `pkg-config --cflags geographiclib` testprogram.cpp + g++ -g -o testprogram testprogram.o `pkg-config --libs geographiclib` + \endverbatim + +Here is a very simple test code, which uses the Geodesic +class: +\include example-Geodesic-small.cpp +This example is examples/example-Geodesic-small.cpp. If you +compile, link, and run it according to the instructions above, it should +print out \verbatim + 5551.76 km \endverbatim +Here is a complete CMakeList.txt files you can use to build this test +code using the installed library: \verbatim +project (geodesictest) +cmake_minimum_required (VERSION 2.8.4) + +find_package (GeographicLib 1.34 REQUIRED) + +if (NOT MSVC) + set (CMAKE_INSTALL_RPATH_USE_LINK_PATH TRUE) +endif () + +if (CMAKE_VERSION VERSION_LESS 2.8.11) + include_directories (${GeographicLib_INCLUDE_DIRS}) + add_definitions (${GeographicLib_DEFINITIONS}) +endif () +add_executable (${PROJECT_NAME} example-Geodesic-small.cpp) +target_link_libraries (${PROJECT_NAME} ${GeographicLib_LIBRARIES}) + +if (MSVC) + get_target_property (_LIBTYPE ${GeographicLib_LIBRARIES} TYPE) + if (_LIBTYPE STREQUAL "SHARED_LIBRARY") + # On Windows systems, copy the shared library to build directory + add_custom_command (TARGET ${PROJECT_NAME} POST_BUILD + COMMAND ${CMAKE_COMMAND} -E + copy $ ${CMAKE_CFG_INTDIR} + COMMENT "Copying shared library for GeographicLib") + endif () +endif () \endverbatim + +The next steps are: + - Learn about and run the \ref utilities. + - Read the section, \ref organization, for an overview of the library. + - Browse the Class List for full documentation + on the classes in the library. + - Look at the example code in the examples directory. Each file + provides a very simple standalone example of using one GeographicLib + class. These are included in the descriptions of the classes. + - Look at the source code for the utilities in the tools directory for + more examples of using GeographicLib from C++ code, e.g., + GeodesicProj.cpp is a program to performing various geodesic + projections. + +Here's a list of some of the abbreviations used here with links to the +corresponding Wikipedia articles: + - + WGS84, World Geodetic System 1984. + - + UTM, Universal Transverse Mercator coordinate system. + - + UPS, Universal Polar Stereographic coordinate system. + - + MGRS, Military Grid Reference System. + - + EGM, Earth Gravity Model. + - + WMM, World Magnetic Model. + - + IGRF, International Geomagnetic Reference Field. + +
+Back to \ref install. Forward to \ref utilities. Up to \ref contents. +
+ +**********************************************************************/ +/** +\page utilities Utility programs + +
+Back to \ref start. Forward to \ref organization. Up to \ref contents. +
+ +Various utility programs are provided with GeographicLib. These should +be installed in a directory included in your PATH (e.g., +/usr/local/bin). These programs are wrapper programs that invoke +the underlying functionality provided by the library. + +The utilities are + - + GeoConvert: convert geographic coordinates using + GeoCoords. See \ref GeoConvert.cpp. + - + GeodSolve: perform geodesic calculations using + Geodesic and GeodesicLine. See \ref GeodSolve.cpp. + - + Planimeter: compute the area of geodesic polygons using + PolygonAreaT. See \ref Planimeter.cpp. + - + TransverseMercatorProj: convert between geographic + and transverse Mercator. This is for testing + TransverseMercatorExact and + TransverseMercator. See \ref TransverseMercatorProj.cpp. + - + CartConvert: convert geodetic coordinates to geocentric or + local cartesian using Geocentric and + LocalCartesian. See \ref CartConvert.cpp. + - + GeodesicProj: perform projections based on geodesics + using AzimuthalEquidistant, Gnomonic, + and CassiniSoldner. See \ref GeodesicProj.cpp. + - + ConicProj: perform conic projections using + LambertConformalConic and + AlbersEqualArea. See \ref ConicProj.cpp. + - + GeoidEval: look up geoid heights using + Geoid. See \ref GeoidEval.cpp. + - + Gravity: compute the earth's gravitational field using + GravityModel and GravityCircle. See \ref Gravity.cpp. + - + MagneticField: compute the earth's magnetic field using + MagneticModel and MagneticCircle. See \ref MagneticField.cpp. + - + RhumbSolve: perform rhumb line calculations using Rhumb + and RhumbLine. See \ref RhumbSolve.cpp. + . +The documentation for these utilities is in the form of man pages. This +documentation can be accessed by clicking on the utility name in the +list above, running the man command on Unix-like systems, or by invoking +the utility with the \--help option. A brief summary of +usage is given by invoking the utility with the -h option. +The version of the utility is given by the \--version +option. + +The utilities all accept data on standard input, transform it in some +way, and print the results on standard output. This makes the utilities +easy to use within scripts to transform tabular data; however they can +also be used interactively, often with the input supplied via a pipe, +e.g., + - echo 38SMB4488 | GeoConvert -d + +Online versions of four of these utilities are provided: + - GeoConvert + - GeodSolve + - Planimeter + - GeoidEval + - RhumbSolve + +
+Back to \ref start. Forward to \ref organization. Up to \ref contents. +
+ +**********************************************************************/ +/** +\page organization Code organization + +
+Back to \ref utilities. Forward to \ref other. Up to \ref contents. +
+ +Here is a brief description of the relationship between the various +components of GeographicLib. All of these are defined in the +GeographicLib namespace. + +TransverseMercator, PolarStereographic, LambertConformalConic, and +AlbersEqualArea provide the basic projections. The constructors for +these classes specify the ellipsoid and the forward and reverse +projections are implemented as const member functions. +TransverseMercator uses Krüger's series which have been extended to +sixth order in the square of the eccentricity. PolarStereographic, +LambertConformalConic, and AlbersEqualArea use the exact formulas for +the projections (e.g., from Snyder). + +TransverseMercator::UTM and PolarStereographic::UPS are const static +instantiations specific for the WGS84 ellipsoid with the UTM and UPS +scale factors. (These do \e not add the standard false eastings or +false northings for UTM and UPS.) Similarly +LambertConformalConic::Mercator is a const static instantiation of this +projection for a WGS84 ellipsoid and a standard parallel of 0 (which +gives the Mercator projection). AlbersEqualArea::CylindricalEqualArea, +AzimuthalEqualAreaNorth, and AzimuthalEqualAreaSouth, likewise provide +special cases of the equal area projection. + +UTMUPS uses TransverseMercator::UTM and PolarStereographic::UPS to +perform the UTM and UPS projections. The class offers a uniform +interface to UTM and UPS by treating UPS as UTM zone 0. This class +stores no internal state and the forward and reverse projections are +provided via static member functions. The forward projection offers the +ability to override the standard UTM/UPS choice and the UTM zone. + +MGRS transforms between UTM/UPS coordinates and MGRS. +UPS coordinates are handled as UTM zone 0. This class stores no +internal state and the forward (UTM/UPS to MGRS) and reverse (MGRS to +UTM/UPS) conversions are provided via static member functions. + +GeoCoords holds a single geographic location which may be +specified as latitude and longitude, UTM or UPS, or MGRS. Member +functions are provided to convert between coordinate systems and to +provide formatted representations of them. +GeoConvert is a simple command line +utility to provide access to the GeoCoords class. + +TransverseMercatorExact is a drop in replacement for TransverseMercator +which uses the exact formulas, based on elliptic functions, for the +projection as given by Lee. +TransverseMercatorProj is a +simple command line utility to test to the TransverseMercator and +TransverseMercatorExact. + +Geodesic and GeodesicLine perform geodesic calculations. The +constructor for Geodesic specifies the ellipsoid and the direct and +inverse calculations are implemented as const member functions. +Geocentric::WGS84 is a const static instantiation of Geodesic specific +for the WGS84 ellipsoid. In order to perform a series of direct +geodesic calculations on a single line, the GeodesicLine class can be +used. This packages all the information needed to specify a geodesic. +A const member function returns the coordinates a specified distance +from the starting point. GeodSolve is a +simple command line utility to perform geodesic calculations. +PolygonAreaT is a class which compute the area of geodesic polygons +using the Geodesic class and Planimeter +is a command line utility for the same purpose. AzimuthalEquidistant, +CassiniSoldner, and Gnomonic are projections based on the Geodesic +class. GeodesicProj is a command line +utility to exercise these projections. + +GeodesicExact and GeodesicLineExact are drop in replacements for +Geodesic and GeodesicLine in which the solution is given in terms of +elliptic integrals (computed by EllipticFunction). These classes should +be used if the absolute value of the flattening exceeds 0.02. The -E +option to GeodSolve uses these classes. + +NearestNeighbor is a header-only class for efficiently \ref nearest of a +collection of points where the distance function obeys the triangle +inequality. The geodesic distance obeys this condition. + +Geocentric and LocalCartesian convert between +geodetic and geocentric or a local cartesian system. The constructor for +specifies the ellipsoid and the forward and reverse projections are +implemented as const member functions. Geocentric::WGS84 is a +const static instantiation of Geocentric specific for the WGS84 ellipsoid. +CartConvert is a simple command line +utility to provide access to these classes. + +Geoid evaluates geoid heights by interpolation. This is +provided by the operator() member function. +GeoidEval is a simple command line +utility to provide access to this class. This class requires +installation of data files for the various geoid models; see \ref +geoidinst for details. + +Ellipsoid is a class which performs latitude +conversions and returns various properties of the ellipsoid. + +GravityModel evaluates the earth's gravitational field using a +particular gravity model. Various member functions return the +gravitational field, the gravity disturbance, the gravity anomaly, and +the geoid height Gravity is a simple +command line utility to provide access to this class. If the field +several points on a circle of latitude are sought then use +GravityModel::Circle to return a GravityCircle object whose member +functions performs the calculations efficiently. (This is particularly +important for high degree models such as EGM2008.) These classes +requires installation of data files for the various gravity models; see +\ref gravityinst for details. NormalGravity computes the gravity of the +so-called level ellipsoid. + +MagneticModel evaluates the earth's magnetic field using a particular +magnetic model. The field is provided by the operator() member +function. MagneticField is a simple +command line utility to provide access to this class. If the field +several points on a circle of latitude are sought then use +MagneticModel::Circle to return a MagneticCircle object whose operator() +member function performs the calculation efficiently. (This is +particularly important for high degree models such as emm2010.) These +classes requires installation of data files for the various magnetic +models; see \ref magneticinst for details. + +Constants, Math, Utility, DMS, are general utility class which are used +internally by the library; in addition EllipticFunction is used by +TransverseMercatorExact, Ellipsoid, and GeodesicExact, and +GeodesicLineExact; Accumulator is used by PolygonAreaT, and +SphericalEngine, CircularEngine, SphericalHarmonic, SphericalHarmonic1, +and SphericalHarmonic2 facilitate the summation of spherical harmonic +series which is needed by and MagneticModel and MagneticCircle. One +important definition is Math::real which is the type used for real +numbers. This allows the library to be easily switched to using floats, +doubles, or long doubles. However all the testing has been with real +set to double and the library should be installed in this way. + +GeographicLib uniformly represents all angle-like variables (latitude, +longitude, azimuth) in terms of degrees. To convert from degrees to +radians, multiple the quantity by Math::degree(). To convert from +radians to degrees , divide the quantity by Math::degree(). + +In general, the constructors for the classes in GeographicLib check +their arguments and throw GeographicErr exceptions with a +explanatory message if these are illegal. The member functions, e.g., +the projections implemented by TransverseMercator and +PolarStereographic, the solutions to the geodesic problem, etc., +typically do not check their arguments; the calling program +should ensure that the arguments are legitimate. However, the functions +implemented by UTMUPS, MGRS, and GeoCoords do check their arguments and +may throw GeographicErr exceptions. Similarly Geoid may +throw exceptions on file errors. If a function does throw an exception, +then the function arguments used for return values will not have been +altered. + +GeographicLib attempts to act sensibly with NaNs. NaNs in constructors +typically throw errors (an exception is GeodesicLine). However, calling +the class functions with NaNs as arguments is not an error; NaNs are +returned as appropriate. "INV" is treated as an invalid zone +designation by UTMUPS. "INVALID" is the corresponding invalid MGRS +string (and similarly for GARS, Geohash, and Georef strings). NaNs +allow the projection of polylines which are separated by NaNs; in this +format they can be easily plotted in MATLAB. + +A note about portability. For the most part, the code uses standard C++ +and should be able to be deployed on any system with a modern C++ +compiler. System dependencies come into + - Math -- GeographicLib needs to define functions such + as atanh for systems that lack them. The system dependence will + disappear with the adoption of C++11 because the needed functions are + part of that standard. + - use of long double -- the type is used only for testing. On systems + which lack this data type the cmake and autoconf configuration + methods should detect its absence and omit the code that depends on + it. + - Geoid, GravityModel, and + MagneticModel -- these class uses system-dependent + default paths for looking up the respective datasets. It also relies + on getenv to find the value of the environment variables. + - Utility::readarray reads numerical data from binary + files. This assumes that floating point numbers are in IEEE format. + It attempts to handled the "endianness" of the target platform using + the GEOGRAPHICLIB_WORDS_BIGENDIAN macro (which sets the compile-time + constant Math::bigendian). + +An attempt is made to maintain backward compatibility with GeographicLib +(especially at the level of your source code). Sometimes it's necessary +to take actions that depend on what version of GeographicLib is being +used; for example, you may want to use a new feature of GeographicLib, +but want your code still to work with older versions. In that case, you +can test the values of the macros GEOGRAPHICLIB_VERSION_MAJOR, +GEOGRAPHICLIB_VERSION_MINOR, and GEOGRAPHICLIB_VERSION_PATCH; these +expand to numbers (and the last one is usually 0); these macros appeared +starting in version 1.31. There's also a macro +GEOGRAPHICLIB_VERSION_STRING which expands to, e.g., +"@PROJECT_VERSION@"; this macro has been defined since version 1.9. +Since version 1.37, there's also been a macro GEOGRAPHICLIB_VERSION +which encodes the version as a single number, e.g, 1003900. Do not rely +on this particular packing; instead use the macro +GEOGRAPHICLIB_VERSION_NUM(a,b,c) which allows you to compare versions +with, e.g., +\code +#if GEOGRAPHICLIB_VERSION >= GEOGRAPHICLIB_VERSION_NUM(1,37,0) +... +#endif \endcode + +
+Back to \ref utilities. Forward to \ref other. Up to \ref contents. +
+ +**********************************************************************/ +/** +\page other Implementations in other languages + +
+Back to \ref organization. Forward to \ref geoid. Up to \ref contents. +
+ +Various subsets of GeographicLib have been implemented in other +languages. In some cases, these are available as independent packages. +Here is a summary: +- C (geodesic routines): + + documentation, also included with recent versions of + + proj.4; +- Fortran (geodesic routines): + + documentation; +- Java (geodesic routines): + + Maven Central package, + + documentation; +- JavaScript (geodesic routines): + + npm package, + + documentation; +- Python (geodesic routines): + + PyPI package, + + documentation; +- MATLAB/Octave (geodesic and some other routines): + + MATLAB Central package, + + documentation; +- C# (.NET wrapper for C++ library): + + documentation. + +Some more details are available in the following sections +- \ref c-fortran +- \ref java. +- \ref javascript. +- \ref python. +- \ref matlab. +- \ref dotnet. +- \ref maxima. + +\section c-fortran C and Fortran implementation + +This includes the geodesic capabilities of GeographicLib. The source +code is in the directories legacy/C and +legacy/Fortran. These are intended for use in old codes +written in these languages and should work any reasonably modern +compiler. These implementations are entirely self-contained and do not +depend on the rest of GeographicLib. Sample main programs to solve the +direct and inverse geodesic problems and to compute polygonal areas are +provided. + +The C library is also included as part of +proj.4 starting with +version 4.9.0, where it is used as the computational backend for +geod(1). + +For documentation, see + - C library for geodesics, + - Fortran library for geodesics. + +It is also possible to call the C++ version of GeographicLib directly +from C and the directory wrapper/C contains a small +example, which converts heights above the geoid to heights above the +ellipsoid. + +\section java Java implementation + +This includes the geodesic capabilities of GeographicLib. The source +code is in the directory java. This implementation is +entirely self-contained and does not depend on the rest of +GeographicLib. Sample main programs to solve the direct and inverse +geodesic problems and to compute polygonal areas are provided. + +This package is available on Maven Central; so if you're using Apache +Maven as your build system, you can use this package by including the +dependency \verbatim + + net.sf.geographiclib + GeographicLib-Java + 1.46 + + \endverbatim +in your pom.xml. + +For documentation, see + - Java library for geodesics. + +\section javascript JavaScript implementation + +This includes the geodesic capabilities of GeographicLib. The source +code is in the directory js. This implementation is +entirely self-contained and does not depend on the rest of +GeographicLib. + +The library is available as an + + npm package. +To install this package, use \verbatim + npm install geographiclib \endverbatim + +For documentation, see + - JavaScript library for geodesics. + +Examples of using this interface are +- a geodesic calculator showing + the solution of direct and inverse geodesic problem, finding + intermediate points on a geodesic line, and computing the area of a + geodesic polygon; +- displaying geodesics in Google + Maps which shows the geodesic, the geodesic circle, and various + geodesic envelopes. + +\section python Python implementation + +This includes the geodesic capabilities of GeographicLib. The source +code is in the directory python. This implementation is +entirely self-contained and does not depend on the rest of +GeographicLib. + +The library is available as an + + PyPI package. +To install this package, use \verbatim + pip install geographiclib \endverbatim + +For documentation, see + - Python library for geodesics. + +It is also possible to call the C++ version of GeographicLib directly +from Python and the directory wrapper/python contains a +small example, which converts heights above the geoid to heights above +the ellipsoid. + +\section matlab MATLAB and Octave implementations + +The includes the geodesic capabilities of GeographicLib and +implementations of the TransverseMercator, PolarStereographic, +AzimuthalEquidistant, CassiniSoldner, Gnomonic, UTMUPS, MGRS, Geocentric, +and LocalCartesian classes. In addition, it includes solutions of the +direct, inverse, and area problems for \ref greatellipse. Because these +functions are all vectorized, their performance is comparable to the C++ +routines. The minimum version numbers required are + - MATLAB, version 7.9, 2009b, + - Octave, version 3.4, Feb. 2011. + . +In addition, in order to use the geoid routines, Octave needs to have +been built with a version of GraphicsMagick which supports 16-bit +images. The source code is in the directory +matlab/geographiclib. This implementation is entirely +self-contained and does not depend on the rest of GeographicLib. + +The library is available as an MATLAB Central package, + + GeographicLib toolbox. + +A summary of the routines is obtained by \verbatim + help geographiclib \endverbatim + +Prior to version 1.42, GeographicLib was distributed with some MATLAB +functionality offered via compiled interface code. This has now been +replaced by native MATLAB wrapper functions in +matlab/geographiclib-legacy; these depend on the + +GeographicLib toolbox. +A summary of the routines is obtained by \verbatim + help geographiclib-legacy \endverbatim + +It is also possible to call the C++ version of GeographicLib directly +from MATLAB or Octave and the directory wrapper/matlab +contains a small example, which solves the inverse geodesic problem for +ellipsoids with arbitrary flattening. (This example is taken from the +MATLAB interface code which was provided prior to version 1.42.) + +\section dotnet .NET wrapper + +This is a comprehensive wrapper library, written and maintained by Scott +Heiman, which exposes all of the functionality of GeographicLib to the +.NET family of languages. For documentation, see + - NETGeographicLib .NET wrapper library. + +\section maxima Maxima routines + +Maxima is a free computer algebra system which can be downloaded from +http://maxima.sourceforge.net. Maxima was used to generate the series used by +TransverseMercator ( tmseries.mac), Geodesic +( geod.mac), Rhumb ( +rhumbarea.mac), \ref gearea ( gearea.mac), +the relation between \ref auxlat ( auxlat.mac), +and to generate accurate data for testing ( tm.mac +and geodesic.mac). The latter uses Maxima's +bigfloat arithmetic together with series extended to high order or +solutions in terms of elliptic integrals ( +ellint.mac). These files contain brief instructions on how to use +them. + +
+Back to \ref organization. Forward to \ref geoid. Up to \ref contents. +
+ +**********************************************************************/ +/** +\page geoid Geoid height + +
+Back to \ref other. Forward to \ref gravity. Up to \ref contents. +
+ +The gravitational equipotential surface approximately coinciding with +mean sea level is called the geoid. The Geoid class and +the GeoidEval utility evaluate the height +of the geoid above the WGS84 ellipsoid. This can be used to convert +heights above mean sea level to heights above the WGS84 ellipsoid. +Because the normal to the ellipsoid differs from the normal to the geoid +(the direction of a plumb line) there is a slight ambiguity in the +measurement of heights; however for heights up to 10 km this ambiguity +is only 1 mm. + +The geoid is usually approximated by an "earth gravity model" (EGM). +The models published by the NGA are: +- EGM84: + http://earth-info.nga.mil/GandG/wgs84/gravitymod/wgs84_180/wgs84_180.html +- EGM96: + http://earth-info.nga.mil/GandG/wgs84/gravitymod/egm96/egm96.html +- EGM2008: + http://earth-info.nga.mil/GandG/wgs84/gravitymod/egm2008 +. +Geoid offers a uniform way to handle all 3 geoids at a variety of grid +resolutions. (In contrast, the software tools that NGA offers are +different for each geoid, and the interpolation programs are different +for each grid resolution. In addition these tools are written in +Fortran with is nowadays difficult to integrate with other software.) + +The height of the geoid above the ellipsoid, \e N, is sometimes called +the geoid undulation. It can be used to convert a height above the +ellipsoid, \e h, to the corresponding height above the geoid (the +orthometric height, roughly the height above mean sea level), \e H, +using the relations + +   \e h = \e N + \e H;   \e H = −\e N + \e h. + +Unlike other components of GeographicLib, there is a appreciable error +in the results obtained (at best, the RMS error is 1 mm). However the +class provides methods to report the maximum and RMS errors in the +results. The class also returns the gradient of the geoid. This can be +used to estimate the direction of a plumb line relative to the WGS84 +ellipsoid. + +The GravityModel class calculates geoid heights using the +underlying gravity model. This is slower then Geoid but +considerably more accurate. This class also can accurately compute all +the components of the acceleration due to gravity (and hence the +direction of plumb line). + +Go to + - \ref geoidinst + - \ref geoidformat + - \ref geoidinterp + - \ref geoidcache + - \ref testgeoid + +\section geoidinst Installing the geoid datasets + +The geoid heights are computed using interpolation into a rectangular +grid. The grids are read from data files which have been are computed +using the NGA synthesis programs in the case of the EGM84 and EGM96 +models and using the NGA binary gridded data files in the case of +EGM2008. These data files are available for download: +
+ + + + + + + + + + + + + + + +
Available geoid data files
name geoid grid + size\n(MB) +
Download Links (size, MB)
tar fileWindows\n installerzip file
egm84-30 + EGM84 +
30'
+
0.6
+
+ + link (0.5)
+
+ + link (0.8)
+
+ + link (0.5)
+
egm84-15 + EGM84 +
15'
+
2.1
+
+ + link (1.5)
+
+ + link (1.9)
+
+ + link (2.0)
+
egm96-15 + EGM96 +
15'
+
2.1
+
+ + link (1.5)
+
+ + link (1.9)
+
+ + link (2.0)
+
egm96-5 + EGM96 +
5'
+
19
+
+ + link (11)
+
+ + link (11)
+
+ + link (17)
+
egm2008-5 + EGM2008 +
5'
+
19
+
+ + link (11)
+
+ + link (11)
+
+ + link (17)
+
egm2008-2_5 + EGM2008 +
2.5'
+
75
+
+ + link (35)
+
+ + link (33)
+
+ + link (65)
+
egm2008-1 + EGM2008 +
1'
+
470
+
+ + link (170)
+
+ + link (130)
+
+ + link (390)
+
+
+The "size" column is the size of the uncompressed data and it also +gives the memory requirements for caching the entire dataset using the +Geoid::CacheAll method. +At a minimum you should install egm96-5 and either egm2008-1 or +egm2008-2_5. Many applications use the EGM96 geoid, however the use of +EGM2008 is growing. (EGM84 is rarely used now.) + +For Linux and Unix systems, GeographicLib provides a shell script +geographiclib-get-geoids (typically installed in /usr/local/sbin) which +automates the process of downloading and installing the geoid data. For +example +\verbatim + geographiclib-get-geoids best # to install egm84-15, egm96-5, egm2008-1 + geographiclib-get-geoids -h # for help +\endverbatim +This script should be run as a user with write access to the +installation directory, which is typically +/usr/local/share/GeographicLib (this can be overridden with the -p +flag), and the data will then be placed in the "geoids" subdirectory. + +Windows users should download and run the Windows installers. These +will prompt for an installation directory with the default being +\verbatim + C:/ProgramData/GeographicLib +\endverbatim +(which you probably should not change) and the data is installed in the +"geoids" sub-directory. (The second directory name is an alternate name +that Windows 7 uses for the "Application Data" directory.) + +Otherwise download \e either the tar.bz2 file \e or the zip file (they +have the same contents). If possible use the tar.bz2 files, since these +are compressed about 2 times better than the zip file. To unpack these, +run, for example +\verbatim + mkdir -p /usr/local/share/GeographicLib + tar xofjC egm96-5.tar.bz2 /usr/local/share/GeographicLib + tar xofjC egm2008-2_5.tar.bz2 /usr/local/share/GeographicLib + etc. +\endverbatim +and, again, the data will be placed in the "geoids" subdirectory. + +However you install the geoid data, all the datasets should +be installed in the same directory. Geoid and +GeoidEval uses a compile time default to +locate the datasets. This is +- /usr/local/share/GeographicLib/geoids, for non-Windows systems +- C:/ProgramData/GeographicLib/geoids, for Windows systems +. +consistent with the examples above. This may be overridden at run-time +by defining the GEOGRAPHICLIB_GEOID_PATH or the GEOGRAPHICLIB_DATA +environment variables; see Geoid::DefaultGeoidPath() for +details. Finally, the path may be set using the optional second +argument to the Geoid constructor or with the "-d" flag +to GeoidEval. Supplying the "-h" flag to +GeoidEval reports the default geoid path +for that utility. The "-v" flag causes GeoidEval to report the full +path name of the data file it uses. + +\section geoidformat The format of the geoid data files + +The gridded data used by the Geoid class is stored in +16-bit PGM files. Thus the data for egm96-5 might be stored in the file +- /usr/local/share/GeographicLib/geoids/egm96-5.pgm +. +PGM simple graphic format with the following properties +- it is well documented + here; +- there are no separate "little-endian" and "big-endian" versions; +- it uses 1 or 2 bytes per pixel; +- pixels can be randomly accessed; +- comments can be added to the file header; +- it is sufficiently simple that it can be easily read without using the + libnetpbm + library (and thus we avoid adding a software dependency to + GeographicLib). +. +The major drawback of this format is that since there are only 65535 +possible pixel values, the height must be quantized to 3 mm. However, +the resulting quantization error (up to 1.5 mm) is typically smaller +than the linear interpolation errors. The comments in the header for +egm96-5 are +\verbatim + # Geoid file in PGM format for the GeographicLib::Geoid class + # Description WGS84 EGM96, 5-minute grid + # URL http://earth-info.nga.mil/GandG/wgs84/gravitymod/egm96/egm96.html + # DateTime 2009-08-29 18:45:03 + # MaxBilinearError 0.140 + # RMSBilinearError 0.005 + # MaxCubicError 0.003 + # RMSCubicError 0.001 + # Offset -108 + # Scale 0.003 + # Origin 90N 0E + # AREA_OR_POINT Point + # Vertical_Datum WGS84 +\endverbatim +Of these lines, the Scale and Offset lines are required and define the +conversion from pixel value to height (in meters) using \e height = +\e offset + \e scale \e pixel. The Geoid constructor also reads the +Description, DateTime, and error lines (if present) and stores the +resulting data so that it can be returned by +Geoid::Description, Geoid::DateTime, +Geoid::MaxError, and Geoid::RMSError +methods. The other lines serve as additional documentation but are not +used by this class. Accompanying egm96-5.pgm (and similarly with the +other geoid data files) are two files egm96-5.wld and +egm96-5.pgm.aux.xml. The first is an ESRI "world" file and the second +supplies complete projection metadata for use by +GDAL. Neither of these files is read +by Geoid. + +You can use gdal_translate to convert the data files to a standard +GeoTiff, e.g., with +\verbatim + gdal_translate -ot Float32 -scale 0 65000 -108 87 egm96-5.pgm egm96-5.tif +\endverbatim +The arguments to -scale here are specific to the Offset and Scale +parameters used in the pgm file (note 65000 * 0.003 − 108 = 87). +You can check these by running GeoidEval +with the "-v" option. + +Here is a sample script which uses GDAL to create a 1-degree +squared grid of geoid heights at 3" resolution (matching DTED1) by +bilinear interpolation. +\verbatim + #! /bin/sh + lat=37 + lon=067 + res=3 # resolution in seconds + TEMP=`mktemp junkXXXXXXXXXX` # temporary file for GDAL + gdalwarp -q -te `echo $lon $lat $res | awk '{ + lon = $1; lat = $2; res = $3; + printf "%.14f %.14f %.14f %.14f", + lon -0.5*res/3600, lat -0.5*res/3600, + lon+1+0.5*res/3600, lat+1+0.5*res/3600; + }'` -ts $((3600/res+1)) $((3600/res+1)) -r bilinear egm96-5.tif $TEMP + gdal_translate -quiet \ + -mo AREA_OR_POINT=Point \ + -mo Description="WGS84 EGM96, $res-second grid" \ + -mo Vertical_Datum=WGS84 \ + -mo Tie_Point_Location=pixel_corner \ + $TEMP e$lon-n$lat.tif + rm -f $TEMP +\endverbatim + +Because the pgm files are uncompressed, they can take up a lot of disk +space. Some compressed formats compress in tiles and so might be +compatible with the requirement that the data can be randomly accessed. +In particular gdal_translate can be used to convert the pgm files to +compressed tiff files with +\verbatim +gdal_translate -co COMPRESS=LZW -co PREDICTOR=2 \ + -co TILED=YES -co BLOCKXSIZE=256 -co BLOCKYSIZE=256 \ + egmyy-g.pgm egmyy-g.tif +\endverbatim +The resulting files sizes are +\verbatim + pgm tif + egm84-30 0.6 MB 0.5 MB + egm84-15 2.1 MB 1.4 MB + egm96-15 2.1 MB 1.5 MB + egm96-5 19 MB 8.5 MB + egm2008-5 19 MB 9.8 MB + egm2008-2_5 75 MB 28 MB + egm2008-1 470 MB 97 MB +\endverbatim +Currently, there are no plans for GeographicLib to support this +compressed format. + +The Geoid class only handles world-wide geoid models. The pgm provides +geoid height postings on grid of points with uniform spacing in latitude +(row) and longitude (column). If the dimensions of the pgm file are +\e h × \e w, then latitude (resp. longitude) spacing is +180°/(\e h − 1) (resp. 360°/\e w), with the (0,0) pixel +given the value at φ = 90°, λ = 0°. Models covering a +restricted area will need to be "inserted" into a world-wide grid before +being accessible to the Geoid class. + +\section geoidinterp Interpolating the geoid data + +Geoid evaluates the geoid height using bilinear or cubic +interpolation. The gradient of the geoid height is obtained by +differentiating the interpolated height and referencing the result to +distance on the WGS84 ellipsoid. + +WARNING: Although Geoid computes the gradient of +the geoid height, this is subject to large quantization errors as a +result of the way that the geoid data is stored. This is particularly +acute for fine grids, at high latitudes, and for the easterly gradient. +If you need to compute the direction of the acceleration due to gravity +accurately, you should use GravityModel::Gravity. + +The bilinear interpolation is based on the values at the 4 corners of +the enclosing cell. The interpolated height is a continuous function of +position; however the gradient has discontinuities are cell boundaries. +The quantization of the data files exacerbates the errors in the +gradients. + +The cubic interpolation is a least-squares fit to the values on a +12-point stencil with weights as follows: +\verbatim + . 1 1 . + 1 2 2 1 + 1 2 2 1 + . 1 1 . +\endverbatim +The cubic is constrained to be independent of longitude when evaluating +the height at one of the poles. Cubic interpolation is considerably +more accurate than bilinear interpolation; however, in this +implementation there are small discontinuities in the heights are cell +boundaries. The over-constrained cubic fit slightly reduces the +quantization errors on average. + +The algorithm for the least squares fit is taken from, F. H. Lesh, +Multi-dimensional least-squares polynomial curve fitting, CACM 2, 29--30 +(1959). This algorithm is not part of Geoid; instead it is implemented +as +Maxima +code which is used to precompute the matrices to convert the function +values on the stencil into the coefficients from the cubic polynomial. +This code is included as a comment in Geoid.cpp. + +The interpolation methods are quick and give good accuracy. Here is a +summary of the combined quantization and interpolation errors for the +heights. +
+ + + + + + + + + + + + +
Interpolation and quantization errors for geoid heights
name + geoid + grid +
bilinear error
cubic error
max
rms
+
max
rms
+
egm84-30 EGM84
30'
+
1.546 m
70 mm
+
0.274 m
14 mm
+
egm84-15 EGM84
15'
+
0.413 m
18 mm
+
0.021 m
1.2 mm
+
egm96-15 EGM96
15'
+
1.152 m
40 mm
+
0.169 m
7.0 mm
+
egm96-5 EGM96
5'
+
0.140 m
4.6 mm
+
0.0032 m
0.7 mm
+
egm2008-5 EGM2008
5'
+
0.478 m
12 mm
+
0.294 m
4.5 mm
+
egm2008-2_5EGM2008
2.5'
+
0.135 m
3.2 mm
+
0.031 m
0.8 mm
+
egm2008-1 EGM2008
1'
+
0.025 m
0.8 mm
+
0.0022 m
0.7 mm
+
+The errors are with respect to the specific NGA earth gravity model +(not to any "real" geoid). The RMS values are obtained using 5 million +uniformly distributed random points. The maximum values are obtained by +evaluating the errors using a different grid with points at the +centers of the original grid. (The RMS difference between EGM96 and +EGM2008 is about 0.5 m. The RMS difference between EGM84 and EGM96 is +about 1.5 m.) + +The errors in the table above include the quantization errors that arise +because the height data that Geoid uses are quantized to +3 mm. If, instead, Geoid were to use data files without +such quantization artifacts, the overall error would be reduced but +only modestly as shown in the following table, where only the +changed rows are included and where the changed entries are given in +bold: +
+ + + + + + + + +
Interpolation (only!) errors for geoid heights
name + geoid + grid +
bilinear error
cubic error
max
rms
+
max
rms
+
egm96-5 EGM96
5'
+
0.140 m
4.6 mm
+
0.0026 m
0.1 mm
+
egm2008-2_5EGM2008
2.5'
+
0.135 m
3.2 mm
+
0.031 m
0.4 mm
+
egm2008-1 EGM2008
1'
+
0.025 m
0.6 mm
+
0.0010 m
0.011 mm
+
+ +\section geoidcache Caching the geoid data + +A simple way of calling Geoid is as follows +\code + #include + #include + ... + GeographicLib::Geoid g("egm96-5"); + double lat, lon; + while (std::cin >> lat >> lon) + std::cout << g(lat, lon) << "\n"; + ... +\endcode + +The first call to g(lat, lon) causes the data for the stencil points (4 +points for bilinear interpolation and 12 for cubic interpolation) to be +read and the interpolated value returned. A simple 0th-order caching +scheme is provided by default, so that, if the second and subsequent +points falls within the same grid cell, the data values are not reread +from the file. This is adequate for most interactive use and also +minimizes disk accesses for the case when a continuous track is being +followed. + +If a large quantity of geoid calculations are needed, the calculation +can be sped up by preloading the data for a rectangular block with +Geoid::CacheArea or the entire dataset with +Geoid::CacheAll. If the requested points lie within the +cached area, the cached data values are used; otherwise the data is read +from disk as before. Caching all the data is a reasonable choice for +the 5' grids and coarser. Caching all the data for the 1' grid will +require 0.5 GB of RAM and should only be used on systems with sufficient +memory. + +The use of caching does not affect the values returned. Because of the +caching and the random file access, this class is \e not normally thread +safe; i.e., a single instantiation cannot be safely used by multiple +threads. If multiple threads need to calculate geoid heights, there are +two alternatives: + - they should all construct thread-local instantiations. + - Geoid should be constructed with \e threadsafe = true. + This causes all the data to be read at the time of construction (and + if this fails, an exception is thrown), the data file to be closed + and the single-cell caching to be turned off. The resulting object + may then be shared safely between threads. + +\section testgeoid Test data for geoids + +A test set for the geoid models is available at + - + GeoidHeights.dat.gz + . +This is about 11 MB (compressed). This test set consists of a set of +500000 geographic coordinates together with the corresponding geoid +heights according to various earth gravity models. + +Each line of the test set gives 6 space delimited numbers + - latitude (degrees, exact) + - longitude (degrees, exact) + - EGM84 height (meters, accurate to 1 μm) + - EGM96 height (meters, accurate to 1 μm) + - EGM2008 height (meters, accurate to 1 μm) + . +The latitude and longitude are all multiples of 10−6 +deg and should be regarded as exact. The geoid heights are computed +using the harmonic NGA synthesis programs, where the programs were +compiled (with gfortran) and run under Linux. In the case of the +EGM2008 program, a SAVE statement needed to be added to +subroutine latf, in order for the program to compile +correctly with a stack-based compiler. Similarly the EGM96 code +requires a SAVE statement in subroutine +legfdn. + +
+Back to \ref other. Forward to \ref gravity. Up to \ref contents. +
+ +**********************************************************************/ +/** +\page gravity Gravity models + +
+Back to \ref geoid. Forward to \ref normalgravity. Up to \ref contents. +
+ +GeographicLib can compute the earth's gravitational field with an earth +gravity model using the GravityModel and GravityCircle classes and with +the Gravity utility. These models expand +the gravitational potential of the earth as sum of spherical harmonics. +The models also specify a reference ellipsoid, relative to which geoid +heights and gravity disturbances are measured. Underlying all these +models is normal gravity which is the exact solution for an +idealized rotating ellipsoidal body. This is implemented with the +NormalGravity class and some notes on are provided in section \ref +normalgravity + +Go to + - \ref gravityinst + - \ref gravityformat + - \ref gravitynga + - \ref gravitygeoid + - \ref gravityatmos + - \ref gravityparallel + - \ref normalgravity (now on its own page) + +The supported models are + - egm84, the + + Earth Gravity Model 1984, which includes terms up to degree 180. + - egm96, the + + Earth Gravity Model 1996, which includes terms up to degree 360. + - egm2008, the + + Earth Gravity Model 2008, which includes terms up to degree 2190. + - wgs84, the + + WGS84 Reference Ellipsoid. This is just reproduces the normal + gravitational field for the reference ellipsoid. This includes the + zonal coefficients up to order 20. Usually NormalGravity::WGS84() + should be used instead. + - grs80, the + GRS80 Reference Ellipsoid. This is just reproduces the normal + gravitational field for the GRS80 ellipsoid. This includes the + zonal coefficients up to order 20. Usually NormalGravity::GRS80() + should be used instead. + +See + - W. A. Heiskanen and H. Moritz, Physical Geodesy (Freeman, San + Francisco, 1967). + . +for more information. + +Acknowledgment: I would like to thank Mathieu Peyréga for +sharing EGM_Geoid_CalculatorClass from his Geo library with me. His +implementation was the first I could easily understand and he and I +together worked through some of the issues with overflow and underflow +the occur while performing high-degree spherical harmonic sums. + +\section gravityinst Installing the gravity models + +These gravity models are available for download: +
+ + + + + + + + + + + + +
Available gravity models
name max\n degree + size\n(kB) +
Download Links (size, kB)
tar fileWindows\n installerzip file
egm84 +
180
+
27
+
+ + link (26)
+
+ + link (55)
+
+ + link (26)
+
egm96 +
360
+
2100
+
+ + link (2100)
+
+ + link (2300)
+
+ + link (2100)
+
egm2008 +
2190
+
76000
+
+ + link (75000)
+
+ + link (72000)
+
+ + link (73000)
+
wgs84 +
20
+
1
+
+ + link (1)
+
+ + link (30)
+
+ + link (1)
+
+
+The "size" column is the size of the uncompressed data. + +For Linux and Unix systems, GeographicLib provides a shell script +geographiclib-get-gravity (typically installed in /usr/local/sbin) +which automates the process of downloading and installing the gravity +models. For example +\verbatim + geographiclib-get-gravity all # to install egm84, egm96, egm2008, wgs84 + geographiclib-get-gravity -h # for help +\endverbatim +This script should be run as a user with write access to the +installation directory, which is typically +/usr/local/share/GeographicLib (this can be overridden with the -p +flag), and the data will then be placed in the "gravity" subdirectory. + +Windows users should download and run the Windows installers. These +will prompt for an installation directory with the default being +\verbatim + C:/ProgramData/GeographicLib +\endverbatim +(which you probably should not change) and the data is installed in the +"gravity" sub-directory. (The second directory name is an alternate name +that Windows 7 uses for the "Application Data" directory.) + +Otherwise download \e either the tar.bz2 file \e or the zip file (they +have the same contents). To unpack these, run, for example +\verbatim + mkdir -p /usr/local/share/GeographicLib + tar xofjC egm96.tar.bz2 /usr/local/share/GeographicLib + tar xofjC egm2008.tar.bz2 /usr/local/share/GeographicLib + etc. +\endverbatim +and, again, the data will be placed in the "gravity" subdirectory. + +However you install the gravity models, all the datasets should be +installed in the same directory. GravityModel and +Gravity uses a compile time default to +locate the datasets. This is +- /usr/local/share/GeographicLib/gravity, for non-Windows systems +- C:/ProgramData/GeographicLib/gravity, for Windows systems +. +consistent with the examples above. This may be overridden at run-time +by defining the GEOGRAPHICLIB_GRAVITY_PATH or the GEOGRAPHICLIB_DATA +environment variables; see +GravityModel::DefaultGravityPath() for details. Finally, +the path may be set using the optional second argument to the +GravityModel constructor or with the "-d" flag to +Gravity. Supplying the "-h" flag to +Gravity reports the default path for +gravity models for that utility. The "-v" flag causes Gravity to report +the full path name of the data file it uses. + +\section gravityformat The format of the gravity model files + +The constructor for GravityModel reads a file called +NAME.egm which specifies various properties for the gravity model. It +then opens a binary file NAME.egm.cof to obtain the coefficients of the +spherical harmonic sum. + +The first line of the .egm file must consist of "EGMF-v" where EGMF +stands for "Earth Gravity Model Format" and v is the version number of +the format (currently "1"). + +The rest of the File is read a line at a time. A # character and +everything after it are discarded. If the result is just white space it +is discarded. The remaining lines are of the form "KEY WHITESPACE +VALUE". In general, the KEY and the VALUE are case-sensitive. + +GravityModel only pays attention to the following +keywords + - keywords that affect the field calculation, namely: + - ModelRadius (required), the normalizing radius for the model + in meters. + - ReferenceRadius (required), the equatorial radius \e a for + the reference ellipsoid meters. + - ModelMass (required), the mass constant \e GM for the model + in meters3/seconds2. + - ReferenceMass (required), the mass constant \e GM for the + reference ellipsoid in meters3/seconds2. + - AngularVelocity (required), the angular velocity ω for + the model \e and the reference ellipsoid in rad + seconds−1. + - Flattening, the flattening of the reference ellipsoid; this + can be given a fraction, e.g., 1/298.257223563. One of + Flattening and DynamicalFormFactor is required. + - DynamicalFormFactor, the dynamical form factor + J2 for the reference ellipsoid. One of + Flattening and DynamicalFormFactor is required. + - HeightOffset (default 0), the constant height offset + (meters) added to obtain the geoid height. + - CorrectionMultiplier (default 1), the multiplier for the + "zeta-to-N" correction terms for the geoid height to convert them + to meters. + - Normalization (default full), the normalization used for the + associated Legendre functions (full or schmidt). + - ID (required), 8 printable characters which serve as a + signature for the .egm.cof file (they must appear as the first 8 + bytes of this file). + . + The parameters ModelRadius, ModelMass, and + AngularVelocity apply to the gravity model, while + ReferenceRadius, ReferenceMass, AngularVelocity, + and either Flattening or DynamicalFormFactor + characterize the reference ellipsoid. AngularVelocity + (because it can be measured precisely) is the same for the gravity + model and the reference ellipsoid. ModelRadius is merely a + scaling parameter for the gravity model and there's no requirement + that it be close to the equatorial radius of the earth (although + that's typically how it is chosen). ModelMass and + ReferenceMass need not be the same and, indeed, they are + slightly difference for egm2008. As a result the disturbing + potential \e T has a 1/\e r dependence at large distances. + - keywords that store data that the user can query: + - Name, the name of the model. + - Description, a more descriptive name of the model. + - ReleaseDate, when the model was created. + - keywords that are examined to verify that their values are valid: + - ByteOrder (default little), the order of bytes in the + .egm.cof file. Only little endian is supported at present. + . +Other keywords are ignored. + +The coefficient file NAME.egm.cof is a binary file in little endian +order. The first 8 bytes of this file must match the ID given in +NAME.egm. This is followed by 2 sets of spherical harmonic +coefficients. The first of these gives the gravity potential and the +second gives the zeta-to-N corrections to the geoid height. The format +for each set of coefficients is: + - \e N, the maximum degree of the sum stored as a 4-byte signed integer. + This must satisfy \e N ≥ −1. + - \e M, the maximum order of the sum stored as a 4-byte signed integer. + This must satisfy \e N ≥ \e M ≥ −1. + - Cnm, the coefficients of the cosine + coefficients of the sum in column (i.e., \e m) major order. There + are (\e M + 1) (2\e N - \e M + 2) / 2 elements which are stored as + IEEE doubles (8 bytes). For example for \e N = \e M = 3, there are + 10 coefficients arranged as + C00, + C10, + C20, + C30, + C11, + C21, + C31, + C22, + C32, + C33. + - Snm, the coefficients of the sine + coefficients of the sum in column (i.e., \e m) major order starting + at \e m = 1. There are \e M (2\e N - \e M + 1) / 2 elements which + are stored as IEEE doubles (8 bytes). For example for \e N = \e M = + 3, there are 6 coefficients arranged as + S11, + S21, + S31, + S22, + S32, + S33. + . +Although the coefficient file is in little endian order, GeographicLib +can read it on big endian machines. It can only be read on machines +which store doubles in IEEE format. + +As an illustration, here is egm2008.egm: +\verbatim +EGMF-1 +# An Earth Gravity Model (Format 1) file. For documentation on the +# format of this file see +# https://geographiclib.sourceforge.io/html/gravity.html#gravityformat +Name egm2008 +Publisher National Geospatial Intelligence Agency +Description Earth Gravity Model 2008 +URL http://earth-info.nga.mil/GandG/wgs84/gravitymod/egm2008 +ReleaseDate 2008-06-01 +ConversionDate 2011-11-19 +DataVersion 1 +ModelRadius 6378136.3 +ModelMass 3986004.415e8 +AngularVelocity 7292115e-11 +ReferenceRadius 6378137 +ReferenceMass 3986004.418e8 +Flattening 1/298.257223563 +HeightOffset -0.41 + +# Gravitational and correction coefficients taken from +# EGM2008_to2190_TideFree and Zeta-to-N_to2160_egm2008 from +# the egm2008 distribution. +ID EGM2008A +\endverbatim + +The code to produce the coefficient files for the wgs84 and grs80 models +is +\include make-egmcof.cpp + +\section gravitynga Comments on the NGA harmonic synthesis code + +GravityModel attempts to reproduce the results of NGA's +harmonic synthesis code for EGM2008, hsynth_WGS84.f. Listed here are +issues that I encountered using the NGA code: + -# A compiler which allocates local variables on the stack produces an + executable with just returns NaNs. The problem here is a missing + SAVE statement in subroutine latf. + -# Because the model and references masses for egm2008 differ (by about + 1 part in 109), there should be a 1/\e r contribution to + the disturbing potential \e T. However, this term is set to zero in + hsynth_WGS84 (effectively altering the normal potential). This + shifts the surface \e W = U0 outward by about + 5 mm. Note too that the reference ellipsoid is no longer a + level surface of the effective normal potential. + -# Subroutine radgrav computes the ellipsoidal coordinate + β incorrectly. This leads to small errors in the deflection + of the vertical, ξ and η, when the height above the + ellipsoid, \e h, is non-zero (about 10−7 arcsec at + \e h = 400 km). + -# There are several expressions which will return inaccurate results + due to cancellation. For example, subroutine grs + computes the flattening using \e f = 1 − sqrt(1 − + e2). Much better is to use \e f = + e2/(1 + sqrt(1 − e2)). The + expressions for \e q and \e q' in grs and + radgrav suffer from similar problems. The resulting + errors are tiny (about 50 pm in the geoid height); however, given + that's there's essentially no cost to using more accurate + expressions, it's preferable to do so. + -# hsynth_WGS84 returns an "undefined" value for \e xi and \e eta at the + poles. Better would be to return the value obtained by taking the + limit \e lat → ± 90°. + . +Issues 1--4 have been reported to the authors of hsynth_WGS84. +Issue 1 is peculiar to Fortran and is not encountered in C++ code and +GravityModel corrects issues 3--5. On issue 2, +GravityModel neglects the 1/\e r term in \e T in +GravityModel::GeoidHeight and +GravityModel::SphericalAnomaly in order to produce +results which match NGA's for these quantities. On the other hand, +GravityModel::Disturbance and +GravityModel::T do include this term. + +\section gravitygeoid Details of the geoid height and anomaly calculations + +Ideally, the geoid represents a surface of constant gravitational +potential which approximates mean sea level. In reality some +approximations are taken in determining this surface. The steps taking +by GravityModel in computing the geoid height are +described here (in the context of EGM2008). This mimics NGA's code +hsynth_WGS84 closely because most users of EGM2008 use the gridded data +generated by this code (e.g., Geoid) and it is desirable +to use a consistent definition of the geoid height. + - The model potential is band limited; the minimum wavelength that is + represented is 360°/2160 = 10' (i.e., about 10NM or + 18.5km). The maximum degree for the spherical harmonic sum is 2190; + however the model was derived using ellipsoidal harmonics of degree + and order 2160 and the degree was increased to 2190 in order to + capture the ellipsoidal harmonics faithfully with spherical + harmonics. + - The 1/\e r term is omitted from the \e T (this is issue 2 in \ref + gravitynga). This moves the equipotential surface by about 5mm. + - The surface \e W = U0 is determined by Bruns' + formula, which is roughly equivalent to a single iteration of + Newton's method. The RMS error in this approximation is about 1.5mm + with a maximum error of about 10 mm. + - The model potential is only valid above the earth's surface. A + correction therefore needs to be included where the geoid lies + beneath the terrain. This is NGA's "zeta-to-N" correction, which is + represented by a spherical harmonic sum of degree and order 2160 (and + so it misses short wavelength terrain variations). In addition, it + entails estimating the isostatic equilibrium of the earth's crust. + The correction lies in the range [−5.05 m, 0.05 m], + however for 99.9% of the earth's surface the correction is less than + 10 mm in magnitude. + - The resulting surface lies above the observed mean sea level, + so −0.41m is added to the geoid height. (Better would be to change + the potential used to define the geoid; but this would only change + the result by about 2mm.) + . +A useful discussion of the problems with defining a geoid is given by +Dru A. Smith in + +There is no such thing as "The" EGM96 geoid: Subtle points on the use of +a global geopotential model, IGeS Bulletin No. 8, International +Geoid Service, Milan, Italy, pp. 17--28 (1998). + +GravityModel::GeoidHeight reproduces the results of the +several NGA codes for harmonic synthesis with the following maximum +discrepancies: + - egm84 = 1.1mm. This is probably due to inconsistent parameters for the + reference ellipsoid in the NGA code. (In particular, the value of + mass constant excludes the atmosphere; however, it's not clear + whether the other parameters have been correspondingly adjusted.) + Note that geoid heights predicted by egm84 differ from those of more + recent gravity models by about 1 meter. + - egm96 = 23nm. + - egm2008 = 78pm. After addressing some of the issues alluded to in + issue 4 in \ref gravitynga, the maximum discrepancy becomes 23pm. + +The formula for the gravity anomaly vector involves computing gravity +and normal gravity at two different points (with the displacement +between the points unknown ab initio). Since the gravity anomaly +is already a small quantity it is sometimes acceptable to employ +approximations that change the quantities by \e O(\e f). The NGA code +uses the spherical approximation described by Heiskanen and Moritz, +Sec. 2-14 and GravityModel::SphericalAnomaly uses the +same approximation for compatibility. In this approximation, the +gravity disturbance delta = grad \e T is calculated. +Here, \e T once again excludes the 1/\e r term (this is issue 2 in \ref +gravitynga and is consistent with the computation of the geoid height). +Note that delta compares the gravity and the normal gravity at +the \e same point; the gravity anomaly vector is then found by +estimating the gradient of the normal gravity in the limit that the +earth is spherically symmetric. delta is expressed in \e +spherical coordinates as \e deltax, \e deltay, \e deltaz where, for +example, \e deltaz is the \e radial component of delta (not the +component perpendicular to the ellipsoid) and \e deltay is similarly +slightly different from the usual northerly component. The components +of the anomaly are then given by + - gravity anomaly, \e Dg01 = \e deltaz − 2T/\e R, where \e R + distance to the center of the earth; + - northerly component of the deflection of the vertical, \e xi = − + deltay/\e gamma, where \e gamma is the magnitude of the normal + gravity; + - easterly component of the deflection of the vertical, \e eta = − + deltax/\e gamma. + . +NormalGravity computes the normal gravity accurately and +avoids issue 3 of \ref gravitynga. Thus while +GravityModel::SphericalAnomaly reproduces the results for +\e xi and \e eta at \e h = 0, there is a slight discrepancy if \e h is +non-zero. + +\section gravityatmos The effect of the mass of the atmosphere + +All of the supported models use WGS84 for the reference ellipsoid. This +has (see + +TR8350.2, table 3.1) + - \e a = 6378137 m + - \e f = 1/298.257223563 + - ω = 7292115 × 10−11 rad + s−1 + - \e GM = 3986004.418 × 108 m3 + s−2. + . +The value of \e GM includes the mass of the atmosphere and so strictly +only applies above the earth's atmosphere. Near the surface of the +earth, the value of \e g will be less (in absolute value) than the value +predicted by these models by about δ\e g = (4πG/\e +g) \e A = 8.552 × 10−11 \e +A m2/kg, where \e G is the gravitational constant, \e g +is the earth's gravity, and \e A is the pressure of the atmosphere. At +sea level we have \e A = 101.3 kPa, and δ\e g = +8.7−×−10−6 m s−2, +approximately. (In other words the effect is about 1 part in a +million; by way of comparison, buoyancy effects are about 100 times +larger.) + +\section gravityparallel Geoid heights on a multi-processor system + +The egm2008 model includes many terms (over 2 million spherical +harmonics). For that reason computations using this model may be slow; +for example it takes about 78 ms to compute the geoid height at a single +point. There are two ways to speed up this computation: + - Use a GravityCircle to compute the geoid height at + several points on a circle of latitude. This reduces the cost per + point to about 92 μs (a reduction by a factor of over 800). + - Compute the values on several circles of latitude in parallel. One + of the simplest ways of doing this is with + OpenMP; on an 8-processor system, + this can speed up the computation by another factor of 8. + . +Both of these techniques are illustrated by the following code, +which computes a table of geoid heights on +a regular grid and writes on the result in a +.gtx +file. On an 8-processor Intel 2.66 GHz machine using OpenMP +(-DHAVE_OPENMP=1), it takes about 40 minutes of elapsed time to compute +the geoid height for EGM2008 on a 1' grid. (Without these +optimizations, the computation would have taken about 200 days!) +\include GeoidToGTX.cpp + +cmake will add in support for OpenMP for +examples/GeoidToGTX.cpp, if it is available. + +
+Back to \ref geoid. Forward to \ref normalgravity. Up to \ref contents. +
+ +**********************************************************************/ +/** +\page normalgravity Normal gravity + +
+Back to \ref gravity. Forward to \ref magnetic. Up to \ref contents. +
+ +The NormalGravity class computes "normal gravity" which refers to the +exact (classical) solution of an idealised system consisting of an +ellipsoid of revolution with the following properties: + - \e M the mass interior to the ellipsoid, + - \e a the equatorial radius, + - \e b the polar semi-axis, + - ω the rotation rate about the polar axis. + . +(N.B. The mass always appears in the combination \e GM, with units +m3/s2, where \e G is the gravtitational constant.) +The distribution of the mass \e M within the ellipsoid is such that the +surface of the ellipsoid is at a constant normal potential where the +normal potential is the sum of the gravitational potential (due to the +gravitational attraction) and the centrifugal potential (due to the +rotation). The resulting field exterior to the ellipsoid is called +normal gravity and was found by Somigliana (1929). Because the +potential is constant on the ellipsoid it is sometimes referred to as +the level ellipsoid. + +Go to + - \ref normalgravcoords + - \ref normalgravpot + - \ref normalgravmass + - \ref normalgravsurf + - \ref normalgravmean + - \ref normalgravj2 + +References: + - C. Somigliana, Teoria generale del campo gravitazionale dell'ellissoide + di rotazione, Mem. Soc. Astron. Ital, 4, 541--599 (1929). + - W. A. Heiskanen and H. Moritz, Physical Geodesy (Freeman, San + Francisco, 1967), Secs. 1-19, 2-7, 2-8 (2-9, 2-10), 6-2 (6-3). + - B. Hofmann-Wellenhof, H. Moritz, Physical Geodesy (Second edition, + Springer, 2006). https://doi.org/10.1007/978-3-211-33545-1 + - H. Moritz, Geodetic Reference System 1980, J. Geodesy 54(3), 395--405 + (1980). https://doi.org/10.1007/BF02521480 + - H. Moritz, The Figure of the Earth (Wichmann, 1990). + - M. Chasles, Solution nouvelle du problème de l’attraction d’un + ellipsoïde hétérogène sur un point + exterieur, Jour. Liouville 5, 465--488 (1840), Note 2. + http://sites.mathdoc.fr/JMPA/PDF/JMPA_1840_1_5_A41_0.pdf + +\section normalgravcoords Ellipsoidal coordinates + +Two set of formulas are presented: those of Heiskanen and Moritz (1967) +which are applicable to an oblate ellipsoid and a second set where the +variables are distinguished with primes which apply to a prolate +ellipsoid. The primes are omitted from those variables which are the +same in the two cases. In the text, the parenthetical "alt." clauses +apply to prolate ellipsoids. + +Cylindrical coordinates \f$ R,Z \f$ are expressed in terms of +ellipsoidal coordinates +\f[ +\begin{align} + R &= \sqrt{u^2 + E^2} \cos\beta = u' \cos\beta,\\ + Z &= u \sin\beta = \sqrt{u'^2 + E'^2} \sin\beta, +\end{align} +\f] +where +\f[ +\begin{align} + E^2 = a^2 - b^2,&{} \qquad u^2 = u'^2 + E'^2,\\ + E'^2 = b^2 - a^2,&{} \qquad u'^2 = u^2 + E^2. +\end{align} +\f] +Surfaces of constant \f$ u \f$ (or \f$ u' \f$) are confocal ellipsoids. +The surface \f$ u = 0 \f$ (alt. \f$ u' = 0 \f$) corresponds to the +focal disc of diameter \f$ 2E \f$ (alt. focal rod of length +\f$ 2E' \f$). The level ellipsoid is given by \f$ u = b \f$ +(alt. \f$ u' = a \f$). On the level ellipsoid, \f$ \beta \f$ is the +familiar parametric latitude. + +In writing the potential and the gravity, it is useful to introduce the +functions +\f[ +\begin{align} + Q(z) &= \frac1{2z^3} + \biggl[\biggl(1 + \frac3{z^2}\biggr)\tan^{-1}z - \frac3z\biggr],\\ + Q'(z') &= \frac{(1+z'^2)^{3/2}}{2z'^3} + \biggl[\biggl(2 + \frac3{z'^2}\biggr)\sinh^{-1}z' - + \frac{3\sqrt{1+z'^2}}{z'}\biggr],\\ + H(z) &= \biggl(3Q(z)+z\frac{dQ(z)}{dz}\biggr)(1+z^2)\\ + &= \frac1{z^4}\biggl[3(1+z^2) + \biggl(1-\frac{\tan^{-1}z}z\biggr)-z^2\biggr],\\ + H'(z') &= \frac{3Q'(z')}{1+z'^2}+z'\frac{dQ'(z')}{dz'}\\ + &= \frac{1+z'^2}{z'^4} + \biggl[3\biggl(1-\frac{\sqrt{1+z'^2}\sinh^{-1}z'}{z'}\biggr) + +z'^2\biggr]. +\end{align} +\f] +The function arguments are \f$ z = E/u \f$ +(alt. \f$ z' = E'/u' \f$) and the unprimed and primed quantities are +related by +\f[ +\begin{align} +Q'(z') = Q(z),&{} \qquad H'(z') = H(z),\\ +z'^2 = -\frac{z^2}{1 + z^2},&{} \qquad z^2 = -\frac{z'^2}{1 + z'^2}. +\end{align} +\f] +The functions \f$ q(u) \f$ and \f$ q'(u) \f$ used by Heiskanen and +Moritz are given by +\f[ + q(u) = \frac{E^3}{u^3}Q\biggl(\frac Eu\biggr),\qquad + q'(u) = \frac{E^2}{u^2}H\biggl(\frac Eu\biggr). +\f] +The functions \f$ Q(z) \f$, \f$ Q'(z') \f$, \f$ H(z) \f$, and +\f$ H'(z') \f$ are more convenient for use in numerical codes because +they are finite in the spherical limit \f$ E \rightarrow 0 \f$, i.e., +\f$ Q(0) = Q'(0) = \frac2{15} \f$, and \f$ H(0) = H'(0) = \frac25 \f$. + +\section normalgravpot The normal potential + +The normal potential is the sum of three components, a mass term, a +quadrupole term and a centrifugal term, +\f[ U = U_m + U_q + U_r. \f] +The mass term is +\f[ U_m = \frac {GM}E \tan^{-1}\frac Eu + = \frac {GM}{E'} \sinh^{-1}\frac{E'}{u'}; \f] +the quadrupole term is +\f[ +\begin{align} + U_q &= \frac{\omega^2}2 \frac{a^2 b^3}{u^3} \frac{Q(E/u)}{Q(E/b)} + \biggl(\sin^2\beta-\frac13\biggr)\\ + &= \frac{\omega^2}2 \frac{a^2 b^3}{(u'^2+E'^2)^{3/2}} + \frac{Q'(E'/u')}{Q'(E'/a)} + \biggl(\sin^2\beta-\frac13\biggr); +\end{align} +\f] +finally, the rotational term is +\f[ +U_r = \frac{\omega^2}2 R^2 + = \frac{\omega^2}2 (u^2 + E^2) \cos^2\beta + = \frac{\omega^2}2 u'^2 \cos^2\beta. +\f] + +\f$ U_m \f$ and \f$ U_q \f$ are both gravitational potentials (due to +mass within the ellipsoid). The total mass contributing to \f$ U_m \f$ +is \f$ M \f$; the total mass contributing to \f$ U_q \f$ vanishes (far +from the ellipsoid, the \f$ U_q \f$ decays inversely as the cube of the +distance). + +\f$ U_m \f$ and \f$ U_q + U_r \f$ are separately both constant on the +level ellipsoid. \f$ U_m \f$ is the normal potential for a massive +non-rotating ellipsoid. \f$ U_q + U_r \f$ is the potential for a +massless rotating ellipsoid. Combining all the terms, \f$ U \f$ is the +normal potential for a massive rotating ellipsoid. + +The figure shows normal gravity for the case \f$ GM = 1 \f$, +\f$ a = 1 \f$, \f$ b = 0.8 \f$, \f$ \omega = 0.3 \f$. The level +ellipsoid is shown in red. Contours of constant gravity potential are +shown in blue; the contour spacing is constant outside the ellipsoid and +equal to 1/20 of the difference between the potentials on the ellipsoid +and at the geostationary point (\f$ R = 2.2536 \f$, \f$ Z = 0 \f$); +inside the ellipsoid the contour spacing is 5 times greater. The green +lines are stream lines for the gravity; these are spaced at intervals of +10° in parametric latitude on the surface of the ellipsoid. The +normal gravity is continued into the level ellipsoid under the +assumption that the mass is concentrated on the focal disc, shown in +black. + +\image html normal-gravity-potential-1.svg "Normal gravity" + +\section normalgravmass The mass distribution + +Typically, the normal potential, \f$ U \f$, is only of interest for +outside the ellipsoid \f$ u \ge b \f$ (alt. \f$ u' \ge a \f$). In +planetary applications, an open problem is finding a mass distribution +which is in hydrostatic equilibrium (the mass density is non-negative +and a non-decreasing function of the potential interior to the +ellipsoid). + +However it is possible to give singular mass distributions consistent +with the normal potential. + +For a non-rotating body, the potential \f$ U = U_m \f$ is generated by a +sandwiching the mass \f$ M \f$ uniformly between the level ellipsoid +with semi-axes \f$ a \f$ and \f$ b \f$ and a close similar +ellipsoid with semi-axes \f$ (1-\epsilon)a \f$ and +\f$ (1-\epsilon)b \f$. Chasles (1840) extends a theorem of Newton to +show that the field interior to such an ellipsoidal shell vanishes. +Thus the potential on the ellipsoid is constant, i.e., it is indeed a +level ellipsoid. This result also holds for a non-rotating triaxial +ellipsoid. + +Observing that \f$ U_m \f$ and \f$ U_q \f$ as defined above obey +\f$ \nabla^2 U_m = \nabla^2 U_q = 0 \f$ everywhere for \f$ u > 0 \f$ +(alt. \f$ u' > 0 \f$), we see that these potentials correspond to +masses concentrated at \f$ u = 0 \f$ (alt. \f$ u' = 0 \f$). + +In the oblate case, \f$ U_m \f$ is generated by a massive disc at +\f$ Z = 0 \f$, \f$ R < E \f$, with mass density (mass per unit area) \f$ +\rho_m \f$ and moments of inertia about the equatorial (resp. polar) +axis of \f$ A_m \f$ (resp. \f$ C_m \f$) given by +\f[ +\begin{align} +\rho_m &= \frac M{2\pi E\sqrt{E^2 - R^2}},\\ +A_m &= \frac {ME^2}3, \\ +C_m &= \frac {2ME^2}3, \\ +C_m-A_m &= \frac {ME^2}3. +\end{align} +\f] +This mass distribution is the same as that produced by projecting a +uniform spheric shell of mass \f$ M \f$ and radius \f$ E \f$ onto the +equatorial plane. + +In the prolate case, \f$ U_m \f$ is generated by a massive rod at \f$ R += 0 \f$, \f$ Z < E' \f$ and now the mass density \f$ \rho'_m \f$ has +units mass per unit length, +\f[ +\begin{align} +\rho'_m &= \frac M{2E'},\\ +A_m &= \frac {ME'^2}3, \\ +C_m &= 0, \\ +C_m-A_m &= -\frac {ME'^2}3. +\end{align} +\f] +This mass distribution is the same as that produced by projecting a +uniform spheric shell of mass \f$ M \f$ and radius \f$ E' \f$ onto the +polar axis. + +Similarly, \f$ U_q \f$ is generated in the oblate case by +\f[ +\begin{align} +\rho_q &= \frac{a^2 b^3 \omega^2}G + \frac{2E^2 - 3R^2}{6\pi E^5 \sqrt{E^2 - R^2} Q(E/b)}, \\ +A_q &= -\frac{a^2 b^3 \omega^2}G \frac2{45 Q(E/b)}, \\ +C_q &= -\frac{a^2 b^3 \omega^2}G \frac4{45 Q(E/b)}, \\ +C_q-A_q &= -\frac{a^2 b^3 \omega^2}G \frac2{45 Q(E/b)}. +\end{align} +\f] +The corresponding results for a prolate ellipsoid are +\f[ +\begin{align} +\rho_q' &= \frac{a^2 b^3 \omega^2}G + \frac{3Z^2 - E'^2}{12 E'^5 Q'(E'/a)}, \\ +A_q &= \frac{a^2 b^3 \omega^2}G \frac2{45 Q'(E'/a)}, \\ +C_q &= 0, \\ +C_q-A_q &= -\frac{a^2 b^3 \omega^2}G \frac2{45 Q'(E'/a)}. +\end{align} +\f] + +Summing up the mass and quadrupole terms, we have +\f[ +\begin{align} +A &= A_m + A_q, \\ +C &= C_m + C_q, \\ +J_2 & = \frac{C - A}{Ma^2}, +\end{align} +\f] +where \f$ J_2 \f$ is the dynamical form factor. + +\section normalgravsurf The surface gravity + +Each term in the potential contributes to the gravity on the surface of +the ellipsoid +\f[ +\gamma = \gamma_m + \gamma_q + \gamma_r; +\f] +These are the components of gravity normal to the ellipsoid and, by +convention, \f$ \gamma \f$ is positive downwards. The tangential +components of the total gravity and that due to \f$ U_m \f$ vanish. +Those tangential components of the gravity due to \f$ U_q \f$ and \f$ +U_r \f$ cancel one another. + +The gravity \f$ \gamma \f$ has the following dependence on latitude +\f[ +\begin{align} +\gamma &= \frac{b\gamma_a\cos^2\beta + a\gamma_b\sin^2\beta} + {\sqrt{b^2\cos^2\beta + a^2\sin^2\beta}}\\ + &= \frac{a\gamma_a\cos^2\phi + b\gamma_b\sin^2\phi} + {\sqrt{a^2\cos^2\phi + b^2\sin^2\phi}}, +\end{align} +\f] +and the individual components, \f$ \gamma_m \f$, \f$ \gamma_q \f$, and +\f$ \gamma_r \f$, have the same dependence on latitude. The equatorial +and polar gravities are +\f[ +\begin{align} +\gamma_a &= \gamma_{ma} + \gamma_{qa} + \gamma_{ra},\\ +\gamma_b &= \gamma_{mb} + \gamma_{qb} + \gamma_{rb}, +\end{align} +\f] +where +\f[ +\begin{align} +\gamma_{ma} &= \frac{GM}{ab},\qquad \gamma_{mb} = \frac{GM}{a^2},\\ +\gamma_{qa} &= -\frac{\omega^2 a}6 \frac{H(E/b)}{Q(E/b)} + = -\frac{\omega^2 a}6 \frac{H'(E'/a)}{Q'(E'/a)},\\ +\gamma_{qb} &= -\frac{\omega^2 b}3 \frac{H(E/b)}{Q(E/b)} + = -\frac{\omega^2 b}3 \frac{H'(E'/a)}{Q'(E'/a)},\\ +\gamma_{ra} &= -\omega^2 a,\qquad \gamma_{rb} = 0. +\end{align} +\f] + +\section normalgravmean The mean gravity + +Performing an average of the surface gravity over the area of the +ellipsoid gives +\f[ +\langle \gamma \rangle = \frac {4\pi a^2 b}A + \biggl(\frac{2\gamma_a}{3a} + \frac{\gamma_b}{3b}\biggr), +\f] +where \f$ A \f$ is the area of the ellipsoid +\f[ +\begin{align} + A &= 2\pi\biggl( a^2 + ab\frac{\sinh^{-1}(E/b)}{E/b} \biggr)\\ + &= 2\pi\biggl( a^2 + b^2\frac{\tan^{-1}(E'/a)}{E'/a} \biggr). +\end{align} +\f] + +The contributions to the mean gravity are +\f[ +\begin{align} +\langle \gamma_m \rangle &= \frac{4\pi}A GM, \\ +\langle \gamma_q \rangle &= 0 \quad \text{(as expected)}, \\ +\langle \gamma_r \rangle &= -\frac{4\pi}A \frac{2\omega^2 a^2b}3,\\ +\end{align} +\f] +resulting in +\f[ +\langle \gamma \rangle = \frac{4\pi}A + \biggl(GM - \frac{2\omega^2 a^2b}3\biggr). +\f] + +\section normalgravj2 Possible values of the dynamical form factor + +The solution for the normal gravity is well defined for arbitrary +\f$ M \f$, \f$ \omega \f$, \f$ a > 0\f$, and \f$ f < 1 \f$. (Note that +arbitrary oblate and prolate ellipsoids are possible, although +hydrostatic equilibrium would not result in a prolate ellipsoid.) +However, if is much easier to measure the dynamical form factor +\f$ J_2 \f$ (from the motion of artificial satellites) than the +flattening \f$ f \f$. (Note too that \f$ GM \f$ is also typically +measured from from satellite or astronomical observations and so it +includes the mass of the atmosphere.) + +So a question for the software developer is: given values of \f$ M > 0\f$, +\f$ \omega \f$, and \f$ a > 0 \f$, what are the allowed values of +\f$ J_2 \f$? We restrict the question to \f$ M > 0 \f$. The +(unphysical) case \f$ M = 0 \f$ is problematic because \f$ M \f$ appears +in the denominator in the definition of \f$ J_2 \f$. In the (also +unphysical) case \f$ M < 0 \f$, a given \f$ J_2 \f$ can result from two +distinct values of \f$ f \f$. + +Holding \f$ M > 0\f$, \f$ \omega \f$, and \f$ a > 0 \f$ fixed and +varying \f$ f \f$ from \f$ -\infty \f$ to \f$ 1 \f$, we find that +\f$ J_2 \f$ monotonically increases from \f$ -\infty \f$ to +\f[ +\frac13 - \frac8{45\pi} \frac{\omega^2 a^3}{GM}. +\f] +Thus any value of \f$ J_2 \f$ less that this value is permissible (but +some of these values may be unphysical). In obtaining this limiting +value, we used the result +\f$ Q(z \rightarrow \infty) \rightarrow \pi/(4 z^3) \f$. The value +\f[ +J_2 = -\frac13 \frac{\omega^2 a^3}{GM} +\f] +results in a sphere (\f$ f = 0 \f$). + +
+Back to \ref gravity. Forward to \ref magnetic. Up to \ref contents. +
+ +**********************************************************************/ +/** +\page magnetic Magnetic models + +
+Back to \ref normalgravity. Forward to \ref geodesic. Up to \ref contents. +
+ +GeographicLib can compute the earth's magnetic field by a magnetic +model using the MagneticModel and +MagneticCircle classes and with the +MagneticField utility. These models +expand the internal magnetic potential of the earth as sum of spherical +harmonics. They neglect magnetic fields due to the ionosphere, the +magnetosphere, nearby magnetized materials, electric machinery, etc. +Users of MagneticModel are advised to read the +"Health +Warning" this is provided with igrf11. Although the advice is +specific to igrf11, many of the comments apply to all magnetic field +models. + +The supported models are + - wmm2010, the + World + Magnetic Model 2010, which approximates the main magnetic field + for the period 2010--2015. + - wmm2015, the + World + Magnetic Model 2015, which approximates the main magnetic field + for the period 2015--2020. + - igrf11, the + International + Geomagnetic Reference Field (11th generation), which approximates + the main magnetic field for the period 1900--2015. + - igrf12, the + International + Geomagnetic Reference Field (12th generation), which approximates + the main magnetic field for the period 1900--2020. + - emm2010, the + Enhanced + Magnetic Model 2010, which approximates the main and crustal + magnetic fields for the period 2010--2015. + - emm2015, the + Enhanced + Magnetic Model 2015, which approximates the main and crustal + magnetic fields for the period 2000--2020. + - emm2017, the + Enhanced + Magnetic Model 2017, which approximates the main and crustal + magnetic fields for the period 2000--2022. + +Go to + - \ref magneticinst + - \ref magneticformat + +\section magneticinst Installing the magnetic field models + +These magnetic models are available for download: +
+ + + + + + + + + + + + + + + +
Available magnetic models
name max\n degree + time\n interval + size\n(kB) +
Download Links (size, kB)
tar fileWindows\n installerzip file
wmm2010 +
12
+
2010--2015
+
3
+
+ + link (2)
+
+ + link (300)
+
+ + link (2)
+
wmm2015 +
12
+
2015--2020
+
3
+
+ + link (2)
+
+ + link (300)
+
+ + link (2)
+
igrf11 +
13
+
1900--2015
+
25
+
+ + link (7)
+
+ + link (310)
+
+ + link (8)
+
igrf12 +
13
+
1900--2020
+
26
+
+ + link (7)
+
+ + link (310)
+
+ + link (8)
+
emm2010 +
739
+
2010--2015
+
4400
+
+ + link (3700)
+
+ + link (3000)
+
+ + link (4100)
+
emm2015 +
729
+
2000--2020
+
4300
+
+ + link (660)
+
+ + link (990)
+
+ + link (1030)
+
emm2017 +
790
+
2000--2022
+
5050
+
+ + link (1740)
+
+ + link (1700)
+
+ + link (2750)
+
+
+The "size" column is the size of the uncompressed data. + +For Linux and Unix systems, GeographicLib provides a shell script +geographiclib-get-magnetic (typically installed in /usr/local/sbin) +which automates the process of downloading and installing the magnetic +models. For example +\verbatim + geographiclib-get-magnetic all # install wmm2010, wmm2015, igrf11, igrf12, emm2010, emm2015, emm2017 + geographiclib-get-magnetic -h # for help +\endverbatim +This script should be run as a user with write access to the +installation directory, which is typically +/usr/local/share/GeographicLib (this can be overridden with the -p +flag), and the data will then be placed in the "magnetic" subdirectory. + +Windows users should download and run the Windows installers. These +will prompt for an installation directory with the default being +\verbatim + C:/ProgramData/GeographicLib +\endverbatim +(which you probably should not change) and the data is installed in the +"magnetic" sub-directory. (The second directory name is an alternate name +that Windows 7 uses for the "Application Data" directory.) + +Otherwise download \e either the tar.bz2 file \e or the zip file (they +have the same contents). To unpack these, run, for example +\verbatim + mkdir -p /usr/local/share/GeographicLib + tar xofjC wmm2015.tar.bz2 /usr/local/share/GeographicLib + tar xofjC emm2010.tar.bz2 /usr/local/share/GeographicLib + etc. +\endverbatim +and, again, the data will be placed in the "magnetic" subdirectory. + +However you install the magnetic models, all the datasets should be +installed in the same directory. MagneticModel and +MagneticField uses a compile time +default to locate the datasets. This is +- /usr/local/share/GeographicLib/magnetic, for non-Windows systems +- C:/ProgramData/GeographicLib/magnetic, for Windows systems +. +consistent with the examples above. This may be overridden at run-time +by defining the GEOGRAPHICLIB_MAGNETIC_PATH or the GEOGRAPHIC_DATA +environment variables; see +MagneticModel::DefaultMagneticPath() for details. +Finally, the path may be set using the optional second argument to the +MagneticModel constructor or with the "-d" flag to +MagneticField. Supplying the "-h" +flag to +MagneticField reports the default +path for magnetic models for that utility. The "-v" flag causes +MagneticField to report the full path name of the data file it uses. + +\section magneticformat The format of the magnetic model files + +The constructor for MagneticModel reads a file called +NAME.wmm which specifies various properties for the magnetic model. It +then opens a binary file NAME.wmm.cof to obtain the coefficients of the +spherical harmonic sum. + +The first line of the .wmm file must consist of "WMMF-v" where WMMF +stands for "World Magnetic Model Format" and v is the version number of +the format (currently "2"). + +The rest of the File is read a line at a time. A # character and +everything after it are discarded. If the result is just white space it +is discarded. The remaining lines are of the form "KEY WHITESPACE +VALUE". In general, the KEY and the VALUE are case-sensitive. + +MagneticModel only pays attention to the following +keywords + - keywords that affect the field calculation, namely: + - Radius (required), the normalizing radius of the model in + meters. + - NumModels (default 1), the number of models. WMM2015 + consists of a single model giving the magnetic field and its time + variation at 2015. IGRF12 consists of 24 models for 1900 thru 2015 + at 5 year intervals. The time variation is given only for the last + model to allow extrapolation beyond 2015. For dates prior to 2015, + linear interpolation is used. + - NumConstants (default 0), the number of time-independent + terms; this can be 0 or 1. This keyword was introduced in format + version 2 (GeographicLib version 1.43) to support the EMM2015 and + later models. This model includes long wavelength time-varying + components of degree 15. This is supplemented by a short + wavelength time-independent component with much higher degree. + - Epoch (required), the time origin (in fractional years) for + the first model. + - DeltaEpoch (default 1), the interval between models in years + (only relevant for NumModels > 1). + - Normalization (default schmidt), the normalization used for + the associated Legendre functions (schmidt or full). + - ID (required), 8 printable characters which serve as a + signature for the .wmm.cof file (they must appear as the first 8 + bytes of this file). + - keywords that store data that the user can query: + - Name, the name of the model. + - Description, a more descriptive name of the model. + - ReleaseDate, when the model was created. + - MinTime, the minimum date at which the model should be used. + - MaxTime, the maximum date at which the model should be used. + - MinHeight, the minimum height above the ellipsoid for which + the model should be used. + - MaxHeight, the maximum height above the ellipsoid for which + the model should be used. + . + MagneticModel does not enforce the restrictions + implied by last four quantities. However, + MagneticField issues a warning if + these limits are exceeded. + - keywords that are examined to verify that their values are valid: + - Type (default linear), the type of the model. "linear" + means that the time variation is piece-wise linear (either using + interpolation between the field at two dates or using the field and + its first derivative with respect to time). This is the only type + of model supported at present. + - ByteOrder (default little), the order of bytes in the + .wmm.cof file. Only little endian is supported at present. + . +Other keywords are ignored. + +The coefficient file NAME.wmm.cof is a binary file in little endian +order. The first 8 bytes of this file must match the ID given in +NAME.wmm. This is followed by NumModels + 1 sets of spherical harmonic +coefficients. The first NumModels of these model the magnetic field at +Epoch + \e i * DeltaEpoch for 0 ≤ \e i < NumModels. The last set of +coefficients model the rate of change of the magnetic field at Epoch + +(NumModels − 1) * DeltaEpoch. The format for each set of coefficients +is: + - \e N, the maximum degree of the sum stored as a 4-byte signed integer. + This must satisfy \e N ≥ −1. + - \e M, the maximum order of the sum stored as a 4-byte signed integer. + This must satisfy \e N ≥ \e M ≥ −1. + - Cnm, the coefficients of the cosine + coefficients of the sum in column (i.e., \e m) major order. There + are (\e M + 1) (2\e N − \e M + 2) / 2 elements which are stored + as IEEE doubles (8 bytes). For example for \e N = \e M = 3, there + are 10 coefficients arranged as + C00, + C10, + C20, + C30, + C11, + C21, + C31, + C22, + C32, + C33. + - Snm, the coefficients of the sine + coefficients of the sum in column (i.e., \e m) major order starting + at \e m = 1. There are \e M (2\e N − \e M + 1) / 2 elements + which are stored as IEEE doubles (8 bytes). For example for \e N = + \e M = 3, there are 6 coefficients arranged as + S11, + S21, + S31, + S22, + S32, + S33. + . +Although the coefficient file is in little endian order, GeographicLib +can read it on big endian machines. It can only be read on machines +which store doubles in IEEE format. + +As an illustration, here is igrf11.wmm: +\verbatim +WMMF-1 +# A World Magnetic Model (Format 1) file. For documentation on the +# format of this file see +# https://geographiclib.sourceforge.io/html/magnetic.html#magneticformat +Name igrf11 +Description International Geomagnetic Reference Field 11th Generation +URL https://ngdc.noaa.gov/IAGA/vmod/igrf.html +Publisher National Oceanic and Atmospheric Administration +ReleaseDate 2009-12-15 +DataCutOff 2009-10-01 +ConversionDate 2011-11-04 +DataVersion 1 +Radius 6371200 +NumModels 23 +Epoch 1900 +DeltaEpoch 5 +MinTime 1900 +MaxTime 2015 +MinHeight -1000 +MaxHeight 600000 + +# The coefficients are stored in a file obtained by appending ".cof" to +# the name of this file. The coefficients were obtained from IGRF11.COF +# in the geomag70 distribution. +ID IGRF11-A +\endverbatim + +
+Back to \ref normalgravity. Forward to \ref geodesic. Up to \ref contents. +
+ +**********************************************************************/ +/** +\page geodesic Geodesics on an ellipsoid of revolution + +
+Back to \ref magnetic. Forward to \ref nearest. Up to \ref contents. +
+ +Geodesic and GeodesicLine provide accurate +solutions to the direct and inverse geodesic problems. The +GeodSolve utility provides an interface +to these classes. AzimuthalEquidistant implements the +azimuthal equidistant projection in terms of geodesics. +CassiniSoldner implements a transverse cylindrical +equidistant projection in terms of geodesics. The +GeodesicProj utility provides an +interface to these projections. + +The algorithms used by Geodesic and GeodesicLine are based on a Taylor +expansion of the geodesic integrals valid when the flattening \e f is +small. GeodesicExact and GeodesicLineExact evaluate the integrals +exactly (in terms of incomplete elliptic integrals). For the WGS84 +ellipsoid, the series solutions are about 2--3 times faster and 2--3 +times more accurate (because it's easier to control round-off errors +with series solutions); thus Geodesic and GeodesicLine are recommended +for most geodetic applications. However, in applications where the +absolute value of \e f is greater than about 0.02, the exact classes +should be used. + +Go to + - \ref testgeod + - \ref geodseries + - \ref geodellip + - \ref meridian + - \ref geodshort + . +For some background information on geodesics on triaxial ellipsoids, see +\ref triaxial. + +References: + - F. W. Bessel, + The calculation + of longitude and latitude from geodesic measurements (1825), + Astron. Nachr. 331(8), 852--861 (2010); + translated by C. F. F. Karney and R. E. Deakin; preprint: + arXiv:0908.1824. + - F. R. Helmert, + + Mathematical and Physical Theories of Higher Geodesy, Part 1 (1880), + Aeronautical Chart and Information Center (St. Louis, 1964), + Chaps. 5--7. + - J. Danielsen, + The area under the geodesic, + Survey Review 30(232), 61--66 (1989). + DOI: + 10.1179/003962689791474267 + - C. F. F. Karney, + + Algorithms for geodesics, + J. Geodesy 87(1), 43--55 (2013); + DOI: + 10.1007/s00190-012-0578-z; + addenda: + geod-addenda.html; + resource page: + geod.html. + - A collection of some papers on geodesics is available at + https://geographiclib.sourceforge.io/geodesic-papers/biblio.html + - The wikipedia page, + + Geodesics on an ellipsoid. + +\section testgeod Test data for geodesics + +A test set a geodesics is available at + - + GeodTest.dat.gz + - C. F. F. Karney, Test set for geodesics (2010),
+ DOI: + 10.5281/zenodo.32156. + . +This is about 39 MB (compressed). This consists of a set of geodesics +for the WGS84 ellipsoid. A subset of this (consisting of 1/50 of the +members — about 690 kB, compressed) is available at + - + GeodTest-short.dat.gz + +Each line of the test set gives 10 space delimited numbers + - latitude at point 1, \e lat1 (degrees, exact) + - longitude at point 1, \e lon1 (degrees, always 0) + - azimuth at point 1, \e azi1 (clockwise from north in degrees, exact) + - latitude at point 2, \e lat2 (degrees, accurate to + 10−18 deg) + - longitude at point 2, \e lon2 (degrees, accurate to + 10−18 deg) + - azimuth at point 2, \e azi2 (degrees, accurate to + 10−18 deg) + - geodesic distance from point 1 to point 2, \e s12 (meters, exact) + - arc distance on the auxiliary sphere, \e a12 (degrees, accurate to + 10−18 deg) + - reduced length of the geodesic, \e m12 (meters, accurate to 0.1 pm) + - the area under the geodesic, \e S12 (m2, accurate to + 1 mm2) + . +These are computed using as direct geodesic calculations with the given +\e lat1, \e lon1, \e azi1, and \e s12. The distance \e s12 always +corresponds to an arc length \e a12 ≤ 180°, so the given +geodesics give the shortest paths from point 1 to point 2. For +simplicity and without loss of generality, \e lat1 is chosen in +[0°, 90°], \e lon1 is taken to be zero, \e azi1 is +chosen in [0°, 180°]. Furthermore, \e lat1 and \e +azi1 are taken to be multiples of 10−12 deg and \e s12 +is a multiple of 0.1 μm in [0 m, 20003931.4586254 m]. +This results in \e lon2 in [0°, 180°] and \e azi2 in [0°, +180°]. + +The direct calculation uses an expansion of the geodesic equations +accurate to f30 (approximately 1 part in 1050) +and is computed with with +Maxima's +bfloats and fpprec set to 100 (so the errors in the data are probably +1/2 of the values quoted above). + +The contents of the file are as follows: + - 100000 entries randomly distributed + - 50000 entries which are nearly antipodal + - 50000 entries with short distances + - 50000 entries with one end near a pole + - 50000 entries with both ends near opposite poles + - 50000 entries which are nearly meridional + - 50000 entries which are nearly equatorial + - 50000 entries running between vertices (\e azi1 = \e azi2 = 90°) + - 50000 entries ending close to vertices + . +(a total of 500000 entries). The values for \e s12 for the geodesics +running between vertices are truncated to a multiple of 0.1 pm and this +is used to determine point 2. + +This data can be fed to the GeodSolve +utility as follows + - Direct from point 1: +\verbatim + gunzip -c GeodTest.dat.gz | cut -d' ' -f1,2,3,7 | ./GeodSolve +\endverbatim + This should yield columns 4, 5, 6, and 9 of the test set. + - Direct from point 2: +\verbatim + gunzip -c GeodTest.dat.gz | cut -d' ' -f4,5,6,7 | + sed "s/ \([^ ]*$\)/ -\1/" | ./GeodSolve +\endverbatim + (The sed command negates the distance.) This should yield columns 1, + 2, and 3, and the negative of column 9 of the test set. + - Inverse between points 1 and 2: +\verbatim + gunzip -c GeodTest.dat.gz | cut -d' ' -f1,2,4,5 | ./GeodSolve -i +\endverbatim + This should yield columns 3, 6, 7, and 9 of the test set. + . +Add, e.g., "-p 6", to the call to GeodSolve to change the precision of +the output. Adding "-f" causes GeodSolve to print 12 fields specifying +the geodesic; these include the 10 fields in the test set plus the +geodesic scales \e M12 and \e M21 which are inserted between \e m12 and +\e S12. + +Code for computing arbitrarily accurate geodesics in maxima is available +in geodesic.mac (this depends on + ellint.mac and uses the series computed by + geod.mac). This solve both the direct and +inverse geodesic problems and offers the ability to solve the problems +either using series expansions (similar to Geodesic) or in terms of +elliptic integrals (similar to GeodesicExact). + +\section geodseries Expansions for geodesics + +We give here the series expansions for the various geodesic integrals +valid to order f10. In this release of the code, we +use a 6th-order expansions. This is sufficient to maintain accuracy for +doubles for the SRMmax ellipsoid (\e a = 6400 km, \e f = 1/150). +However, the preprocessor macro GEOGRAPHICLIB_GEODESIC_ORDER can be used +to select an order from 3 thru 8. (If using long doubles, with a 64-bit +fraction, the default order is 7.) The series expanded to order +f30 are given in +geodseries30.html. + +In the formulas below ^ indicates exponentiation (f^3 = +f3) and / indicates real division (3/5 = 0.6). The +equations need to be converted to Horner form, but are here left in +expanded form so that they can be easily truncated to lower order. +These expansions were obtained using the Maxima code, +geod.mac. + +In the expansions below, we have + - \f$ \alpha \f$ is the azimuth + - \f$ \alpha_0 \f$ is the azimuth at the equator crossing + - \f$ \lambda \f$ is the longitude measured from the equator crossing + - \f$ \sigma \f$ is the spherical arc length + - \f$ \omega = \tan^{-1}(\sin\alpha_0\tan\sigma) \f$ is the spherical longitude + - \f$ a \f$ is the equatorial radius + - \f$ b \f$ is the polar semi-axis + - \f$ f \f$ is the flattening + - \f$ e^2 = f(2 - f) \f$ + - \f$ e'^2 = e^2/(1-e^2) \f$ + - \f$ k^2 = e'^2 \cos^2\alpha_0 = 4 \epsilon / (1 - \epsilon)^2 \f$ + - \f$ n = f / (2 - f) \f$ + - \f$ c^2 = a^2/2 + b^2/2 (\tanh^{-1}e)/e \f$ + - \e ep2 = \f$ e'^2 \f$ + - \e k2 = \f$ k^2 \f$ + - \e eps = \f$ \epsilon = k^2 / (\sqrt{1 + k^2} + 1)^2\f$ + +The formula for distance is +\f[ + \frac sb = I_1(\sigma) +\f] +where +\f[ +\begin{align} + I_1(\sigma) &= A_1\bigl(\sigma + B_1(\sigma)\bigr) \\ + B_1(\sigma) &= \sum_{j=1} C_{1j} \sin 2j\sigma +\end{align} +\f] +and +\verbatim +A1 = (1 + 1/4 * eps^2 + + 1/64 * eps^4 + + 1/256 * eps^6 + + 25/16384 * eps^8 + + 49/65536 * eps^10) / (1 - eps); +\endverbatim +\verbatim +C1[1] = - 1/2 * eps + + 3/16 * eps^3 + - 1/32 * eps^5 + + 19/2048 * eps^7 + - 3/4096 * eps^9; +C1[2] = - 1/16 * eps^2 + + 1/32 * eps^4 + - 9/2048 * eps^6 + + 7/4096 * eps^8 + + 1/65536 * eps^10; +C1[3] = - 1/48 * eps^3 + + 3/256 * eps^5 + - 3/2048 * eps^7 + + 17/24576 * eps^9; +C1[4] = - 5/512 * eps^4 + + 3/512 * eps^6 + - 11/16384 * eps^8 + + 3/8192 * eps^10; +C1[5] = - 7/1280 * eps^5 + + 7/2048 * eps^7 + - 3/8192 * eps^9; +C1[6] = - 7/2048 * eps^6 + + 9/4096 * eps^8 + - 117/524288 * eps^10; +C1[7] = - 33/14336 * eps^7 + + 99/65536 * eps^9; +C1[8] = - 429/262144 * eps^8 + + 143/131072 * eps^10; +C1[9] = - 715/589824 * eps^9; +C1[10] = - 2431/2621440 * eps^10; +\endverbatim + +The function \f$ \tau(\sigma) = s/(b A_1) = \sigma + B_1(\sigma) \f$ +may be inverted by series reversion giving +\f[ + \sigma(\tau) = \tau + \sum_{j=1} C'_{1j} \sin 2j\sigma +\f] +where +\verbatim +C1'[1] = + 1/2 * eps + - 9/32 * eps^3 + + 205/1536 * eps^5 + - 4879/73728 * eps^7 + + 9039/327680 * eps^9; +C1'[2] = + 5/16 * eps^2 + - 37/96 * eps^4 + + 1335/4096 * eps^6 + - 86171/368640 * eps^8 + + 4119073/28311552 * eps^10; +C1'[3] = + 29/96 * eps^3 + - 75/128 * eps^5 + + 2901/4096 * eps^7 + - 443327/655360 * eps^9; +C1'[4] = + 539/1536 * eps^4 + - 2391/2560 * eps^6 + + 1082857/737280 * eps^8 + - 2722891/1548288 * eps^10; +C1'[5] = + 3467/7680 * eps^5 + - 28223/18432 * eps^7 + + 1361343/458752 * eps^9; +C1'[6] = + 38081/61440 * eps^6 + - 733437/286720 * eps^8 + + 10820079/1835008 * eps^10; +C1'[7] = + 459485/516096 * eps^7 + - 709743/163840 * eps^9; +C1'[8] = + 109167851/82575360 * eps^8 + - 550835669/74317824 * eps^10; +C1'[9] = + 83141299/41287680 * eps^9; +C1'[10] = + 9303339907/2972712960 * eps^10; +\endverbatim + +The reduced length is given by +\f[ +\begin{align} + \frac mb &= \sqrt{1 + k^2 \sin^2\sigma_2} \cos\sigma_1 \sin\sigma_2 \\ + &\quad {}-\sqrt{1 + k^2 \sin^2\sigma_1} \sin\sigma_1 \cos\sigma_2 \\ + &\quad {}-\cos\sigma_1 \cos\sigma_2 \bigl(J(\sigma_2) - J(\sigma_1)\bigr) +\end{align} +\f] +where +\f[ +\begin{align} + J(\sigma) &= I_1(\sigma) - I_2(\sigma) \\ + I_2(\sigma) &= A_2\bigl(\sigma + B_2(\sigma)\bigr) \\ + B_2(\sigma) &= \sum_{j=1} C_{2j} \sin 2j\sigma +\end{align} +\f] +\verbatim +A2 = (1 - 3/4 * eps^2 + - 7/64 * eps^4 + - 11/256 * eps^6 + - 375/16384 * eps^8 + - 931/65536 * eps^10) / (1 + eps); +\endverbatim +\verbatim +C2[1] = + 1/2 * eps + + 1/16 * eps^3 + + 1/32 * eps^5 + + 41/2048 * eps^7 + + 59/4096 * eps^9; +C2[2] = + 3/16 * eps^2 + + 1/32 * eps^4 + + 35/2048 * eps^6 + + 47/4096 * eps^8 + + 557/65536 * eps^10; +C2[3] = + 5/48 * eps^3 + + 5/256 * eps^5 + + 23/2048 * eps^7 + + 191/24576 * eps^9; +C2[4] = + 35/512 * eps^4 + + 7/512 * eps^6 + + 133/16384 * eps^8 + + 47/8192 * eps^10; +C2[5] = + 63/1280 * eps^5 + + 21/2048 * eps^7 + + 51/8192 * eps^9; +C2[6] = + 77/2048 * eps^6 + + 33/4096 * eps^8 + + 2607/524288 * eps^10; +C2[7] = + 429/14336 * eps^7 + + 429/65536 * eps^9; +C2[8] = + 6435/262144 * eps^8 + + 715/131072 * eps^10; +C2[9] = + 12155/589824 * eps^9; +C2[10] = + 46189/2621440 * eps^10; +\endverbatim + +The longitude is given in terms of the spherical longitude by +\f[ +\lambda = \omega - f \sin\alpha_0 I_3(\sigma) +\f] +where +\f[ +\begin{align} + I_3(\sigma) &= A_3\bigl(\sigma + B_3(\sigma)\bigr) \\ + B_3(\sigma) &= \sum_{j=1} C_{3j} \sin 2j\sigma +\end{align} +\f] +and +\verbatim +A3 = 1 - (1/2 - 1/2*n) * eps + - (1/4 + 1/8*n - 3/8*n^2) * eps^2 + - (1/16 + 3/16*n + 1/16*n^2 - 5/16*n^3) * eps^3 + - (3/64 + 1/32*n + 5/32*n^2 + 5/128*n^3 - 35/128*n^4) * eps^4 + - (3/128 + 5/128*n + 5/256*n^2 + 35/256*n^3 + 7/256*n^4) * eps^5 + - (5/256 + 15/1024*n + 35/1024*n^2 + 7/512*n^3) * eps^6 + - (25/2048 + 35/2048*n + 21/2048*n^2) * eps^7 + - (175/16384 + 35/4096*n) * eps^8 + - 245/32768 * eps^9; +\endverbatim +\verbatim +C3[1] = + (1/4 - 1/4*n) * eps + + (1/8 - 1/8*n^2) * eps^2 + + (3/64 + 3/64*n - 1/64*n^2 - 5/64*n^3) * eps^3 + + (5/128 + 1/64*n + 1/64*n^2 - 1/64*n^3 - 7/128*n^4) * eps^4 + + (3/128 + 11/512*n + 3/512*n^2 + 1/256*n^3 - 7/512*n^4) * eps^5 + + (21/1024 + 5/512*n + 13/1024*n^2 + 1/512*n^3) * eps^6 + + (243/16384 + 189/16384*n + 83/16384*n^2) * eps^7 + + (435/32768 + 109/16384*n) * eps^8 + + 345/32768 * eps^9; +C3[2] = + (1/16 - 3/32*n + 1/32*n^2) * eps^2 + + (3/64 - 1/32*n - 3/64*n^2 + 1/32*n^3) * eps^3 + + (3/128 + 1/128*n - 9/256*n^2 - 3/128*n^3 + 7/256*n^4) * eps^4 + + (5/256 + 1/256*n - 1/128*n^2 - 7/256*n^3 - 3/256*n^4) * eps^5 + + (27/2048 + 69/8192*n - 39/8192*n^2 - 47/4096*n^3) * eps^6 + + (187/16384 + 39/8192*n + 31/16384*n^2) * eps^7 + + (287/32768 + 47/8192*n) * eps^8 + + 255/32768 * eps^9; +C3[3] = + (5/192 - 3/64*n + 5/192*n^2 - 1/192*n^3) * eps^3 + + (3/128 - 5/192*n - 1/64*n^2 + 5/192*n^3 - 1/128*n^4) * eps^4 + + (7/512 - 1/384*n - 77/3072*n^2 + 5/3072*n^3 + 65/3072*n^4) * eps^5 + + (3/256 - 1/1024*n - 71/6144*n^2 - 47/3072*n^3) * eps^6 + + (139/16384 + 143/49152*n - 383/49152*n^2) * eps^7 + + (243/32768 + 95/49152*n) * eps^8 + + 581/98304 * eps^9; +C3[4] = + (7/512 - 7/256*n + 5/256*n^2 - 7/1024*n^3 + 1/1024*n^4) * eps^4 + + (7/512 - 5/256*n - 7/2048*n^2 + 9/512*n^3 - 21/2048*n^4) * eps^5 + + (9/1024 - 43/8192*n - 129/8192*n^2 + 39/4096*n^3) * eps^6 + + (127/16384 - 23/8192*n - 165/16384*n^2) * eps^7 + + (193/32768 + 3/8192*n) * eps^8 + + 171/32768 * eps^9; +C3[5] = + (21/2560 - 9/512*n + 15/1024*n^2 - 7/1024*n^3 + 9/5120*n^4) * eps^5 + + (9/1024 - 15/1024*n + 3/2048*n^2 + 57/5120*n^3) * eps^6 + + (99/16384 - 91/16384*n - 781/81920*n^2) * eps^7 + + (179/32768 - 55/16384*n) * eps^8 + + 141/32768 * eps^9; +C3[6] = + (11/2048 - 99/8192*n + 275/24576*n^2 - 77/12288*n^3) * eps^6 + + (99/16384 - 275/24576*n + 55/16384*n^2) * eps^7 + + (143/32768 - 253/49152*n) * eps^8 + + 33/8192 * eps^9; +C3[7] = + (429/114688 - 143/16384*n + 143/16384*n^2) * eps^7 + + (143/32768 - 143/16384*n) * eps^8 + + 429/131072 * eps^9; +C3[8] = + (715/262144 - 429/65536*n) * eps^8 + + 429/131072 * eps^9; +C3[9] = + 2431/1179648 * eps^9; +\endverbatim + +The formula for area between the geodesic and the equator is given in +Sec. 6 of +Algorithms for geodesics in terms of \e S, +\f[ +S = c^2 \alpha + e^2 a^2 \cos\alpha_0 \sin\alpha_0 I_4(\sigma) +\f] +where +\f[ +I_4(\sigma) = \sum_{j=0} C_{4j} \cos(2j+1)\sigma +\f] +In the paper, this was expanded in \f$ e'^2 \f$ and \f$ k^2 \f$. +However, the series converges faster for eccentric ellipsoids if the +expansion is in \f$ n \f$ and \f$ \epsilon \f$. The series to order +\f$ f^{10} \f$ becomes +\verbatim +C4[0] = + (2/3 - 4/15*n + 8/105*n^2 + 4/315*n^3 + 16/3465*n^4 + 20/9009*n^5 + 8/6435*n^6 + 28/36465*n^7 + 32/62985*n^8 + 4/11305*n^9) + - (1/5 - 16/35*n + 32/105*n^2 - 16/385*n^3 - 64/15015*n^4 - 16/15015*n^5 - 32/85085*n^6 - 112/692835*n^7 - 128/1616615*n^8) * eps + - (2/105 + 32/315*n - 1088/3465*n^2 + 1184/5005*n^3 - 128/3465*n^4 - 3232/765765*n^5 - 1856/1616615*n^6 - 6304/14549535*n^7) * eps^2 + + (11/315 - 368/3465*n - 32/6435*n^2 + 976/4095*n^3 - 154048/765765*n^4 + 368/11115*n^5 + 5216/1322685*n^6) * eps^3 + + (4/1155 + 1088/45045*n - 128/1287*n^2 + 64/3927*n^3 + 2877184/14549535*n^4 - 370112/2078505*n^5) * eps^4 + + (97/15015 - 464/45045*n + 4192/153153*n^2 - 88240/969969*n^3 + 31168/1322685*n^4) * eps^5 + + (10/9009 + 4192/765765*n - 188096/14549535*n^2 + 23392/855855*n^3) * eps^6 + + (193/85085 - 6832/2078505*n + 106976/14549535*n^2) * eps^7 + + (632/1322685 + 3456/1616615*n) * eps^8 + + 107/101745 * eps^9; +C4[1] = + (1/45 - 16/315*n + 32/945*n^2 - 16/3465*n^3 - 64/135135*n^4 - 16/135135*n^5 - 32/765765*n^6 - 112/6235515*n^7 - 128/14549535*n^8) * eps + - (2/105 - 64/945*n + 128/1485*n^2 - 1984/45045*n^3 + 256/45045*n^4 + 64/109395*n^5 + 128/855855*n^6 + 2368/43648605*n^7) * eps^2 + - (1/105 - 16/2079*n - 5792/135135*n^2 + 3568/45045*n^3 - 103744/2297295*n^4 + 264464/43648605*n^5 + 544/855855*n^6) * eps^3 + + (4/1155 - 2944/135135*n + 256/9009*n^2 + 17536/765765*n^3 - 3053056/43648605*n^4 + 1923968/43648605*n^5) * eps^4 + + (1/9009 + 16/19305*n - 2656/153153*n^2 + 65072/2078505*n^3 + 526912/43648605*n^4) * eps^5 + + (10/9009 - 1472/459459*n + 106112/43648605*n^2 - 204352/14549535*n^3) * eps^6 + + (349/2297295 + 28144/43648605*n - 32288/8729721*n^2) * eps^7 + + (632/1322685 - 44288/43648605*n) * eps^8 + + 43/479655 * eps^9; +C4[2] = + (4/525 - 32/1575*n + 64/3465*n^2 - 32/5005*n^3 + 128/225225*n^4 + 32/765765*n^5 + 64/8083075*n^6 + 32/14549535*n^7) * eps^2 + - (8/1575 - 128/5775*n + 256/6825*n^2 - 6784/225225*n^3 + 4608/425425*n^4 - 128/124355*n^5 - 5888/72747675*n^6) * eps^3 + - (8/1925 - 1856/225225*n - 128/17325*n^2 + 42176/1276275*n^3 - 2434816/72747675*n^4 + 195136/14549535*n^5) * eps^4 + + (8/10725 - 128/17325*n + 64256/3828825*n^2 - 128/25935*n^3 - 266752/10392525*n^4) * eps^5 + - (4/25025 + 928/3828825*n + 292288/72747675*n^2 - 106528/6613425*n^3) * eps^6 + + (464/1276275 - 17152/10392525*n + 83456/72747675*n^2) * eps^7 + + (1168/72747675 + 128/1865325*n) * eps^8 + + 208/1119195 * eps^9; +C4[3] = + (8/2205 - 256/24255*n + 512/45045*n^2 - 256/45045*n^3 + 1024/765765*n^4 - 256/2909907*n^5 - 512/101846745*n^6) * eps^3 + - (16/8085 - 1024/105105*n + 2048/105105*n^2 - 1024/51051*n^3 + 4096/373065*n^4 - 1024/357357*n^5) * eps^4 + - (136/63063 - 256/45045*n + 512/1072071*n^2 + 494336/33948915*n^3 - 44032/1996995*n^4) * eps^5 + + (64/315315 - 16384/5360355*n + 966656/101846745*n^2 - 868352/101846745*n^3) * eps^6 + - (16/97461 + 14848/101846745*n + 74752/101846745*n^2) * eps^7 + + (5024/33948915 - 96256/101846745*n) * eps^8 + - 1744/101846745 * eps^9; +C4[4] = + (64/31185 - 512/81081*n + 1024/135135*n^2 - 512/109395*n^3 + 2048/1247103*n^4 - 2560/8729721*n^5) * eps^4 + - (128/135135 - 2048/405405*n + 77824/6891885*n^2 - 198656/14549535*n^3 + 8192/855855*n^4) * eps^5 + - (512/405405 - 2048/530145*n + 299008/130945815*n^2 + 280576/43648605*n^3) * eps^6 + + (128/2297295 - 2048/1438965*n + 241664/43648605*n^2) * eps^7 + - (17536/130945815 + 1024/43648605*n) * eps^8 + + 2944/43648605 * eps^9; +C4[5] = + (128/99099 - 2048/495495*n + 4096/765765*n^2 - 6144/1616615*n^3 + 8192/4849845*n^4) * eps^5 + - (256/495495 - 8192/2807805*n + 376832/53348295*n^2 - 8192/855855*n^3) * eps^6 + - (6784/8423415 - 432128/160044885*n + 397312/160044885*n^2) * eps^7 + + (512/53348295 - 16384/22863555*n) * eps^8 + - 16768/160044885 * eps^9; +C4[6] = + (512/585585 - 4096/1422135*n + 8192/2078505*n^2 - 4096/1322685*n^3) * eps^6 + - (1024/3318315 - 16384/9006855*n + 98304/21015995*n^2) * eps^7 + - (103424/189143955 - 8192/4203199*n) * eps^8 + - 1024/189143955 * eps^9; +C4[7] = + (1024/1640925 - 65536/31177575*n + 131072/43648605*n^2) * eps^7 + - (2048/10392525 - 262144/218243025*n) * eps^8 + - 84992/218243025 * eps^9; +C4[8] = + (16384/35334585 - 131072/82447365*n) * eps^8 + - 32768/247342095 * eps^9; +C4[9] = + 32768/92147055 * eps^9; +\endverbatim + +\section geodellip Geodesics in terms of elliptic integrals + +GeodesicExact and GeodesicLineExact solve the geodesic problem using +elliptic integrals. The formulation of geodesic in terms of incomplete +elliptic integrals is given in + - C. F. F. Karney, + Geodesics + on an ellipsoid of revolution, + Feb. 2011; preprint + arxiv:1102.1215v1. + . +It is most convenient to use the form derived for a prolate ellipsoid in +Appendix D. For an oblate ellipsoid this results in elliptic integrals +with an imaginary modulus. However, the integrals themselves are real +and the algorithms used to compute the elliptic integrals handles the +case of an imaginary modulus using real arithmetic. + +The key relations used by GeographicLib are +\f[ + \begin{align} + \frac sb &= E(\sigma, ik), \\ + \lambda &= (1 - f) \sin\alpha_0 G(\sigma, \cos^2\alpha_0, ik) \\ + &= \chi + - \frac{e'^2}{\sqrt{1+e'^2}}\sin\alpha_0 H(\sigma, -e'^2, ik), \\ + J(\sigma) &= k^2 D(\sigma, ik), + \end{align} +\f] +where \f$ \chi \f$ is a modified spherical longitude given by +\f[ +\tan\chi = \sqrt{\frac{1+e'^2}{1+k^2\sin^2\sigma}}\tan\omega, +\f] +and +\f[ + \begin{align} + D(\phi,k) &= \int_0^\phi + \frac{\sin^2\theta}{\sqrt{1 - k^2\sin^2\theta}}\,d\theta\\ + &=\frac{F(\phi, k) - E(\phi, k)}{k^2},\\ + G(\phi,\alpha^2,k) &= \int_0^\phi + \frac{\sqrt{1 - k^2\sin^2\theta}}{1 - \alpha^2\sin^2\theta}\,d\theta\\ + &=\frac{k^2}{\alpha^2}F(\phi, k) + +\biggl(1-\frac{k^2}{\alpha^2}\biggr)\Pi(\phi, \alpha^2, k),\\ + H(\phi, \alpha^2, k) + &= \int_0^\phi + \frac{\cos^2\theta}{(1-\alpha^2\sin^2\theta)\sqrt{1-k^2\sin^2\theta}} + \,d\theta \\ + &= + \frac1{\alpha^2} F(\phi, k) + + \biggl(1 - \frac1{\alpha^2}\biggr) \Pi(\phi, \alpha^2, k), + \end{align} +\f] +and \f$F(\phi, k)\f$, \f$E(\phi, k)\f$, \f$D(\phi, k)\f$, and +\f$\Pi(\phi, \alpha^2, k)\f$, are incomplete elliptic integrals (see +http://dlmf.nist.gov/19.2.ii). The formula for \f$ s \f$ and the +first expression for \f$ \lambda \f$ are given by Legendre (1811) and +are the most common representation of geodesics in terms of elliptic +integrals. The second (equivalent) expression for \f$ \lambda \f$, +which was given by Cayley (1870), is useful in that the elliptic +integral is relegated to a small correction term. This form allows +the longitude to be computed more accurately and is used in +GeographicLib. (The equivalence of the two expressions for \f$ +\lambda \f$ follows from http://dlmf.nist.gov/19.7.E8.) + +Nominally, GeodesicExact and GeodesicLineExact will give "exact" results +for any value of the flattening. However, the geographic latitude is a +distorted measure of distance from the equator with very eccentric +ellipsoids and this introducing an irreducible representational error in +the algorithms in this case. It is therefore recommended to restrict +the use of these classes to b/\e a ∈ [0.01, 100] or \e f +∈ [−99, 0.99]. Note that GeodesicExact still uses a series +expansion for the area \e S12. However the series is taken out to 30th +order and gives accurate results for b/\e a ∈ [1/2, 2]; the +accuracy is about 8 decimal digits for b/\e a ∈ [1/4, 4]. +Additional work planned for this aspect of the geodesic problem: +- formulate the area integral \e S12 in terms of elliptic integrals; +- generate accurate test geodesics for highly eccentric ellipsoids so + that the roundoff errors can be quantified. + +Thomas (1952) and Rollins (2010) use a different independent variable +for geodesics, \f$\theta\f$ instead of \f$\sigma\f$, where \f$ +\tan\theta = \sqrt{1 + k^2} \tan\sigma \f$. The corresponding +expressions for \f$ s \f$ and \f$ \lambda \f$ are given here for +completeness: +\f[ +\begin{align} +\frac sb &= \sqrt{1-k'^2} \Pi(\theta, k'^2, k'), \\ +\lambda &= (1-f) \sqrt{1-k'^2} \sin\alpha_0 \Pi(\theta, k'^2/e^2, k'), +\end{align} +\f] +where \f$ k' = k/\sqrt{1 + k^2} \f$. The expression for \f$ s \f$ +can be written in terms of elliptic integrals of the second kind and +Cayley's technique can be used to subtract out the leading order +behavior of \f$ \lambda \f$ to give +\f[ +\begin{align} +\frac sb &=\frac1{\sqrt{1-k'^2}} + \biggl( E(\theta, k') - + \frac{k'^2 \sin\theta \cos\theta}{\sqrt{1-k'^2\sin^2\theta}} \biggr), \\ +\lambda &= \psi + (1-f) \sqrt{1-k'^2} \sin\alpha_0 +\bigl( F(\theta, k') - \Pi(\theta, e^2, k') \bigr), +\end{align} +\f] +where +\f[ +\begin{align} +\tan\psi &= \sqrt{\frac{1+k^2\sin^2\sigma}{1+e'^2}}\tan\omega \\ + &= \sqrt{\frac{1-e^2}{1+k^2\cos^2\theta}}\sin\alpha_0\tan\theta. +\end{align} +\f] +The tangents of the three "longitude-like" angles are in geometric +progression, \f$ \tan\chi/\tan\omega = \tan\omega/\tan\psi \f$. + +\section meridian Parameters for the meridian + +The formulas for \f$ s \f$ given in the previous section are the same as +those for the distance along a meridian for an ellipsoid with equatorial +radius \f$ a \sqrt{1 - e^2 \sin^2\alpha_0} \f$ and polar semi-axis \f$ b +\f$. Here is a list of possible ways of expressing the meridian +distance in terms of elliptic integrals using the notation: +- \f$ a \f$, equatorial axis, +- \f$ b \f$, polar axis, +- \f$ e = \sqrt{(a^2 - b^2)/a^2} \f$, eccentricity, +- \f$ e' = \sqrt{(a^2 - b^2)/b^2} \f$, second eccentricity, +- \f$ \phi = \mathrm{am}(u, e) \f$, the geographic latitude, +- \f$ \phi' = \mathrm{am}(v', ie') = \pi/2 - \phi \f$, + the geographic colatitude, +- \f$ \beta = \mathrm{am}(v, ie') \f$, the parametric latitude + (\f$ \tan^2\beta = (1 - e^2) \tan^2\phi \f$), +- \f$ \beta' = \mathrm{am}(u', e) = \pi/2 - \beta \f$, + the parametric colatitude, +- \f$ M \f$, the length of a quarter meridian (equator to pole), +- \f$ y \f$, the distance along the meridian (measured from the equator). +- \f$ y' = M -y \f$, the distance along the meridian (measured from the pole). +. +The eccentricities \f$ (e, e') \f$ are real (resp. imaginary) for +oblate (resp. prolate) ellipsoids. The elliptic variables \f$(u, +u')\f$ and \f$(v, v')\f$ are defined by +- \f$ u = F(\phi, e) ,\quad u' = F(\beta', e) \f$ +- \f$ v = F(\beta, ie') ,\quad v' = F(\phi', ie') \f$, +. +and are linearly related by +- \f$ u + u' = K(e) ,\quad v + v' = K(ie') \f$ +- \f$ v = \sqrt{1-e^2} u ,\quad u = \sqrt{1+e'^2} v \f$. +. +The cartesian coordinates for the meridian \f$ (x, z) \f$ are given by +\f[ +\begin{align} + x &= a \cos\beta = a \cos\phi / \sqrt{1 - e^2 \sin^2\phi} \\ + &= a \sin\beta' = (a^2/b) \sin\phi' / \sqrt{1 + e'^2 \sin^2\phi'} \\ + &= a \,\mathrm{cn}(v, ie) = a \,\mathrm{cd}(u, e) \\ + &= a \,\mathrm{sn}(u', e) = (a^2/b) \,\mathrm{sd}(v', ie'), +\end{align} +\f] +\f[ +\begin{align} + z &= b \sin\beta = (b^2/a) \sin\phi / \sqrt{1 - e^2 \sin^2\phi} \\ + &= b \cos\beta' = b \cos\phi' / \sqrt{1 + e'^2 \sin^2\phi'} \\ + &= b \,\mathrm{sn}(v, ie) = (b^2/a) \,\mathrm{sd}(u, e) \\ + &= b \,\mathrm{cn}(u', e) = b \,\mathrm{cd}(v', ie'). +\end{align} +\f] +The distance along the meridian can be expressed variously as +\f[ +\begin{align} + y &= b \int \sqrt{1 + e'^2 \sin^2\beta}\, d\beta + = b E(\beta, ie') \\ + &= \frac{b^2}a \int \frac1{(1 - e^2 \sin^2\phi)^{3/2}}\, d\phi + = \frac{b^2}a \Pi(\phi, e^2, e) \\ + &= a \biggl(E(\phi, e) - + \frac{e^2\sin\phi \cos\phi}{\sqrt{1 - e^2\sin^2\phi}}\biggr) \\ + &= b \int \mathrm{dn}^2(v, ie')\, dv + = \frac{b^2}a \int \mathrm{nd}^2(u, e)\, du + = \cal E(v, ie'), +\end{align} +\f] +\f[ +\begin{align} + y' &= a \int \sqrt{1 - e^2 \sin^2\beta'}\, d\beta' + = a E(\beta', e) \\ + &= \frac{a^2}b \int \frac1{(1 + e'^2 \sin^2\phi')^{3/2}}\, d\phi' + = \frac{a^2}b \Pi(\phi', -e'^2, ie') \\ + &= b \biggl(E(\phi', ie') + + \frac{e'^2\sin\phi' \cos\phi'}{\sqrt{1 + e'^2\sin^2\phi'}}\biggr) \\ + &= a \int \mathrm{dn}^2(u', e)\, du' + = \frac{a^2}b \int \mathrm{nd}^2(v', ie')\, dv' + = \cal E(u', e), +\end{align} +\f] +with the quarter meridian distance given by +\f[ + M = aE(e) = bE(ie') = (b^2/a)\Pi(e^2,e) = (a^2/b)\Pi(-e'^2,ie'). +\f] +(Here \f$ E, F, \Pi \f$ are elliptic integrals defined in +http://dlmf.nist.gov/19.2.ii. \f$ \cal E, \mathrm{am}, \mathrm{sn}, +\mathrm{cn}, \mathrm{sd}, \mathrm{cd}, \mathrm{dn}, \mathrm{nd} \f$ are +Jacobi elliptic functions defined in http://dlmf.nist.gov/22.2 and +http://dlmf.nist.gov/22.16.) + +There are several considerations in the choice of independent variable +for evaluate the meridian distance +- The use of an imaginary modulus (namely, \f$ ie' \f$, above) is of no + practical concern. The integrals are real in this case and modern + methods (GeographicLib uses the method given in + http://dlmf.nist.gov/19.36.i) for computing integrals handles this + case using just real arithmetic. +- If the "natural" origin is the equator, choose one of \f$ \phi, \beta, + u, v \f$ (this might be preferred in geodesy). If it's the pole, + choose one of the complementary quantities \f$ \phi', \beta', u', v' + \f$ (this might be preferred by mathematicians). +- Applying these formulas to the geodesic problems, \f$ \beta \f$ + becomes the arc length, \f$ \sigma \f$, on the auxiliary sphere. This + is the traditional method of solution used by Legendre (1806), Oriani + (1806), Bessel (1825), Helmert (1880), Rainsford (1955), Thomas + (1970), Vincenty (1975), Rapp (1993), and so on. Many of the + solutions in terms of elliptic functions use one of the elliptic + variables (\f$ u \f$ or \f$ v \f$), see, for example, Jacobi (1855), + Halphen (1888), Forsyth (1896). In the context of geodesics \f$ + \phi \f$ becomes Thomas' variable \f$ \theta \f$; this is used by + Thomas (1952) and Rollins (2010) in their formulation of the + geodesic problem (see the previous section). +- For highly eccentric ellipsoids the variation of the meridian with + respect to \f$ \beta \f$ is considerably "better behaved" than other + choices (see the figure below). The choice of \f$ \phi \f$ is + probably a poor one in this case. +. +GeographicLib uses the geodesic generalization of +\f$ y = b E(\beta, ie') \f$, namely \f$ s = b E(\sigma, ik) \f$. See +\ref geodellip. + +\image html meridian-measures.png "Comparison of meridian measures" + +\section geodshort Short geodesics + +Here we describe Bowring's method for solving the inverse geodesic +problem in the limit of short geodesics and contrast it with the great +circle solution using Bessel's auxiliary sphere. References: + - B. R. Bowring, The Direct and Inverse Problems for Short Geodesic + Lines on the Ellipsoid, Surveying and Mapping 41(2), 135--141 (1981). + - R. H. Rapp, + + Geometric Geodesy, Part I, Ohio State Univ. (1991), Sec. 6.5. + +Bowring considers the conformal mapping of the ellipsoid to a sphere of +radius \f$ R \f$ such that circles of latitude and meridians are +preserved (and hence the azimuth of a line is preserved). Let \f$ +(\phi, \lambda) \f$ and \f$ (\phi', \lambda') \f$ be the latitude and +longitude on the ellipsoid and sphere respectively. Define isometric +latitudes for the sphere and the ellipsoid as +\f[ +\begin{align} + \psi' &= \sinh^{-1} \tan \phi', \\ + \psi &= \sinh^{-1} \tan \phi - e \tanh^{-1}(e \sin\phi). +\end{align} +\f] +The most general conformal mapping satisfying Bowring's conditions is +\f[ +\psi' = A \psi + K, \quad \lambda' = A \lambda, +\f] +where \f$ A \f$ and \f$ K \f$ are constants. (In fact a constant can be +added to the equation for \f$ \lambda' \f$, but this does affect the +analysis.) The scale of this mapping is +\f[ +m(\phi) = \frac{AR}{\nu}\frac{\cos\phi'}{\cos\phi}, +\f] +where \f$ \nu = a/\sqrt{1 - e^2\sin^2\phi} \f$ is the transverse radius +of curvature. (Note that in Bowring's Eq. (10), \f$ \phi \f$ should be +replaced by \f$ \phi' \f$.) The mapping from the ellipsoid to the sphere +depends on three parameters \f$ R, A, K \f$. These will be selected to +satisfy certain conditions at some representative latitude \f$ \phi_0 +\f$. Two possible choices are given below. + +\subsection bowring Bowring's method + +Bowring (1981) requires that +\f[ +m(\phi_0) = 1,\quad +\left.\frac{dm(\phi)}{d\phi}\right|_{\phi=\phi_0} = 0,\quad +\left.\frac{d^2m(\phi)}{d\phi^2}\right|_{\phi=\phi_0} = 0, +\f] +i.e, \f$m\approx 1\f$ in the vicinity of \f$\phi = \phi_0\f$. +This gives +\f[ +\begin{align} +R &= \frac{\sqrt{1 + e'^2}}{B^2} a, \\ +A &= \sqrt{1 + e'^2 \cos^4\phi_0}, \\ +\tan\phi'_0 &= \frac1B \tan\phi_0, +\end{align} +\f] +where \f$ e' = e/\sqrt{1-e^2} \f$ is the second eccentricity, \f$ B = +\sqrt{1+e'^2\cos^2\phi_0} \f$, and \f$ K \f$ is defined implicitly by +the equation for \f$\phi'_0\f$. The radius \f$ R \f$ is the (Gaussian) +mean radius of curvature of the ellipsoid at \f$\phi_0\f$ (so near +\f$\phi_0\f$ the ellipsoid can be deformed to fit the sphere snugly). +The third derivative of \f$ m \f$ is given by +\f[ +\left.\frac{d^3m(\phi)}{d\phi^3}\right|_{\phi=\phi_0} = +\frac{-2e'^2\sin2\phi_0}{B^4}. +\f] + +The method for solving the inverse problem between two nearby points \f$ +(\phi_1, \lambda_1) \f$ and \f$ (\phi_2, \lambda_2) \f$ is as follows: +Set \f$\phi_0 = (\phi_1 + \phi_2)/2\f$. Compute \f$ R, A, \phi'_0 \f$, +and hence find \f$ (\phi'_1, \lambda'_1) \f$ and \f$ (\phi'_2, +\lambda'_2) \f$. Finally, solve for the great circle on a sphere of +radius \f$ R \f$; the resulting distance and azimuths are good +approximations for the corresponding quantities for the ellipsoidal +geodesic. + +Consistent with the accuracy of this method, we can compute +\f$\phi'_1\f$ and \f$\phi'_2\f$ using a Taylor expansion about +\f$\phi_0\f$. This also avoids numerical errors that arise from +subtracting nearly equal quantities when using the equation for +\f$\phi'\f$ directly. Write \f$\Delta \phi = \phi - \phi_0\f$ and +\f$\Delta \phi' = \phi' - \phi'_0\f$; then we have +\f[ +\Delta\phi' \approx +\frac{\Delta\phi}B \biggl[1 + +\frac{\Delta\phi}{B^2}\frac{e'^2}2 + \biggl(3\sin\phi_0\cos\phi_0 + + \frac{\Delta\phi}{B^2} + \bigl(B^2 - \sin^2\phi_0(2 - 3 e'^2 \cos^2\phi_0)\bigr)\biggr)\biggr], +\f] +where the error is \f$O(f\Delta\phi^4)\f$. +This is essentially Bowring's method. Significant differences between +this result, "Bowring (improved)", compared to Bowring's paper, "Bowring +(original)", are: + - Bowring elects to use \f$\phi_0 = \phi_1\f$. This simplifies the + calculations somewhat but increases the error by about a factor of + 4. + - Bowring's expression for \f$ \Delta\phi' \f$ is only accurate in the + limit \f$ e' \rightarrow 0 \f$. + . +In fact, arguably, the highest order \f$O(f\Delta\phi^3)\f$ terms should +be dropped altogether. Their inclusion does result in a better estimate +for the distance. However, if your goal is to generate both accurate +distances \e and accurate azimuths, then \f$\Delta\phi\f$ needs to be +restricted sufficiently to allow these terms to be dropped to give the +"Bowring (truncated)" method. + +With highly eccentric ellipsoids, the parametric latitude \f$ \beta \f$ +is a better behaved independent variable to use. In this case, \f$ +\phi_0 \f$ is naturally defined using \f$\beta_0 = (\beta_1 + +\beta_2)/2\f$ and in terms of \f$\Delta\beta = \beta - \beta_0\f$, we +have +\f[ +\Delta\phi' \approx +\frac{\Delta\beta}{B'} \biggl[1 + +\frac{\Delta\beta}{B'^2}\frac{e'^2}2 + \biggl(\sin\beta_0\cos\beta_0 + + \frac{\Delta\beta}{3B'^2} + \bigl( \cos^2\beta_0 - \sin^2\beta_0 B'^2\bigr) +\biggr)\biggr], +\f] +where \f$B' = \sqrt{1+e'^2\sin^2\beta_0} = \sqrt{1+e'^2}/B\f$, and the +error once again is \f$O(f\Delta\phi^4)\f$. This is the "Bowring +(using \f$\beta\f$)" method. + +\subsection auxsphere Bessel's auxiliary sphere + +GeographicLib's uses the auxiliary sphere method of Legendre, Bessel, +and Helmert. For short geodesics, this is equivalent to picking +\f$ R, A, K \f$ so that +\f[ +m(\phi_0) = 1,\quad +\left.\frac{dm(\phi)}{d\phi}\right|_{\phi=\phi_0} = 0,\quad +\tan\phi'_0 = (1 - f) \tan\phi_0. +\f] +Bowring's requirement that the second derivative of \f$m\f$ vanish has +been replaced by the last relation which states that \f$\phi'_0 = +\beta_0\f$, the parametric latitude corresponding to \f$\phi_0\f$. This +gives +\f[ +\begin{align} +R &= B'(1-f)a, \\ +A &= \frac1{B'(1-f)}, \\ +\left.\frac{d^2m(\phi)}{d\phi^2}\right|_{\phi=\phi_0} &= +-e^2B'^2\sin^2\phi_0. +\end{align} +\f] + +Similar to Bowring's method, we can compute \f$\phi'_1\f$ and +\f$\phi'_2\f$ using a Taylor expansion about \f$\beta_0\f$. This results +in the simple expression +\f[ +\Delta\phi' \approx \Delta\beta, +\f] +where the error is \f$O(f\Delta\beta^2)\f$. + +\subsection shorterr Estimating the accuracy + +In assessing the accuracy of these methods we use two metrics: + - The absolute error in the distance. + - The consistency of the predicted azimuths. Imagine starting + ellipsoidal geodesics at \f$ (\phi_1, \lambda_1) \f$ and \f$ (\phi_2, + \lambda_2) \f$ with the predicted azimuths. What is the distance + between them when they are extended a distance \f$ a \f$ beyond the + second point? + . +(The second metric is much more stringent.) We may now compare the +methods by asking for a bound to the length of a geodesic which ensures +that the one or other of the errors fall below 1 mm (an "engineering" +definition of accurate) or 1 nm (1 nanometer, about the round-off +limit). + +
+ + + + + + + + + + + + + + + +
Maximum distance that can be used in various methods for +computing short geodesics while keeping the errors within prescribed +bounds
method +
distance metric
azimuth metric
1 mm error1 nm error1 mm error1 nm error
Bowring (original) +
87 km
+
870 m
+
35 km
+
350 m
+
Bowring (improved) +
180 km
+
1.8 km
+
58 km
+
580 m
+
Bowring (truncated) +
52 km
+
520 m
+
52 km
+
520 m
+
Bowring (using \f$\beta\f$) +
380 km
+
24 km
+
60 km
+
600 m
+
Bessel's aux. sphere +
42 km
+
420 m
+
1.7 km
+
1.7 m
+
+
+ +For example, if you're only interested in measuring distances and an +accuracy of 1 mm is sufficient, then Bowring's improved method can +be used for distances up to 180 km. On the other hand, +GeographicLib uses Bessel's auxiliary sphere and we require both the +distance and the azimuth to be accurate, so the great circle +approximation can only be used for distances less than 1.7 m. The +reason that GeographicLib does not use Bowring's method is that the +information necessary for auxiliary sphere method is already available +as part of the general solution and, as much as possible, we allow all +geodesics to be computed by the general method. + +
+Back to \ref magnetic. Forward to \ref nearest. Up to \ref contents. +
+ +**********************************************************************/ +/** +\page nearest Finding nearest neighbors + +
+Back to \ref geodesic. Forward to \ref triaxial. Up to \ref contents. +
+ +The problem of finding the maritime boundary defined by the "median +line" is discussed in Section 14 of + - C. F. F. Karney, + Geodesics + on an ellipsoid of revolution, + Feb. 2011; preprint + arxiv:1102.1215v1. + . +Figure 14 shows the median line which is equidistant from Britain and +mainland Europe. Determining the median line involves finding, for any +given \e P, the closest points on the coast of Britain and on the coast +of mainland Europe. The operation of finding the closest in a set of +points is usually referred to as the nearest neighbor problem and +the NearestNeighbor class implements an efficient algorithm for solving +it. + +The NearestNeighbor class implements nearest-neighbor calculations using +the vantage-point tree described by +- J. K. Uhlmann, + + Satisfying general proximity/similarity queries with metric trees, + Information Processing Letters 40 175–179 (1991). +- P. N. Yianilos, + + Data structures and algorithms for nearest neighbor search in general + metric spaces, Proc. 4th ACM-SIAM Symposium on Discrete Algorithms, + (SIAM, 1993). pp. 311–321. + +Given a set of points \e x, \e y, \e z, …, in some space and a +distance function \e d satisfying the metric conditions, +\f[ +\begin{align} + d(x,y) &\ge 0,\\ + d(x,y) &= 0, \ \text{iff $x = y$},\\ + d(x,y) &= d(y,x),\\ + d(x,z) &\le d(x,y) + d(y,z), +\end{align} +\f] +the vantage-point (VP) tree provides an efficient way of determining +nearest neighbors. The geodesic distance (implemented by the Geodesic +class) satisfies these metric conditions, while the great ellipse +distance and the rhumb line distance do not (they do not satisfy +the last condition, the triangle inequality). Typically the cost of +constructing a VP tree of \e N points is \e N log \e N, while the cost +of a query is log \e N. Thus a VP tree should be used in situations +where \e N is large and at least log \e N queries are to be made. The +condition, \e N is large, means that \f$ N \gg 2^D \f$, where \e D is +the dimensionality of the space. + +- This implementation includes Yianilos' upper and lower bounds for the + inside and outside sets. This helps limit the number of searches + (compared to just using the median distance). +- Rather than do a depth-first or breath-first search on the tree, the + nodes to be processed are put on a priority queue with the nodes most + likely to contain close points processed first. Frequently, this allows + nodes lower down on the priority queue to be skipped. +- This technique also allows non-exhaustive searchs to be performed (to + answer questions such as "are there any points within 1km of the query + point?). +- When building the tree, the first vantage point is (arbitrarily) + chosen as the middle element of the set. Thereafter, the points + furthest from the parent vantage point in both the inside and outside + sets are selected as the children's vantage points. This information + is already available from the computation of the upper and lower + bounds of the children. This choice seems to lead to a reasonably + optimized tree. +- The leaf nodes can contain a bucket of points (instead of just a vantage + point). +- Coincident points are allowed in the set; these are treated as distinct + points. + +The figure below shows the construction of the VP tree for the points +making up the coastlines of Britain and Ireland (about 5000 points shown +in blue). The set of points is recursively split into 2 equal "inside" +and "outside" subsets based on the distance from a "vantage point". The +boundaries between the inside and outside sets are shown as green +circular arcs (arcs of geodesic circles). At each stage, the newly +added vantage points are shown as red dots and the vantage points for +the next stage are shown as red plus signs. The data is shown in the +Cassini-Soldner projection with a central meridian of 5°W. + +\image html vptree.gif "Vantage-point tree" + +
+Back to \ref geodesic. Forward to \ref triaxial. Up to \ref contents. +
+ +**********************************************************************/ +/** +\page triaxial Geodesics on a triaxial ellipsoid + +
+Back to \ref nearest. Forward to \ref jacobi. Up to \ref contents. +
+ +Jacobi (1839) showed that the problem of geodesics on a triaxial +ellipsoid (with 3 unequal axes) can be reduced to quadrature. Despite +this, the detailed behavior of the geodesics is not very well known. In +this section, I briefly give Jacobi's solution and illustrate the +behavior of the geodesics and outline an algorithm for the solution of +the inverse problem. + +See also + - The wikipedia page, + + Geodesics on a triaxial ellipsoid. + +Go to + - \ref triaxial-coords + - \ref triaxial-jacobi + - \ref triaxial-survey + - \ref triaxial-stab + - \ref triaxial-inverse + +NOTES + -# A triaxial ellipsoid approximates the earth only slightly better + than an ellipsoid of revolution. If you are really considering + measuring distances on the earth using a triaxial ellipsoid, you + should also be worrying about the shape of the geoid, which + essentially makes the geodesic problem a hopeless mess; see, for + example, Waters + (2011). + -# There is nothing new in this section. It is just an exercise in + exploring Jacobi's solution. My interest here is in generating long + geodesics with the correct long-time behavior. Arnold gives a + nice qualitative description of the solution in Mathematical + Methods of Classical Mechanics (2nd edition, Springer, 1989), + pp. 264--266. + -# Possible reasons this problem might, nevertheless, be of interest + are: + - It is the first example of a dynamical system which has a + non-trivial constant of motion. As such, Jacobi's paper generated + a lot of excitement and was followed by many papers elaborating + his solution. In particular, the unstable behavior of one of the + closed geodesics of the ellipsoid, is an early example of a system + with a positive Lyapunov exponent (one of the essential + ingredients for chaotic behavior in dynamical systems). + - Knowledge of ellipsoidal coordinates (used by Jacobi) might be + useful in other areas of geodesy. + - Geodesics which pass through the pole on an ellipsoid of revolution + represent a degenerate class (they are all closed and all pass + through the opposite pole). It is of interest to see how this + degeneracy is broken with a surface with a more general shape. + - Similarly, it is of interest to see how the Mercator projection of + the ellipsoid generalizes; this is another problem addressed by + Jacobi. + -# My interest in this problem was piqued by Jean-Marc Baillard. I put + him onto Jacobi's solution without having looked at it in detail + myself; and he quickly implemented the solution for an HP-41 + calculator(!) which is posted + here. + -# I do not give full citations of the papers here. You can find these + in the + + Geodesic Bibliography; this includes links to online + versions of the papers. + -# An alternative to exploring geodesics using Jacobi's solution is to + integrate the equations for the geodesics directly. This is the + approach taken by + + Oliver Knill and Michael Teodorescu. However it is difficult to + ensure that the long time behavior is correctly modeled with such an + approach. + -# At this point, I have no plans to add the solution of triaxial + geodesic problem to GeographicLib. + -# If you only want to learn about geodesics on a biaxial ellipsoid (an + ellipsoid of revolution), then see \ref geodesic or the paper + - C. F. F. Karney, + + Algorithms for geodesics, + J. Geodesy 87(1), 43--55 (2013); + DOI: + 10.1007/s00190-012-0578-z; + addenda: + geod-addenda.html. + +\section triaxial-coords Triaxial coordinate systems + +Consider the ellipsoid defined by +\f[ + f = \frac{X^2}{a^2} + \frac{Y^2}{b^2} + \frac{Z^2}{c^2} = 1, +\f] +where, without loss of generality, \f$ a \ge b \ge c \gt 0\f$. A +point on the surface is specified by a latitude and longitude. The \e +geographical latitude and longitude \f$(\phi, \lambda)\f$ are defined by +\f[ + \frac{\nabla f}{\left| \nabla f\right|} = \left( +\begin{array}{c} \cos\phi \cos\lambda \\ \cos\phi \sin\lambda \\ \sin\phi +\end{array}\right). +\f] +The \e parametric latitude and longitude \f$(\phi', \lambda')\f$ are +defined by +\f[ +\begin{align} + X &= a \cos\phi' \cos\lambda', \\ + Y &= b \cos\phi' \sin\lambda', \\ + Z &= c \sin\phi'. +\end{align} +\f] +Jacobi employed the \e ellipsoidal latitude and longitude \f$(\beta, +\omega)\f$ defined by +\f[ +\begin{align} + X &= a \cos\omega + \frac{\sqrt{a^2 - b^2\sin^2\beta - c^2\cos^2\beta}} + {\sqrt{a^2 - c^2}}, \\ + Y &= b \cos\beta \sin\omega, \\ + Z &= c \sin\beta + \frac{\sqrt{a^2\sin^2\omega + b^2\cos^2\omega - c^2}} + {\sqrt{a^2 - c^2}}. +\end{align} +\f] +Grid lines of constant \f$\beta\f$ and \f$\omega\f$ are given in Fig. 1. + +
+Geodesic grid on a triaxial ellipsoid +Fig. 1 +
\n +Fig. 1: +The ellipsoidal grid. The blue (resp. green) lines are lines of constant +\f$\beta\f$ (resp. \f$\omega\f$); the grid spacing is 10°. Also +shown in red are two of the principal sections of the ellipsoid, defined +by \f$x = 0\f$ and \f$z = 0\f$. The third principal section, \f$y = +0\f$, is covered by the lines \f$\beta = \pm 90^\circ\f$ and \f$\omega = +90^\circ \pm 90^\circ\f$. These lines meet at four umbilical points (two +of which are visible in this figure) where the principal radii of +curvature are equal. The parameters of the ellipsoid are \f$a = +1.01\f$, \f$b = 1\f$, \f$c = 0.8\f$, and it is viewed in an orthographic +projection from a point above \f$\phi = 40^\circ\f$, \f$\lambda = +30^\circ\f$. These parameters were chosen to accentuate the ellipsoidal +effects on geodesics (relative to those on the earth) while still +allowing the connection to an ellipsoid of revolution to be made. + +The grid lines of the ellipsoid coordinates are "lines of curvature" on +the ellipsoid, i.e., they are parallel to the direction of principal +curvature (Monge, 1796). They are also intersections of the ellipsoid +with confocal systems of hyperboloids of one and two sheets (Dupin, +1813). Finally they are geodesic ellipses and hyperbolas defined using +two adjacent umbilical points. For example, the lines of constant +\f$\beta\f$ in Fig. 1 can be generated with the familiar string +construction for ellipses with the ends of the string pinned to the two +umbilical points. + +The element of length on the ellipsoid in ellipsoidal coordinates is +given by +\f[ +\begin{align} +\frac{ds^2}{(a^2-b^2)\sin^2\omega+(b^2-c^2)\cos^2\beta} &= +\frac{b^2\sin^2\beta+c^2\cos^2\beta} + {a^2-b^2\sin^2\beta-c^2\cos^2\beta} + d\beta^2 \\ +&\qquad+ +\frac{a^2\sin^2\omega+b^2\cos^2\omega} + {a^2\sin^2\omega+b^2\cos^2\omega-c^2} + d\omega^2. +\end{align} +\f] + +The torus \f$(\omega, \beta) \in [-\pi,\pi] \times [-\pi,\pi]\f$ covers +the ellipsoid twice. In order to facilitate passing to the limit of an +oblate ellipsoid, we may regard as the principal sheet \f$[-\pi,\pi] +\times [-\frac12\pi,\frac12\pi]\f$ and insert branch cuts at +\f$\beta=\pm\frac12\pi\f$. The rule for switching sheets is +\f[ +\begin{align} +\omega & \rightarrow -\omega,\\ +\beta & \rightarrow \pi-\beta,\\ +\alpha & \rightarrow \pi+\alpha, +\end{align} +\f] +where \f$\alpha\f$ is the heading of a path, relative to a line of +constant \f$\omega\f$. + +In the limit \f$b\rightarrow a\f$ (resp. \f$b\rightarrow c\f$), the +umbilic points converge on the \f$z\f$ (resp. \f$x\f$) axis and an +oblate (resp. prolate) ellipsoid is obtained with \f$\beta\f$ +(resp. \f$\omega\f$) becoming the standard parametric latitude and +\f$\omega\f$ (resp. \f$\beta\f$) becoming the standard longitude. The +sphere is a non-uniform limit, with the position of the umbilic points +depending on the ratio \f$(a-b)/(b-c)\f$. + +Inter-conversions between the three different latitudes and longitudes +and the cartesian coordinates are simple algebraic exercises. + +\section triaxial-jacobi Jacobi's solution + +Solving the geodesic problem for an ellipsoid of revolution is, from the +mathematical point of view, trivial; because of symmetry, geodesics have +a constant of the motion (analogous to the angular momentum) which was +found by Clairaut (1733). By 1806 (with the work of Legendre, Oriani, +et al.), there was a complete understanding of the qualitative behavior +of geodesics on an ellipsoid of revolution. + +On the other hand, geodesics on a triaxial ellipsoid have no obvious +constant of the motion and thus represented a challenging "unsolved" +problem in the first half of the nineteenth century. Jacobi discovered +that the geodesic equations are separable if they are expressed in +ellipsoidal coordinates. You can get an idea of the importance Jacobi +attached to his discovery from the + +letter he wrote to his friend and neighbor Bessel: +
The day before yesterday, I reduced to quadrature the +problem of geodesic lines on an ellipsoid with three unequal +axes. They are the simplest formulas in the world, Abelian +integrals, which become the well known elliptic integrals if 2 axes are +set equal.\n +Königsberg, 28th Dec. '38. +
+ +On the same day he wrote a similar letter to the editor of Compte Rendus +and his result was published in J. Crelle in (1839) with a French +translation (from German) appearing in J. Liouville in (1841). + +Here is the solution, exactly as given by Jacobi + here +(with minor changes in notation): +\f[ +\begin{align} +\delta &= \int \frac +{\sqrt{b^2\sin^2\beta + c^2\cos^2\beta}\,d\beta} +{\sqrt{a^2 - b^2\sin^2\beta - c^2\cos^2\beta} + \sqrt{(b^2-c^2)\cos^2\beta - \gamma}}\\ +&\quad - +\int \frac +{\sqrt{a^2\sin^2\omega + b^2\cos^2\omega}\,d\omega} +{\sqrt{a^2\sin^2\omega + b^2\cos^2\omega - c^2} + \sqrt{(a^2-b^2)\sin^2\omega + \gamma}} +\end{align} +\f] +As Jacobi notes "a function of the angle \f$\beta\f$ equals a +function of the angle \f$\omega\f$. These two functions are just +Abelian integrals…" Two constants \f$\delta\f$ and \f$\gamma\f$ +appear in the solution. Typically \f$\delta\f$ is zero if the lower +limits of the integrals are taken to be the starting point of the geodesic +and the direction of the geodesics is determined by \f$\gamma\f$. +However for geodesics that start at an umbilical points, we have \f$\gamma += 0\f$ and \f$\delta\f$ determines the direction at the umbilical point. +Incidentally the constant \f$\gamma\f$ may be expressed as +\f[ +\gamma = (b^2-c^2)\cos^2\beta\sin^2\alpha-(a^2-b^2)\sin^2\omega\cos^2\alpha +\f] +where \f$\alpha\f$ is the angle the geodesic makes with lines of +constant \f$\omega\f$. In the limit \f$b\rightarrow a\f$, this reduces +to \f$\cos\beta\sin\alpha = \text{const.}\f$, the familiar Clairaut +relation. A nice derivation of Jacobi's result is given by Darboux +(1894) +§§583--584 where he gives the solution found by Liouville +(1846) for general quadratic surfaces. In this formulation, the +distance along the geodesic, \f$s\f$, is also found using +\f[ +\begin{align} +\frac{ds}{(b^2-c^2)\cos^2\beta + (a^2-b^2)\sin^2\omega} +&= \frac +{\sqrt{b^2\sin^2\beta + c^2\cos^2\beta}\,d\beta} +{\sqrt{a^2 - b^2\sin^2\beta - c^2\cos^2\beta} + \sqrt{(b^2-c^2)\cos^2\beta - \gamma}}\\ +&= \frac +{\sqrt{a^2\sin^2\omega + b^2\cos^2\omega}\,d\omega} +{\sqrt{a^2\sin^2\omega + b^2\cos^2\omega - c^2} + \sqrt{(a^2-b^2)\sin^2\omega + \gamma}} +\end{align} +\f] +An alternative expression for the distance is +\f[ +\begin{align} +ds +&= \frac +{\sqrt{b^2\sin^2\beta + c^2\cos^2\beta} + \sqrt{(b^2-c^2)\cos^2\beta - \gamma}\,d\beta} +{\sqrt{a^2 - b^2\sin^2\beta - c^2\cos^2\beta}}\\ +&\quad {}+ \frac +{\sqrt{a^2\sin^2\omega + b^2\cos^2\omega} + \sqrt{(a^2-b^2)\sin^2\omega + \gamma}\,d\omega} +{\sqrt{a^2\sin^2\omega + b^2\cos^2\omega - c^2}} +\end{align} +\f] + +Jacobi's solution is a convenient way to compute geodesics on an +ellipsoid. Care must be taken with the signs of the square roots (which +are determined by the initial azimuth of the geodesic). Also if +\f$\gamma \gt 0\f$ (resp. \f$\gamma \lt 0\f$), then the \f$\beta\f$ +(resp. \f$\omega\f$) integrand diverges. The integrand can be +transformed into a finite one by a change of variable, e.g., +\f$\sin\beta = \sin\sigma \sqrt{1 - \gamma/(b^2-c^2)}\f$. The resulting +integrals are periodic, so the behavior of an arbitrarily long geodesic +is entirely captured by tabulating the integrals over a single period. + +The situation is more complicated if \f$\gamma = 0\f$ (corresponding to +umbilical geodesics). Both integrands have simple poles at the umbilical +points. However, this behavior may be subtracted from the integrands to +yield (for example) the sum of a term involving +\f$\tanh^{-1}\sin\beta\f$ and a finite integral. Since both integrals +contain similar logarithmic singularities they can be equated (thus +fixing the ratio \f$\cos\beta/\sin\omega\f$ at the umbilical point) and +connection formulas can be found which allow the geodesic to be followed +through the umbilical point. The study of umbilical geodesics was of +special interest to a group of Irish mathematicians in the 1840's and +1850's, including Michael and William Roberts (twins!), Hart, Graves, +and Salmon. + +\section triaxial-survey Survey of triaxial geodesics + +Before delving into the nature of geodesics on a triaxial geodesic, it +is worth reviewing geodesics on an ellipsoid of revolution. There are +two classes of simple closed geodesics (i.e., geodesics which close on +themselves without intersection): the equator and all the meridians. +All other geodesics oscillate between two equal and opposite circles of +latitude; but after completing a full oscillation in latitude these fall +slightly short (for an oblate ellipsoid) of completing a full circuit in +longitude. + +Turning to the triaxial case, we find that there are only 3 simple +closed geodesics, the three principal sections of the ellipsoid given by +\f$x = 0\f$, \f$y = 0\f$, and \f$z = 0\f$. To survey the other +geodesics, it is convenient to consider geodesics which intersect the +middle principal section, \f$y = 0\f$, at right angles. Such geodesics +are shown in Figs. 2--6, where I use the same ellipsoid parameters as in +Fig. 1 and the same viewing direction. In addition, the three principal +ellipses are shown in red in each of these figures. + +If the starting point is \f$\beta_1 \in (-90^\circ, 90^\circ)\f$, +\f$\omega_1 = 0\f$, and \f$\alpha_1 = 90^\circ\f$, then the geodesic +encircles the ellipsoid in a "circumpolar" sense. The geodesic +oscillates north and south of the equator; on each oscillation it +completes slightly less that a full circuit around the ellipsoid +resulting in the geodesic filling the area bounded by the two latitude +lines \f$\beta = \pm \beta_1\f$. Two examples are given in +Figs. 2 and 3. Figure 2 shows practically the same behavior as for an +oblate ellipsoid of revolution (because \f$a \approx b\f$). However, if +the starting point is at a higher latitude (Fig. 3) the distortions +resulting from \f$a \ne b\f$ are evident. + +
+Example of a circumpolar geodesic on a
+triaxial ellipsoid +Fig. 2 +
\n +Fig. 2: +Example of a circumpolar geodesic on a triaxial ellipsoid. The starting +point of this geodesic is \f$\beta_1 = 45.1^\circ\f$, \f$\omega_1 = +0^\circ\f$, and \f$\alpha_1 = 90^\circ\f$. + +
+Another example of a circumpolar geodesic on a
+triaxial ellipsoid +Fig. 3 +
\n +Fig. 3: +Another example of a circumpolar geodesic on a triaxial ellipsoid. The +starting point of this geodesic is \f$\beta_1 = 87.48^\circ\f$, \f$\omega_1 = +0^\circ\f$, and \f$\alpha_1 = 90^\circ\f$. + +If the starting point is \f$\beta_1 = 90^\circ\f$, \f$\omega_1 \in +(0^\circ, 180^\circ)\f$, and \f$\alpha_1 = 180^\circ\f$, then the geodesic +encircles the ellipsoid in a "transpolar" sense. The geodesic +oscillates east and west of the ellipse \f$x = 0\f$; on each oscillation +it completes slightly more that a full circuit around the ellipsoid +resulting in the geodesic filling the area bounded by the two longitude +lines \f$\omega = \omega_1\f$ and \f$\omega = 180^\circ - \omega_1\f$. +If \f$a = b\f$, all meridians are geodesics; the effect of \f$a \ne b\f$ +causes such geodesics to oscillate east and west. Two examples are +given in Figs. 4 and 5. + +
+Example of a transpolar geodesic on a
+triaxial ellipsoid +Fig. 4 +
\n +Fig. 4: +Example of a transpolar geodesic on a triaxial ellipsoid. The +starting point of this geodesic is \f$\beta_1 = 90^\circ\f$, \f$\omega_1 = +39.9^\circ\f$, and \f$\alpha_1 = 180^\circ\f$. + +
+Another example of a transpolar geodesic on a
+triaxial ellipsoid +Fig. 5 +
\n +Fig. 5: +Another example of a transpolar geodesic on a triaxial ellipsoid. The +starting point of this geodesic is \f$\beta_1 = 90^\circ\f$, \f$\omega_1 = +9.966^\circ\f$, and \f$\alpha_1 = 180^\circ\f$. + +If the starting point is \f$\beta_1 = 90^\circ\f$, \f$\omega_1 = +0^\circ\f$ (an umbilical point), and \f$\alpha_1 = 135^\circ\f$ (the +geodesic leaves the ellipse \f$y = 0\f$ at right angles), then the +geodesic repeatedly intersects the opposite umbilical point and returns to +its starting point. However on each circuit the angle at which it +intersects \f$y = 0\f$ becomes closer to \f$0^\circ\f$ or +\f$180^\circ\f$ so that asymptotically the geodesic lies on the ellipse +\f$y = 0\f$. This is shown in Fig. 6. Note that a single geodesic does +not fill an area on the ellipsoid. + +
+Example of an umbilical geodesic on a
+triaxial ellipsoid +Fig. 6 +
\n +Fig. 6: +Example of an umbilical geodesic on a triaxial ellipsoid. The +starting point of this geodesic is \f$\beta_1 = 90^\circ\f$, \f$\omega_1 = +0^\circ\f$, and \f$\alpha_1 = 135^\circ\f$ and the geodesics is followed +forwards and backwards until it lies close to the plane \f$y = 0\f$ in +both directions. + +Umbilical geodesics enjoy several interesting properties. + - Through any point on the ellipsoid, there are two umbilical geodesics. + - The geodesic distance between opposite umbilical points is the same + regardless of the initial direction of the geodesic. + - Whereas the closed geodesics on the ellipses \f$x = 0\f$ and \f$z = + 0\f$ are stable (an geodesic initially close to and nearly parallel to + the ellipse remains close to the ellipse), the closed geodesic on the + ellipse \f$y = 0\f$, which goes through all 4 umbilical points, is \e + unstable. If it is perturbed, it will swing out of the plane \f$y = + 0\f$ and flip around before returning to close to the plane. (This + behavior may repeat depending on the nature of the initial + perturbation.). + +\section triaxial-stab The stability of closed geodesics + +The stability of the three simple closed geodesics can be determined by +examining the properties of Jacobi's solution. In particular the +unstable behavior of umbilical geodesics was shown by Hart (1849). +However an alternative approach is to use the equations that Gauss +(1828) gives for a perturbed geodesic +\f[ +\frac {d^2m}{ds^2} + Km = 0 +\f] +where \f$m\f$ is the distance of perturbed geodesic from a reference +geodesic and \f$K\f$ is the Gaussian curvature of the surface. If the +reference geodesic is closed, then this is a linear homogeneous +differential equation with periodic coefficients. In fact it's a +special case of Hill's equation which can be treated using Floquet +theory, see DLMF, §28.29. +Using the notation of §3 of + Algorithms for +geodesics, the stability is determined by computing the reduced +length \f$m_{12}\f$ and the geodesic scales \f$M_{12}, M_{21}\f$ over +half the perimeter of the ellipse and determining the eigenvalues +\f$\lambda_{1,2}\f$ of +\f[ +{\cal M} = \left(\begin{array}{cc} +M_{12} & m_{12}\\ +-\frac{1 - M_{12}M_{21}}{m_{12}} & M_{21} +\end{array}\right). +\f] +Because \f$\mathrm{det}\,{\cal M} = 1\f$, the eigenvalues are determined +by \f$\mathrm{tr}\,{\cal M}\f$. In particular if +\f$\left|\mathrm{tr}\,{\cal M}\right| < 2\f$, we have +\f$\left|\lambda_{1,2}\right| = 1\f$ and the solution is stable; if +\f$\left|\mathrm{tr}\,{\cal M}\right| > 2\f$, one of +\f$\left|\lambda_{1,2}\right|\f$ is larger than unity and the solution +is (exponentially) unstable. In the transition case, +\f$\left|\mathrm{tr}\,{\cal M}\right| = 2\f$, the solution is stable +provided that the off-diagonal elements of \f${\cal M}\f$ are zero; +otherwise the solution is linearly unstable. + +The exponential instability of the geodesic on the ellipse \f$y = 0\f$ +is confirmed by this analysis and results from the resonance between the +natural frequency of the equation for \f$m\f$ and the driving frequency +when \f$b\f$ lies in \f$(c, a)\f$. If \f$b\f$ is equal to either of the +other axes (and the triaxial ellipsoid degenerates to an ellipsoid of +revolution), then the solution is linearly unstable. (For example, a +geodesic is which is close to a meridian on an oblate ellipsoid, slowly +moves away from that meridian.) + +\section triaxial-inverse The inverse problem + +In order to solve the inverse geodesic problem, it helps to have an +understanding of the properties of all the geodesics emanating from a +single point \f$(\beta_1, \omega_1)\f$. + - If the point is an umbilical point, all the lines meet at the + opposite umbilical point. + - Otherwise, the first envelope of the geodesics is a 4-pointed + astroid. The cusps of the astroid lie on either \f$\beta = - + \beta_1\f$ or \f$\omega = \omega_1 + \pi\f$; see + Sinclair + (2003). + - All geodesics intersect (or, in the case of \f$\alpha_1 = 0\f$ or + \f$\pi\f$, touch) the line \f$\omega = \omega_1 + \pi\f$. + - All geodesics intersect (or, in the case of \f$\alpha_1 = + \pm\pi/2\f$, touch) the line \f$\beta = -\beta_1\f$. + - Two geodesics with azimuths \f$\pm\alpha_1\f$ first intersect on + \f$\omega = \omega_1 + \pi\f$ and their lengths to the point of + intersection are equal. + - Two geodesics with azimuths \f$\alpha_1\f$ and \f$\pi-\alpha_1\f$ + first intersect on \f$\beta = -\beta_1\f$ and their lengths to the + point of intersection are equal. + . +(These assertions follow directly from the equations for the geodesics; +some of them are somewhat surprising given the asymmetries of the +ellipsoid.) Consider now terminating the geodesics from \f$(\beta_1, +\omega_1)\f$ at the point where they first intersect (or touch) the line +\f$\beta = -\beta_1\f$. To focus the discussion, take \f$\beta_1 \le +0\f$. + - The geodesics completely fill the portion of the ellipsoid satisfying + \f$\beta \le -\beta_1\f$. + - None of geodesics intersect any other geodesics. + - Any initial portion of these geodesics is a shortest path. + - Each geodesic intersects the line \f$\beta = \beta_2\f$, where + \f$\beta_1 < \beta_2 < -\beta_1\f$, exactly once. + - For a given \f$\beta_2\f$, this defines a continuous monotonic + mapping of the circle of azimuths \f$\alpha_1\f$ to the circle of + longitudes \f$\omega_2\f$. + - If \f$\beta_2 = \pm \beta_1\f$, then the previous two assertions need + to be modified similarly to the case for an ellipsoid of revolution. + +These properties show that the inverse problem can be solved using +techniques similar to those employed for an ellipsoid of revolution (see +§4 of + Algorithms for +geodesics). + - If the points are opposite umbilical points, an arbitrary + \f$\alpha_1\f$ may be chosen. + - If the points are neighboring umbilical points, the shortest path + lies on the ellipse \f$y = 0\f$. + - If only one point is an umbilicial point, the azimuth at the + non-umbilical point is found using the generalization of Clairaut's + equation (given above) with \f$\gamma = 0\f$. + - Treat the cases where the geodesic might follow a line of constant + \f$\beta\f$. There are two such cases: (a) the points lie on + the ellipse \f$z = 0\f$ on a general ellipsoid and (b) the + points lie on an ellipse whose major axis is the \f$x\f$ axis on a + prolate ellipsoid (\f$a = b > c\f$). Determine the reduced length + \f$m_{12}\f$ for the geodesic which is the shorter path along the + ellipse. If \f$m_{12} \ge 0\f$, then this is the shortest path on + the ellipsoid; otherwise proceed to the general case (next). + - Swap the points, if necessary, so that the first point is the one + closest to a pole. Estimate \f$\alpha_1\f$ (by some means) and solve + the \e hybrid problem, i.e., determine the longitude \f$\omega_2\f$ + corresponding to the first intersection of the geodesic with \f$\beta + = \beta_2\f$. Adjust \f$\alpha_1\f$ so that the value of + \f$\omega_2\f$ matches the given \f$\omega_2\f$ (there is a single + root). If a sufficiently close solution can be found, Newton's + method can be employed since the necessary derivative can be + expressed in terms of the reduced length \f$m_{12}\f$. + +The shortest path found by this method is unique unless: + - The length of the geodesic vanishes \f$s_{12}=0\f$, in which case any + constant can be added to the azimuths. + - The points are opposite umbilical points. In this case, + \f$\alpha_1\f$ can take on any value and \f$\alpha_2\f$ needs to be + adjusted to maintain the value of \f$\tan\alpha_1 / \tan\alpha_2\f$. + Note that \f$\alpha\f$ increases by \f$\pm 90^\circ\f$ as the + geodesic passes through an umbilical point, depending on whether the + geodesic is considered as passing to the right or left of the point. + Here \f$\alpha_2\f$ is the \e forward azimuth at the second umbilical + point, i.e., its azimuth immediately \e after passage through the + umbilical point. + - \f$\beta_1 + \beta_2 = 0\f$ and \f$\cos\alpha_1\f$ and + \f$\cos\alpha_2\f$ have opposite signs. In this case, there another + shortest geodesic with azimuths \f$\pi - \alpha_1\f$ and + \f$\pi - \alpha_2\f$. + +\section triaxial-conformal Jacobi's conformal projection + +This material is now on its own page; see \ref jacobi. + +
+Back to \ref nearest. Forward to \ref jacobi. Up to \ref contents. +
+ +**********************************************************************/ +/** +\page jacobi Jacobi's conformal projection + +
+Back to \ref triaxial. Forward to \ref rhumb. Up to \ref contents. +
+ +In addition to solving the geodesic problem for the triaxial ellipsoid, +Jacobi (1839) briefly mentions the problem of the conformal projection +of ellipsoid. He covers this in greater detail in + +Vorlesungen über Dynamik, §28, which is now +available in an +English translation: Lectures on Dynamics +( +errata). + +\section jacobi-conformal Conformal projection + +It is convenient to rotate Jacobi's ellipsoidal coordinate system so +that \f$(X,Y,Z)\f$ are respectively the middle, large, and small axes of +the ellipsoid. The longitude \f$\omega\f$ is shifted so that +\f$(\beta=0,\omega=0)\f$ is the point \f$(b,0,0)\f$. The coordinates +are thus defined by +\f[ +\begin{align} + X &= b \cos\beta \cos\omega, \\ + Y &= a \sin\omega + \frac{\sqrt{a^2 - b^2\sin^2\beta - c^2\cos^2\beta}} + {\sqrt{a^2 - c^2}}, \\ + Z &= c \sin\beta + \frac{\sqrt{a^2\cos^2\omega + b^2\sin^2\omega - c^2}} + {\sqrt{a^2 - c^2}}. +\end{align} +\f] +After this change, the large principal ellipse is the equator, +\f$\beta=0\f$, while the small principal ellipse is the prime meridian, +\f$\omega=0\f$. The four umbilic points, \f$\left|\omega\right| = +\left|\beta\right| = \frac12\pi\f$, lie on middle principal ellipse in +the plane \f$X=0\f$. + +Jacobi gives the following conformal mapping of the triaxial ellipsoid +onto a plane +\f[ +\begin{align} +x &= \frac{\sqrt{a^2-c^2}}b \int \frac +{\sqrt{a^2 \cos^2\omega + b^2 \sin^2\omega}} +{\sqrt{a^2 \cos^2\omega + b^2 \sin^2\omega - c^2}}\, d\omega, \\ +y &= \frac{\sqrt{a^2-c^2}}b \int \frac +{\sqrt{b^2 \sin^2\beta + c^2 \cos^2\beta}} +{\sqrt{a^2 - b^2 \sin^2\beta - c^2 \cos^2\beta}}\, d\beta. +\end{align} +\f] +The scale of the projection is +\f[ +k = \frac{\sqrt{a^2-c^2}} +{b\sqrt{a^2 \cos^2\omega + b^2 (\sin^2\omega-\sin^2\beta) - c^2 \cos^2\beta}}. +\f] +I have scaled the Jacobi's projection by a constant factor, +\f[ +\frac{\sqrt{a^2-c^2}}{2b}, +\f] +so that it reduces to the familiar formulas in the case of an oblate ellipsoid. + +\section jacobi-elliptic The projection in terms of elliptic integrals + +The projection may be expressed in terms of elliptic integrals, +\f[ +\begin{align} +x&=(1+e_a^2)\,\Pi(\omega',-e_a^2, \cos\nu),\\ +y&=(1-e_c^2)\,\Pi(\beta' , e_c^2, \sin\nu),\\ +k&=\frac{\sqrt{e_a^2+e_c^2}}{b\sqrt{e_a^2\cos^2\omega+e_c^2\cos^2\beta}}, +\end{align} +\f] +where +\f[ +\begin{align} +e_a &= \frac{\sqrt{a^2-b^2}}b, \qquad +e_c = \frac{\sqrt{b^2-c^2}}b, \\ +\tan\omega' &= \frac ba \tan\omega = \frac 1{\sqrt{1+e_a^2}} \tan\omega, \\ +\tan\beta' &= \frac bc \tan\beta = \frac 1{\sqrt{1-e_c^2}} \tan\beta, \\ +\tan\nu &= \frac ac \frac{\sqrt{b^2-c^2}}{\sqrt{a^2-b^2}} +=\frac{e_c}{e_a}\frac{\sqrt{1+e_a^2}}{\sqrt{1-e_c^2}}, +\end{align} +\f] +\f$\nu\f$ is the geographic latitude of the umbilic point at \f$\beta = +\omega = \frac12\pi\f$ (the angle a normal at the umbilic point makes +with the equatorial plane), and \f$\Pi(\phi,\alpha^2,k)\f$ is the +elliptic integral of the third kind, http://dlmf.nist.gov/19.2.E7. This +allows the projection to be numerically computed using +EllipticFunction::Pi(real phi) const. + +Nyrtsov, et al., + - M. V. Nyrtsov, M. E. Flies, M. M. Borisov, P. J. Stooke, + + Jacobi conformal projection of the triaxial ellipsoid: new projection + for mapping of small celestial bodies, in + Cartography from Pole to Pole + (Springer, 2014), pp. 235--246. + . +also expressed the projection in terms of elliptic integrals. +However, their expressions don't allow the limits of ellipsoids of +revolution to be readily recovered. The relations +http://dlmf.nist.gov/19.7.E5 can be used to put their results in the +form given here. + +\section jacobi-properties Properties of the projection + +\f$x\f$ (resp. \f$y\f$) depends on \f$\omega\f$ (resp. \f$\beta\f$) +alone, so that latitude-longitude grid maps to straight lines in the +projection. In this sense, the Jacobi projection is the natural +generalization of the Mercator projection for the triaxial ellipsoid. +(See below for the limit \f$a\rightarrow b\f$, which makes this +connection explicit.) + +In the general case (all the axes are different), the scale diverges +only at the umbilic points. The behavior of these singularities is +illustrated by the complex function +\f[ +f(z;e) = \cosh^{-1}(z/e) - \log(2/e). +\f] +For \f$e > 0\f$, this function has two square root singularities at +\f$\pm e\f$, corresponding to the two northern umbilic points. +Plotting contours of its real (resp. imaginary) part gives the +behavior of the lines of constant latitude (resp. longitude) near the +north pole in Fig. 1. If we pass to the limit \f$e\rightarrow 0\f$, +then \f$ f(z;e)\rightarrow\log z\f$, and the two branch points merge +yielding a stronger (logarithmic) singularity at \f$z = 0\f$, +concentric circles of latitude, and radial lines of longitude. + +Again in the general case, the extents of \f$x\f$ and \f$y\f$ are +finite, +\f[ +\begin{align} +x\bigl(\tfrac12\pi\bigr) &=(1+e_a^2)\,\Pi(-e_a^2, \cos\nu),\\ +y\bigl(\tfrac12\pi\bigr) &=(1-e_c^2)\,\Pi(e_c^2, \sin\nu), +\end{align} +\f] +where \f$\Pi(\alpha^2,k)\f$ is the complete elliptic integral of the +third kind, http://dlmf.nist.gov/19.2.E8. + +In particular, if we substitute values appropriate for the earth, +\f[ +\begin{align} +a&=(6378137+35)\,\mathrm m,\\ +b&=(6378137-35)\,\mathrm m,\\ +c&=6356752\,\mathrm m,\\ +\end{align} +\f] +we have +\f[ +\begin{align} +x\bigl({\textstyle\frac12}\pi\bigr) &= 1.5720928 = \hphantom{0}90.07428^\circ,\\ +y\bigl({\textstyle\frac12}\pi\bigr) &= 4.2465810 = 243.31117^\circ.\\ +\end{align} +\f] + +The projection may be inverted (to give \f$\omega\f$ in terms of \f$x\f$ +and \f$\beta\f$ in terms of \f$y\f$) by using Newton's method to find +the root of, for example, \f$x(\omega) - x_0 = 0\f$. The derivative of +the elliptic integral is, of course, just given by its defining +relation. + +If rhumb lines are defined as curves with a constant bearing relative +to the ellipsoid coordinates, then these are straight lines in the +Jacobi projection. A rhumb line which passes over an umbilic point +immediately retraces its path. A rhumb line which crosses the line +joining the two northerly umbilic points starts traveling south with +a reversed heading (e.g., a NE heading becomes a SW heading). This +behavior is preserved in the limit \f$a\rightarrow b\f$ (although the +longitude becomes indeterminate in this limit). + +\section jacobi-limiting Limiting cases + +Oblate ellipsoid, \f$a\rightarrow b\f$. The coordinate system +is +\f[ +\begin{align} + X &= b \cos\beta \cos\omega, \\ + Y &= b \cos\beta \sin\omega, \\ + Z &= c \sin\beta. +\end{align} +\f] +Thus \f$\beta\f$ (resp. \f$\beta'\f$) is the parametric +(resp. geographic) latitude and \f$\omega=\omega'\f$ is the longitude; +the quantity \f$e_c\f$ is the eccentricity of the ellipsoid. +Using http://dlmf.nist.gov/19.6.E12 and http://dlmf.nist.gov/19.2.E19 +the projection reduces to the normal Mercator projection for an oblate +ellipsoid, +\f[ +\begin{align} +x &= \omega,\\ +y &= \sinh^{-1}\tan\beta' +- e_c \tanh^{-1}(e_c\sin\beta'),\\ +k &= \frac1{b\cos\beta}. +\end{align} +\f] + +Prolate ellipsoid, \f$c\rightarrow b\f$. The coordinate system +is +\f[ +\begin{align} + X &= b \cos\omega \cos\beta, \\ + Y &= a \sin\omega, \\ + Z &= b \cos\omega \sin\beta. +\end{align} +\f] +Thus \f$\omega\f$ (resp. \f$\omega'\f$) now plays the role of the +parametric (resp. geographic) latitude and while \f$\beta=\beta'\f$ is +the longitude. Using http://dlmf.nist.gov/19.6.E12 +http://dlmf.nist.gov/19.2.E19 and http://dlmf.nist.gov/19.2.E18 the +projection reduces to similar expressions with the roles of \f$\beta\f$ +and \f$\omega\f$ switched, +\f[ +\begin{align} +x &= \sinh^{-1}\tan\omega' ++ e_a + \tan^{-1}(e_a\sin\omega'),\\ +y &= \beta,\\ +k &= \frac1{b\cos\omega}. +\end{align} +\f] + +Sphere, \f$a\rightarrow b\f$ and \f$c\rightarrow b\f$. This is a +non-uniform limit depending on the parameter \f$\nu\f$, +\f[ +\begin{align} + X &= b \cos\omega \cos\beta, \\ + Y &= b \sin\omega \sqrt{1 - \sin^2\nu\sin^2\beta}, \\ + Z &= b \sin\beta \sqrt{1 - \cos^2\nu\sin^2\omega}. +\end{align} +\f] +Using http://dlmf.nist.gov/19.6.E13 the projection can be put in terms +of the elliptic integral of the first kind, http://dlmf.nist.gov/19.2.E4 +\f[ +\begin{align} +x &= F(\omega, \cos\nu), \\ +y &= F(\beta, \sin\nu), \\ +k &= \frac1{b \sqrt{\cos^2\nu\cos^2\omega + \sin^2\nu\cos^2\beta}}, +\end{align} +\f] +Obtaining the limit of a sphere via an oblate (resp. prolate) ellipsoid +corresponds to setting \f$\nu = \frac12\pi\f$ (resp. \f$\nu +=0\f$). In these limits, the elliptic integral reduces to elementary +functions http://dlmf.nist.gov/19.6.E7 and http://dlmf.nist.gov/19.6.E8 +\f[ +\begin{align} +F(\phi, 0) &= \phi, \\ +F(\phi, 1) &= \mathop{\mathrm{gd}}\nolimits^{-1}\phi = \sinh^{-1}\tan\phi. +\end{align} +\f] +The spherical limit gives the projection found by É. Guyou in + - + Sur un nouveau système de projection de la sphère, + Comptes Rendus 102(6), 308--310 (1886). + - + Nouveau système de projection de la sphère: + généralisation de la projection de Mercator, + Annales Hydrographiques (2nd series) 9, 16--35 (1887). + . +who apparently derived it without realizing that it is just a special +case of the projection Jacobi had given some 40 years earlier. Guyou's +name is usually associated with the particular choice, +\f$\nu=\frac14\pi\f$, in which case the hemisphere +\f$\left|\omega\right|\le\frac12\pi\f$ is mapped into a square. +However, by varying \f$\nu\in[0,\frac12\pi]\f$ the hemisphere can be +mapped into a rectangle with any aspect ratio, \f$K(\cos\nu) : +K(\sin\nu)\f$, where \f$K(k)\f$ is the complete elliptic integral of +the first find, http://dlmf.nist.gov/19.2.E8. + +\section jacobi-sphere Conformal mapping of an ellipsoid to a sphere + +An essential tool in deriving conformal projections of an ellipsoid of +revolution is the conformal mapping of the ellipsoid onto a sphere. +This allows conformal projections of the sphere to be generalized to the +case of an ellipsoid of revolution. This conformal mapping is obtained +by using the ellipsoidal Mercator projection to map the ellipsoid to +the plane and then using the spherical Mercator projection to map the +plane onto the sphere. + +A similar construction is possible for a triaxial ellipsoid. Map each +octant of the ellipsoid onto a rectangle using the Jacobi projection. +The aspect ratio of this rectangle is +\f[ +(1+e_a^2)\,\Pi(-e_a^2, \cos\nu) : +(1-e_c^2)\,\Pi( e_c^2, \sin\nu). +\f] +Find the value of \f$\nu'\f$ such that this ratio equals +\f[ +K(\cos\nu') : K(\sin\nu'). +\f] +Map the rectangle onto the equivalent octant of the sphere using Guyou's +projection with parameter \f$\nu = \nu'\f$. This reduces to the +standard construction in the limit of an ellipsoid of revolution. + +\section jacobi-implementation An implementation of the projection + +The JacobiConformal class provides an implementation of the Jacobi +conformal projection is given here. NOTE: This is just sample +code. It is not part of GeographicLib itself. + +
+Back to \ref triaxial. Forward to \ref rhumb. Up to \ref contents. +
+ +**********************************************************************/ +/** +\page rhumb Rhumb lines + +
+Back to \ref jacobi. Forward to \ref greatellipse. Up to \ref contents. +
+ +The Rhumb and RhumbLine classes together with the +RhumbSolve utility perform rhumb line +calculations. A rhumb line (also called a loxodrome) is a line of +constant azimuth on the surface of the ellipsoid. It is important for +historical reasons because sailing with a constant compass heading is +simpler than sailing the shorter geodesic course; see Osborne (2013). +The formulation of the problem on an ellipsoid is covered by Smart +(1946) and Carlton-Wippern (1992). Computational approaches are given +by Williams (1950) and Bennett (1996). My interest in this problem was +piqued by Botnev and Ustinov (2014) who discuss various techniques to +improve the accuracy of rhumb line calculations. The items of interest +here are: + - Review of accurate formulas for the auxiliary latitudes. + - The calculation of the area under a rhumb line. + - Using divided differences to compute \f$\mu_{12}/\psi_{12}\f$ + maintaining full accuracy. Two cases are treated: + - If \f$f\f$ is small, Krüger's series for the transverse + Mercator projection relate \f$\chi\f$ and \f$\mu\f$. + - For arbitrary \f$f\f$, the divided difference formula for + incomplete elliptic integrals of the second relates \f$\beta\f$ and + \f$\mu\f$. + . + - Extending Clenshaw summation to compute the divided difference of a + trigonometric sum. + +Go to + - \ref rhumbform + - \ref rhumblat + - \ref rhumbarea + - \ref divideddiffs + - \ref dividedclenshaw + +References: + - G. G. Bennett, + + Practical Rhumb Line Calculations on the Spheroid + J. Navigation 49(1), 112--119 (1996). + - F. W. Bessel, + The calculation + of longitude and latitude from geodesic measurements (1825), + Astron. Nachr. 331(8), 852--861 (2010); + translated by C. F. F. Karney and R. E. Deakin; preprint: + arXiv:0908.1824. + - V.A. Botnev, S.M. Ustinov, + + Metody resheniya pryamoy i obratnoy geodezicheskikh zadach s vysokoy + tochnost'yu + (Methods for direct and inverse geodesic problems + solving with high precision), St. Petersburg State Polytechnical + University Journal 3(198), 49--58 (2014). + - K. C. Carlton-Wippern + + On Loxodromic Navigation, + J. Navigation 45(2), 292--297 (1992). + - K. E. Engsager and K. Poder, + + A highly accurate world wide algorithm for the + transverse Mercator mapping (almost), + Proc. XXIII Intl. Cartographic Conf. (ICC2007), Moscow (2007). + - F. R. Helmert, + + Mathematical and Physical Theories of Higher Geodesy, Part 1 (1880), + Aeronautical Chart and Information Center (St. Louis, 1964), + Chaps. 5--7. + - W. M. Kahan and R. J. Fateman, + + Symbolic computation of divided differences, + SIGSAM Bull. 33(3), 7--28 (1999) + DOI: + 10.1145/334714.334716. + - C. F. F. Karney, + + Transverse Mercator with an accuracy of a few nanometers, + J. Geodesy 85(8), 475--485 (Aug. 2011); + addenda: + tm-addenda.html; + preprint: + arXiv:1002.1417; + resource page: + tm.html. + - C. F. F. Karney, + + Algorithms for geodesics, + J. Geodesy 87(1), 43--55 (2013); + DOI: + 10.1007/s00190-012-0578-z; + addenda: + geod-addenda.html; + resource page: + geod.html. + - L. Krüger, + Konforme + Abbildung des Erdellipsoids in der Ebene (Conformal mapping of + the ellipsoidal earth to the plane), Royal Prussian Geodetic Institute, + New Series 52, 172 pp. (1912). + - P. Osborne, + + The Mercator Projections (2013), §2.5 and §6.5; + DOI: + 10.5281/zenodo.35392. + - W. M. Smart + + On a Problem in Navigation + MNRAS 106(2), 124--127 (1946). + - J. E. D. Williams + + Loxodromic Distances on the Terrestrial Spheroid Journal, + J. Navigation 3(2), 133--140 (1950) + +\section rhumbform Formulation of the rhumb line problem + +The rhumb line can formulated in terms of three types of latitude, the +isometric latitude \f$\psi\f$ (this serves to define the course of rhumb +lines), the rectifying latitude \f$\mu\f$ (needed for computing +distances along rhumb lines), and the parametric latitude \f$\beta\f$ +(needed for dealing with rhumb lines that run along a parallel). These +are defined in terms of the geographical latitude \f$\phi\f$ by +\f[ +\begin{align} + \frac{d\psi}{d\phi} &= \frac{\rho}R, \\ + \frac{d\mu}{d\phi} &= \frac{\pi}{2M}\rho, \\ +\end{align} +\f] +where \f$\rho\f$ is the meridional radius of curvature, \f$R = +a\cos\beta\f$ is the radius of a circle of latitude, and \f$M\f$ is the +length of a quarter meridian (from the equator to the pole). + +Rhumb lines are straight in the Mercator projection, which maps a point +with geographical coordinates \f$ (\phi,\lambda) \f$ on the ellipsoid to +a point \f$ (\psi,\lambda) \f$. The azimuth \f$\alpha_{12}\f$ of a +rhumb line from \f$ (\phi_1,\lambda_1) \f$ to \f$ (\phi_2,\lambda_2) \f$ +is thus given by +\f[ +\tan\alpha_{12} = \frac{\lambda_{12}}{\psi_{12}}, +\f] +where the quadrant of \f$\alpha_{12}\f$ is determined by the signs of +the numerator and denominator of the right-hand side, \f$\lambda_{12} = +\lambda_2 - \lambda_1\f$, \f$\psi_{12} = \psi_2 - \psi_1\f$, and, +typically, \f$\lambda_{12}\f$ is reduced to the range \f$[-\pi,\pi]\f$ +(thus giving the course of the shortest rhumb line). + +The distance is given by +\f[ +\begin{align} +s_{12} &= \frac {2M}{\pi} \mu_{12} \sec\alpha_{12} \\ + &= \frac {2M}{\pi} +\frac{\mu_{12}}{\psi_{12}} \sqrt{\lambda_{12}^2 + \psi_{12}^2}, +\end{align} +\f] +where \f$\mu_{12} = \mu_2 - \mu_1\f$. This relation is indeterminate if +\f$\phi_1 = \phi_2\f$, so we take the limits +\f$\psi_{12}\rightarrow0\f$ and \f$\mu_{12}\rightarrow0\f$ and apply +L'Hôpital's rule to yield +\f[ +\begin{align} + s_{12} &= \frac {2M}{\pi} \frac{d\mu}{d\psi} \left|\lambda_{12}\right|\\ +&=a \cos\beta \left|\lambda_{12}\right|, +\end{align} +\f] +where the last relation is given by the defining equations for +\f$\psi\f$ and \f$\mu\f$. + +This provides a complete solution for rhumb lines. This formulation +entirely encapsulates the ellipsoidal shape of the earth via the +auxiliary latitudes; thus in the Rhumb class, the ellipsoidal +generalization is handled by the Ellipsoid class where the auxiliary +latitudes are defined. + +\section rhumblat Determining the auxiliary latitudes + +Here we brief develop the necessary formulas for the auxiliary +latitudes. + +Isometric latitude: The equation for \f$\psi\f$ can be integrated +to give +\f[ +\psi = \sinh^{-1}\tan\phi - e\tanh^{-1}(e \sin\phi), +\f] +where \f$e = \sqrt{f(2-f)}\f$ is the eccentricity of the ellipsoid. To +invert this equation (to give \f$\phi\f$ in terms of \f$\psi\f$), it is +convenient to introduce the variables \f$\tau=\tan\phi\f$ and \f$\tau' = +\tan\chi = \sinh\psi\f$ (\f$\chi\f$ is the conformal latitude) which are +related by (Karney, 2011) +\f[ +\begin{align} +\tau' &= \tau \sqrt{1 + \sigma^2} - \sigma \sqrt{1 + \tau^2}, \\ +\sigma &= \sinh\bigl(e \tanh^{-1}(e \tau/\sqrt{1 + \tau^2}) \bigr). +\end{align} +\f] +The equation for \f$\tau'\f$ can be inverted to give \f$\tau\f$ in terms +of \f$\tau'\f$ using Newton's method with \f$\tau_0 = \tau'/(1-e^2)\f$ +as a starting guess; and, of course, \f$\phi\f$ and \f$\psi\f$ are then +given by +\f[ +\begin{align} +\phi &= \tan^{-1}\tau,\\ +\psi &= \sinh^{-1}\tau'. +\end{align} +\f] +This allows conversions to and from \f$\psi\f$ to be carried out for any +value of the flattening \f$f\f$; these conversions are implemented by +Ellipsoid::IsometricLatitude and Ellipsoid::InverseIsometricLatitude. +(For prolate ellipsoids, \f$f\f$ is negative and \f$e\f$ is imaginary, +and the equation for \f$\sigma\f$ needs to be recast in terms of the +tangent function.) + +For small values of \f$f\f$, Engsager and Poder (2007) express +\f$\chi\f$ as a trigonometric series in \f$\phi\f$. This series can be +reverted to give a series for \f$\phi\f$ in terms of \f$\chi\f$. Both +series can be efficiently evaluated using Clenshaw summation and this +provides a fast non-iterative way of making the conversions. + +Parametric latitude: This is given by +\f[ +\tan\beta = (1-f)\tan\phi, +\f] +which allows rapid and accurate conversions; these conversions are +implemented by Ellipsoid::ParametricLatitude and +Ellipsoid::InverseParametricLatitude. + +Rectifying latitude: Solving for distances on the meridian is +naturally carried out in terms of the parametric latitude instead of the +geographical latitude. This leads to a simpler elliptic integral which +is easier to evaluate and to invert. Helmert (1880, §5.11) notes +that the series for meridian distance in terms of \f$\beta\f$ converge +faster than the corresponding ones in terms of \f$\phi\f$. + +In terms of \f$\beta\f$, the rectifying latitude is given by +\f[ +\mu = \frac{\pi}{2E(ie')} E(\beta,ie'), +\f] +where \f$e'=e/\sqrt{1-e^2}\f$ is the second eccentricity and \f$E(k)\f$ +and \f$E(\phi,k)\f$ are the complete and incomplete elliptic integrals +of the second kind; see http://dlmf.nist.gov/19.2.ii. These can be +evaluated accurately for arbitrary flattening using the method given in +http://dlmf.nist.gov/19.36.i. To find \f$\beta\f$ in terms of +\f$\mu\f$, Newton's method can be used (noting that \f$dE(\phi,k)/d\phi += \sqrt{1 - k^2\sin^2\phi}\f$); for a starting guess use \f$\beta_0 = +\mu\f$ (or use the first terms in the reverted series; see below). +These conversions are implemented by Ellipsoid::RectifyingLatitude and +Ellipsoid::InverseRectifyingLatitude. + +If the flattening is small, \f$\mu\f$ can be expressed as a series in +various ways. The most economical series is in terms of the third +flattening \f$ n = f/(2-f)\f$ and was found by Bessel (1825); see +Eq. 5.5.7 of Helmert (1880). Helmert (1880, Eq. 5.6.8) also gives the +reverted series (finding \f$\beta\f$ given \f$\mu\f$). These series are +used by the Geodesic class where the coefficients are \f$C_{1j}\f$ and +\f$C_{1j}'\f$; see Eqs. (18) and (21) of Karney (2013) and \ref +geodseries. (Make the replacements, \f$\sigma\rightarrow\beta\f$, +\f$\tau\rightarrow\mu\f$, \f$\epsilon\rightarrow n\f$, to convert the +notation of the geodesic problem to the problem at hand.) The series +are evaluated by Clenshaw summation. + +These relations allow inter-conversions between the various latitudes +\f$\phi\f$, \f$\psi\f$, \f$\chi\f$, \f$\beta\f$, \f$\mu\f$ to be carried +out simply and accurately. The approaches using series apply only if +\f$f\f$ is small. The others apply for arbitrary values of \f$f\f$. + +\section rhumbarea The area under a rhumb line + +The area between a rhumb line and the equator is given by +\f[ +S_{12} = \int_{\lambda_1}^{\lambda_2} c^2 \sin\xi \,d\lambda, +\f] +where \f$c\f$ is the authalic radius and \f$\xi\f$ is the authalic +latitude. Express \f$\sin\xi\f$ in terms of the conformal latitude +\f$\chi\f$ and expand as a series in the third flattening \f$n\f$. This +can be expressed in terms of powers of \f$\sin\chi\f$. Substitute +\f$\sin\chi=\tanh\psi\f$, where \f$\psi\f$ is the isometric latitude. +For a rhumb line we have +\f[ +\begin{align} +\psi &= m(\lambda-\lambda_0),\\ +m &= \frac{\psi_2 - \psi_1}{\lambda_2 - \lambda_1}. +\end{align} +\f] +Performing the integral over \f$\lambda\f$ gives +\f[ +S_{12} = c^2 \lambda_{12} \left<\sin\xi\right>_{12}, +\f] +where \f$\left<\sin\xi\right>_{12}\f$ is the mean value of \f$\sin\xi\f$ +given by +\f[ +\begin{align} +\left<\sin\xi\right>_{12} &= \frac{S(\chi_2) - S(\chi_1)}{\psi_2 - \psi_1},\\ +S(\chi) &= \log\sec\chi + \sum_{l=1} R_l\cos(2l\chi), +\end{align} +\f] +\f$\log\f$ is the natural logarithm, and \f$R_l = O(n^l)\f$ is given as +a series in \f$n\f$ below. In the spherical limit, the sum vanishes. + +Note the simple way that longitude enters into the expression for the +area. In the limit \f$\chi_2 \rightarrow \chi_1\f$, we can apply +l'Hôpital's rule +\f[ +\left<\sin\xi\right>_{12} +\rightarrow \frac{dS(\chi_1)/d\chi_1}{\sec\chi_1} +=\sin\xi_1, +\f] +as expected. + +In order to maintain accuracy, particularly for rhumb lines which nearly +follow a parallel, evaluate \f$\left<\sin\xi\right>_{12}\f$ using +divided differences (see the \ref divideddiffs "next section") and use +Clenshaw summation to evaluate the sum (see the \ref dividedclenshaw +"last section"). + +Here is the series expansion accurate to 10th order, found by the Maxima +script rhumbarea.mac: + +\verbatim +R[1] = - 1/3 * n + + 22/45 * n^2 + - 356/945 * n^3 + + 1772/14175 * n^4 + + 41662/467775 * n^5 + - 114456994/638512875 * n^6 + + 258618446/1915538625 * n^7 + - 1053168268/37574026875 * n^8 + - 9127715873002/194896477400625 * n^9 + + 33380126058386/656284056553125 * n^10; +R[2] = - 2/15 * n^2 + + 106/315 * n^3 + - 1747/4725 * n^4 + + 18118/155925 * n^5 + + 51304574/212837625 * n^6 + - 248174686/638512875 * n^7 + + 2800191349/14801889375 * n^8 + + 10890707749202/64965492466875 * n^9 + - 3594078400868794/10719306257034375 * n^10; +R[3] = - 31/315 * n^3 + + 104/315 * n^4 + - 23011/51975 * n^5 + + 1554472/14189175 * n^6 + + 114450437/212837625 * n^7 + - 8934064508/10854718875 * n^8 + + 4913033737121/21655164155625 * n^9 + + 591251098891888/714620417135625 * n^10; +R[4] = - 41/420 * n^4 + + 274/693 * n^5 + - 1228489/2027025 * n^6 + + 3861434/42567525 * n^7 + + 1788295991/1550674125 * n^8 + - 215233237178/123743795175 * n^9 + + 95577582133463/714620417135625 * n^10; +R[5] = - 668/5775 * n^5 + + 1092376/2027025 * n^6 + - 3966679/4343625 * n^7 + + 359094172/10854718875 * n^8 + + 7597613999411/3093594879375 * n^9 + - 378396252233936/102088631019375 * n^10; +R[6] = - 313076/2027025 * n^6 + + 4892722/6081075 * n^7 + - 1234918799/834978375 * n^8 + - 74958999806/618718975875 * n^9 + + 48696857431916/9280784638125 * n^10; +R[7] = - 3189007/14189175 * n^7 + + 930092876/723647925 * n^8 + - 522477774212/206239658625 * n^9 + - 2163049830386/4331032831125 * n^10; +R[8] = - 673429061/1929727800 * n^8 + + 16523158892/7638505875 * n^9 + - 85076917909/18749059875 * n^10; +R[9] = - 39191022457/68746552875 * n^9 + + 260863656866/68746552875 * n^10; +R[10] = - 22228737368/22915517625 * n^10; +\endverbatim + +\section divideddiffs Use of divided differences + +Despite our ability to compute latitudes accurately, the way that +distances enter into the solution involves the ratio +\f$\mu_{12}/\psi_{12}\f$; the numerical calculation of this term is +subject to catastrophic round-off errors when \f$\phi_1\f$ and +\f$\phi_2\f$ are close. A simple solution, suggested by Bennett (1996), +is to extend the treatment of rhumb lines along parallels to this case, +i.e., to replace the ratio by the derivative evaluated at the midpoint. +However this is not entirely satisfactory: you have to pick the +transition point where the derivative takes over from the ratio of +differences; and, near this transition point, many bits of accuracy will +be lost (I estimate that about 1/3 of bits are lost, leading to errors +on the order of 0.1 mm for double precision). Note too that this +problem crops up even in the spherical limit. + +It turns out that we can do substantially better than this and maintain +full double precision accuracy. Indeed Botnev and Ustinov provide +formulas which allow \f$\mu_{12}/\psi_{12}\f$ to be computed accurately +(but the formula for \f$\mu_{12}\f$ applies only for small flattening). + +Here I give a more systematic treatment using the algebra of divided +differences. Many readers will be already using this technique, +e.g., when writing, for example, +\f[ + \frac{\sin(2x) - \sin(2y)}{x-y} = 2\frac{\sin(x-y)}{x-y}\cos(x+y). +\f] +However, Kahan and Fateman (1999) provide an extensive set of rules +which allow the technique to be applied to a wide range of problems. +(The classes LambertConformalConic and AlbersEqualArea use this +technique to improve the accuracy.) + +To illustrate the technique, consider the relation between \f$\psi\f$ +and \f$\chi\f$, +\f[ + \psi = \sinh^{-1}\tan\chi. +\f] +The divided difference operator is defined by +\f[ + \Delta[f](x,y) = +\begin{cases} +df(x)/dx, & \text{if $x=y$,} \\ +\displaystyle\frac{f(x)-f(y)}{x-y}, & \text{otherwise.} +\end{cases} +\f] +Many of the rules for differentiation apply to divided differences; in +particular, we can use the chain rule to write +\f[ +\frac{\psi_1 - \psi_2}{\chi_1 - \chi_2} += \Delta[\sinh^{-1}](\tan\chi_1,\tan\chi_2) \times + \Delta[\tan](\chi_1,\chi_2). +\f] + +Kahan and Fateman catalog the divided difference formulas for all the +elementary functions. In this case, we need +\f[ +\begin{align} +\Delta[\tan](x,y) &= \frac{\tan(x-y)}{x-y} (1 + \tan x\tan y),\\ +\Delta[\sinh^{-1}](x,y) &= \frac1{x-y} +\sinh^{-1}\biggl(\frac{(x-y)(x+y)}{x\sqrt{1+y^2}+y\sqrt{1+x^2}}\biggr). +\end{align} +\f] +The crucial point in these formulas is that the right hand sides can be +evaluated accurately even if \f$x-y\f$ is small. (I've only included +the basic results here; Kahan and Fateman supplement these with the +derivatives if \f$x-y\f$ vanishes or the direct ratios if \f$x-y\f$ is +not small.) + +To complete the computation of \f$\mu_{12}/\psi_{12}\f$, we now need +\f$(\mu_1 - \mu_2)/(\chi_1 - \chi_2)\f$, i.e., we need the divided +difference of the function that converts the conformal latitude to +rectifying latitude. We could go through the chain of relations between +these quantities. However, we can take a short cut and recognize that +this function was given as a trigonometric series by Krüger (1912) +in his development of the transverse Mercator projection. This is also +given by Eqs. (5) and (35) of Karney (2011) with the replacements +\f$\zeta \rightarrow \mu\f$ and \f$\zeta' \rightarrow \chi\f$. The +coefficients appearing in this series and the reverted series Eqs. (6) +and (36) are already computed by the TransverseMercator class. The +series can be readily converted to divided difference form (see the +example at the beginning of this section) and Clenshaw summation can be +used to evaluate it (see below). + +The approach of using the series for the transverse Mercator projection +limits the applicability of the method to \f$\left|f\right|\lt 0.01\f$. +If we want to extend the method to arbitrary flattening we need to +compute \f$\Delta[E](x,y;k)\f$. The necessary relation is the "addition +theorem" for the incomplete elliptic integral of the second kind given +in http://dlmf.nist.gov/19.11.E2. This can be converted in the +following divided difference formula +\f[ +\Delta[E](x,y;k) +=\begin{cases} +\sqrt{1 - k^2\sin^2x}, & \text{if $x=y$,} \\ +\displaystyle \frac{E(x,k)-E(y,k)}{x-y}, & \text{if $xy \le0$,}\\ +\displaystyle +\biggl(\frac{E(z,k)}{\sin z} - k^2 \sin x \sin y\biggr)\frac{\sin z}{x-y}, +&\text{otherwise,} +\end{cases} +\f] +where the angle \f$z\f$ is given by +\f[ +\begin{align} +\sin z &= \frac{2t}{1 + t^2},\quad\cos z = \frac{(1-t)(1+t)}{1 + t^2},\\ +t &= +\frac{(x-y)\Delta[\sin](x,y)} +{\sin x\sqrt{1 - k^2\sin^2y} + \sin y\sqrt{1 - k^2\sin^2x}} +\frac{\sin x + \sin y}{\cos x + \cos y}. +\end{align} +\f] +We also need to apply the divided difference formulas to the conversions +from \f$\phi\f$ to \f$\beta\f$ and \f$\phi\f$ to \f$\psi\f$; but these +all involve elementary functions and the techniques given in Kahan and +Fateman can be used. + +The end result is that the Rhumb class allows the computation of all +rhumb lines for any flattening with full double precision accuracy (the +maximum error is about 10 nanometers). I've kept the implementation +simple, which results in rather a lot of repeated evaluations of +quantities. However, in this case, the need for clarity trumps the +desire for speed. + +\section dividedclenshaw Clenshaw evaluation of differenced sums + +The use of + +Clenshaw summation for summing series of the form, +\f[ +g(x) = \sum_{k=1}^N c_k \sin kx, +\f] +is well established. However when computing divided differences, we are +interested in evaluating +\f[ +g(x)-g(y) = \sum_{k=1}^N 2 c_k +\sin\bigl({\textstyle\frac12}k(x-y)\bigr) +\cos\bigl({\textstyle\frac12}k(x+y)\bigr). +\f] +Clenshaw summation can be used in this case if we simultaneously compute +\f$g(x)+g(y)\f$ and perform a matrix summation, +\f[ +\mathsf G(x,y) = \begin{bmatrix} +(g(x) + g(y)) / 2\\ +(g(x) - g(y)) / (x - y) +\end{bmatrix} = \sum_{k=1}^N c_k \mathsf F_k(x,y), +\f] +where +\f[ +\mathsf F_k(x,y)= +\begin{bmatrix} + \cos kd \sin kp\\ + {\displaystyle\frac{\sin kd}d} \cos kp +\end{bmatrix}, +\f] +\f$d=\frac12(x-y)\f$, \f$p=\frac12(x+y)\f$, and, in the limit +\f$d\rightarrow0\f$, \f$(\sin kd)/d \rightarrow k\f$. The first element +of \f$\mathsf G(x,y)\f$ is the average value of \f$g\f$ and the second +element, the divided difference, is the average slope. \f$\mathsf +F_k(x,y)\f$ satisfies the recurrence relation +\f[ + \mathsf F_{k+1}(x,y) = + \mathsf A(x,y) \mathsf F_k(x,y) - \mathsf F_{k-1}(x,y), +\f] +where +\f[ + \mathsf A(x,y) = 2\begin{bmatrix} + \cos d \cos p & -d\sin d \sin p \\ +- {\displaystyle\frac{\sin d}d} \sin p & \cos d \cos p +\end{bmatrix}, +\f] +and \f$\lim_{d\rightarrow0}(\sin d)/d = 1\f$. The standard Clenshaw +algorithm can now be applied to yield +\f[ +\begin{align} +\mathsf B_{N+1} &= \mathsf B_{N+2} = \mathsf 0, \\ +\mathsf B_k &= \mathsf A \mathsf B_{k+1} - \mathsf B_{k+2} + +c_k \mathsf I, \qquad\text{for $N\ge k \ge 1$},\\ +\mathsf G(x,y) &= \mathsf B_1 \mathsf F_1(x,y), +\end{align} +\f] +where \f$\mathsf B_k\f$ are \f$2\times2\f$ matrices. The divided +difference \f$\Delta[g](x,y)\f$ is given by the second element of +\f$\mathsf G(x,y)\f$. + +The same basic recursion applies to the more general case, +\f[ +g(x) = \sum_{k=0}^N c_k \sin\bigl( (k+k_0)x + x_0\bigr). +\f] +For example, the sum area arising in the computation of geodesic areas, +\f[ +\sum_{k=0}^N c_k\cos\bigl((2k+1)\sigma) +\f] +is given by \f$x=2\sigma\f$, \f$x_0=\frac12\pi\f$, \f$k_0=\frac12\f$. +Again we consider the matrix sum, +\f[ +\mathsf G(x,y) = \begin{bmatrix} +(g(x) + g(y)) / 2\\ +(g(x) - g(y)) / (x - y) +\end{bmatrix} = \sum_{k=0}^N c_k \mathsf F_k(x,y), +\f] +where +\f[ +\mathsf F_k(x,y)= +\begin{bmatrix} + \cos\bigl( (k+k_0)d \bigr) \sin \bigl( (k+k_0)p + x_0 \bigr)\\ + {\displaystyle\frac{\sin\bigl( (k+k_0)d \bigr)}d} + \cos \bigl( (k+k_0)p + x_0 \bigr) +\end{bmatrix}. +\f] +The recursion for \f$\mathsf B_k\f$ is identical to the previous case; +in particular, the expression for \f$\mathsf A(x,y)\f$ remains +unchanged. The result for the sum is +\f[ +\mathsf G(x,y) = + (c_0\mathsf I - \mathsf B_2) \mathsf F_0(x,y) + + \mathsf B_1 \mathsf F_1(x,y). +\f] + +
+Back to \ref jacobi. Forward to \ref greatellipse. Up to \ref contents. +
+ +**********************************************************************/ +/** +\page greatellipse Great Ellipses + +
+Back to \ref rhumb. Forward to \ref transversemercator. Up to \ref contents. +
+ +Great ellipses are sometimes proposed (Williams, 1996; Pallikaris & +Latsas, 2009) as alternatives to geodesics for the purposes of +navigation. This is predicated on the assumption that solving the +geodesic problems is complex and costly. These assumptions are no +longer true, and geodesics should normally be used in place of great +ellipses. This is discussed in more detail in \ref gevsgeodesic. + +Solutions of the great ellipse problems implemented for MATLAB and +Octave are provided by + - gedoc: briefly describe the routines + - gereckon: solve the direct great ellipse problem + - gedistance: solve the inverse great ellipse problem + . +At this time, there is C++ support in GeographicLib for great +ellipses. + +References: + - P. D. Thomas, + + Mathematical Models for Navigation Systems, + TR-182 (U.S. Naval Oceanographic Office, 1965). + - B. R. Bowring, + + The direct and inverse solutions for the great elliptic line on the + reference ellipsoid, Bull. Geod. 58, 101--108 (1984). + - M. A. Earle, + A vector solution for navigation on a great ellipse, + J. Navigation 53(3), 473--481 (2000). + - M. A. Earle, + + Vector solutions for azimuth, + J. Navigation 61(3), 537--545 (2008). + - C. F. F. Karney, + + Algorithms for geodesics, J. Geodesy 87(1), 43--55 (2013); + addenda: + geod-addenda.html. + - A. Pallikaris & G. Latsas, + + New algorithm for great elliptic sailing (GES), + J. Navigation 62(3), 493--507 (2009). + - A. Pallikaris, L. Tsoulos, & D. Paradissis, + New meridian arc formulas for sailing calculations in navigational + GIS, International Hydrographic Review, 24--34 (May 2009). + - L. E. Sjöberg, + + Solutions to the direct and inverse navigation problems on the great + ellipse, J. Geodetic Science 2(3), 200--205 (2012). + - R. Williams, + + The Great Ellipse on the Surface of the Spheroid, + J. Navigation 49(2), 229--234 (1996). + - T. Vincenty, + + Direct and Inverse Solutions of Geodesics on the Ellipsoid with + Application of Nested Equations, + Survey Review 23(176), 88--93 (1975). + - Wikipedia page, + Great ellipse. + +Go to + - \ref geformulation + - \ref gearea + - \ref gevsgeodesic + +\section geformulation Solution of great ellipse problems + +Adopt the usual notation for the ellipsoid: equatorial semi-axis +\f$a\f$, polar semi-axis \f$b\f$, flattening \f$f = (a-b)/a\f$, +eccentricity \f$e = \sqrt{f(2-f)}\f$, second eccentricity \f$e' = +e/(1-f)\f$, and third flattening \f$n=(a-b)/(a+b)=f/(2-f)\f$. + +There are several ways in which an ellipsoid can be mapped into a sphere +converting the great ellipse into a great circle. The simplest ones +entail scaling the ellipsoid in the \f$\hat z\f$ direction, the +direction of the axis of rotation, scaling the ellipsoid radially, or a +combination of the two. + +One such combination (scaling by \f$a^2/b\f$ in the \f$\hat z\f$ +direction, following by a radial scaling to the sphere) preserves the +geographical latitude \f$\phi\f$. This enables a great ellipse to be +plotted on a chart merely by determining way points on the corresponding +great circle and transferring them directly on the chart. In this +exercise the flattening of the ellipsoid can be ignored! + +Bowring (1984), Williams (1996), Earle (2000, 2008) and Pallikaris & +Latsas (2009), scale the ellipsoid radially onto a sphere preserving the +geocentric latitude \f$\theta\f$. More convenient than this is to scale +the ellipsoid along \f$\hat z\f$ onto the sphere, as is done by +Thomas (1965) and Sjöberg (2012), thus preserving the parametric +latitude \f$\beta\f$. The advantage of this "parametric" mapping is +that Bessel's rapidly converging series for meridian arc in terms of +parametric latitude can be used (a possibility that is overlooked by +Sjöberg). + +The full parametric mapping is: + - The geographic latitude \f$\phi\f$ on the ellipsoid maps to the + parametric latitude \f$\beta\f$ on the sphere, + where + \f[a\tan\beta = b\tan\phi.\f] + - The longitude \f$\lambda\f$ is unchanged. + - The azimuth \f$\alpha\f$ on the ellipsoid maps to an azimuth + \f$\gamma\f$ on the sphere where + \f[ + \begin{align} + \tan\alpha &= \frac{\tan\gamma}{\sqrt{1-e^2\cos^2\beta}}, \\ + \tan\gamma &= \frac{\tan\alpha}{\sqrt{1+e'^2\cos^2\phi}}, + \end{align} + \f] + and the quadrants of \f$\alpha\f$ and \f$\gamma\f$ are the same. + - Positions on the great circle of radius \f$a\f$ are parametrized by + arc length \f$\sigma\f$ measured from the northward crossing of the + equator. The great ellipse has semi-axes \f$a\f$ and + \f$b'=a\sqrt{1-e^2\cos^2\gamma_0}\f$, where \f$\gamma_0\f$ is the + great-circle azimuth at the northward equator crossing, and + \f$\sigma\f$ is the parametric angle on the ellipse. [In contrast, + the ellipse giving distances on a geodesic has semi-axes + \f$b\sqrt{1+e'^2\cos^2\alpha_0}\f$ and \f$b\f$.] + . +To determine the distance along the ellipse in terms of \f$\sigma\f$ and +vice versa, the series for distance \f$s\f$ and for \f$\tau\f$ given in +\ref geodseries can be used. The direct and inverse great ellipse +problems are now simply solved by mapping the problem to the sphere, +solving the resulting great circle problem, and mapping this back onto +the ellipsoid. + +\section gearea The area under a great ellipse + +The area between the segment of a great ellipse and the equator can be +found by very similar methods to those used for geodesic areas; see + Danielsen +(1989). The notation here is similar to that employed by + Karney +(2013). +\f[ +\begin{align} +S_{12} &= S(\sigma_2) - S(\sigma_1) \\ +S(\sigma) &= c^2\gamma + e^2 a^2 \cos\gamma_0 \sin\gamma_0 I_4(\sigma)\\ +c^2 &= {\textstyle\frac12}\bigl(a^2 + b^2 (\tanh^{-1}e)/e\bigr) +\end{align} +\f] +\f[ +I_4(\sigma) = - \sqrt{1+e'^2}\int +\frac{r(e'^2) - r(k^2\sin^2\sigma)}{e'^2 - k^2\sin^2\sigma} +\frac{\sin\sigma}2 \,d\sigma +\f] +\f[ +\begin{align} +k &= e' \cos\gamma_0,\\ +r(x) &= \sqrt{1+x} + (\sinh^{-1}\sqrt x)/\sqrt x. +\end{align} +\f] +Expand in terms of the third flattening of the ellipsoid, \f$n\f$, and the +third flattening of the great ellipse, \f$\epsilon=(a-b')/(a+b')\f$, by +substituting +\f[ +\begin{align} +e'&=\frac{2\sqrt n}{1-n},\\ +k&=\frac{1+n}{1-n} \frac{2\sqrt{\epsilon}}{1+\epsilon}, +\end{align} +\f] +to give +\f[ +I_4(\sigma) = \sum_{l = 0}^\infty G_{4l}\cos \bigl((2l+1)\sigma\bigr). +\f] +Compared to the area under a geodesic, we have +- \f$\gamma\f$ and \f$\gamma_0\f$ instead of \f$\alpha\f$ and + \f$\alpha_0\f$. In both cases, these are azimuths on the auxiliary + sphere; however, for the geodesic, they are also the azimuths on the + ellipsoid. +- \f$r(x) = \bigl(1+t(x)\bigr)/\sqrt{1+x}\f$ instead of \f$t(x)\f$ with + a balancing factor of \f$\sqrt{1+e'^2}\f$ appearing in front of the + integral. These changes are because expressing + \f$\sin\phi\,d\lambda\f$ in terms of \f$\sigma\f$ is a little more + complicated with great ellipses. (Don't worry about the addition of + \f$1\f$ to \f$t(x)\f$; that's immaterial.) +- the factors involving \f$n\f$ in the expression for \f$k\f$ in terms + of \f$\epsilon\f$. This is because \f$k\f$ is defined in terms of + \f$e'\f$, whereas it is \f$e\cos\gamma_0\f$ that plays the role of the + eccentricity for the great ellipse. + +Here is the series expansion accurate to 10th order, found by +gearea.mac: + +\verbatim +G4[0] = + (1/6 + 7/30 * n + 8/105 * n^2 + 4/315 * n^3 + 16/3465 * n^4 + 20/9009 * n^5 + 8/6435 * n^6 + 28/36465 * n^7 + 32/62985 * n^8 + 4/11305 * n^9) + - (3/40 + 12/35 * n + 589/840 * n^2 + 1063/1155 * n^3 + 14743/15015 * n^4 + 14899/15015 * n^5 + 254207/255255 * n^6 + 691127/692835 * n^7 + 1614023/1616615 * n^8) * eps + + (67/280 + 7081/5040 * n + 5519/1320 * n^2 + 6417449/720720 * n^3 + 708713/45045 * n^4 + 2700154/109395 * n^5 + 519037063/14549535 * n^6 + 78681626/1616615 * n^7) * eps^2 + - (29597/40320 + 30013/5280 * n + 33759497/1441440 * n^2 + 100611307/1441440 * n^3 + 16639623457/98017920 * n^4 + 3789780779/10581480 * n^5 + 1027832503/1511640 * n^6) * eps^3 + + (357407/147840 + 19833349/823680 * n + 61890679/480480 * n^2 + 97030756063/196035840 * n^3 + 2853930388817/1862340480 * n^4 + 15123282583393/3724680960 * n^5) * eps^4 + - (13200233/1537536 + 306285589/2882880 * n + 26279482199/37340160 * n^2 + 3091446335399/931170240 * n^3 + 93089556575647/7449361920 * n^4) * eps^5 + + (107042267/3294720 + 253176989449/522762240 * n + 57210830762263/14898723840 * n^2 + 641067300459403/29797447680 * n^3) * eps^6 + - (51544067373/398295040 + 38586720036247/17027112960 * n + 104152290127363/4966241280 * n^2) * eps^7 + + (369575321823/687964160 + 1721481081751393/158919720960 * n) * eps^8 + - 10251814360817/4445306880 * eps^9; +G4[1] = + (1/120 + 4/105 * n + 589/7560 * n^2 + 1063/10395 * n^3 + 14743/135135 * n^4 + 14899/135135 * n^5 + 254207/2297295 * n^6 + 691127/6235515 * n^7 + 1614023/14549535 * n^8) * eps + - (53/1680 + 847/4320 * n + 102941/166320 * n^2 + 1991747/1441440 * n^3 + 226409/90090 * n^4 + 3065752/765765 * n^5 + 24256057/4157010 * n^6 + 349229428/43648605 * n^7) * eps^2 + + (4633/40320 + 315851/332640 * n + 5948333/1441440 * n^2 + 11046565/864864 * n^3 + 9366910279/294053760 * n^4 + 23863367599/349188840 * n^5 + 45824943037/349188840 * n^6) * eps^3 + - (8021/18480 + 39452953/8648640 * n + 3433618/135135 * n^2 + 29548772933/294053760 * n^3 + 44355142973/139675536 * n^4 + 4771229132843/5587021440 * n^5) * eps^4 + + (2625577/1537536 + 5439457/247104 * n + 353552588953/2352430080 * n^2 + 405002114215/558702144 * n^3 + 61996934629789/22348085760 * n^4) * eps^5 + - (91909777/13178880 + 2017395395921/18819440640 * n + 51831652526149/59594895360 * n^2 + 1773086701957889/357569372160 * n^3) * eps^6 + + (35166639971/1194885120 + 26948019211109/51081338880 * n + 7934238355871/1596291840 * n^2) * eps^7 + - (131854991623/1031946240 + 312710596037369/119189790720 * n) * eps^8 + + 842282436291/1481768960 * eps^9; +G4[2] = + (1/560 + 29/2016 * n + 1027/18480 * n^2 + 203633/1441440 * n^3 + 124051/450450 * n^4 + 1738138/3828825 * n^5 + 98011493/145495350 * n^6 + 4527382/4849845 * n^7) * eps^2 + - (533/40320 + 14269/110880 * n + 908669/1441440 * n^2 + 15253627/7207200 * n^3 + 910103119/163363200 * n^4 + 2403810527/193993800 * n^5 + 746888717/30630600 * n^6) * eps^3 + + (2669/36960 + 2443153/2882880 * n + 1024791/200200 * n^2 + 10517570057/490089600 * n^3 + 164668999127/2327925600 * n^4 + 1826633124599/9311702400 * n^5) * eps^4 + - (5512967/15375360 + 28823749/5765760 * n + 31539382001/871270400 * n^2 + 1699098121381/9311702400 * n^3 + 287618085731/398361600 * n^4) * eps^5 + + (22684703/13178880 + 25126873327/896163840 * n + 10124249914577/42567782400 * n^2 + 836412216748957/595948953600 * n^3) * eps^6 + - (3259030001/398295040 + 2610375232847/17027112960 * n + 2121882247763/1418926080 * n^2) * eps^7 + + (13387413913/343982080 + 939097138279/1135140864 * n) * eps^8 + - 82722916855/444530688 * eps^9; +G4[3] = + (5/8064 + 23/3168 * n + 1715/41184 * n^2 + 76061/480480 * n^3 + 812779/1782144 * n^4 + 9661921/8953560 * n^5 + 40072069/18106088 * n^6) * eps^3 + - (409/59136 + 10211/109824 * n + 46381/73920 * n^2 + 124922951/43563520 * n^3 + 12524132449/1241560320 * n^4 + 30022391821/1022461440 * n^5) * eps^4 + + (22397/439296 + 302399/384384 * n + 461624513/74680320 * n^2 + 1375058687/41385344 * n^3 + 4805085120841/34763688960 * n^4) * eps^5 + - (14650421/46126080 + 17533571183/3136573440 * n + 1503945368767/29797447680 * n^2 + 43536234862451/139054755840 * n^3) * eps^6 + + (5074867067/2788065280 + 479752611137/13243310080 * n + 1228808683449/3310827520 * n^2) * eps^7 + - (12004715823/1203937280 + 17671119291563/79459860480 * n) * eps^8 + + 118372499107/2222653440 * eps^9; +G4[4] = + (7/25344 + 469/109824 * n + 13439/411840 * n^2 + 9282863/56010240 * n^3 + 37558503/59121920 * n^4 + 44204289461/22348085760 * n^5) * eps^4 + - (5453/1317888 + 58753/823680 * n + 138158857/224040960 * n^2 + 191056103/53209728 * n^3 + 712704605341/44696171520 * n^4) * eps^5 + + (28213/732160 + 331920271/448081920 * n + 2046013913/283785216 * n^2 + 11489035343/241274880 * n^3) * eps^6 + - (346326947/1194885120 + 11716182499/1891901440 * n + 860494893431/12770334720 * n^2) * eps^7 + + (750128501/386979840 + 425425087409/9287516160 * n) * eps^8 + - 80510858479/6667960320 * eps^9; +G4[5] = + (21/146432 + 23/8320 * n + 59859/2263040 * n^2 + 452691/2687360 * n^3 + 21458911/26557440 * n^4) * eps^5 + - (3959/1464320 + 516077/9052160 * n + 51814927/85995520 * n^2 + 15444083489/3611811840 * n^3) * eps^6 + + (1103391/36208640 + 120920041/171991040 * n + 18522863/2263040 * n^2) * eps^7 + - (92526613/343982080 + 24477436759/3611811840 * n) * eps^8 + + 1526273559/740884480 * eps^9; +G4[6] = + (11/133120 + 1331/696320 * n + 145541/6615040 * n^2 + 46863487/277831680 * n^3) * eps^6 + - (68079/36208640 + 621093/13230080 * n + 399883/680960 * n^2) * eps^7 + + (658669/26460160 + 186416197/277831680 * n) * eps^8 + - 748030679/2963537920 * eps^9; +G4[7] = + (143/2785280 + 11011/7938048 * n + 972829/52093440 * n^2) * eps^7 + - (434863/317521920 + 263678129/6667960320 * n) * eps^8 + + 185257501/8890613760 * eps^9; +G4[8] = + (715/21168128 + 27313/26148864 * n) * eps^8 + - 1838551/1778122752 * eps^9; +G4[9] = + 2431/104595456 * eps^9; +\endverbatim + +\section gevsgeodesic Great ellipses vs geodesics + +Some papers advocating the use of great ellipses for navigation exhibit +a prejudice against the use of geodesics. These excerpts from +Pallikaris, Tsoulos, & Paradissis (2009) give the flavor + - … it is required to adopt realistic accuracy standards in order not + only to eliminate the significant errors of the spherical model but + also to avoid the exaggerated and unrealistic requirements of sub + meter accuracy. + - Calculation of shortest sailings paths on the ellipsoid by a geodetic + inverse method involve formulas that are much too complex. + - Despite the fact that contemporary computers are fast enough to + handle more complete geodetic formulas of sub meter accuracy, a basic + principle for the design of navigational systems is the avoidance of + unnecessary consumption of computing power. + . +This prejudice was probably due to the fact that the most well-known +algorithms for geodesics, by Vincenty (1975), come with some +"asterisks": + - no derivation was given (although they follow in a straightforward + fashion from classic 19th century methods); + - the accuracy is "only" 0.5 mm or so, surely good enough for most + applications, but still a reason for a user to worry and a spur to + numerous studies "validating" the algorithms; + - no indication is given for how to extend the series to improve the + accuracy; + - there was a belief in some quarters (erroneous!) that the Vincenty + algorithms could not be used to compute waypoints; + - the algorithm for the inverse problem fails to converge for some + inputs. + . +These problems meant that users were reluctant to bundle the algorithms +into a library and treat them as a part of the software infrastructure +(much as you might regard the computation of \f$\sin x\f$ as a given). +In particular, I regard the last issue, lack of convergence of the +inverse solution, as fatal. Even though the problem only arises for +nearly antipodal points, it means all users of the library must have +some way to handle this problem. + +For these reasons, substitution of a great ellipse for the geodesic +makes some sense. The solution of the great ellipse is, in principle, +no more difficult than solving for the great circle and, for paths of +less then 10000 km, the error in the distance is less than +13.5 m. + +Now (2014), however, the situation has reversed. The algorithms given +by Karney (2013)—and used in GeographicLib since +2009—explicitly resolve the issues with Vincenty's algorithm. The +geodesic problem is conveniently bundled into a library. Users can call +this with an assurance of an accurate result much as they would when +evaluating \f$\sin x\f$. On the other hand, great ellipses come with +their own set of asterisks: + - To the extent that they are regarded as approximations to geodesics, + the errors need to be quantified, the limits of allowable use + documented, etc. + - The user is now left with decisions on when to trust the results and + to find alternative solutions if necessary. + - Even though the great ellipse is no more that 13.5 m longer than + a 10000 km geodesic, the path of the great ellipse can deviate + from the geodesic by as much as 8.3 km. This disqualifies great + ellipses from use in congested air corridors where the + + strategic lateral offset procedure is in effect and in any + situation which demands coordination in the routes of vessels. + - Because geodesics obey the triangle inequality, while great ellipses + do not, the solutions for realistic navigational problems, e.g., + determining the time of closest approach of two vessels, are often + simpler in terms of geodesics. + +To address some other of the objections in the quotes from Pallikaris et +al. given above: + - "exaggerated and unrealistic requirements of sub meter accuracy": The + geodesic algorithms allow full double precision accuracy at + essentially no cost. This is because Clenshaw summation allows + additional terms to be added to the series without the need for + addition trigonometric evaluations. Full accuracy is important to + maintain because it allows the results to be used reliably in more + complex problems (e.g., in the determination of maritime boundaries). + - "unnecessary consumption of computing power": The solution of the + inverse geodesic problem takes 2.3 μs; multiple points on a + geodesic can be computed at a rate of one point per 0.4 μs. + The actual power consumed in these calculations is minuscule compared + to the power needed to drive the display of a navigational computer. + - "formulas that are much too complex": There's no question that the + solution of the geodesic problem is more complex than for great + ellipses. However this complexity is only an issue when + implementing the algorithms. For the end user, + navigational software employing geodesics is less complex + compared with that employing great ellipses. Here is what the user + needs to know about the geodesic solution: +
"The shortest path is found."
+ And here is the corresponding documentation for great ellipses: +
"A path which closely approximates the shortest path is + found. Provided that the distance is less than 10000 km, the + error in distance is no more than 14 m and the deviation the + route from that of the shortest path is no more than 9 km. + These bounds apply to the WGS84 ellipsoid. The deviation of the path + means that it should be used with caution when planning routes. In + addition, great ellipses do not obey the triangle inequality; this + disqualifies them from use in some applications."
+ +Having all the geodesic functions bundled up into a reliable "black box" +enables users to concentrate on how to solve problems using geodesics +(instead of figuring out how to solve for the geodesics). A wide range +of problems (intersection of paths, the path for an interception, the +time of closest approach, median lines, tri-points, etc.) are all +amenable to simple and fast solutions in terms of geodesics. + +
+Back to \ref rhumb. Forward to \ref transversemercator. Up to \ref contents. +
+ +**********************************************************************/ +/** +\page transversemercator Transverse Mercator projection + +
+Back to \ref greatellipse. Forward to \ref geocentric. Up to \ref contents. +
+ +TransverseMercator and TransverseMercatorExact provide accurate +implementations of the transverse Mercator projection. The +TransverseMercatorProj +utility provides an interface to these classes. + +Go to + - \ref testmerc + - \ref tmseries + - \ref tmfigures + +References: + - L. Krüger, + Konforme + Abbildung des Erdellipsoids in der Ebene (Conformal mapping of + the ellipsoidal earth to the plane), Royal Prussian Geodetic Institute, + New Series 52, 172 pp. (1912). + - L. P. Lee, + Conformal Projections Based on Elliptic Functions, + (B. V. Gutsell, Toronto, 1976), 128pp., + ISBN: 0919870163 + (Also appeared as: + Monograph 16, Suppl. No. 1 to Canadian Cartographer, Vol 13). + Part V, pp. 67--101, + Conformal + Projections Based On Jacobian Elliptic Functions. + - C. F. F. Karney, + + Transverse Mercator with an accuracy of a few nanometers, + J. Geodesy 85(8), 475--485 (Aug. 2011); + addenda: + tm-addenda.html; + preprint: + arXiv:1002.1417; + resource page: + tm.html. + . +The algorithm for TransverseMercator is based on +Krüger (1912); that for TransverseMercatorExact is +based on Lee (1976). + +See tm-grid.kmz, for an +illustration of the exact transverse Mercator grid in Google Earth. + +\section testmerc Test data for the transverse Mercator projection + +A test set for the transverse Mercator projection is available at + - + TMcoords.dat.gz + - C. F. F. Karney, Test data for the transverse Mercator projection + (2009),
+ DOI: + 10.5281/zenodo.32470. + . +This is about 17 MB (compressed). This test set consists of a set of +geographic coordinates together with the corresponding transverse +Mercator coordinates. The WGS84 ellipsoid is used, with central +meridian 0°, central scale factor 0.9996 (the UTM value), +false easting = false northing = 0 m. + +Each line of the test set gives 6 space delimited numbers + - latitude (degrees, exact) + - longitude (degrees, exact — see below) + - easting (meters, accurate to 0.1 pm) + - northing (meters, accurate to 0.1 pm) + - meridian convergence (degrees, accurate to 10−18 deg) + - scale (accurate to 10−20) + . +The latitude and longitude are all multiples of 10−12 +deg and should be regarded as exact, except that longitude = +82.63627282416406551 should be interpreted as exactly (1 − \e e) +90°. These results are computed using Lee's formulas with +Maxima's +bfloats and fpprec set to 80 (so the errors in the data are probably 1/2 +of the values quoted above). The Maxima code, +tm.mac and ellint.mac, +was used to prepare this data set is included in the distribution; you +will need to have Maxima installed to use this code. The comments at +the top of tm.mac illustrate how to run it. + +The contents of the file are as follows: + - 250000 entries randomly distributed in lat in [0°, 90°], lon + in [0°, 90°]; + - 1000 entries randomly distributed on lat in [0°, 90°], lon = + 0°; + - 1000 entries randomly distributed on lat = 0°, lon in [0°, + 90°]; + - 1000 entries randomly distributed on lat in [0°, 90°], lon = + 90°; + - 1000 entries close to lat = 90° with lon in [0°, 90°]; + - 1000 entries close to lat = 0°, lon = 0° with lat ≥ + 0°, lon ≥ 0°; + - 1000 entries close to lat = 0°, lon = 90° with lat ≥ + 0°, lon ≤ 90°; + - 2000 entries close to lat = 0°, lon = (1 − \e e) 90° + with lat ≥ 0°; + - 25000 entries randomly distributed in lat in [−89°, + 0°], lon in [(1 − \e e) 90°, 90°]; + - 1000 entries randomly distributed on lat in [−89°, 0°], + lon = 90°; + - 1000 entries randomly distributed on lat in [−89°, 0°], + lon = (1 − \e e) 90°; + - 1000 entries close to lat = 0°, lon = 90° (lat < 0°, lon + ≤ 90°); + - 1000 entries close to lat = 0°, lon = (1 − \e e) 90° + (lat < 0°, lon ≤ (1 − \e e) 90°); + . +(a total of 287000 entries). The entries for lat < 0° and +lon in [(1 − \e e) 90°, 90°] use the "extended" +domain for the transverse Mercator projection explained in Sec. 5 of +Karney (2011). The first +258000 entries have lat ≥ 0° and are suitable for testing +implementations following the standard convention. + +\section tmseries Series approximation for transverse Mercator + +Krüger (1912) gives a 4th-order approximation to the transverse +Mercator projection. This is accurate to about 200 nm (200 +nanometers) within the UTM domain. Here we present the series +extended to 10th order. By default, TransverseMercator +uses the 6th-order approximation. The preprocessor macro +GEOGRAPHICLIB_TRANSVERSEMERCATOR_ORDER can be used to select an order +from 4 thru 8. The series expanded to order n30 are +given in tmseries30.html. + +In the formulas below ^ indicates exponentiation (n^3 = +n*n*n) and / indicates real division (3/5 = 0.6). +The equations need to be converted to Horner form, but are here left in +expanded form so that they can be easily truncated to lower order in \e +n. Some of the integers here are not representable as 32-bit integers +and will need to be included as 64-bit integers. + +\e A in Krüger, p. 12, eq. (5) +\verbatim + A = a/(n + 1) * (1 + 1/4 * n^2 + + 1/64 * n^4 + + 1/256 * n^6 + + 25/16384 * n^8 + + 49/65536 * n^10); +\endverbatim + +γ in Krüger, p. 21, eq. (41) +\verbatim +alpha[1] = 1/2 * n + - 2/3 * n^2 + + 5/16 * n^3 + + 41/180 * n^4 + - 127/288 * n^5 + + 7891/37800 * n^6 + + 72161/387072 * n^7 + - 18975107/50803200 * n^8 + + 60193001/290304000 * n^9 + + 134592031/1026432000 * n^10; +alpha[2] = 13/48 * n^2 + - 3/5 * n^3 + + 557/1440 * n^4 + + 281/630 * n^5 + - 1983433/1935360 * n^6 + + 13769/28800 * n^7 + + 148003883/174182400 * n^8 + - 705286231/465696000 * n^9 + + 1703267974087/3218890752000 * n^10; +alpha[3] = 61/240 * n^3 + - 103/140 * n^4 + + 15061/26880 * n^5 + + 167603/181440 * n^6 + - 67102379/29030400 * n^7 + + 79682431/79833600 * n^8 + + 6304945039/2128896000 * n^9 + - 6601904925257/1307674368000 * n^10; +alpha[4] = 49561/161280 * n^4 + - 179/168 * n^5 + + 6601661/7257600 * n^6 + + 97445/49896 * n^7 + - 40176129013/7664025600 * n^8 + + 138471097/66528000 * n^9 + + 48087451385201/5230697472000 * n^10; +alpha[5] = 34729/80640 * n^5 + - 3418889/1995840 * n^6 + + 14644087/9123840 * n^7 + + 2605413599/622702080 * n^8 + - 31015475399/2583060480 * n^9 + + 5820486440369/1307674368000 * n^10; +alpha[6] = 212378941/319334400 * n^6 + - 30705481/10378368 * n^7 + + 175214326799/58118860800 * n^8 + + 870492877/96096000 * n^9 + - 1328004581729009/47823519744000 * n^10; +alpha[7] = 1522256789/1383782400 * n^7 + - 16759934899/3113510400 * n^8 + + 1315149374443/221405184000 * n^9 + + 71809987837451/3629463552000 * n^10; +alpha[8] = 1424729850961/743921418240 * n^8 + - 256783708069/25204608000 * n^9 + + 2468749292989891/203249958912000 * n^10; +alpha[9] = 21091646195357/6080126976000 * n^9 + - 67196182138355857/3379030566912000 * n^10; +alpha[10]= 77911515623232821/12014330904576000 * n^10; +\endverbatim + +β in Krüger, p. 18, eq. (26*) +\verbatim + beta[1] = 1/2 * n + - 2/3 * n^2 + + 37/96 * n^3 + - 1/360 * n^4 + - 81/512 * n^5 + + 96199/604800 * n^6 + - 5406467/38707200 * n^7 + + 7944359/67737600 * n^8 + - 7378753979/97542144000 * n^9 + + 25123531261/804722688000 * n^10; + beta[2] = 1/48 * n^2 + + 1/15 * n^3 + - 437/1440 * n^4 + + 46/105 * n^5 + - 1118711/3870720 * n^6 + + 51841/1209600 * n^7 + + 24749483/348364800 * n^8 + - 115295683/1397088000 * n^9 + + 5487737251099/51502252032000 * n^10; + beta[3] = 17/480 * n^3 + - 37/840 * n^4 + - 209/4480 * n^5 + + 5569/90720 * n^6 + + 9261899/58060800 * n^7 + - 6457463/17740800 * n^8 + + 2473691167/9289728000 * n^9 + - 852549456029/20922789888000 * n^10; + beta[4] = 4397/161280 * n^4 + - 11/504 * n^5 + - 830251/7257600 * n^6 + + 466511/2494800 * n^7 + + 324154477/7664025600 * n^8 + - 937932223/3891888000 * n^9 + - 89112264211/5230697472000 * n^10; + beta[5] = 4583/161280 * n^5 + - 108847/3991680 * n^6 + - 8005831/63866880 * n^7 + + 22894433/124540416 * n^8 + + 112731569449/557941063680 * n^9 + - 5391039814733/10461394944000 * n^10; + beta[6] = 20648693/638668800 * n^6 + - 16363163/518918400 * n^7 + - 2204645983/12915302400 * n^8 + + 4543317553/18162144000 * n^9 + + 54894890298749/167382319104000 * n^10; + beta[7] = 219941297/5535129600 * n^7 + - 497323811/12454041600 * n^8 + - 79431132943/332107776000 * n^9 + + 4346429528407/12703122432000 * n^10; + beta[8] = 191773887257/3719607091200 * n^8 + - 17822319343/336825216000 * n^9 + - 497155444501631/1422749712384000 * n^10; + beta[9] = 11025641854267/158083301376000 * n^9 + - 492293158444691/6758061133824000 * n^10; + beta[10]= 7028504530429621/72085985427456000 * n^10; +\endverbatim + +The high-order expansions for α and β were produced by the +Maxima program tmseries.mac (included in the +distribution). To run, start Maxima and enter +\verbatim + load("tmseries.mac")$ +\endverbatim +Further instructions are included at the top of the file. + +\section tmfigures Figures from paper on transverse Mercator projection + +This section gives color versions of the figures in + - C. F. F. Karney, + + Transverse Mercator with an accuracy of a few nanometers, + J. Geodesy 85(8), 475--485 (Aug. 2011); + addenda: + tm-addenda.html; + preprint: + arXiv:1002.1417; + resource page: + tm.html. + +\b NOTE: +The numbering of the figures matches that in the paper cited above. The +figures in this section are relatively small in order to allow them to +be displayed quickly. Vector versions of these figures are available in + tm-figs.pdf. This allows you to magnify the +figures to show the details more clearly. + +\image html gauss-schreiber-graticule-a.png "Fig. 1(a)" +Fig. 1(a): +The graticule for the spherical transverse Mercator projection. +The equator lies on \e y = 0. +Compare this with Lee, Fig. 1 (right), which shows the graticule for +half a sphere, but note that in his notation \e x and \e y have switched +meanings. The graticule for the ellipsoid differs from that for a +sphere only in that the latitude lines have shifted slightly. (The +conformal transformation from an ellipsoid to a sphere merely relabels +the lines of latitude.) This projection places the point latitude = +0°, longitude = 90° at infinity. + +\image html gauss-krueger-graticule-a.png "Fig. 1(b)" +Fig. 1(b): +The graticule for the Gauss-Krüger transverse Mercator projection. +The equator lies on \e y = 0 for longitude < 81°; beyond +this, it arcs up to meet \e y = 1. Compare this with Lee, Fig. 45 +(upper), which shows the graticule for the International Ellipsoid. Lee, +Fig. 46, shows the graticule for the entire ellipsoid. This projection +(like the Thompson projection) projects the ellipsoid to a finite area. + +\image html thompson-tm-graticule-a.png "Fig. 1(c)" +Fig. 1(c): +The graticule for the Thompson transverse Mercator projection. The +equator lies on \e y = 0 for longitude < 81°; at longitude = +81°, it turns by 120° and heads for \e y = 1. +Compare this with Lee, Fig. 43, which shows the graticule for the +International Ellipsoid. Lee, Fig. 44, shows the graticule for the +entire ellipsoid. This projection (like the Gauss-Krüger +projection) projects the ellipsoid to a finite area. + +\image html gauss-krueger-error.png "Fig. 2" +Fig. 2: +The truncation error for the series for the Gauss-Krüger transverse +Mercator projection. The blue curves show the truncation error for the +order of the series \e J = 2 (top) thru \e J = 12 (bottom). The red +curves show the combined truncation and round-off errors for + - float and \e J = 4 (top) + - double and \e J = 6 (middle) + - long double and \e J = 8 (bottom) + +\image html gauss-krueger-graticule.png "Fig. 3(a)" +Fig. 3(a): +The graticule for the extended domain. The blue lines show +latitude and longitude at multiples of 10°. The green lines +show 1° intervals for longitude in [80°, 90°] and latitude in +[−5°, 10°]. + +\image html gauss-krueger-convergence-scale.png "Fig. 3(b)" +Fig. 3(b): +The convergence and scale for the Gauss-Krüger +transverse Mercator projection in the extended domain. The blue lines +emanating from the top left corner (the north pole) are lines of +constant convergence. Convergence = 0° is given by the +dog-legged line joining the points (0,1), (0,0), (1.71,0), +(1.71,−∞). +Convergence = 90° is given by the line y = 1. The other +lines show multiples of 10° between 0° and +90°. The other blue, the green and the black lines show +scale = 1 thru 2 at intervals of 0.1, 2 thru 15 at intervals of 1, and +15 thru 35 at intervals of 5. Multiples of 5 are shown in black, +multiples of 1 are shown in blue, and the rest are shown in green. +Scale = 1 is given by the line segment (0,0) to (0,1). The red line +shows the equator between lon = 81° and 90°. The +scale and convergence at the branch point are 1/\e e = 10 and +0°, respectively. + +\image html thompson-tm-graticule.png "Fig. 3(c)" +Fig. 3(c): +The graticule for the Thompson transverse Mercator +projection for the extended domain. The range of the projection is the +rectangular region shown + - 0 ≤ \e u ≤ K(e2), + 0 ≤ \e v ≤ K(1 − e2) + . +The coloring of the lines is the same as Fig. 3(a), except that latitude +lines extended down to −10° and a red line has been added +showing the line \e y = 0 for \e x > 1.71 in the Gauss-Krüger +projection (Fig. 3(a)). The extended Thompson projection figure has +reflection symmetry on all the four sides of Fig. 3(c). + +
+Back to \ref greatellipse. Forward to \ref geocentric. Up to \ref contents. +
+ +**********************************************************************/ +/** +\page geocentric Geocentric coordinates + +
+Back to \ref transversemercator. Forward to \ref auxlat. Up to \ref contents. +
+ +The implementation of Geocentric::Reverse is adapted from + - H. Vermeille, + + Direct transformation from geocentric coordinates to geodetic + coordinates, J. Geodesy 76, 451--454 (2002). + +This provides a closed-form solution but can't directly be applied close to +the center of the earth. Several changes have been made to remove this +restriction and to improve the numerical accuracy. Now the method is +accurate for all inputs (even if \e h is infinite). The changes are +described in Appendix B of + - C. F. F. Karney, + Geodesics + on an ellipsoid of revolution, + Feb. 2011; preprint + arxiv:1102.1215v1. + . +Vermeille similarly updated his method in + - H. Vermeille, + + An analytical method to transform geocentric into + geodetic coordinates, J. Geodesy 85, 105--117 (2011). + +The problems encountered near the center of the ellipsoid are: + - There's a potential division by zero in the definition of \e s. The + equations are easily reformulated to avoid this problem. + - t3 may be negative. This is OK; we just take the + real root. + - The solution for \e t may be complex. However this leads to 3 real roots + for u/\e r. It's then just a matter of picking the one that computes + the geodetic result which minimizes |h| and which avoids large + round-off errors. + - Some of the equations result in a large loss of accuracy due to + subtracting nearly equal quantities. E.g., \e k = sqrt(\e u + \e v + + w2) − \e w is inaccurate if \e u + \e v is small; + we can fix this by writing \e k = (\e u + \e v)/(sqrt(\e u + \e v + + w2) + \e w). + +The error is computed as follows. Write a version of +Geocentric::WGS84.Forward which uses long doubles (including using long +doubles for the WGS84 parameters). Generate random (long double) +geodetic coordinates (\e lat0, \e lon0, \e h0) and use the "long double" +WGS84.Forward to obtain the corresponding (long double) geocentric +coordinates (\e x0, \e y0, \e z0). [We restrict \e h0 so that \e h0 +≥ − \e a (1 − e2) / sqrt(1 − +e2 sin2\e lat0), which ensures that (\e +lat0, \e lon0, \e h0) is the principal geodetic inverse of (\e x0, \e +y0, \e z0).] Because the forward calculation is numerically stable and +because long doubles (on Linux systems using g++) provide 11 bits +additional accuracy (about 3.3 decimal digits), we regard this set of +test data as exact. + +Apply the double version of WGS84.Reverse to (\e x0, \e y0, \e z0) to +compute the approximate geodetic coordinates (\e lat1, \e lon1, \e h1). +Convert (\e lat1 − \e lat0, \e lon1 − \e lon0) to a +distance, \e ds, on the surface of the ellipsoid and define \e err = +hypot(\e ds, \e h1 − \e h0). For |h0| < 5000 km, we +have \e err < 7 nm (7 nanometers). + +This methodology is not very useful very far from the globe, because the +absolute errors in the approximate geodetic height become large, or +within 50 km of the center of the earth, because of errors in +computing the approximate geodetic latitude. To illustrate the second +issue, the maximum value of \e err for \e h0 < 0 is about 80 mm. +The error is maximum close to the circle given by geocentric coordinates +satisfying hypot(\e x, \e y) = \e a e2 (= +42.7 km), \e z = 0. (This is the center of meridional curvature +for \e lat = 0.) The geodetic latitude for these points is \e lat = 0. +However, if we move 1 nm towards the center of the earth, the +geodetic latitude becomes 0.04", a distance of 1.4 m from the +equator. If, instead, we move 1 nm up, the geodetic latitude +becomes 7.45", a distance of 229 m from the equator. In light of +this, Reverse does quite well in this vicinity. + +To obtain a practical measure of the error for the general case we define +- errh = |\e h1 − h0| / max(1, \e h0 / \e a) +- for \e h0 > 0, errout = \e ds +- for \e h0 < 0, apply the long double version of WGS84.Forward to (\e + lat1, \e lon1, \e h1) to give (\e x1, \e y1, \e z1) and compute + errin = hypot(\e x1 − \e x0, \e y1 − \e + y0, \e z1 − \e z0). +. +We then find errh < 8 nm, +errout < 4 nm, and errin < +7 nm. (1 nm = 1 nanometer.) + +The testing has been confined to the WGS84 ellipsoid. The method will +work for all ellipsoids used in terrestrial geodesy. However, the +central region, which leads to multiple real roots for the cubic +equation in Reverse, pokes outside the ellipsoid (at the poles) for +ellipsoids with \e e > 1/sqrt(2); Reverse has not been analyzed for this +case. Similarly ellipsoids which are very nearly spherical may yield +inaccurate results due to underflow; in the other hand, the case of the +sphere, \e f = 0, is treated specially and gives accurate results. + +Other comparable methods are K. M. Borkowski, + Transformation +of geocentric to geodetic coordinates without approximations, +Astrophys. Space Sci. 139, 1--4 (1987) +( erratum) +and T. Fukushima, + Fast transform from +geocentric to geodetic coordinates, J. Geodesy 73, 603--610 (1999). +However the choice of independent variables in these methods leads +to a loss of accuracy for points near the equatorial plane. + +
+Back to \ref transversemercator. Forward to \ref auxlat. Up to \ref contents. +
+ +**********************************************************************/ +/** +\page auxlat Auxiliary latitudes + +
+Back to \ref geocentric. Forward to \ref highprec. Up to \ref contents. +
+ +Go to + - \ref auxlatformula + - \ref auxlattable + - \ref auxlaterror + +Six latitudes are used by GeographicLib: +- φ, the (geographic) latitude; +- β, the parametric latitude; +- θ, the geocentric latitude; +- μ, the rectifying latitude; +- χ, the conformal latitude; +- ξ, the authalic latitude. +. +The last five of these are called auxiliary latitudes. These +quantities are all defined in the + +Wikipedia article on latitudes. + +In addition there's the isometric latitude, ψ, defined by ψ = +gd−1χ = sinh−1 tanχ and +χ = gdψ = tan−1 sinhψ. This is not an +angle-like variable (for example, it diverges at the poles) and so we +don't treat it further here. However conversions between ψ and any +of the auxiliary latitudes is easily accomplished via an intermediate +conversion to χ. + +The relations between φ, β, and θ are all simple +elementary functions. The latitudes χ and ξ can be expressed as +elementary functions of φ; however, these functions can only be +inverted iteratively. The rectifying latitude μ as a function of +φ (or β) involves the incomplete elliptic integral of the +second kind (which is not an elementary function) and this needs to be +inverted iteratively. The Ellipsoid class evaluates all the auxiliary +latitudes (and the corresponding inverse relations) in terms of their +basic definitions. + +An alternative method of evaluating these auxiliary latitudes is in +terms of trigonometric series. This offers some advantages: +- these series give a uniform way of expressing any latitude in terms of + any other latitude; +- the evaluation may be faster, particularly if + + Clenshaw summation is used; +- provided that the flattening is sufficiently small, the result may be + more accurate. + +Here we give the complete matrix of relations between all six latitudes; +there are 30 (= 6 × 5) such relations. These +expansions complement the work of +- O. S. Adams, + + Latitude developments connected with geodesy and cartography, + Spec. Pub. 67 (US Coast and Geodetic Survey, 1921). +- P. Osborne, + + The Mercator Projections (2013), Chap. 5. +- S. Orihuela, + + Funciones de Latitud (2013). +. +Here, the expansions are in terms of the third flattening n = +(a − b)/(a + b). +This choice of expansion parameter results in expansions in which half +the coefficients vanish for all relations between φ, β, +θ, and μ. In addition, the expansions converge for +b/a ∈ (0, ∞). These expansions were +obtained with the the maxima code, auxlat.mac. + +Adams (1921) uses the eccentricity squared e2 as the +expansion parameter, but the resulting series only converge for +b/a ∈ (0, √2). In addition, it is shown +in \ref auxlaterror, that the errors when the series are truncated are +much worse than for the corresponding series in \e n. + +\section auxlatformula Series approximations for conversions + +Here are the relations between φ, β, θ, and μ carried +out to 4th order in n: +\f[ +\begin{align} +\beta-\phi&=\textstyle{} +-n\sin 2\phi ++\frac{1}{2}n^{2}\sin 4\phi +-\frac{1}{3}n^{3}\sin 6\phi ++\frac{1}{4}n^{4}\sin 8\phi +-\ldots\\ +\phi-\beta&=\textstyle{} ++n\sin 2\beta ++\frac{1}{2}n^{2}\sin 4\beta ++\frac{1}{3}n^{3}\sin 6\beta ++\frac{1}{4}n^{4}\sin 8\beta ++\ldots\\ +\theta-\phi&=\textstyle{} +-\bigl(2n-2n^{3}\bigr)\sin 2\phi ++\bigl(2n^{2}-4n^{4}\bigr)\sin 4\phi +-\frac{8}{3}n^{3}\sin 6\phi ++4n^{4}\sin 8\phi +-\ldots\\ +\phi-\theta&=\textstyle{} ++\bigl(2n-2n^{3}\bigr)\sin 2\theta ++\bigl(2n^{2}-4n^{4}\bigr)\sin 4\theta ++\frac{8}{3}n^{3}\sin 6\theta ++4n^{4}\sin 8\theta ++\ldots\\ +\theta-\beta&=\textstyle{} +-n\sin 2\beta ++\frac{1}{2}n^{2}\sin 4\beta +-\frac{1}{3}n^{3}\sin 6\beta ++\frac{1}{4}n^{4}\sin 8\beta +-\ldots\\ +\beta-\theta&=\textstyle{} ++n\sin 2\theta ++\frac{1}{2}n^{2}\sin 4\theta ++\frac{1}{3}n^{3}\sin 6\theta ++\frac{1}{4}n^{4}\sin 8\theta ++\ldots\\ +\mu-\phi&=\textstyle{} +-\bigl(\frac{3}{2}n-\frac{9}{16}n^{3}\bigr)\sin 2\phi ++\bigl(\frac{15}{16}n^{2}-\frac{15}{32}n^{4}\bigr)\sin 4\phi +-\frac{35}{48}n^{3}\sin 6\phi ++\frac{315}{512}n^{4}\sin 8\phi +-\ldots\\ +\phi-\mu&=\textstyle{} ++\bigl(\frac{3}{2}n-\frac{27}{32}n^{3}\bigr)\sin 2\mu ++\bigl(\frac{21}{16}n^{2}-\frac{55}{32}n^{4}\bigr)\sin 4\mu ++\frac{151}{96}n^{3}\sin 6\mu ++\frac{1097}{512}n^{4}\sin 8\mu ++\ldots\\ +\mu-\beta&=\textstyle{} +-\bigl(\frac{1}{2}n-\frac{3}{16}n^{3}\bigr)\sin 2\beta +-\bigl(\frac{1}{16}n^{2}-\frac{1}{32}n^{4}\bigr)\sin 4\beta +-\frac{1}{48}n^{3}\sin 6\beta +-\frac{5}{512}n^{4}\sin 8\beta +-\ldots\\ +\beta-\mu&=\textstyle{} ++\bigl(\frac{1}{2}n-\frac{9}{32}n^{3}\bigr)\sin 2\mu ++\bigl(\frac{5}{16}n^{2}-\frac{37}{96}n^{4}\bigr)\sin 4\mu ++\frac{29}{96}n^{3}\sin 6\mu ++\frac{539}{1536}n^{4}\sin 8\mu ++\ldots\\ +\mu-\theta&=\textstyle{} ++\bigl(\frac{1}{2}n+\frac{13}{16}n^{3}\bigr)\sin 2\theta +-\bigl(\frac{1}{16}n^{2}-\frac{33}{32}n^{4}\bigr)\sin 4\theta +-\frac{5}{16}n^{3}\sin 6\theta +-\frac{261}{512}n^{4}\sin 8\theta +-\ldots\\ +\theta-\mu&=\textstyle{} +-\bigl(\frac{1}{2}n+\frac{23}{32}n^{3}\bigr)\sin 2\mu ++\bigl(\frac{5}{16}n^{2}-\frac{5}{96}n^{4}\bigr)\sin 4\mu ++\frac{1}{32}n^{3}\sin 6\mu ++\frac{283}{1536}n^{4}\sin 8\mu ++\ldots\\ +\end{align} +\f] + +Here are the remaining relations (including χ and ξ) carried out +to 3rd order in n: +\f[ +\begin{align} +\chi-\phi&=\textstyle{} +-\bigl(2n-\frac{2}{3}n^{2}-\frac{4}{3}n^{3}\bigr)\sin 2\phi ++\bigl(\frac{5}{3}n^{2}-\frac{16}{15}n^{3}\bigr)\sin 4\phi +-\frac{26}{15}n^{3}\sin 6\phi ++\ldots\\ +\phi-\chi&=\textstyle{} ++\bigl(2n-\frac{2}{3}n^{2}-2n^{3}\bigr)\sin 2\chi ++\bigl(\frac{7}{3}n^{2}-\frac{8}{5}n^{3}\bigr)\sin 4\chi ++\frac{56}{15}n^{3}\sin 6\chi ++\ldots\\ +\chi-\beta&=\textstyle{} +-\bigl(n-\frac{2}{3}n^{2}\bigr)\sin 2\beta ++\bigl(\frac{1}{6}n^{2}-\frac{2}{5}n^{3}\bigr)\sin 4\beta +-\frac{1}{15}n^{3}\sin 6\beta ++\ldots\\ +\beta-\chi&=\textstyle{} ++\bigl(n-\frac{2}{3}n^{2}-\frac{1}{3}n^{3}\bigr)\sin 2\chi ++\bigl(\frac{5}{6}n^{2}-\frac{14}{15}n^{3}\bigr)\sin 4\chi ++\frac{16}{15}n^{3}\sin 6\chi ++\ldots\\ +\chi-\theta&=\textstyle{} ++\bigl(\frac{2}{3}n^{2}+\frac{2}{3}n^{3}\bigr)\sin 2\theta +-\bigl(\frac{1}{3}n^{2}-\frac{4}{15}n^{3}\bigr)\sin 4\theta +-\frac{2}{5}n^{3}\sin 6\theta +-\ldots\\ +\theta-\chi&=\textstyle{} +-\bigl(\frac{2}{3}n^{2}+\frac{2}{3}n^{3}\bigr)\sin 2\chi ++\bigl(\frac{1}{3}n^{2}-\frac{4}{15}n^{3}\bigr)\sin 4\chi ++\frac{2}{5}n^{3}\sin 6\chi ++\ldots\\ +\chi-\mu&=\textstyle{} +-\bigl(\frac{1}{2}n-\frac{2}{3}n^{2}+\frac{37}{96}n^{3}\bigr)\sin 2\mu +-\bigl(\frac{1}{48}n^{2}+\frac{1}{15}n^{3}\bigr)\sin 4\mu +-\frac{17}{480}n^{3}\sin 6\mu +-\ldots\\ +\mu-\chi&=\textstyle{} ++\bigl(\frac{1}{2}n-\frac{2}{3}n^{2}+\frac{5}{16}n^{3}\bigr)\sin 2\chi ++\bigl(\frac{13}{48}n^{2}-\frac{3}{5}n^{3}\bigr)\sin 4\chi ++\frac{61}{240}n^{3}\sin 6\chi ++\ldots\\ +\xi-\phi&=\textstyle{} +-\bigl(\frac{4}{3}n+\frac{4}{45}n^{2}-\frac{88}{315}n^{3}\bigr)\sin 2\phi ++\bigl(\frac{34}{45}n^{2}+\frac{8}{105}n^{3}\bigr)\sin 4\phi +-\frac{1532}{2835}n^{3}\sin 6\phi ++\ldots\\ +\phi-\xi&=\textstyle{} ++\bigl(\frac{4}{3}n+\frac{4}{45}n^{2}-\frac{16}{35}n^{3}\bigr)\sin 2\xi ++\bigl(\frac{46}{45}n^{2}+\frac{152}{945}n^{3}\bigr)\sin 4\xi ++\frac{3044}{2835}n^{3}\sin 6\xi ++\ldots\\ +\xi-\beta&=\textstyle{} +-\bigl(\frac{1}{3}n+\frac{4}{45}n^{2}-\frac{32}{315}n^{3}\bigr)\sin 2\beta +-\bigl(\frac{7}{90}n^{2}+\frac{4}{315}n^{3}\bigr)\sin 4\beta +-\frac{83}{2835}n^{3}\sin 6\beta +-\ldots\\ +\beta-\xi&=\textstyle{} ++\bigl(\frac{1}{3}n+\frac{4}{45}n^{2}-\frac{46}{315}n^{3}\bigr)\sin 2\xi ++\bigl(\frac{17}{90}n^{2}+\frac{68}{945}n^{3}\bigr)\sin 4\xi ++\frac{461}{2835}n^{3}\sin 6\xi ++\ldots\\ +\xi-\theta&=\textstyle{} ++\bigl(\frac{2}{3}n-\frac{4}{45}n^{2}+\frac{62}{105}n^{3}\bigr)\sin 2\theta ++\bigl(\frac{4}{45}n^{2}-\frac{32}{315}n^{3}\bigr)\sin 4\theta +-\frac{524}{2835}n^{3}\sin 6\theta +-\ldots\\ +\theta-\xi&=\textstyle{} +-\bigl(\frac{2}{3}n-\frac{4}{45}n^{2}+\frac{158}{315}n^{3}\bigr)\sin 2\xi ++\bigl(\frac{16}{45}n^{2}-\frac{16}{945}n^{3}\bigr)\sin 4\xi +-\frac{232}{2835}n^{3}\sin 6\xi ++\ldots\\ +\xi-\mu&=\textstyle{} ++\bigl(\frac{1}{6}n-\frac{4}{45}n^{2}-\frac{817}{10080}n^{3}\bigr)\sin 2\mu ++\bigl(\frac{49}{720}n^{2}-\frac{2}{35}n^{3}\bigr)\sin 4\mu ++\frac{4463}{90720}n^{3}\sin 6\mu ++\ldots\\ +\mu-\xi&=\textstyle{} +-\bigl(\frac{1}{6}n-\frac{4}{45}n^{2}-\frac{121}{1680}n^{3}\bigr)\sin 2\xi +-\bigl(\frac{29}{720}n^{2}-\frac{26}{945}n^{3}\bigr)\sin 4\xi +-\frac{1003}{45360}n^{3}\sin 6\xi +-\ldots\\ +\xi-\chi&=\textstyle{} ++\bigl(\frac{2}{3}n-\frac{34}{45}n^{2}+\frac{46}{315}n^{3}\bigr)\sin 2\chi ++\bigl(\frac{19}{45}n^{2}-\frac{256}{315}n^{3}\bigr)\sin 4\chi ++\frac{248}{567}n^{3}\sin 6\chi ++\ldots\\ +\chi-\xi&=\textstyle{} +-\bigl(\frac{2}{3}n-\frac{34}{45}n^{2}+\frac{88}{315}n^{3}\bigr)\sin 2\xi ++\bigl(\frac{1}{45}n^{2}-\frac{184}{945}n^{3}\bigr)\sin 4\xi +-\frac{106}{2835}n^{3}\sin 6\xi +-\ldots\\ +\end{align} +\f] + +\section auxlattable Series approximations in tabular form + +Finally, this is a listing of all the coefficients for the expansions +carried out to 8th order in n. Here's how to interpret this +data: the 5th line for φ − θ is [32/5, 0, +-32, 0]; this means that the coefficient of sin(10θ) is +[(32/5)n5 − +32n7 + O(n9)]. +

β − φ:
+   [-1, 0, 0, 0, 0, 0, 0, 0]
+   [1/2, 0, 0, 0, 0, 0, 0]
+   [-1/3, 0, 0, 0, 0, 0]
+   [1/4, 0, 0, 0, 0]
+   [-1/5, 0, 0, 0]
+   [1/6, 0, 0]
+   [-1/7, 0]
+   [1/8]
+
+

φ − β:
+   [1, 0, 0, 0, 0, 0, 0, 0]
+   [1/2, 0, 0, 0, 0, 0, 0]
+   [1/3, 0, 0, 0, 0, 0]
+   [1/4, 0, 0, 0, 0]
+   [1/5, 0, 0, 0]
+   [1/6, 0, 0]
+   [1/7, 0]
+   [1/8]
+
+

θ − φ:
+   [-2, 0, 2, 0, -2, 0, 2, 0]
+   [2, 0, -4, 0, 6, 0, -8]
+   [-8/3, 0, 8, 0, -16, 0]
+   [4, 0, -16, 0, 40]
+   [-32/5, 0, 32, 0]
+   [32/3, 0, -64]
+   [-128/7, 0]
+   [32]
+
+

φ − θ:
+   [2, 0, -2, 0, 2, 0, -2, 0]
+   [2, 0, -4, 0, 6, 0, -8]
+   [8/3, 0, -8, 0, 16, 0]
+   [4, 0, -16, 0, 40]
+   [32/5, 0, -32, 0]
+   [32/3, 0, -64]
+   [128/7, 0]
+   [32]
+
+

θ − β:
+   [-1, 0, 0, 0, 0, 0, 0, 0]
+   [1/2, 0, 0, 0, 0, 0, 0]
+   [-1/3, 0, 0, 0, 0, 0]
+   [1/4, 0, 0, 0, 0]
+   [-1/5, 0, 0, 0]
+   [1/6, 0, 0]
+   [-1/7, 0]
+   [1/8]
+
+

β − θ:
+   [1, 0, 0, 0, 0, 0, 0, 0]
+   [1/2, 0, 0, 0, 0, 0, 0]
+   [1/3, 0, 0, 0, 0, 0]
+   [1/4, 0, 0, 0, 0]
+   [1/5, 0, 0, 0]
+   [1/6, 0, 0]
+   [1/7, 0]
+   [1/8]
+
+

μ − φ:
+   [-3/2, 0, 9/16, 0, -3/32, 0, 57/2048, 0]
+   [15/16, 0, -15/32, 0, 135/2048, 0, -105/4096]
+   [-35/48, 0, 105/256, 0, -105/2048, 0]
+   [315/512, 0, -189/512, 0, 693/16384]
+   [-693/1280, 0, 693/2048, 0]
+   [1001/2048, 0, -1287/4096]
+   [-6435/14336, 0]
+   [109395/262144]
+
+

φ − μ:
+   [3/2, 0, -27/32, 0, 269/512, 0, -6607/24576, 0]
+   [21/16, 0, -55/32, 0, 6759/4096, 0, -155113/122880]
+   [151/96, 0, -417/128, 0, 87963/20480, 0]
+   [1097/512, 0, -15543/2560, 0, 2514467/245760]
+   [8011/2560, 0, -69119/6144, 0]
+   [293393/61440, 0, -5962461/286720]
+   [6459601/860160, 0]
+   [332287993/27525120]
+
+

μ − β:
+   [-1/2, 0, 3/16, 0, -1/32, 0, 19/2048, 0]
+   [-1/16, 0, 1/32, 0, -9/2048, 0, 7/4096]
+   [-1/48, 0, 3/256, 0, -3/2048, 0]
+   [-5/512, 0, 3/512, 0, -11/16384]
+   [-7/1280, 0, 7/2048, 0]
+   [-7/2048, 0, 9/4096]
+   [-33/14336, 0]
+   [-429/262144]
+
+

β − μ:
+   [1/2, 0, -9/32, 0, 205/1536, 0, -4879/73728, 0]
+   [5/16, 0, -37/96, 0, 1335/4096, 0, -86171/368640]
+   [29/96, 0, -75/128, 0, 2901/4096, 0]
+   [539/1536, 0, -2391/2560, 0, 1082857/737280]
+   [3467/7680, 0, -28223/18432, 0]
+   [38081/61440, 0, -733437/286720]
+   [459485/516096, 0]
+   [109167851/82575360]
+
+

μ − θ:
+   [1/2, 0, 13/16, 0, -15/32, 0, 509/2048, 0]
+   [-1/16, 0, 33/32, 0, -1673/2048, 0, 2599/4096]
+   [-5/16, 0, 349/256, 0, -2989/2048, 0]
+   [-261/512, 0, 963/512, 0, -43531/16384]
+   [-921/1280, 0, 5545/2048, 0]
+   [-6037/6144, 0, 16617/4096]
+   [-19279/14336, 0]
+   [-490925/262144]
+
+

θ − μ:
+   [-1/2, 0, -23/32, 0, 499/1536, 0, -14321/73728, 0]
+   [5/16, 0, -5/96, 0, 6565/12288, 0, -201467/368640]
+   [1/32, 0, -77/128, 0, 2939/4096, 0]
+   [283/1536, 0, -4037/7680, 0, 1155049/737280]
+   [1301/7680, 0, -19465/18432, 0]
+   [17089/61440, 0, -442269/286720]
+   [198115/516096, 0]
+   [48689387/82575360]
+
+

χ − φ:
+   [-2, 2/3, 4/3, -82/45, 32/45, 4642/4725, -8384/4725, 1514/1323]
+   [5/3, -16/15, -13/9, 904/315, -1522/945, -2288/1575, 142607/42525]
+   [-26/15, 34/21, 8/5, -12686/2835, 44644/14175, 120202/51975]
+   [1237/630, -12/5, -24832/14175, 1077964/155925, -1097407/187110]
+   [-734/315, 109598/31185, 1040/567, -12870194/1216215]
+   [444337/155925, -941912/184275, -126463/72765]
+   [-2405834/675675, 3463678/467775]
+   [256663081/56756700]
+
+

φ − χ:
+   [2, -2/3, -2, 116/45, 26/45, -2854/675, 16822/4725, 189416/99225]
+   [7/3, -8/5, -227/45, 2704/315, 2323/945, -31256/1575, 141514/8505]
+   [56/15, -136/35, -1262/105, 73814/2835, 98738/14175, -2363828/31185]
+   [4279/630, -332/35, -399572/14175, 11763988/155925, 14416399/935550]
+   [4174/315, -144838/6237, -2046082/31185, 258316372/1216215]
+   [601676/22275, -115444544/2027025, -2155215124/14189175]
+   [38341552/675675, -170079376/1216215]
+   [1383243703/11351340]
+
+

χ − β:
+   [-1, 2/3, 0, -16/45, 2/5, -998/4725, -34/4725, 1384/11025]
+   [1/6, -2/5, 19/45, -22/105, -2/27, 1268/4725, -12616/42525]
+   [-1/15, 16/105, -22/105, 116/567, -1858/14175, 1724/51975]
+   [17/1260, -8/105, 2123/14175, -26836/155925, 115249/935550]
+   [-1/105, 128/4455, -424/6237, 140836/1216215]
+   [149/311850, -31232/2027025, 210152/4729725]
+   [-499/225225, 30208/6081075]
+   [-68251/113513400]
+
+

β − χ:
+   [1, -2/3, -1/3, 38/45, -1/3, -3118/4725, 4769/4725, -25666/99225]
+   [5/6, -14/15, -7/9, 50/21, -247/270, -14404/4725, 193931/42525]
+   [16/15, -34/21, -5/3, 17564/2835, -36521/14175, -1709614/155925]
+   [2069/1260, -28/9, -49877/14175, 2454416/155925, -637699/85050]
+   [883/315, -28244/4455, -20989/2835, 48124558/1216215]
+   [797222/155925, -2471888/184275, -16969807/1091475]
+   [2199332/225225, -1238578/42525]
+   [87600385/4540536]
+
+

χ − θ:
+   [0, 2/3, 2/3, -2/9, -14/45, 1042/4725, 18/175, -1738/11025]
+   [-1/3, 4/15, 43/45, -4/45, -712/945, 332/945, 23159/42525]
+   [-2/5, 2/105, 124/105, 274/2835, -1352/945, 13102/31185]
+   [-55/126, -16/105, 21068/14175, 1528/4725, -2414843/935550]
+   [-22/45, -9202/31185, 20704/10395, 60334/93555]
+   [-90263/155925, -299444/675675, 40458083/14189175]
+   [-8962/12285, -3818498/6081075]
+   [-4259027/4365900]
+
+

θ − χ:
+   [0, -2/3, -2/3, 4/9, 2/9, -3658/4725, 76/225, 64424/99225]
+   [1/3, -4/15, -23/45, 68/45, 61/135, -2728/945, 2146/1215]
+   [2/5, -24/35, -46/35, 9446/2835, 428/945, -95948/10395]
+   [83/126, -80/63, -34712/14175, 4472/525, 29741/85050]
+   [52/45, -2362/891, -17432/3465, 280108/13365]
+   [335882/155925, -548752/96525, -48965632/4729725]
+   [51368/12285, -197456/15795]
+   [1461335/174636]
+
+

χ − μ:
+   [-1/2, 2/3, -37/96, 1/360, 81/512, -96199/604800, 5406467/38707200, -7944359/67737600]
+   [-1/48, -1/15, 437/1440, -46/105, 1118711/3870720, -51841/1209600, -24749483/348364800]
+   [-17/480, 37/840, 209/4480, -5569/90720, -9261899/58060800, 6457463/17740800]
+   [-4397/161280, 11/504, 830251/7257600, -466511/2494800, -324154477/7664025600]
+   [-4583/161280, 108847/3991680, 8005831/63866880, -22894433/124540416]
+   [-20648693/638668800, 16363163/518918400, 2204645983/12915302400]
+   [-219941297/5535129600, 497323811/12454041600]
+   [-191773887257/3719607091200]
+
+

μ − χ:
+   [1/2, -2/3, 5/16, 41/180, -127/288, 7891/37800, 72161/387072, -18975107/50803200]
+   [13/48, -3/5, 557/1440, 281/630, -1983433/1935360, 13769/28800, 148003883/174182400]
+   [61/240, -103/140, 15061/26880, 167603/181440, -67102379/29030400, 79682431/79833600]
+   [49561/161280, -179/168, 6601661/7257600, 97445/49896, -40176129013/7664025600]
+   [34729/80640, -3418889/1995840, 14644087/9123840, 2605413599/622702080]
+   [212378941/319334400, -30705481/10378368, 175214326799/58118860800]
+   [1522256789/1383782400, -16759934899/3113510400]
+   [1424729850961/743921418240]
+
+

ξ − φ:
+   [-4/3, -4/45, 88/315, 538/4725, 20824/467775, -44732/2837835, -86728/16372125, -88002076/13956067125]
+   [34/45, 8/105, -2482/14175, -37192/467775, -12467764/212837625, -895712/147349125, -2641983469/488462349375]
+   [-1532/2835, -898/14175, 54968/467775, 100320856/1915538625, 240616/4209975, 8457703444/488462349375]
+   [6007/14175, 24496/467775, -5884124/70945875, -4832848/147349125, -4910552477/97692469875]
+   [-23356/66825, -839792/19348875, 816824/13395375, 9393713176/488462349375]
+   [570284222/1915538625, 1980656/54729675, -4532926649/97692469875]
+   [-496894276/1915538625, -14848113968/488462349375]
+   [224557742191/976924698750]
+
+

φ − ξ:
+   [4/3, 4/45, -16/35, -2582/14175, 60136/467775, 28112932/212837625, 22947844/1915538625, -1683291094/37574026875]
+   [46/45, 152/945, -11966/14175, -21016/51975, 251310128/638512875, 1228352/3007125, -14351220203/488462349375]
+   [3044/2835, 3802/14175, -94388/66825, -8797648/10945935, 138128272/147349125, 505559334506/488462349375]
+   [6059/4725, 41072/93555, -1472637812/638512875, -45079184/29469825, 973080708361/488462349375]
+   [768272/467775, 455935736/638512875, -550000184/147349125, -1385645336626/488462349375]
+   [4210684958/1915538625, 443810768/383107725, -2939205114427/488462349375]
+   [387227992/127702575, 101885255158/54273594375]
+   [1392441148867/325641566250]
+
+

ξ − β:
+   [-1/3, -4/45, 32/315, 34/675, 2476/467775, -70496/8513505, -18484/4343625, 29232878/97692469875]
+   [-7/90, -4/315, 74/2025, 3992/467775, 53836/212837625, -4160804/1915538625, -324943819/488462349375]
+   [-83/2835, 2/14175, 7052/467775, -661844/1915538625, 237052/383107725, -168643106/488462349375]
+   [-797/56700, 934/467775, 1425778/212837625, -2915326/1915538625, 113042383/97692469875]
+   [-3673/467775, 390088/212837625, 6064888/1915538625, -558526274/488462349375]
+   [-18623681/3831077250, 41288/29469825, 155665021/97692469875]
+   [-6205669/1915538625, 504234982/488462349375]
+   [-8913001661/3907698795000]
+
+

β − ξ:
+   [1/3, 4/45, -46/315, -1082/14175, 11824/467775, 7947332/212837625, 9708931/1915538625, -5946082372/488462349375]
+   [17/90, 68/945, -338/2025, -16672/155925, 39946703/638512875, 164328266/1915538625, 190673521/69780335625]
+   [461/2835, 1102/14175, -101069/467775, -255454/1563705, 236067184/1915538625, 86402898356/488462349375]
+   [3161/18900, 1786/18711, -189032762/638512875, -98401826/383107725, 110123070361/488462349375]
+   [88868/467775, 80274086/638512875, -802887278/1915538625, -200020620676/488462349375]
+   [880980241/3831077250, 66263486/383107725, -296107325077/488462349375]
+   [37151038/127702575, 4433064236/18091198125]
+   [495248998393/1302566265000]
+
+

ξ − θ:
+   [2/3, -4/45, 62/105, 778/4725, -193082/467775, -4286228/42567525, 53702182/212837625, 182466964/8881133625]
+   [4/45, -32/315, 12338/14175, 92696/467775, -61623938/70945875, -32500616/273648375, 367082779691/488462349375]
+   [-524/2835, -1618/14175, 612536/467775, 427003576/1915538625, -663111728/383107725, -42668482796/488462349375]
+   [-5933/14175, -8324/66825, 427770788/212837625, 421877252/1915538625, -327791986997/97692469875]
+   [-320044/467775, -9153184/70945875, 6024982024/1915538625, 74612072536/488462349375]
+   [-1978771378/1915538625, -46140784/383107725, 489898512247/97692469875]
+   [-2926201612/1915538625, -42056042768/488462349375]
+   [-2209250801969/976924698750]
+
+

θ − ξ:
+   [-2/3, 4/45, -158/315, -2102/14175, 109042/467775, 216932/2627625, -189115382/1915538625, -230886326/6343666875]
+   [16/45, -16/945, 934/14175, -7256/155925, 117952358/638512875, 288456008/1915538625, -11696145869/69780335625]
+   [-232/2835, 922/14175, -25286/66825, -7391576/54729675, 478700902/1915538625, 91546732346/488462349375]
+   [719/4725, 268/18711, -67048172/638512875, -67330724/383107725, 218929662961/488462349375]
+   [14354/467775, 46774256/638512875, -117954842/273648375, -129039188386/488462349375]
+   [253129538/1915538625, 2114368/34827975, -178084928947/488462349375]
+   [13805944/127702575, 6489189398/54273594375]
+   [59983985827/325641566250]
+
+

ξ − μ:
+   [1/6, -4/45, -817/10080, 1297/18900, 7764059/239500800, -9292991/302702400, -25359310709/1743565824000, 39534358147/2858202547200]
+   [49/720, -2/35, -29609/453600, 35474/467775, 36019108271/871782912000, -14814966289/245188944000, -13216941177599/571640509440000]
+   [4463/90720, -2917/56700, -4306823/59875200, 3026004511/30648618000, 99871724539/1569209241600, -27782109847927/250092722880000]
+   [331799/7257600, -102293/1871100, -368661577/4036032000, 2123926699/15324309000, 168979300892599/1600593426432000]
+   [11744233/239500800, -875457073/13621608000, -493031379277/3923023104000, 1959350112697/9618950880000]
+   [453002260127/7846046208000, -793693009/9807557760, -145659994071373/800296713216000]
+   [103558761539/1426553856000, -53583096419057/500185445760000]
+   [12272105438887727/128047474114560000]
+
+

μ − ξ:
+   [-1/6, 4/45, 121/1680, -1609/28350, -384229/14968800, 12674323/851350500, 7183403063/560431872000, -375027460897/125046361440000]
+   [-29/720, 26/945, 16463/453600, -431/17325, -31621753811/1307674368000, 1117820213/122594472000, 30410873385097/2000741783040000]
+   [-1003/45360, 449/28350, 3746047/119750400, -32844781/1751349600, -116359346641/3923023104000, 151567502183/17863765920000]
+   [-40457/2419200, 629/53460, 10650637121/326918592000, -13060303/766215450, -317251099510901/8002967132160000]
+   [-1800439/119750400, 205072597/20432412000, 146875240637/3923023104000, -2105440822861/125046361440000]
+   [-59109051671/3923023104000, 228253559/24518894400, 91496147778023/2000741783040000]
+   [-4255034947/261534873600, 126430355893/13894040160000]
+   [-791820407649841/42682491371520000]
+
+

ξ − χ:
+   [2/3, -34/45, 46/315, 2458/4725, -55222/93555, 2706758/42567525, 16676974/30405375, -64724382148/97692469875]
+   [19/45, -256/315, 3413/14175, 516944/467775, -340492279/212837625, 158999572/1915538625, 85904355287/37574026875]
+   [248/567, -15958/14175, 206834/467775, 4430783356/1915538625, -7597644214/1915538625, 2986003168/37574026875]
+   [16049/28350, -832976/467775, 62016436/70945875, 851209552/174139875, -375566203/39037950]
+   [15602/18711, -651151712/212837625, 3475643362/1915538625, 5106181018156/488462349375]
+   [2561772812/1915538625, -10656173804/1915538625, 34581190223/8881133625]
+   [873037408/383107725, -5150169424688/488462349375]
+   [7939103697617/1953849397500]
+
+

χ − ξ:
+   [-2/3, 34/45, -88/315, -2312/14175, 27128/93555, -55271278/212837625, 308365186/1915538625, -17451293242/488462349375]
+   [1/45, -184/945, 6079/14175, -65864/155925, 106691108/638512875, 149984636/1915538625, -101520127208/488462349375]
+   [-106/2835, 772/14175, -14246/467775, 5921152/54729675, -99534832/383107725, 10010741462/37574026875]
+   [-167/9450, -5312/467775, 75594328/638512875, -35573728/273648375, 1615002539/75148053750]
+   [-248/13365, 2837636/638512875, 130601488/1915538625, -3358119706/488462349375]
+   [-34761247/1915538625, -3196/3553875, 46771947158/488462349375]
+   [-2530364/127702575, -18696014/18091198125]
+   [-14744861191/651283132500]
+
+ +\section auxlaterror Truncation errors + +There are two sources of error when using these series. The truncation +error arises from retaing terms up to a certain order in \e n; it is the +absolute difference between the value of the truncated series compared +with the exact latitude (evaluated with exact arithmetic). In addition, +using standard double-precision arithmetic entails accumulating +round-off errors so that at the end of a complex calculation a few of +the trailing bits of the result are wrong. + +Here's a table of the truncation errors. The errors are given in "units +in the last place (ulp)" where 1 ulp = 2−53 radian = +6.4 × 10−15 degree = 2.3 × +10−11 arcsecond which is a measure of the round-off +error for double precision. Here is some rough guidance on how to +interpret these errors: +- if the truncation error is less than 1 ulp, then round-off errors + dominate; +- if the truncation error is greater than 8 ulp, then truncation errors + dominate; +- otherwise, round-off and truncation errors are comparable. +. +The truncation errors are given accurate to 2 significant figures. + +

+ + + + +
Auxiliary latitude truncation errors (ulp)
expression + [f = 1/150, order = 6] + [f = 1/297, order = 5] +
n series e2 series + n series e2 series +
β − φ
0.0060 
28   
 0.035 
 41   
+
φ − β
0.0060 
28   
 0.035 
 41   
+
θ − φ
2.9    
82   
 6.0   
120   
+
φ − θ
2.9    
82   
 6.0   
120   
+
θ − β
0.0060 
28   
 0.035 
 41   
+
β − θ
0.0060 
28   
 0.035 
 41   
+
μ − φ
0.037  
41   
 0.18  
 60   
+
φ − μ
0.98   
59   
 2.3   
 84   
+
μ − β
0.00069
 5.8 
 0.0024
  9.6 
+
β − μ
0.13   
12   
 0.35  
 19   
+
μ − θ
0.24   
30   
 0.67  
 40   
+
θ − μ
0.099  
23   
 0.23  
 33   
+
χ − φ
0.78   
43   
 2.1   
 64   
+
φ − χ
9.0    
71   
17     
100   
+
χ − β
0.018  
 3.7 
 0.11  
  6.4 
+
β − χ
1.7    
16   
 3.4   
 24   
+
χ − θ
0.18   
31   
 0.56  
 43   
+
θ − χ
0.87   
23   
 1.9   
 32   
+
χ − μ
0.022  
 0.56
 0.11  
  0.91
+
μ − χ
0.31   
 1.2 
 0.86  
  2.0 
+
ξ − φ
0.015  
39   
 0.086 
 57   
+
φ − ξ
0.34   
53   
 1.1   
 75   
+
ξ − β
0.00042
 6.3 
 0.0039
 10   
+
β − ξ
0.040  
10   
 0.15  
 15   
+
ξ − θ
0.28   
28   
 0.75  
 38   
+
θ − ξ
0.040  
23   
 0.11  
 33   
+
ξ − μ
0.015  
 0.79
 0.058 
  1.5 
+
μ − ξ
0.0043 
 0.54
 0.018 
  1.1 
+
ξ − χ
0.60   
 1.9 
 1.5   
  3.6 
+
χ − ξ
0.023  
 0.53
 0.079 
  0.92
+
+
+ +\if SKIP + 0 beta phi ,0.0060!,28!!!,!0.035!,!41!!! + 1 phi beta ,0.0060!,28!!!,!0.035!,!41!!! + 2 theta phi ,2.9!!!!,82!!!,!6.0!!!,120!!! + 3 phi theta,2.9!!!!,82!!!,!6.0!!!,120!!! + 4 theta beta ,0.0060!,28!!!,!0.035!,!41!!! + 5 beta theta,0.0060!,28!!!,!0.035!,!41!!! + 6 mu phi ,0.037!!,41!!!,!0.18!!,!60!!! + 7 phi mu ,0.98!!!,59!!!,!2.3!!!,!84!!! + 8 mu beta ,0.00069,!5.8!,!0.0024,!!9.6! + 9 beta mu ,0.13!!!,12!!!,!0.35!!,!19!!! +10 mu theta,0.24!!!,30!!!,!0.67!!,!40!!! +11 theta mu ,0.099!!,23!!!,!0.23!!,!33!!! +12 chi phi ,0.78!!!,43!!!,!2.1!!!,!64!!! +13 phi chi ,9.0!!!!,71!!!,17!!!!!,100!!! +14 chi beta ,0.018!!,!3.7!,!0.11!!,!!6.4! +15 beta chi ,1.7!!!!,16!!!,!3.4!!!,!24!!! +16 chi theta,0.18!!!,31!!!,!0.56!!,!43!!! +17 theta chi ,0.87!!!,23!!!,!1.9!!!,!32!!! +18 chi mu ,0.022!!,!0.56,!0.11!!,!!0.91 +19 mu chi ,0.31!!!,!1.2!,!0.86!!,!!2.0! +20 xi phi ,0.015!!,39!!!,!0.086!,!57!!! +21 phi xi ,0.34!!!,53!!!,!1.1!!!,!75!!! +22 xi beta ,0.00042,!6.3!,!0.0039,!10!!! +23 beta xi ,0.040!!,10!!!,!0.15!!,!15!!! +24 xi theta,0.28!!!,28!!!,!0.75!!,!38!!! +25 theta xi ,0.040!!,23!!!,!0.11!!,!33!!! +26 xi mu ,0.015!!,!0.79,!0.058!,!!1.5! +27 mu xi ,0.0043!,!0.54,!0.018!,!!1.1! +28 xi chi ,0.60!!!,!1.9!,!1.5!!!,!!3.6! +29 chi xi ,0.023!!,!0.53,!0.079!,!!0.92 +\endif + +The 2nd and 3rd columns show the results for the SRMmax ellipsoid, \e f += 1/150, retaining 6th order terms in the series expansion. The 4th and +5th columns show the results for the International ellipsoid, \e f = +1/297, retaining 5th order terms in the series expansion. The 2nd and +4th columns give the errors for the series expansions in terms of \e n +given in this section (appropriately truncated). The 3rd and 5th +columns give the errors when the series are reexpanded in terms of +e2 = 4\e n/(1 + \e n)2 and truncated +retaining the e12 and e10 terms +respectively. + +Some observations: +- For production use, the 6th order series in \e n are recommended. For + \e f = 1/150, the resulting errors are close to the round-off limit. + The errors in the 6th order series scale as f7; so + the errors with \e f = 1/297 are about 120 times smaller. +- It's inadvisable to use the 5th order series in \e n; this order is + barely acceptable for \e f = 1/297 and the errors grow as + f6 as \e f is increased. +- In all cases, the expansions in terms of e2 are + considerably less accurate than the corresponding series in \e n. +- For every series converting between φ and any of θ, μ, + χ, or ξ, the series where β is substituted for φ is + more accurate. Considering that the transformation between φ and + β is so simple, tanβ = (1 - \e f) tanφ, it sometimes + makes sense to use β internally as the basic measure of latitude. + (This is the case with geodesic calculations.) + +
+Back to \ref geocentric. Forward to \ref highprec. Up to \ref contents. +
+ +**********************************************************************/ +/** +\page highprec Support for high precision arithmetic + +
+Back to \ref auxlat. Forward to \ref changes. Up to \ref contents. +
+ +One of the goals with the algorithms in GeographicLib is to deliver +accuracy close to the limits for double precision. In order to develop +such algorithms it is very useful to be have accurate test data. For +this purpose, I used Maxima's bfloat capability, which support arbitrary +precision floating point arithmetic. As of version 1.37, such +high-precision test data can be generated directly by GeographicLib by +compiling it with GEOGRAPHICLIB_PRECISION equal to 4 or 5. + +Here's what you should know: + - This is mainly for use for algorithm developers. It's not + recommended for installation for all users on a system. + - Configuring with -D GEOGRAPHICLIB_PRECISION=4 gives quad + precision (113-bit precision) via boost::multiprecision::float128; + this requires: + - Boost, version 1.54 or later, + - the quadmath library (the package names are libquadmath + and libquadmath-devel), + - the use of g++. + - Configuring with -D GEOGRAPHICLIB_PRECISION=5 gives + arbitrary precision via mpfr::mpreal; this requires: + - MPFR, version 3.0 or later, + - MPFR C++ + (version 3.6.5, dated 2016-12-19, or later), + - a compiler which supports the explicit cast operator (e.g., g++ 4.5 + or later, Visual Studio 12 2013 or later). + - MPFR, MPFR C++, and Boost all come with their own licenses. Be sure + to respect these. + - The indicated precision is used for all floating point + arithmetic. Thus, you can't compare the results of different + precisions within a single invocation of a program. Instead, you can + create a file of accurate test data at a high precision and use this + to test the algorithms at double precision. + - With MPFR, the precision should be set (using Utility::set_digits) + just once before any other GeographicLib routines are called. + Calling this function after other GeographicLib routines will lead to + inconsistent results (because the precision of some constants like + Math::pi() is set when the functions are first called). + - All the \ref utilities call Utility::set_digits() (with no + arguments). This causes the precision (in bits) to be determined by + the GEOGRAPHICLIB_DIGITS environment variable. If this + is not defined the precision is set to 256 bits (about 77 decimal + digits). + - The accuracy of most calculations should increase as the precision + increases (and typically only a few bits of accuracy should be lost). + We can distinguish 4 sources of error: + - Round-off errors; these are reliably reduced when the precision is + increased. For the most part, the algorithms used by GeographicLib + are carefully tuned to minimize round-off errors, so that only a + few bits of accuracy are lost. + - Convergence errors due to not iterating certain algorithms to + convergence. However, all iterative methods used by GeographicLib + converge quadratically (the number of correct digits doubles on + each iteration) so that full convergence is obtained for + "reasonable" precisions (no more than, say, 100 decimal digits or + about 340 bits). An exception is thrown if the convergence + criterion is not met when using high precision arithmetic. + - Truncation errors. Some classes (namely, Geodesic and + TransverseMercator) use series expansion to approximate the true + solution. Additional terms in the series are used for high + precision, however there's always a finite truncation error which + varies as some power of the flattening. On the other hand, + GeodesicExact and TransverseMercatorExact are somewhat slower + classes offering the same functionality implemented with + EllipticFunction. These classes provide arbitrary accuracy. + (However, a caveat is that the evaluation of the area in + GeodesicExact still uses a series (albeit of considerably higher + order). So the area calculations are always have a finite + truncation error.) + - Quantization errors. Geoid, GravityModel, and MagneticModel all + depend on external data files. The coefficient files for + GravityModel and MagneticModel store the coefficients as IEEE + doubles (and perhaps these coefficients can be regarded as exact). + However, with Geoid, the data files for the geoid heights are + quantized at 3mm leading to an irreducible ±1.5mm + quantization error. On the other hand, all the physical constants + used by GeographicLib, e.g., the flattening of the WGS84 ellipsoid, + are evaluated as exact decimal numbers. + - Where might high accuracy be important? + - checking the truncation error of series approximations; + - checking for excessive round-off errors (typically due to subtraction); + - checking the round-off error in computing areas of many-sided polygons; + - checking the summation of high order spherical harmonic expansions + (where underflow and overflow may also be a problem). + - Because only a tiny number of people will be interested in using this + facility: + - the cmake support for the required libraries is rudimentary; + - however geographiclib-config.cmake does export + GEOGRAPHICLIB_PRECISION and + GEOGRAPHICLIB_HIGHPREC_LIBRARIES, the libraries + providing the support for high-precision arithmetic; + - support for the C++11 mathematical functions and the explicit cast + operator is required; + - quad precision is only available on Linux; + - mpfr has been mostly tested on Linux (but it works on Windows with + Visual Studio 12 and MacOS too). + +The following steps needed to be taken + + - Phase 1, make sure you can switch easily between double, float, and + long double. + - use \#include <cmath> instead of \#include + <math.h>; + - use, e.g., std::sqrt instead of sqrt in + header files (similarly for sin, cos, + atan2, etc.); + - use using namespace std; and plain sqrt, + etc., in code files; + - express all convergence criteria in terms of\code + numeric_limits::epsilon() \endcode + etc., instead of using "magic constants", such as 1.0e-15; + - use typedef double real; and replace all occurrences of + double by real; + - write all literals by, e.g., real(0.5). Some + constants might need the L suffix, e.g., real f = + 1/real(298.257223563L) (but see below); + - Change the typedef of real to float or + long double, compile, and test. In this way, the + library can be run with any of the three basic floating point + types. + - If you want to run the library with multiple floating point types + within a single executable, then make all your classes take a + template parameter specifying the floating-point type and + instantiate your classes with the floating-point types that you + plan to use. I did not take this approach with GeographicLib + because double precision is suitable for the vast majority of + applications and turning all the classes into templates classes + would end up needlessly complicating (and bloating) the library. + + - Phase 2, changes to support arbitrary, but fixed, precision + - Use, e.g., \code + typedef boost::multiprecision::float128 real; \endcode + - Change std::sqrt(...), etc. to \code + using std::sqrt; + sqrt(...) \endcode + (but note that std::max can stay). It's only necessary + to do this in header files (code files already have using + namespace std;). + - In the case of boost's multiprecision numbers, the C++11 + mathematical functions need special treatment, see Math.hpp. + - If necessary, use series with additional terms to improve the + accuracy. + - Replace slowly converging root finding methods with rapidly + converging methods. In particular, the simple iterative method to + determine the flattening from the dynamical form factor in + NormalGravity converged too slowly; this was replaced by Newton's + method. + - If necessary, increase the maximum allowed iteration count in root + finding loops. Also throw an exception of the maximum iteration + count is exceeded. + - Write literal constants in a way that works for any precision, e.g., + \code + real f = 1/( real(298257223563LL) / 1000000000 ); \endcode + [Note that \code + real f = 1/( 298 + real(257223563) / 1000000000 ); \endcode + and 1/real(298.257223563L) are susceptible to + double rounding errors. We normally want to avoid such errors when + real is a double.] + - For arbitrary constants, you might have to resort to macros \code + #if GEOGRAPHICLIB_PRECISION == 1 + #define REAL(x) x##F + #elif GEOGRAPHICLIB_PRECISION == 2 + #define REAL(x) x + #elif GEOGRAPHICLIB_PRECISION == 3 + #define REAL(x) x##L + #elif GEOGRAPHICLIB_PRECISION == 4 + #define REAL(x) x##Q + #else + #define REAL(x) real(#x) + #endif \endcode + and then use \code + real f = 1/REAL(298.257223563); \endcode + - Perhaps use local static declarations to avoid the overhead of + reevaluating constants, e.g., \code + static inline real pi() { + using std::atan2; + // pi is computed just once + static const real pi = atan2(real(0), real(-1)); + return pi; + } \endcode + This is not necessary for built-in floating point types, + since the atan2 function will be evaluated at compile time. + - In Utility::readarray and Utility::writearray, arrays of reals were + treated as plain old data. This assumption now no longer holds and + these functions needed special treatment. + - volatile declarations don't apply. + + - Phase 3, changes to support arbitrary precision which can be set at + runtime. + - The big change now is that the precision is not known at compile + time. All static initializations which involve floating point + numbers need to be eliminated. + - Some static variables (e.g., tolerances which are expressed in + terms of numeric_limits<double>\::epsilon()) + were made member variables and so initialized when the + constructor was called. + - Some simple static real arrays (e.g., the interpolating stencils + for Geoid) were changed into integer arrays. + - Some static variables where converted to static functions similar + to the definition of pi() above. + - All the static instances of classes where converted as follows + \code + // declaration + static const Geodesic WGS84; + // definition + const Geodesic Geodesic::WGS84(Constants::WGS84_a(), + Constants::WGS84_f()); + // use + const Geodesic& geod = Geodesic::WGS84; \endcode + becomes \code + // declaration + static const Geodesic& WGS84(); + // definition + const Geodesic& Geodesic::WGS84() { + static const Geodesic wgs84(Constants::WGS84_a(), + Constants::WGS84_f()); + return wgs84; + static const Geodesic& WGS84(); + } + // use + const Geodesic& geod = Geodesic::WGS84(); \endcode + This is the so-called + + "construct on first use idiom". This is the most disruptive + of the changes since it requires a different calling convention + in user code. However the old static initializations were + invoked every time a code linking to GeographicLib was started, + even if the objects were not subsequently used. The new method + only initializes the static objects if they are used. + . + - numeric_limits<double>\::digits is no longer a + compile-time constant. It becomes + numeric_limits<double>\::digits(). + - Depending on the precision cos(π/2) might be negative. + Similarly atan(tan(π/2)) may evaluate to −π/2. + GeographicLib already handled this, because this happens with long + doubles (64 bits in the fraction). + - The precision needs to be set in each thread in a multi-processing + applications (for an example, see + examples/GeoidToGTX.cpp). + - Passing numbers to functions by value incurs a substantially higher + overhead than with doubles. This could be avoided by passing such + arguments by reference. This was not done here because it + would junk up the code to benefit a narrow application. + - The constants in GeodesicExact, e.g., 831281402884796906843926125, + can't be specified as long doubles nor long longs (since they have + more than 64 significant bits): + - first tried macro which expanded to a string (see the macro REAL + above); + - now use inline function to combine two long long ints each with at + most 52 significant bits; + - also needed to simplify one routine in GeodesicExact which took + inordinately long (15 minutes) to compile using g++; + - but Visual Studio 12 then complained (with an + internal compiler error presumably due to overly aggressive + whole-file optimization); fixed by splitting one function into a + separate file. + +
+Back to \ref auxlat. Forward to \ref changes. Up to \ref contents. +
+ +**********************************************************************/ +/** +\page changes Change log + +
+Back to \ref highprec. Up to \ref contents. +
+ +List of versions in reverse chronological order together with a brief +list of changes. (Note: Old versions of the library use a year-month +style of numbering. Now, the library uses a major and minor version +number.) Recent versions of GeographicLib are available at + +https://sourceforge.net/projects/geographiclib/files/distrib/. +Older versions are in + +https://sourceforge.net/projects/geographiclib/files/distrib/archive/. + +The corresponding documentation for these versions is obtained by +clicking on the “Version m.nn” links below. Some of +the links in the documentation of older versions may be out of date (in +particular the links for the source code will not work if the code has +been migrated to the archive subdirectory). All the releases are +available as tags “rm.nn” in the the "release" branch +of the + +git repository for GeographicLib. + + - Version 1.49 + (released 2017-10-05) + - Add the Enhanced Magnetic Model 2017, emm2017. This is valid for + 2000 thru the end of 2021. + - Avoid potential problems with the order of initializations in DMS, + GARS, Geohash, Georef, MGRS, OSGB, SphericalEngine; this only would + have been an issue if GeographicLib objects were instantiated + globally. Now no GeographicLib initialization code should be run + prior to the entry of main(). + - To support the previous fix, add an overload, + Utility::lookup(const char* s, char c). + - NearestNeighbor::Search throws an error if \e pts is the wrong size + (instead of merely returning no results). + - Use complex arithmetic for Clenshaw sums in TransverseMercator and + tranmerc_{fwd,inv}.m. + - Changes in cmake support: + - fix compiler flags for GEOGRAPHICLIB_PRECISION = 4; + - add CONVERT_WARNINGS_TO_ERRORS option (default OFF), if ON then + compiler warnings are treated as errors. + - Fix warnings about implicit conversions of doubles to bools in C++, + C, and JavaScript packages. + - Binary installers for Windows now use Visual Studio 14 2015. + + - Version 1.48 + (released 2017-04-09) + - The "official" URL for GeographicLib is now + https://geographiclib.sourceforge.io (instead of + http://geographiclib.sourceforge.net). + - The default range for longitude and azimuth is now + (−180°, 180°], instead of [−180°, + 180°). This was already the case for the C++ library; now the + change has been made to the other implementations (C, Fortran, + Java, JavaScript, Python, MATLAB, and Maxima). + - Changes to NearestNeighbor: + - fix BUG in reading a NearestNeighbor object from a stream which + sometimes incorrectly caused a "Bad index" exception to be + thrown; + - add NearestNeighbor::operator<<, NearestNeighbor::operator>>, + NearestNeighbor::swap, std::swap(GeographicLib::NearestNeighbor&, + GeographicLib::NearestNeighbor&); + - Additions to the documentation: + - add documentation on \ref nearest; + - \ref normalgravity documentation is now on its own page and now + has an illustrative figure; + - document the \ref auxlaterror in the series for auxiliary + latitudes. + - Fix BUGS in MATLAB function geodreckon with mixed scalar and array + arguments. + - Workaround bug in math.fmod for Python 2.7 on 32-bit Windows + machines. + - Changes in cmake support: + - add USE_BOOST_FOR_EXAMPLES option (default OFF), if ON search for + Boost libraries for building examples; + - add APPLE_MULTIPLE_ARCHITECTURES option (default OFF), if ON + build for both i386 and x86_64 on Mac OS X systems; + - don't add flag for C++11 for g++ 6.0 (since it's not needed). + - Fix compiler warnings with Visual Studio 2017 and for the C + library. + + - Version 1.47 + (released 2017-02-15) + - Add NearestNeighbor class. + - Improve accuracy of area calculation (fixing a flaw introduced in + version 1.46); fix applied in Geodesic, GeodesicExact, and the + implementations in C, Fortran, Java, JavaScript, Python, MATLAB, + and Maxima. + - Generalize NormalGravity to allow oblate and prolate ellipsoids. + As a consequence a new form of constructor, + NormalGravity::NormalGravity, has been introduced and the old + form is now deprecated (and because the signatures of the two + constructors are similar, the compiler will warn about the use of + the old one). + - Changes in Math class: + - Math::sincosd, Math::sind, Math::cosd only return −0 for + the case sin(−0); + - Math::atan2d and Math::AngNormalize return results in + (−180°, 180°]; this may affect the longitudes and + azimuth returned by several other functions. + - Add Utility::trim() and Utility::val(); Utility::num() is now + deprecated. + - Changes in cmake support: + - remove support of PACKAGE_PATH and INSTALL_PATH in cmake + configuration; + - fix to FindGeographicLib.cmake to make it work on Debian systems; + - use $ (cmake version ≥ 3.1); + - use NAMESPACE for exported targets; + - geographiclib-config.cmake exports GEOGRAPHICLIB_DATA, + GEOGRAPHICLIB_PRECISION, and GeographicLib_HIGHPREC_LIBRARIES. + - Add pkg-config support for cmake and autoconf builds. + - Minor fixes: + - fix the order of declarations in C library, incorporating the + patches in version 1.46.1; + - fix the packaging of the Python library, incorporating the + patches in version 1.46.3; + - restrict junit dependency in the Java package to testing scope + (thanks to Mick Killianey); + - various behind-the-scenes fixes to EllipticFunction; + - fix documentation and default install location for Windows binary + installers; + - fix clang compiler warnings in GeodesicExactC4 and + TransverseMercator. + + - Version 1.46 + (released 2016-02-15) + - The following BUGS have been fixed: + - the -w flag to Planimeter(1) was + being ignored; + - in the Java package, the wrong longitude was being returned with + direct geodesic calculation with a negative distance when + starting point was at a pole (this bug was introduced in version + 1.44); + - in the JavaScript package, PolygonArea.TestEdge contained a + misspelling of a variable name and other typos (problem found by + threepointone). + - INCOMPATIBLE CHANGES: + - make the -w flag (to swap the default order of latitude and + longitude) a toggle for all \ref utilities; + - the -a option to GeodSolve(1) now + toggles (instead of sets) arc mode; + - swap order \e coslon and \e sinlon arguments in CircularEngine + class. + - Remove deprecated functionality: + - remove gradient calculation from the Geoid class and + GeoidEval(1) (this was inaccurate + and of dubious utility); + - remove reciprocal flattening functions, InverseFlattening in many + classes and Constants::WGS84_r(); stop treating flattening > 1 + as the reciprocal flattening in constructors; + - remove DMS::Decode(string), DMS::DecodeFraction, + EllipticFunction:m, EllipticFunction:m1, Math::extradigits, + Math::AngNormalize2, PolygonArea::TestCompute; + - stop treating LONG_NOWRAP as an alias for LONG_UNROLL in + Geodesic (and related classes) and Rhumb; + - stop treating full/schmidt as aliases for FULL/SCHMIDT in + SphericalEngine (and related classes); + - remove qmake project file src/GeographicLib.pro because QtCreator + can handle cmake projects now; + - remove deprecated Visual Studio 2005 project and solution files. + - Changes to GeodesicLine and GeodesicLineExact classes; these + changes (1) simplify the process of computing waypoints on a + geodesic given two endpoints and (2) allow a GeodesicLine to be + defined which is consistent with the solution of the inverse + problem (in particular Geodesic::InverseLine the specification of + south-going lines which pass the poles in a westerly direction by + setting sin α1 = −0): + - the class stores the distance \e s13 and arc length \e a13 to a + reference point 3; by default these quantities are NaNs; + - GeodesicLine::SetDistance (and GeodesicLine::SetArc) specify the + distance (and arc length) to point 3; + - GeodesicLine::Distance (and GeodesicLine::Arc) return the + distance (and arc length) to point 3; + - new methods Geodesic::InverseLine and Geodesic::DirectLine return + a GeodesicLine with the reference point 3 defined as point 2 of + the corresponding geodesic calculation; + - these changes are also included in the C, Java, JavaScript, and + Python packages. + - Other changes to the geodesic routines: + - more accurate solution of the inverse problem when longitude + difference is close to 180° (also in C, Fortran, Java, + JavaScript, Python, MATLAB, and Maxima packages); + - more accurate calculation of lon2 in the inverse calculation with + LONG_UNROLL (also in Java, JavaScript, Python packages). + - Changes to GeodSolve(1) utility: + - the -I and -D options now specify geodesic line calculation via + the standard inverse or direct geodesic problems; + - rename -l flag to -L to parallel the new -I and -D flags (-l is + is retained for backward compatibility but is deprecated), + and similarly for RhumbSolve(1); + - the -F flag (in conjunction with the -I or -D flags) specifies that + distances read on standard input are fractions of \e s13 or \e + a13; + - the -a option now toggles arc mode (noted above); + - the -w option now toggles longitude first mode (noted above). + - Changes to Math class: + - Math::copysign added; + - add overloaded version of Math::AngDiff which returns the error + in the difference. This allows a more accurate treatment of + inverse geodesic problem when \e lon12 is close to 180°; + - Math::AngRound now converts tiny negative numbers to −0 + (instead of +0), however −0 is still converted to +0. + - Add -S and -T options to + GeoConvert(1). + - Add Sphinx + documentation for Python package. + - Samples of wrapping the C++ library, so it's accessible in other + languages, are given in wrapper/C, + wrapper/python, and wrapper/matlab. + - Binary installers for Windows now use Visual Studio 12 2013. + - Remove top-level pom.xml from release (it was specific to SRI). + - A reminder: because of the JavaScript changes introduced in version + 1.45, you should remove the following installation directories from + your system: + - Windows: ${CMAKE_INSTALL_PREFIX}/doc/scripts + - Others: ${CMAKE_INSTALL_PREFIX}/share/doc/GeographicLib/scripts + + - Version 1.45 + (released 2015-09-30) + - Fix BUG in solution of inverse geodesic caused by misbehavior of + some versions of Visual Studio on Windows (fmod(−0.0, 360.0) + returns +0.0 instead of −0.0) and Octave (sind(−0.0) + returns +0.0 instead of −0.0). These bugs were exposed + because max(−0.0, +0.0) returns −0.0 for some + languages. + - Geodesic::Inverse now correctly returns NaNs if one of the + latitudes is a NaN. + - Changes to JavaScript package: + - thanks to help from Yurij Mikhalevich, it is a now a + node package that can be + installed with npm; + - make install now installs the node package in + lib/node_modules/geographiclib; + - add unit tests using mocha; + - add documentation via JSDoc; + - fix bug Geodesic.GenInverse (this bug, introduced in version + 1.44, resulted in the wrong azimuth being reported for points at + the pole). + - Changes to Java package: + - add implementation of ellipsoidal Gnomonic projection (courtesy + of Sebastian Mattheis); + - add unit tests using JUnit; + - Math.toRadians and Math.toDegrees are used instead of + GeoMath.degree (which is now removed), as a result… + - Java version 1.2 (released 1998-12) or later is now required. + - Changes to Python package: + - add unit tests using the unittest framework; + - fixed bug in normalization of the area. + - Changes to MATLAB package: + - fix array size mismatch in geoddistance by avoiding calls to + subfunctions with zero-length arrays; + - fix tranmerc_{fwd,inv} so that they work with arrays and + mixed array/scalar arguments; + - work around Octave problem which causes mgrs_fwd to return + garbage with prec = 10 or 11; + - add geographiclib_test.m to run a test suite. + - Behavior of substituting 1/\e f for \e f if \e f > 1 is now + deprecated. This behavior has been removed from the + JavaScript, C, and Python implementations (it was never + documented). Maxima, MATLAB, and Fortran implementations never + included this behavior. + - Other changes: + - fix bug, introduced in version 1.42, in the C++ implementation to + the computation of area which causes NaNs to be returned in the + case of a sphere; + - fixed bug, introduced in version 1.44, in the detection of C++11 + math functions in configure.ac; + - throw error on non-convergence in Gnomonic::Reverse if + GEOGRAPHICLIB_PRECISION > 3; + - add geod_polygon_clear to C library; + - turn illegal latitudes into NaNs for Fortran library; + - add test suites for the C and Fortran libraries. + + - Version 1.44 + (released 2015-08-14) + - Various changes to improve accuracy, e.g., by minimizing round-off + errors: + - Add Math::sincosd, Math::sind, Math::cosd which take their + arguments in degrees. These functions do exact range reduction + and thus they obey exactly the elementary properties of the + trigonometric functions, e.g., sin 9° = cos 81° = − + sin 123456789°. + - Math::AngNormalize now works for any angles, instead of angles in + the range [−540°, 540°); the function + Math::AngNormalize2 is now deprecated. + - This means that there is now no restriction on longitudes and + azimuths; any values can be used. + - Improve the accuracy of Math::atan2d. + - DMS::Decode avoids unnecessary round-off errors; thus 7:33:36 and + 7.56 result in identical values. DMS::Encode rounds ties to + even. These changes have also been made to DMS.js. + - More accurate rounding in MGRS::Reverse and mgrs_inv.m; this + change only makes a difference at sub-meter precisions. + - With MGRS::Forward and mgrs_fwd.m, ensure that digits in lower + precision results match those at higher precision; as a result, + strings of trailing 9s are less likely to be generated. This + change only makes a difference at sub-meter precisions. + - Replace the series for A2 in the Geodesic class + with one with smaller truncation errors. + - Geodesic::Inverse sets \e s12 to zero for coincident points at + pole (instead of returning a tiny quantity). + - Math::LatFix returns its argument if it is in [−90°, + 90°]; if not, it returns NaN. + - Using Math::LatFix, routines which don't check their arguments + now interpret a latitude outside the legal range of + [−90°, 90°] as a NaN; such routines will return + NaNs instead of finite but incorrect results; caution: + code that (dangerously) relied on the "reasonable" results being + returned for values of the latitude outside the allowed range + will now malfunction. + - All the \ref utilities accept the -w option to swap the + latitude-longitude order on input and output (and where appropriate + on the command-line arguments). CartConvert now accepts the -p + option to set the precision; now all of the utilities except + GeoidEval accept -p. + - Add classes for GARS, the Global Area Reference System, and for + Georef, the World Geographic Reference System. + - Changes to DMS::Decode and DMS.js: + - tighten up the rules: + - 30:70.0 and 30:60 are illegal (minutes and second must be + strictly less than 60), however + - 30:60.0 and 30:60. are legal (floating point 60 is OK, since it + might have been generated by rounding 59.99…); + - generalize a+b concept, introduced in version 1.42, to any number + of pieces; thus 8+0:40-0:0:10 is interpreted as 8:39:50. + - Documentation fixes: + - update man pages to refer to + GeoConvert(1) on handling of + geographic coordinates; + - document limitations of the series used for TransverseMercator; + - hide the documentation of the computation of the gradient of the + geoid height (now deprecated) in the Geoid class; + - warn about the possible misinterpretation of 7.0E+1 by + DMS::Decode; + - \e swaplatlong optional argument of DMS::DecodeLatLon and + various functions in the GeoCoords class is now called \e + longfirst; + - require Doxygen 1.8.7 or later. + - More systematic treatment of version numbers: + - Python: \__init\__.py defines \__version\__ and \__version_info\__; + - JavaScript: + - Math.js defines Constants.version and Constants.version_string; + - version number included as comment in packed script + geographiclib.js; + - geod-calc.html and + geod-google.html + report the version number; + - https://geographiclib.sourceforge.io/scripts/ gives access to + earlier versions of geographiclib.js as + geographiclib-m.nn.js; + - Fortran: add geover subroutine to return version numbers; + - Maxima: geodesic.mac defines geod_version; + - CGI scripts: these report the version numbers of the utilities. + - BUG FIXES: + - NormalGravity now works properly for a sphere (\e omega = \e f = + \e J2 = 0), instead of returning NaNs (problem found by htallon); + - CassiniSoldner::Forward and cassini_fwd.m now returns the correct + azimuth for points at the pole. + - MATLAB-specific fixes: + - mgrs_fwd now treats treats prec > 11 as prec = 11; + - illegal letter combinations are now correctly detected by + mgrs_inv; + - fixed bug where mgrs_inv returned the wrong results for prec = 0 + strings and center = 0; + - mgrs_inv now decodes prec = 11 strings properly; + - routines now return array results with the right shape; + - routines now properly handle mixed scalar and array arguments. + - Add Accumulator::operator*=(T y). + - Geohash uses "invalid" instead of "nan" when the latitude or + longitude is a nan. + + - Version 1.43 + (released 2015-05-23) + - Add the Enhanced Magnetic Model 2015, emm2015. This is valid for + 2000 thru the end of 2019. This required some changes in the + MagneticModel and MagneticCircle classes; so this model cannot be + used with versions of GeographicLib prior to 1.43. + - Fix BLUNDER in PolarStereographic constructor introduced in version + 1.42. This affected UTMUPS conversions for UPS which could be + incorrect by up to 0.5 km. + - Changes in the LONG_NOWRAP option (added in version 1.39) in the + Geodesic and GeodesicLine classes: + - The option is now called LONG_UNROLL (a less negative sounding + term); the original name, LONG_NOWRAP, is retained for backwards + compatibility. + - There were two bad BUGS in the implementation of this capability: + (a) it gave incorrect results for west-going + geodesics; (b) the option was ignored if used + directly via the GeodesicLine class. The first bug affected the + implementations in all languages. The second affected the + implementation in C++ (GeodesicLine and GeodesicLineExact), + JavaScript, Java, C, Python. These bugs have now been FIXED. + - The GeodSolve utility now accepts + a -u option, which turns on the LONG_UNROLL treatment. With this + option lon1 is reported as entered and + lon2 is given such that lon2 − + lon1 indicates how often and in what sense the + geodesic has encircled the earth. (This option also affects the + value of longitude reported when an inverse calculation is run + with the -f option.) + - The inverse calculation with the JavaScript and Python libraries + similarly sets lon1 and lon2 in output + dictionary respecting the LONG_UNROLL flag. + - The online version of + GeodSolve + now offers an option to unroll the longitude. + - To support these changes DMS::DecodeLatLon no longer reduces the + longitude to the range [−180°, 180°) and + Math::AngRound now coverts −0 to +0. + - Add Math::polyval (also to C, Java, JavaScript, Fortran, Python + versions of the library; this is a built-in function for + MATLAB/Octave). This evaluates a polynomial using Horner's method. + The Maxima-generated code fragments for the evaluation of series in + the Geodesic, TransverseMercator, and Rhumb classes and MATLAB + routines for great ellipses have been replaced by Maxima-generated + arrays of polynomial coefficients which are used as input to + Math::polyval. + - Add MGRS::Check() to verify that \e a, \e f, + kUTM, and kUPS are consistent + with the assumptions in the UTMUPS and MGRS classes. This is + invoked with GeoConvert \--version. (This function + was added to document and check the assumptions used in the UTMUPS + and MGRS classes in case they are extended to deal with ellipsoids + other than WS84.) + - MATLAB function mgrs_inv now takes an optional \e center argument + and strips white space from both beginning and end of the string. + - Minor internal changes: + - GeodSolve sets the geodesic mask so that unnecessary calculations + are avoided; + - some routines have migrated into a math class for the Python, + Java, and JavaScript libraries. + - A reminder: because of changes in the installation directories for + non-Windows systems introduced in version 1.42, you should remove + the following directories from your system: + - ${CMAKE_INSTALL_PREFIX}/share/cmake/GeographicLib* + - ${CMAKE_INSTALL_PREFIX}/libexec/GeographicLib/matlab + + - Version 1.42 + (released 2015-04-28) + - DMS::Decode allows a single addition or subtraction operation, + e.g., 70W+0:0:15. This affects the GeoCoords class and the + utilities (which use the DMS class for reading coordinates). + - Add Math::norm, Math::AngRound, Math::tand, Math::atan2d, + Math::eatanhe, Math::taupf, Math::tauf, Math::fma and remove + duplicated (but private) functionality from other classes. + - On non-Windows systems, the cmake config-style find_package files + are now installed under ${CMAKE_INSTALL_PREFIX}/lib${LIB_SUFFIX} + instead of ${CMAKE_INSTALL_PREFIX}/share, because the files are + architecture-specific. This change will let 32-bit and 64-bit + versions coexist on the same machine (in lib and lib64). You + should remove the versions in the old "share" location. + - MATLAB changes: + - provide native MATLAB implementations for compiled interface + functions, see \ref matlab; + - the compiled MATLAB interface is now deprecated and so the + MATLAB_COMPILER option in the cmake build has been removed; + - reorganize directories, so that + - matlab/geographiclib contains the native matlab code; + - matlab/geographiclib-legacy contains wrapper functions to mimic + the previous compiled functionality; + - the installed MATLAB code mirrors this layout, but the parent + installation directory on non-Windows systems is + ${CMAKE_INSTALL_PREFIX}/share (instead of + ${CMAKE_INSTALL_PREFIX}/libexec), because the files are now + architecture independent; + - matlab/geographiclib is now packaged and distributed as + MATLAB File Exchange package + + 50605 (this supersedes three earlier MATLAB packages); + - point fix for geodarea.m to correct bug in area of polygons which + encircle a pole multiple times (released as version 1.41.1 of + MATLAB File Exchange package 39108, 2014-04-22). + - artifactId for Java package changed from GeographicLib to + GeographicLib-Java and the package is now deployed to + Maven Central (thanks to Chris Bennight for help on this). + - Fix autoconf mismatch of version numbers (which were inconsistent + in versions 1.40 and 1.41). + - Mark the computation of the gradient of the geoid height in the + Geoid class and the GeoidEval + utility as deprecated. + - Work around the boost-quadmath bug with setprecision(0). + - Deprecate use of Visual Studio 2005 "-vc8" project files in the + windows directory. + + - Version 1.41 + (released 2015-03-09) + - Fix bug in Rhumb::Inverse (with \e exact = true) and related + functions which causes the wrong distance to be reported if one of + the end points is at a pole. Thanks to Thomas Murray for reporting + this. + - Add International Geomagnetic Reference Field (12th generation), + which approximates the main magnetic field of the earth for the + period 1900--2020. + - Split information about \ref jacobi to a separate section and + include more material. + + - Version 1.40 + (released 2014-12-18) + - Add the World Magnetic Model 2015, wmm2015. This is now the + default magnetic model for + MagneticField (replacing wmm2010 + which is valid thru the end of 2014). + - Geodesic::Inverse didn't return NaN if one of the longitudes was a + NaN (bug introduced in version 1.25). Fixed in the C++, Java, + JavaScript, C, Fortran, and Python implementations of the geodesic + routines. This bug was not present in the MATLAB version. + - Fix bug in Utility::readarray and Utility::writearray which caused + an exception in debug mode with zero-sized arrays. + - Fix BLUNDER in OSGB::GridReference (found by kalderami) where the + wrong result was returned if the easting or northing was negative. + - OSGB::GridReference now returns "INVALID" if either coordinate is + NaN. Similarly a grid reference starting with "IN" results in NaNs + for the coordinates. + - Default constructor for GeoCoords corresponds to an undefined + position (latitude and longitude = NaN), instead of the north pole. + - Add an online version of RhumbSolve + at https://geographiclib.sourceforge.io/cgi-bin/RhumbSolve. + - Additions to the documentation: + - documentation on \ref triaxial-conformal; + - a page on \ref auxlat (actually, this was added in version 1.39); + - document the use of two single quotes to stand for a double quote + in DMS (this feature was introduced in version 1.13). + - The MATLAB function, geographiclibinterface, which compiles the + wrapper routines for MATLAB now works with MATLAB on a Mac. + + - Version 1.39 + (released 2014-11-11) + - GeographicLib usually normalizes longitudes to the range + [−180°, 180°). However, when solving the direct + geodesic and rhumb line problems, it is sometimes necessary to know + how many lines the line encircled the earth by returning the + longitude "unwrapped". So the following changes have been made: + - add a LONG_NOWRAP flag to \e mask enums for the \e outmask + arguments for Geodesic, GeodesicLine, Rhumb, and RhumbLine; + - similar changes have been made to the Python, JavaScript, and + Java implementations of the geodesic routines; + - for the C, Fortran, and MATLAB implementations the \e arcmode + argument to the routines was generalized to allow a combination + of ARCMODE and LONG_NOWRAP bits; + - the Maxima version now returns the longitude unwrapped. + . + These changes were necessary to fix the PolygonAreaT::AddEdge (see + the next item). + - Changes in area calculations: + - fix BUG in PolygonAreaT::AddEdge (also in C, Java, JavaScript, + and Python implementations) which sometimes causes the wrong area + to be returned if the edge spanned more than 180°; + - add area calculation to the Rhumb and RhumbLine classes and the + RhumbSolve utility (see \ref + rhumbarea); + - add PolygonAreaRhumb typedef for PolygonAreaT; + - add -R option to Planimeter to use + PolygonAreaRhumb (and -G option for the default geodesic polygon); + - fix BLUNDER in area calculation in MATLAB routine geodreckon; + - add area calculation to MATLAB/Octave routines for great ellipses + (see \ref gearea). + - Fix bad BUG in Geohash::Reverse; this was introduced in version + 1.37 and affected all platforms where unsigned longs are 32-bits. + Thanks to Christian Csar for reporting and diagnosing this. + - Binary installers for Windows are now built with Visual Studio 11 + 2012 (instead of Visual Studio 10 2010). Compiled MATLAB support + still with version 2013a (64-bit). + - Update GeographicLib.pro for builds with qmake to include all the + source files. + - Cmake updates: + - include cross-compiling checks in cmake config file; + - improve the way unsuitable versions are reported; + - include_directories (${GeographicLib_INCLUDE_DIRS}) is no longer + necessary with cmake 2.8.11 or later. + - legacy/Fortran now includes drop-in replacements for the geodesic + utilities from the NGS. + - geographiclib-get-{geoids,gravity,magnetic} with no arguments now + print the usage instead of loading the minimal sets. + - Utility::date(const std::string&, int&, int&, int&) and hence the + MagneticField utility accepts + the string "now" as a legal time (meaning today). + + - Version 1.38 + (released 2014-10-02) + - On MacOSX, the installed package is relocatable (for cmake version + 2.8.12 and later). + - On Mac OSX, GeographicLib can be installed using homebrew. + - In cmake builds under Windows, set the output directories so that + binaries and shared libraries are together. + - Accept the minus sign as a synonym for - in DMS.{cpp,js}. + - The cmake configuration file geographiclib-depends.cmake has been + renamed to geographiclib-targets.cmake. + - MATLAB/Octave routines for great ellipses added; see \ref + greatellipse. + - Provide man pages for geographiclib-get-{geoids,gravity,magnetic}. + + - Version 1.37 + (released 2014-08-08) + - Add \ref highprec. + - INCOMPATIBLE CHANGE: the static instantiations of various + classes for the WGS84 ellipsoid have been changed to a + + "construct on first use idiom". This avoids a lot of wasteful + initialization before the user's code starts. Unfortunately it + means that existing source code that relies on any of the following + static variables will need to be changed to a function call: + - AlbersEqualArea::AzimuthalEqualAreaNorth + - AlbersEqualArea::AzimuthalEqualAreaSouth + - AlbersEqualArea::CylindricalEqualArea + - Ellipsoid::WGS84 + - Geocentric::WGS84 + - Geodesic::WGS84 + - GeodesicExact::WGS84 + - LambertConformalConic::Mercator + - NormalGravity::GRS80 + - NormalGravity::WGS84 + - PolarStereographic::UPS + - TransverseMercator::UTM + - TransverseMercatorExact::UTM + . + Thus, occurrences of, for example, \code + const Geodesic& geod = Geodesic::WGS84; // version 1.36 and earlier + \endcode + need to be changed to \code + const Geodesic& geod = Geodesic::WGS84(); // version 1.37 and later + \endcode + (note the parentheses!); alternatively use \code + // works with all versions + const Geodesic geod(Constants::WGS84_a(), Constants::WGS84_a()); \endcode + - Incompatible change: the environment variables + {GEOID,GRAVITY,MAGNETIC}_{NAME,PATH} are now prefixed + with GEOGRAPHICLIB_. + - Incompatible change for Windows XP: retire the Windows XP common + data path. If you're still using Windows XP, then you might have + to move the folder C:\\Documents and Settings\\All + Users\\Application Data\\GeographicLib to + C:\\ProgramData\\GeographicLib. + - All macro names affecting the compilation now start with + GEOGRAPHICLIB_; this applies to + GEOID_DEFAULT_NAME, GRAVITY_DEFAULT_NAME, + MAGNETIC_DEFAULT_NAME, PGM_PIXEL_WIDTH, + HAVE_LONG_DOUBLE, STATIC_ASSERT, + WORDS_BIGENDIAN. + - Changes to PolygonArea: + - introduce PolygonAreaT which takes a geodesic class as a parameter; + - PolygonArea and PolygonAreaExact are typedef'ed to + PolygonAreaT and PolygonAreaT; + - add -E option to Planimeter to use + PolygonAreaExact; + - add -Q option to Planimeter to + calculate the area on the authalic sphere. + - Add -p option to Planimeter, + ConicProj, + GeodesicProj, + TransverseMercatorProj. + - Add Rhumb and RhumbLine classes and the + RhumbSolve utility; see \ref rhumb + for more information. + - Minor changes to NormalGravity: + - add NormalGravity::J2ToFlattening and NormalGravity::FlatteningToJ2; + - use Newton's method to determine \e f from \e J2; + - in constructor, allow \e omega = 0 (i.e., treat the spherical case). + - Add grs80 GravityModel, see \ref gravity. + - Make geographiclib-get-{geoids,gravity,magnetic} scripts work on MacOS. + - Minor changes: + - simplify cross-platform support for C++11 mathematical functions; + - change way area coefficients are given in GeodesicExact to improve + compile times; + - enable searching the online documentation; + - add macros GEOGRAPHICLIB_VERSION and + GEOGRAPHICLIB_VERSION_NUM; + - add solution and project files for Visual Studio Express 2010. + + - Version 1.36 + (released 2014-05-13) + - Changes to comply with NGA's prohibition of the use of the + upper-case letters N/S to designate the hemisphere when displaying + UTM/UPS coordinates: + - UTMUPS::DecodeZone allows north/south as hemisphere + designators (in addition to n/s); + - UTMUPS::EncodeZone now encodes the hemisphere in + lower case (to distinguish this use from a grid zone + designator); + - UTMUPS::EncodeZone takes an optional parameter \e + abbrev to indicate whether to use n/s or north/south as the + hemisphere designator; + - GeoCoords::UTMUPSRepresentation and + GeoCoords::AltUTMUPSRepresentation similarly accept + the \e abbrev parameter; + - GeoConvert uses the + flags -a and -l to govern whether UTM/UPS output uses n/s + (the -a flag) or north/south (the -l flag) to denote the + hemisphere; + - Fixed a bug what allowed +3N to be accepted as an alternative UTM + zone designation (instead of 3N). + . + WARNING: The use of lower case n/s for the hemisphere might + cause compatibility problems. However DecodeZone has always + accepted either case; so the issue will only arise with other + software reading the zone information. To avoid possible + misinterpretation of the zone designator, consider calling + EncodeZone with \e abbrev = false and GeoConvert with -l, so that + north/south are used to denote the hemisphere. + - MGRS::Forward with \e prec = -1 will produce a grid + zone designation. Similarly MGRS::Reverse will + decode a grid zone designation (and return \e prec = -1). + - Stop using the throw() declaration specification which is + deprecated in C++11. + - Add missing std:: qualifications to copy in LocalCartesion and + Geocentric headers (bug found by Clemens). + + - Version 1.35 + (released 2014-03-13) + - Fix blunder in UTMUPS::EncodeEPSG (found by Ben + Adler). + - MATLAB wrapper routines geodesic{direct,inverse,line} switch to + "exact" routes if |f| > 0.02. + - GeodSolve.cgi allows ellipsoid to be set (and uses the -E option + for GeodSolve). + - Set title in HTML versions of man pages for the \ref utilities. + - Changes in cmake support: + - add _d to names of executables in debug mode of Visual Studio; + - add support for Android (cmake-only), thanks to Pullan Yu; + - check CPACK version numbers supplied on command line; + - configured version of project-config.cmake.in is + project-config.cmake (instead of geographiclib-config.cmake), to + prevent find_package incorrectly using this file; + - fix tests with multi-line output; + - this release includes a file, pom.xml, which is used by an + experimental build system (based on maven) at SRI. + + - Version 1.34 + (released 2013-12-11) + - Many changes in cmake support: + - minimum version of cmake needed increased to 2.8.4 (which was + released in 2011-02); + - allow building both shared and static libraries with -D + GEOGRAPHICLIB_LIB_TYPE=BOTH; + - both shared and static libraries (Release plus Debug) included in + binary installer; + - find_package uses COMPONENTS and GeographicLib_USE_STATIC_LIBS to + select the library to use; + - find_package version checking allows nmake and Visual Studio + generators to interoperate on Windows; + - find_package (GeographicLib …) requires that GeographicLib be + capitalized correctly; + - on Unix/Linux, don't include the version number in directory for + the cmake configuration files; + - defaults for GEOGRAPHICLIB_DOCUMENTATION and + BUILD_NETGEOGRAPHICLIB are now OFF; + - the GEOGRAPHICLIB_EXAMPLES configuration parameter is no longer + used; cmake always configures to build the examples, but they are + not built by default (instead build targets: exampleprograms and + netexamples); + - matlab-all target renamed to matlabinterface; + - the configuration parameters PACKAGE_PATH and INSTALL_PATH are + now deprecated (use CMAKE_INSTALL_PREFIX instead); + - on Linux, the installed package is relocatable; + - on MacOSX, the installed utilities can find the shared library. + - Use a more precise value for OSGB::CentralScale(). + - Add Arc routines to Python interface. + - The Geod utility has been removed; the same functionality lives on + with GeodSolve (introduced in + version 1.30). + + - Version 1.33 + (released 2013-10-08) + - Add NETGeographic .NET wrapper library + (courtesy of Scott Heiman). + - Make inspector functions in Ellipsoid const. + - Add Accumulator.cpp to instantiate Accumulator. + - Defer some of the initialization of OSGB to when it + is first called. + - Fix bug in autoconf builds under MacOS. + + - Version 1.32 + (released 2013-07-12) + - Generalize C interface for polygon areas to allow vertices to be + specified incrementally. + - Fix way flags for C++11 support are determined. + + - Version 1.31 + (released 2013-07-01) + - Changes breaking binary compatibility (source compatibility is + maintained): + - overloaded versions of DMS::Encode, + EllipticFunction::EllipticFunction, and + GeoCoords::DMSRepresentation, have been eliminated + by the use of optional arguments; + - correct the declaration of first arg to + UTMUPS::DecodeEPSG. + - FIX BUG in GravityCircle constructor (found by + Mathieu Peyréga) which caused bogus results for the gravity + disturbance and gravity anomaly vectors. (This only affected + calculations using GravityCircle. GravityModel calculations did + not suffer from this bug.) + - Improvements to the build: + - add macros GEOGRAPHICLIB_VERSION_{MAJOR,MINOR,PATCH} to Config.h; + - fix documentation for new version of perlpod; + - improving setting of runtime path for Unix-like systems with cmake; + - install PDB files when compiling with Visual Studio to aid + debugging; + - Windows binary release now uses MATLAB R2013a (64-bit) and + uses the -largeArrayDims option. + - fixes to the way the MATLAB interface routines are built (thanks + to Phil Miller and Chris F.). + - Changes to the geodesic routines: + - add \ref java of the geodesic routines (thanks to Skip Breidbach + for the maven support); + - FIX BUG: avoid altering input args in Fortran implementation; + - more systematic treatment of very short geodesic; + - fixes to Python port so that they work with version 3.x, in + addition to 2.x (courtesy of Amato); + - accumulate the perimeter and area of polygons via a double-wide + accumulator in Fortran, C, and MATLAB implementations (this is + already included in the other implementations); + - port PolygonArea::AddEdge and + PolygonArea::TestEdge to JavaScript and Python + interfaces; + - include documentation on \ref geodshort. + - Unix scripts for downloading datasets, + geographiclib-get-{geoids,gravity,magnetic}, skip already download + models by default, unless the -f flag is given. + - FIX BUGS: meridian convergence and scale returned by + TransverseMercatorExact was wrong at a pole. + - Improve efficiency of MGRS::Forward by avoiding the + calculation of the latitude if possible (adapting an idea of Craig + Rollins). + - Fixes to the way the MATLAB interface routines are built (thanks to + Phil Miller and Chris F.). + + - Version 1.30 + (released 2013-02-27) + - Changes to geodesic routines: + - FIX BUG in fail-safe mechanisms in Geodesic::Inverse; + - the command line utility Geod is now called + GeodSolve; + - allow addition of polygon edges in PolygonArea; + - add full Maxima implementation of geodesic algorithms. + + - Version 1.29 + (released 2013-01-16) + - Changes to allow compilation with libc++ (courtesy of Kal Conley). + - Add description of \ref triaxial to documentation. + - Update journal reference for "Algorithms for geodesics". + + - Version 1.28 + (released 2012-12-11) + - Changes to geodesic routines: + - compute longitude difference exactly; + - hence FIX BUG in area calculations for polygons with vertices very + close to the prime meridian; + - FIX BUG is geoddistance.m where the value of m12 was wrong for + meridional geodesics; + - add MATLAB implementations of the geodesic projections; + - remove unneeded special code for geodesics which start at a pole; + - include polygon area routine in C and Fortran implementations; + - add doxygen documentation for C and Fortran libraries. + + - Version 1.27 + (released 2012-11-29) + - Changes to geodesic routines: + - add native MATLAB implementations: geoddistance.m, geodreckon.m, + geodarea.m; + - add C and Fortran implementations; + - improve the solution of the direct problem so that the series + solution is accurate to round off for |f| < 1/50; + - tighten up the convergence criteria for solution of the inverse + problem; + - no longer signal failures of convergence with NaNs (a slightly + less accurate answer is returned instead). + - Fix DMS::Decode double rounding BUG. + - On MacOSX platforms with the cmake configuration, universal + binaries are built. + + - Version 1.26 + (released 2012-10-22) + - Replace the series used for geodesic areas by one with better + convergence (this only makes an appreciable difference if + |f| > 1/150). + + - Version 1.25 + (released 2012-10-16) + - Changes to geodesic calculations: + - restart Newton's method in Geodesic::Inverse when it goes awry; + - back up Newton's method with the bisection method; + - Geodesic::Inverse now converges for any value of \e f; + - add GeodesicExact and GeodesicLineExact which are formulated in + terms of elliptic integrals and thus yield accurate results even + for very eccentric ellipsoids; + - the -E option to Geod invokes these + exact classes. + - Add functionality to EllipticFunction: + - add all the traditional elliptic integrals; + - remove restrictions on argument range for incomplete elliptic integrals; + - allow imaginary modulus for elliptic integrals and elliptic functions; + - make interface to the symmetric elliptic integrals public. + - Allow Ellipsoid to be copied. + - Changes to the build tools: + - cmake uses folders in Visual Studio to reduce clutter; + - allow precision of reals to be set in cmake; + - fail gracefully in the absence of pod documentation tools; + - remove support for maintainer tasks in Makefile.mk; + - upgrade to automake 1.11.6 to fix the "make distcheck" security + vulnerability; see + https://cve.mitre.org/cgi-bin/cvename.cgi?name=CVE-2012-3386 + + - Version 1.24 + (released 2012-09-22) + - Allow the specification of the hemisphere in UTM coordinates in + order to provide continuity across the equator: + - add UTMUPS::Transfer; + - add GeoCoords::UTMUPSRepresentation(bool, int) and + GeoCoords::AltUTMUPSRepresentation(bool, int); + - use the hemisphere letter in, e.g., + GeoConvert -u -z 31n. + - Add UTMUPS::DecodeEPSG and + UTMUPS::EncodeEPSG. + - cmake changes: + - restore support for cmake 2.4.x; + - explicitly check version of doxygen. + - Fix building under cygwin. + - Document restrictions on \e f in \ref intro. + - Fix Python interface to work with version 2.6.x. + + - Version 1.23 + (released 2012-07-17) + - Documentation changes: + - remove html documentation from distribution and use web links if + doxygen is not available; + - use doxygen tags to document exceptions; + - begin migrating the documentation to using Greek letters where + appropriate (requires doxygen 1.8.1.2 or later). + - Add Math::AngNormalize and + Math::AngNormalize2; the allowed range for longitudes + and azimuths widened to [−540°, 540°). + - DMS::Decode understands more unicode symbols. + - Geohash uses geohash code "nan" to stand for not a + number. + - Add Ellipsoid::NormalCurvatureRadius. + - Various fixes in LambertConformalConic, + TransverseMercator, + PolarStereographic, and Ellipsoid to + handle reverse projections of points near infinity. + - Fix programming blunder in LambertConformalConic::Forward + (incorrect results were returned if the tangent latitude was + negative). + + - Version 1.22 + (released 2012-05-27) + - Add Geohash and Ellipsoid classes. + - FIX BUG in AlbersEqualArea for very prolate + ellipsoids (b2 > 2 a2). + - cmake changes: + - optionally use PACKAGE_PATH and INSTALL_PATH to determine + CMAKE_INSTALL_PREFIX; + - use COMMON_INSTALL_PATH to determine layout of installation + directories; + - as a consequence, the installation paths for the documentation, + and Python and MATLAB interfaces are shortened for Windows; + - zip source distribution now uses DOS line endings; + - the tests work in debug mode for Windows; + - default setting of GEOGRAPHICLIB_DATA does not depend on + CMAKE_INSTALL_PREFIX; + - add a cmake configuration for build tree. + + - Version 1.21 + (released 2012-04-25) + - Support colon-separated DMS output: + - DMS::Encode and + GeoCoords::DMSRepresentation generalized; + - GeoConvert and + Geod now accept a -: option. + - GeoidEval does not print the gradient + of the geoid height by default (because it's subject to large + errors); give the -g option to get the gradient printed. + - Work around optimization BUG in Geodesic::Inverse + with tdm mingw g++ version 4.6.1. + - autoconf fixed to ensure that that out-of-sources builds work; + document this as the preferred method of using autoconf. + - cmake tweaks: + - simplify the configuration of doxygen; + - allow the MATLAB compiler to be specified with the + MATLAB_COMPILER option. + + - Version 1.20 + (released 2012-03-23) + - cmake tweaks: + - improve find_package's matching of compiler versions; + - CMAKE_INSTALL_PREFIX set from CMAKE_PREFIX_PATH if available; + - add "x64" to the package name for the 64-bit binary installer; + - fix cmake warning with Visual Studio Express. + - Fix SphericalEngine to deal with aggressive iterator + checking by Visual Studio. + - Fix transcription BUG is Geodesic.js. + + - Version 1.19 + (released 2012-03-13) + - Slight improvement in Geodesic::Inverse for very + short lines. + - Fix argument checking tests in MGRS::Forward. + - Add \--comment-delimiter and \--line-separator options to the \ref + utilities. + - Add installer for 64-bit Windows; the compiled MATLAB interface is + supplied with the Windows 64-bit installer only. + + - Version 1.18 + (released 2012-02-18) + - Improve documentation on configuration with cmake. + - cmake's find_package ensures that the compiler versions match on Windows. + - Improve documentation on compiling MATLAB interface. + - Binary installer for Windows installs under C:/pkg-vc10 by default. + + - Version 1.17 + (released 2012-01-21) + - Work around optimization BUG in Geodesic::Inverse + with g++ version 4.4.0 (mingw). + - Fix BUG in argument checking with OSGB::GridReference. + - Fix missing include file in SphericalHarmonic2. + - Add simple examples of usage for each class. + - Add internal documentation to the cmake configuration files. + + - Version 1.16 + (released 2011-12-07) + - Add calculation of the earth's gravitational field: + - add NormalGravity GravityModel and + GravityCircle classes; + - add command line utility + Gravity; + - add \ref gravity; + - add Constants::WGS84_GM(), Constants::WGS84_omega(), and + similarly for GRS80. + - Build uses GEOGRAPHICLIB_DATA to specify a common parent directory + for geoid, gravity, and magnetic data (instead of + GEOGRAPHICLIB_GEOID_PATH, etc.); similarly, + GeoidEval, + Gravity, and + MagneticField, look at the + environment variable GEOGRAPHICLIB_DATA to locate the data. + - Spherical harmonic software changes: + - capitalize enums SphericalHarmonic::FULL and + SphericalHarmonic::SCHMIDT (the lower case names + are retained but deprecated); + - optimize the sum by using a static table of square roots which is + updated by SphericalEngine::RootTable; + - avoid overflow for high degree models. + - Magnetic software fixes: + - fix documentation BUG in MagneticModel::Circle; + - make MagneticModel constructor explicit; + - provide default MagneticCircle constructor; + - add additional inspector functions to + MagneticCircle; + - add -c option to MagneticField; + - default height to zero in + MagneticField. + + - Version 1.15 + (released 2011-11-08) + - Add calculation of the earth's magnetic field: + - add MagneticModel and MagneticCircle + classes; + - add command line utility + MagneticField; + - add \ref magnetic; + - add \ref magneticinst; + - add \ref magneticformat; + - add classes SphericalEngine, + CircularEngine, SphericalHarmonic, + SphericalHarmonic1, and + SphericalHarmonic2. which sum spherical harmonic + series. + - Add Utility class to support I/O and date + manipulation. + - Cmake configuration includes a _d suffix on the library built in + debug mode. + - For the Python package, include manifest and readme files; don't + install setup.py for non-Windows systems. + - Include Doxygen tag file in distribution as doc/html/Geographic.tag. + + - Version 1.14 + (released 2011-09-30) + - Ensure that geographiclib-config.cmake is relocatable. + - Allow more unicode symbols to be used in DMS::Decode. + - Modify GeoidEval so that it can be + used to convert the height datum for LIDAR data. + - Modest speed-up of Geodesic::Inverse. + - Changes in Python interface: + - FIX BUG in transcription of Geodesic::Inverse; + - include setup.py for easy installation; + - Python only distribution is available at + https://pypi.python.org/pypi/geographiclib + - Supply a minimal Qt qmake project file for library + src/Geographic.pro. + + - Version 1.13 + (released 2011-08-13) + - Changes to I/O: + - allow : (colon) to be used as a DMS separator in + DMS::Decode(const std::string&, flag&); + - also accept Unicode symbols for degrees, minutes, and seconds + (coded as UTF-8); + - provide optional \e swaplatlong argument to various + DMS and GeoCoords functions to make + longitude precede latitude; + - GeoConvert now has a -w option to + make longitude precede latitude on input and output; + - include a JavaScript version of DMS. + - Slight improvement in starting guess for solution of geographic + latitude in terms of conformal latitude in TransverseMercator, + TransverseMercatorExact, and LambertConformalConic. + - For most classes, get rid of const member variables so that the + default copy assignment works. + - Put Math and Accumulator in their own + header files. + - Remove unused "fast" Accumulator method. + - Reorganize the \ref python. + - Withdraw some deprecated routines. + - cmake changes: + - include FindGeographic.cmake in distribution; + - building with cmake creates and installs + geographiclib-config.cmake; + - better support for building a shared library under Windows. + + - Version 1.12 + (released 2011-07-21) + - Change license to MIT/X11. + - Add PolygonArea class and equivalent MATLAB function. + - Provide JavaScript and Python implementations of geodesic routines. + - Fix Windows installer to include runtime dlls for MATLAB. + - Fix (innocuous) unassigned variable in Geodesic::GenInverse. + - Geodesic routines in MATLAB return a12 as first column of aux return + value (incompatible change). + - A couple of code changes to enable compilation with Visual + Studio 2003. + + - Version 1.11 + (released 2011-06-27) + - Changes to Planimeter: + - add -l flag to Planimeter for polyline + calculations; + - trim precision of area to 3 decimal places; + - FIX BUG with pole crossing edges (due to compiler optimization). + - Geod no longer reports the reduced + length by default; however the -f flag still reports this and in + addition gives the geodesic scales and the geodesic area. + - FIX BUGS (compiler-specific) in inverse geodesic calculations. + - FIX BUG: accommodate tellg() returning −1 at end of string. + - Change way flattening of the ellipsoid is specified: + - constructors take \e f argument which is taken to be the + flattening if \e f < 1 and the inverse flattening otherwise + (this is a compatible change for spheres and oblate ellipsoids, but it + is an INCOMPATIBLE change for prolate ellipsoids); + - the -e arguments to the \ref utilities are handled similarly; in + addition, simple fractions, e.g., 1/297, can be used for the + flattening; + - introduce Constants::WGS84_f() for the WGS84 + flattening (and deprecate Constants::WGS84_r() for the inverse + flattening); + - most classes have a Flattening() member function; + - InverseFlattening() has been deprecated (and now returns inf for a + sphere, instead of 0). + + - Version 1.10 + (released 2011-06-11) + - Improvements to MATLAB/Octave interface: + - add {geocentric,localcartesian}{forward,reverse}; + - make geographiclibinterface more general; + - install the source for the interface; + - cmake compiles the interface if ENABLE_MATLAB=ON; + - include compiled interface with Windows binary installer. + - Fix various configuration issues + - autoconf did not install Config.h; + - cmake installed in man/man1 instead of share/man/man1; + - cmake did not set the rpath on the tools. + + - Version 1.9 + (released 2011-05-28) + - FIX BUG in area returned by + Planimeter for pole encircling polygons. + - FIX BUG in error message reported when DMS::Decode reads the string + "5d.". + - FIX BUG in AlbersEqualArea::Reverse (lon0 not being used). + - Ensure that all exceptions thrown in the \ref utilities are caught. + - Avoid using catch within DMS. + - Move Accumulator class from Planimeter.cpp to + Constants.hpp. + - Add Math::sq. + - Simplify \ref geoidinst + - add geographiclib-get-geoids for Unix-like systems; + - add installers for Windows. + - Provide cmake support: + - build binary installer for Windows; + - include regression tests; + - add \--input-string, \--input-file, \--output-file options to the + \ref utilities to support tests. + - Rename utility EquidistantTest as + GeodesicProj and TransverseMercatorTest as + TransverseMercatorProj. + - Add ConicProj. + - Reverse the initial sense of the -s option for + Planimeter. + - Migrate source from subversion to git. + + - Version 1.8 + (released 2011-02-22) + - Optionally return rotation matrix from Geocentric and + LocalCartesian. + - For the \ref utilities, supply man pages, -h prints the synopsis, + \--help prints the man page, \--version prints the version. + - Use accurate summation in Planimeter. + - Add 64-bit targets for Visual Studio 2010. + - Use templates for defining math functions and some constants. + - Geoid updates + - Add Geoid::DefaultGeoidPath and + Geoid::DefaultGeoidName; + - GeoidEval uses environment variable + GEOGRAPHICLIB_GEOID_NAME as the default geoid; + - Add \--msltohae and \--haetomsl as + GeoidEval options (and don't + document the single hyphen versions). + - Remove documentation that duplicates papers on transverse Mercator + and geodesics. + + - Version 1.7 + (released 2010-12-21) + - FIX BUG in scale returned by LambertConformalConic::Reverse. + - Add AlbersEqualArea projection. + - Library created by Visual Studio is Geographic.lib instead of + GeographicLib.lib (compatible with makefiles). + - Make classes NaN aware. + - Use cell arrays for MGRS strings in MATLAB. + - Add solution/project files for Visual Studio 2010 (32-bit only). + - Use C++11 static_assert and math functions, if available. + + - Version 1.6 + (released 2010-11-23) + - FIX BUG introduced in Geoid in version 1.5 (found by + Dave Edwards). + + - Version 1.5 + (released 2010-11-19) + - Improve area calculations for small polygons. + - Add -s and -r flags to Planimeter. + - Improve the accuracy of LambertConformalConic using + divided differences. + - FIX BUG in meridian convergence returned by + LambertConformalConic::Forward. + - Add optional threadsafe parameter to Geoid + constructor. WARNING: This changes may break binary compatibility + with previous versions of GeographicLib. However, the library is + source compatible. + - Add OSGB. + - MATLAB and Octave interfaces to UTMUPS, + MGRS, Geoid, Geodesic + provided. + - Minor changes + - explicitly turn on optimization in Visual Studio 2008 projects; + - add missing dependencies in some Makefiles; + - move pi() and degree() from Constants to + Math; + - introduce Math::extended type to aid testing; + - add Math::epi() and Math::edegree(). + - fixes to compile under cygwin; + - tweak expression used to find latitude from conformal latitude. + + - Version 1.4 + (released 2010-09-12) + - Changes to Geodesic and GeodesicLine: + - FIX BUG in Geodesic::Inverse with prolate ellipsoids; + - add area computations to Geodesic::Direct and Geodesic::Inverse; + - add geodesic areas to geodesic test set; + - make GeodesicLine constructor public; + - change longitude series in Geodesic into Helmert-like form; + - ensure that equatorial geodesics have cos(alpha0) = 0 identically; + - generalize interface for Geodesic and GeodesicLine; + - split GeodesicLine and Geodesic into different files; + - signal convergence failure in Geodesic::Inverse with NaNs; + - deprecate one function in Geodesic and two functions in + GeodesicLine; + - deprecate -n option for Geod. + . + WARNING: These changes may break binary compatibility with + previous versions of GeographicLib. However, the library is + source compatible (with the proviso that + GeographicLib/GeodesicLine.hpp may now need to be included). + - Add the Planimeter utility for + computing the areas of geodesic polygons. + - Improve iterative solution of Gnomonic::Reverse. + - Add Geoid::ConvertHeight. + - Add -msltohae, -haetomsl, and -z options to + GeoidEval. + - Constructors check that minor radius is positive. + - Add overloaded Forward and Reverse functions to the projection + classes which don't return the convergence (or azimuth) and scale. + - Document function parameters and return values consistently. + + - Version 1.3 + (released 2010-07-21) + - Add Gnomonic, the ellipsoid generalization of the + gnomonic projection. + - Add -g and -e options to + EquidistantTest. + - Use fixed-point notation for output from + CartConvert, + EquidistantTest, + TransverseMercatorTest. + - PolarStereographic: + - Improved conversion to conformal coordinates; + - Fix bug with scale at opposite pole; + - Complain if latitude out of range in SetScale. + - Add Math::NaN(). + - Add long double version of hypot for Windows. + - Add EllipticFunction::E(real). + - Update references to Geotrans in MGRS documentation. + - Speed up tmseries.mac. + + - Version 1.2 + (released 2010-05-21) + - FIX BUGS in Geodesic, + - wrong azimuth returned by Direct if point 2 is on a pole; + - Inverse sometimes fails with very close points. + - Improve calculation of scale in CassiniSoldner, + - add GeodesicLine::Scale, + GeodesicLine::EquatorialAzimuth, and + GeodesicLine::EquatorialArc; + - break friend connection between CassiniSoldner and Geodesic. + - Add DMS::DecodeAngle and + DMS::DecodeAzimuth. Extend + DMS::Decode and DMS::Encode to deal + with distances. + - Code and documentation changes in Geodesic and + Geocentric for consistency with + the forthcoming paper on geodesics. + - Increase order of series using in Geodesic to 6 (full + accuracy maintained for ellipsoid flattening < 0.01). + - Macro __NO_LONG_DOUBLE_MATH to disable use of long double. + - Correct declaration of Math::isfinite to return a bool. + - Changes in the \ref utilities, + - improve error reporting when parsing command line arguments; + - accept latitudes and longitudes in decimal degrees or degrees, + minutes, and seconds, with optional hemisphere designators; + - GeoConvert -z accepts zone or + zone+hemisphere; + - GeoidEval accepts any of the input + formats used by GeoConvert; + - CartConvert allows the ellipsoid + to be specified with -e. + + - Version 1.1 + (released 2010-02-09) + - FIX BUG (introduced in 2009-03) in EllipticFunction::E(sn,cn,dn). + - Increase accuracy of scale calculation in TransverseMercator and + TransverseMercatorExact. + - Code and documentation changes for consistency with + arXiv:1002.1417 + + - Version 1.0 + (released 2010-01-07) + - Add autoconf configuration files. + - BUG FIX: Improve initial guess for Newton's method in + PolarStereographic::Reverse. (Previously this failed to converge + when the co-latitude exceeded about 130 deg.) + - Constructors for TransverseMercator, TransverseMercatorExact, + PolarStereographic, Geocentric, and Geodesic now check for obvious + problems with their arguments and throw an exception if necessary. + - Most classes now include inspector functions such as MajorRadius() + so that you can determine how instances were constructed. + - Add LambertConformalConic class. + - Add PolarStereographic::SetScale to allow the + latitude of true scale to be specified. + - Add solution and project files for Visual Studio 2008. + - Add GeographicErr for exceptions. + - Geoid changes: + - BUG FIX: fix typo in Geoid::Cache which could cause + a segmentation fault in some cases when the cached area spanned + the prime meridian. + - Include sufficient edge data to allow heights to be returned for + cached area without disk reads; + - Add inspector functions to query the extent of the cache. + + - Version 2009-11 + (released 2009-11-03) + - Allow specification of "closest UTM zone" in UTMUPS + and GeoConvert (via -t option). + - Utilities now complain is there are too many tokens on input lines. + - Include real-to-real versions of DMS::Decode and + DMS::Encode. + - More house-cleaning changes: + - Ensure that functions which return results through reference + arguments do not alter the arguments when an exception is thrown. + - Improve accuracy of MGRS::Forward. + - Include more information in some error messages. + - Improve accuracy of inverse hyperbolic functions. + - Fix the way Math functions handle different precisions. + + - Version 2009-10 + (released 2009-10-18) + - Change web site to https://geographiclib.sourceforge.io + - Several house-cleaning changes: + - Change from the a flat directory structure to a more easily + maintained one. + - Introduce Math class for common mathematical functions (in + Constants.hpp). + - Use Math::real as the type for all real quantities. By default this + is typedef'ed to double; and the library should be installed this + way. + - Eliminate const reference members of AzimuthalEquidistant, + CassiniSoldner and LocalCartesian so that they may be copied. + - Make several constructors explicit. Disallow some constructors. + Disallow copy constructor/assignment for Geoid. + - Document least squares formulas in Geoid.cpp. + - Use unsigned long long for files positions of geoid files in Geoid. + - Introduce optional mgrslimits argument in UTMUPS::Forward and + UTMUPS::Reverse to enforce stricter MGRS limits on eastings and + northings. + - Add 64-bit targets in Visual Studio project files. + + - Version 2009-09 + (released 2009-09-01) + - Add Geoid and + GeoidEval utility. + + - Version 2009-08 + (released 2009-08-14) + - Add CassiniSoldner class and + EquidistantTest utility. + - Fix bug in Geodesic::Inverse where NaNs were + sometimes returned. + - INCOMPATIBLE CHANGE: AzimuthalEquidistant now returns the reciprocal + of the azimuthal scale instead of the reduced length. + - Add -n option to GeoConvert. + + - Version 2009-07 + (released 2009-07-16) + - Speed up the series inversion code in tmseries.mac and geod.mac. + - Reference Borkowski in section on \ref geocentric. + + - Version 2009-06 + (released 2009-06-01) + - Add routines to decode and encode zone+hemisphere to UTMUPS. + - Clean up code in Geodesic. + + - Version 2009-05 + (released 2009-05-01) + - Improvements to Geodesic: + - more economical series expansions, + - return reduced length (as does the + Geod utility), + - improved calculation of starting point for inverse method, + - use reduced length to give derivative for Newton's method. + - Add AzimuthalEquidistant class. + - Make Geocentric, TransverseMercator, + and PolarStereographic classes work with prolate + ellipsoids. + - CartConvert checks its inputs more + carefully. + - Remove reference to defunct Constants.cpp from GeographicLib.vcproj. + + - Version 2009-04 + (released 2009-04-01) + - Use compile-time constants to select the order of series in + TransverseMercator. + - 2x unroll of Clenshaw summation to avoid data shuffling. + - Simplification of EllipticFunction::E. + - Use STATIC_ASSERT for compile-time checking of constants. + - Improvements to Geodesic: + - compile-time option to change order of series used, + - post Maxima code for generating the series, + - tune the order of series for double, + - improvements in the selection of starting points for Newton's + method, + - accept and return spherical arc lengths, + - works with both oblate and prolate ellipsoids, + - add -a, -e, -b options to the Geod + utility. + + - Version 2009-03 + (released 2009-03-01) + - Add Geodesic and the + Geod utility. + - Declare when no exceptions are thrown by functions. + - Minor changes to DMS class. + - Use invf = 0 to mean a sphere in constructors to some classes. + - The makefile creates a library and includes an install target. + - Rename ECEF to Geocentric, ECEFConvert + to CartConvert. + - Use inline functions to define constant doubles in Constants.hpp. + + - Version 2009-02 + (released 2009-01-30) + - Fix documentation of constructors (flattening → inverse + flattening). + - Use std versions of math functions. + - Add ECEF and LocalCartesian classes + and the ECEFConvert utility. + - Gather the documentation on the \ref utilities onto one page. + + - Version 2009-01 + (released 2009-01-12) + - First proper release of library. + - More robust TransverseMercatorExact: + - Introduce \e extendp version of constructor, + - Test against extended test data, + - Optimize starting positions for Newton's method, + - Fix behavior near all singularities, + - Fix order dependence in C++ start-up code, + - Improved method of computing scale and convergence. + - Documentation on transverse Mercator projection. + - Add MGRS, UTMUPS, etc. + + - Version 2008-09 + - Ad hoc posting of information on the transverse Mercator projection. + +
+Back to \ref highprec. Up to \ref contents. +
+**********************************************************************/ +} diff --git a/gtsam/3rdparty/GeographicLib/doc/Makefile.am b/gtsam/3rdparty/GeographicLib/doc/Makefile.am index 84c8ccc87..d1832930f 100644 --- a/gtsam/3rdparty/GeographicLib/doc/Makefile.am +++ b/gtsam/3rdparty/GeographicLib/doc/Makefile.am @@ -1,26 +1,16 @@ EXTRAFILES = $(srcdir)/tmseries30.html $(srcdir)/geodseries30.html -FIGURES = $(srcdir)/gauss-krueger-graticule.png \ +FIGURES = \ + $(srcdir)/gauss-krueger-graticule.png \ $(srcdir)/thompson-tm-graticule.png \ $(srcdir)/gauss-krueger-convergence-scale.png \ $(srcdir)/gauss-schreiber-graticule-a.png \ $(srcdir)/gauss-krueger-graticule-a.png \ $(srcdir)/thompson-tm-graticule-a.png \ $(srcdir)/gauss-krueger-error.png \ - $(srcdir)/meridian-measures.png - -SCRIPTDRIVERS = \ - $(srcdir)/scripts/geod-calc.html \ - $(srcdir)/scripts/geod-google.html \ - $(srcdir)/scripts/geod-google-instructions.html - -JSSCRIPTS = \ - $(srcdir)/scripts/GeographicLib/Math.js \ - $(srcdir)/scripts/GeographicLib/Geodesic.js \ - $(srcdir)/scripts/GeographicLib/GeodesicLine.js \ - $(srcdir)/scripts/GeographicLib/PolygonArea.js \ - $(srcdir)/scripts/GeographicLib/DMS.js \ - $(srcdir)/scripts/GeographicLib/Interface.js + $(srcdir)/meridian-measures.png \ + $(srcdir)/normal-gravity-potential-1.svg \ + $(srcdir)/vptree.gif HPPFILES = \ $(top_srcdir)/include/GeographicLib/Accumulator.hpp \ @@ -31,14 +21,16 @@ HPPFILES = \ $(top_srcdir)/include/GeographicLib/DMS.hpp \ $(top_srcdir)/include/GeographicLib/Ellipsoid.hpp \ $(top_srcdir)/include/GeographicLib/EllipticFunction.hpp \ - $(top_srcdir)/include/GeographicLib/Geocentric.hpp \ + $(top_srcdir)/include/GeographicLib/GARS.hpp \ $(top_srcdir)/include/GeographicLib/GeoCoords.hpp \ + $(top_srcdir)/include/GeographicLib/Geocentric.hpp \ $(top_srcdir)/include/GeographicLib/Geodesic.hpp \ $(top_srcdir)/include/GeographicLib/GeodesicExact.hpp \ $(top_srcdir)/include/GeographicLib/GeodesicLine.hpp \ $(top_srcdir)/include/GeographicLib/GeodesicLineExact.hpp \ $(top_srcdir)/include/GeographicLib/Geohash.hpp \ $(top_srcdir)/include/GeographicLib/Geoid.hpp \ + $(top_srcdir)/include/GeographicLib/Georef.hpp \ $(top_srcdir)/include/GeographicLib/Gnomonic.hpp \ $(top_srcdir)/include/GeographicLib/LambertConformalConic.hpp \ $(top_srcdir)/include/GeographicLib/LocalCartesian.hpp \ @@ -58,12 +50,14 @@ ALLSOURCES = \ $(top_srcdir)/src/DMS.cpp \ $(top_srcdir)/src/Ellipsoid.cpp \ $(top_srcdir)/src/EllipticFunction.cpp \ - $(top_srcdir)/src/Geocentric.cpp \ + $(top_srcdir)/src/GARS.cpp \ $(top_srcdir)/src/GeoCoords.cpp \ + $(top_srcdir)/src/Geocentric.cpp \ $(top_srcdir)/src/Geodesic.cpp \ $(top_srcdir)/src/GeodesicLine.cpp \ $(top_srcdir)/src/Geohash.cpp \ $(top_srcdir)/src/Geoid.cpp \ + $(top_srcdir)/src/Georef.cpp \ $(top_srcdir)/src/Gnomonic.cpp \ $(top_srcdir)/src/LambertConformalConic.cpp \ $(top_srcdir)/src/LocalCartesian.cpp \ @@ -94,20 +88,9 @@ MANPAGES = \ ../man/Gravity.1.html \ ../man/MagneticField.1.html \ ../man/Planimeter.1.html \ + ../man/RhumbSolve.1.html \ ../man/TransverseMercatorProj.1.html -LEGACYFILES = \ - $(top_srcdir)/legacy/C/geodesic.c \ - $(top_srcdir)/legacy/C/geodesic.h \ - $(top_srcdir)/legacy/C/direct.c \ - $(top_srcdir)/legacy/C/inverse.c \ - $(top_srcdir)/legacy/C/planimeter.c \ - $(top_srcdir)/legacy/Fortran/geodesic.for \ - $(top_srcdir)/legacy/Fortran/geodesic.inc \ - $(top_srcdir)/legacy/Fortran/geoddirect.for \ - $(top_srcdir)/legacy/Fortran/geodinverse.for \ - $(top_srcdir)/legacy/Fortran/planimeter.for - doc: html/index.html if HAVE_DOXYGEN @@ -116,21 +99,16 @@ manpages: $(MANPAGES) cp $^ html/ touch $@ -html/index.html: manpages doxyfile.in GeographicLib.dox \ - $(HPPFILES) $(ALLSOURCES) $(EXTRAFILES) $(FIGURES) \ - doxyfile-c.in geodesic-c.dox doxyfile-for.in geodesic-for.dox \ - $(LEGACYFILES) +html/index.html: manpages doxyfile.in GeographicLib.dox.in \ + $(HPPFILES) $(ALLSOURCES) $(EXTRAFILES) $(FIGURES) cp -p $(EXTRAFILES) $(top_srcdir)/maxima/*.mac \ $(top_srcdir)/LICENSE.txt html/ + sed -e "s%@PROJECT_VERSION@%$(VERSION)%g" \ + $(srcdir)/GeographicLib.dox.in > GeographicLib.dox sed -e "s%@PROJECT_SOURCE_DIR@%$(top_srcdir)%g" \ + -e "s%@PROJECT_BINARY_DIR@%..%g" \ -e "s%@PROJECT_VERSION@%$(VERSION)%g" \ $(srcdir)/doxyfile.in | $(DOXYGEN) - - sed -e "s%@PROJECT_SOURCE_DIR@%$(top_srcdir)%g" \ - -e "s%@PROJECT_VERSION@%$(VERSION)%g" \ - $(srcdir)/doxyfile-c.in | $(DOXYGEN) - - sed -e "s%@PROJECT_SOURCE_DIR@%$(top_srcdir)%g" \ - -e "s%@PROJECT_VERSION@%$(VERSION)%g" \ - $(srcdir)/doxyfile-for.in | $(DOXYGEN) - else html/index.html: index.html.in utilities.html.in if test -d html; then rm -rf html/*; else mkdir html; fi @@ -144,17 +122,11 @@ endif maintainer-clean-local: rm -rf html manpages +htmldir=$(DESTDIR)$(docdir)/html + install-doc: html/index.html - $(INSTALL) -d $(DESTDIR)$(docdir)/html - $(INSTALL) -m 644 `dirname $<`/*.* $(DESTDIR)$(docdir)/html - -test -f `dirname $<`/C/index.html && \ - $(INSTALL) -d $(DESTDIR)$(docdir)/html/C && \ - $(INSTALL) -m 644 `dirname $<`/C/*.* $(DESTDIR)$(docdir)/html/C - -test -f `dirname $<`/Fortran/index.html && \ - $(INSTALL) -d $(DESTDIR)$(docdir)/html/Fortran && \ - $(INSTALL) -m 644 `dirname $<`/Fortran/*.* \ - $(DESTDIR)$(docdir)/html/Fortran - $(INSTALL) -d $(DESTDIR)$(docdir)/scripts - $(INSTALL) -m 644 $(SCRIPTDRIVERS) $(DESTDIR)$(docdir)/scripts - $(INSTALL) -d $(DESTDIR)$(docdir)/scripts/GeographicLib - $(INSTALL) -m 644 $(JSSCRIPTS) $(DESTDIR)$(docdir)/scripts/GeographicLib + $(INSTALL) -d $(htmldir) + $(INSTALL) -m 644 `dirname $<`/*.* $(htmldir) + -test -f `dirname $<`/search/search.js && \ + $(INSTALL) -d $(htmldir)/search && \ + $(INSTALL) -m 644 `dirname $<`/search/*.* $(htmldir)/search || true diff --git a/gtsam/3rdparty/GeographicLib/doc/Makefile.in b/gtsam/3rdparty/GeographicLib/doc/Makefile.in index 859662692..7a4f60e41 100644 --- a/gtsam/3rdparty/GeographicLib/doc/Makefile.in +++ b/gtsam/3rdparty/GeographicLib/doc/Makefile.in @@ -1,7 +1,7 @@ -# Makefile.in generated by automake 1.12.2 from Makefile.am. +# Makefile.in generated by automake 1.15 from Makefile.am. # @configure_input@ -# Copyright (C) 1994-2012 Free Software Foundation, Inc. +# Copyright (C) 1994-2014 Free Software Foundation, Inc. # This Makefile.in is free software; the Free Software Foundation # gives unlimited permission to copy and/or distribute it, @@ -14,23 +14,61 @@ @SET_MAKE@ VPATH = @srcdir@ -am__make_dryrun = \ - { \ - am__dry=no; \ +am__is_gnu_make = { \ + if test -z '$(MAKELEVEL)'; then \ + false; \ + elif test -n '$(MAKE_HOST)'; then \ + true; \ + elif test -n '$(MAKE_VERSION)' && test -n '$(CURDIR)'; then \ + true; \ + else \ + false; \ + fi; \ +} +am__make_running_with_option = \ + case $${target_option-} in \ + ?) ;; \ + *) echo "am__make_running_with_option: internal error: invalid" \ + "target option '$${target_option-}' specified" >&2; \ + exit 1;; \ + esac; \ + has_opt=no; \ + sane_makeflags=$$MAKEFLAGS; \ + if $(am__is_gnu_make); then \ + sane_makeflags=$$MFLAGS; \ + else \ case $$MAKEFLAGS in \ *\\[\ \ ]*) \ - echo 'am--echo: ; @echo "AM" OK' | $(MAKE) -f - 2>/dev/null \ - | grep '^AM OK$$' >/dev/null || am__dry=yes;; \ - *) \ - for am__flg in $$MAKEFLAGS; do \ - case $$am__flg in \ - *=*|--*) ;; \ - *n*) am__dry=yes; break;; \ - esac; \ - done;; \ + bs=\\; \ + sane_makeflags=`printf '%s\n' "$$MAKEFLAGS" \ + | sed "s/$$bs$$bs[$$bs $$bs ]*//g"`;; \ esac; \ - test $$am__dry = yes; \ - } + fi; \ + skip_next=no; \ + strip_trailopt () \ + { \ + flg=`printf '%s\n' "$$flg" | sed "s/$$1.*$$//"`; \ + }; \ + for flg in $$sane_makeflags; do \ + test $$skip_next = yes && { skip_next=no; continue; }; \ + case $$flg in \ + *=*|--*) continue;; \ + -*I) strip_trailopt 'I'; skip_next=yes;; \ + -*I?*) strip_trailopt 'I';; \ + -*O) strip_trailopt 'O'; skip_next=yes;; \ + -*O?*) strip_trailopt 'O';; \ + -*l) strip_trailopt 'l'; skip_next=yes;; \ + -*l?*) strip_trailopt 'l';; \ + -[dEDm]) skip_next=yes;; \ + -[JT]) skip_next=yes;; \ + esac; \ + case $$flg in \ + *$$target_option*) has_opt=yes; break;; \ + esac; \ + done; \ + test $$has_opt = yes +am__make_dryrun = (target_option=n; $(am__make_running_with_option)) +am__make_keepgoing = (target_option=k; $(am__make_running_with_option)) pkgdatadir = $(datadir)/@PACKAGE@ pkgincludedir = $(includedir)/@PACKAGE@ pkglibdir = $(libdir)/@PACKAGE@ @@ -51,18 +89,30 @@ build_triplet = @build@ host_triplet = @host@ target_triplet = @target@ subdir = doc -DIST_COMMON = $(srcdir)/Makefile.am $(srcdir)/Makefile.in ACLOCAL_M4 = $(top_srcdir)/aclocal.m4 am__aclocal_m4_deps = $(top_srcdir)/m4/libtool.m4 \ $(top_srcdir)/m4/ltoptions.m4 $(top_srcdir)/m4/ltsugar.m4 \ $(top_srcdir)/m4/ltversion.m4 $(top_srcdir)/m4/lt~obsolete.m4 \ - $(top_srcdir)/configure.ac + $(top_srcdir)/m4/pkg.m4 $(top_srcdir)/configure.ac am__configure_deps = $(am__aclocal_m4_deps) $(CONFIGURE_DEPENDENCIES) \ $(ACLOCAL_M4) +DIST_COMMON = $(srcdir)/Makefile.am $(am__DIST_COMMON) mkinstalldirs = $(install_sh) -d CONFIG_HEADER = $(top_builddir)/include/GeographicLib/Config-ac.h CONFIG_CLEAN_FILES = CONFIG_CLEAN_VPATH_FILES = +AM_V_P = $(am__v_P_@AM_V@) +am__v_P_ = $(am__v_P_@AM_DEFAULT_V@) +am__v_P_0 = false +am__v_P_1 = : +AM_V_GEN = $(am__v_GEN_@AM_V@) +am__v_GEN_ = $(am__v_GEN_@AM_DEFAULT_V@) +am__v_GEN_0 = @echo " GEN " $@; +am__v_GEN_1 = +AM_V_at = $(am__v_at_@AM_V@) +am__v_at_ = $(am__v_at_@AM_DEFAULT_V@) +am__v_at_0 = @ +am__v_at_1 = SOURCES = DIST_SOURCES = am__can_run_installinfo = \ @@ -70,9 +120,12 @@ am__can_run_installinfo = \ n|no|NO) false;; \ *) (install-info --version) >/dev/null 2>&1;; \ esac +am__tagged_files = $(HEADERS) $(SOURCES) $(TAGS_FILES) $(LISP) +am__DIST_COMMON = $(srcdir)/Makefile.in DISTFILES = $(DIST_COMMON) $(DIST_SOURCES) $(TEXINFOS) $(EXTRA_DIST) ACLOCAL = @ACLOCAL@ AMTAR = @AMTAR@ +AM_DEFAULT_VERBOSITY = @AM_DEFAULT_VERBOSITY@ AR = @AR@ AUTOCONF = @AUTOCONF@ AUTOHEADER = @AUTOHEADER@ @@ -121,6 +174,7 @@ LTLIBOBJS = @LTLIBOBJS@ LT_AGE = @LT_AGE@ LT_CURRENT = @LT_CURRENT@ LT_REVISION = @LT_REVISION@ +LT_SYS_LIBRARY_PATH = @LT_SYS_LIBRARY_PATH@ MAINT = @MAINT@ MAKEINFO = @MAKEINFO@ MANIFEST_TOOL = @MANIFEST_TOOL@ @@ -139,9 +193,11 @@ PACKAGE_TARNAME = @PACKAGE_TARNAME@ PACKAGE_URL = @PACKAGE_URL@ PACKAGE_VERSION = @PACKAGE_VERSION@ PATH_SEPARATOR = @PATH_SEPARATOR@ +PKG_CONFIG = @PKG_CONFIG@ +PKG_CONFIG_LIBDIR = @PKG_CONFIG_LIBDIR@ +PKG_CONFIG_PATH = @PKG_CONFIG_PATH@ POD2HTML = @POD2HTML@ POD2MAN = @POD2MAN@ -POW_LIB = @POW_LIB@ RANLIB = @RANLIB@ SED = @SED@ SET_MAKE = @SET_MAKE@ @@ -178,7 +234,7 @@ host_alias = @host_alias@ host_cpu = @host_cpu@ host_os = @host_os@ host_vendor = @host_vendor@ -htmldir = @htmldir@ +htmldir = $(DESTDIR)$(docdir)/html includedir = @includedir@ infodir = @infodir@ install_sh = @install_sh@ @@ -190,6 +246,7 @@ mandir = @mandir@ mkdir_p = @mkdir_p@ oldincludedir = @oldincludedir@ pdfdir = @pdfdir@ +pkgconfigdir = @pkgconfigdir@ prefix = @prefix@ program_transform_name = @program_transform_name@ psdir = @psdir@ @@ -206,27 +263,17 @@ top_build_prefix = @top_build_prefix@ top_builddir = @top_builddir@ top_srcdir = @top_srcdir@ EXTRAFILES = $(srcdir)/tmseries30.html $(srcdir)/geodseries30.html -FIGURES = $(srcdir)/gauss-krueger-graticule.png \ +FIGURES = \ + $(srcdir)/gauss-krueger-graticule.png \ $(srcdir)/thompson-tm-graticule.png \ $(srcdir)/gauss-krueger-convergence-scale.png \ $(srcdir)/gauss-schreiber-graticule-a.png \ $(srcdir)/gauss-krueger-graticule-a.png \ $(srcdir)/thompson-tm-graticule-a.png \ $(srcdir)/gauss-krueger-error.png \ - $(srcdir)/meridian-measures.png - -SCRIPTDRIVERS = \ - $(srcdir)/scripts/geod-calc.html \ - $(srcdir)/scripts/geod-google.html \ - $(srcdir)/scripts/geod-google-instructions.html - -JSSCRIPTS = \ - $(srcdir)/scripts/GeographicLib/Math.js \ - $(srcdir)/scripts/GeographicLib/Geodesic.js \ - $(srcdir)/scripts/GeographicLib/GeodesicLine.js \ - $(srcdir)/scripts/GeographicLib/PolygonArea.js \ - $(srcdir)/scripts/GeographicLib/DMS.js \ - $(srcdir)/scripts/GeographicLib/Interface.js + $(srcdir)/meridian-measures.png \ + $(srcdir)/normal-gravity-potential-1.svg \ + $(srcdir)/vptree.gif HPPFILES = \ $(top_srcdir)/include/GeographicLib/Accumulator.hpp \ @@ -237,14 +284,16 @@ HPPFILES = \ $(top_srcdir)/include/GeographicLib/DMS.hpp \ $(top_srcdir)/include/GeographicLib/Ellipsoid.hpp \ $(top_srcdir)/include/GeographicLib/EllipticFunction.hpp \ - $(top_srcdir)/include/GeographicLib/Geocentric.hpp \ + $(top_srcdir)/include/GeographicLib/GARS.hpp \ $(top_srcdir)/include/GeographicLib/GeoCoords.hpp \ + $(top_srcdir)/include/GeographicLib/Geocentric.hpp \ $(top_srcdir)/include/GeographicLib/Geodesic.hpp \ $(top_srcdir)/include/GeographicLib/GeodesicExact.hpp \ $(top_srcdir)/include/GeographicLib/GeodesicLine.hpp \ $(top_srcdir)/include/GeographicLib/GeodesicLineExact.hpp \ $(top_srcdir)/include/GeographicLib/Geohash.hpp \ $(top_srcdir)/include/GeographicLib/Geoid.hpp \ + $(top_srcdir)/include/GeographicLib/Georef.hpp \ $(top_srcdir)/include/GeographicLib/Gnomonic.hpp \ $(top_srcdir)/include/GeographicLib/LambertConformalConic.hpp \ $(top_srcdir)/include/GeographicLib/LocalCartesian.hpp \ @@ -264,12 +313,14 @@ ALLSOURCES = \ $(top_srcdir)/src/DMS.cpp \ $(top_srcdir)/src/Ellipsoid.cpp \ $(top_srcdir)/src/EllipticFunction.cpp \ - $(top_srcdir)/src/Geocentric.cpp \ + $(top_srcdir)/src/GARS.cpp \ $(top_srcdir)/src/GeoCoords.cpp \ + $(top_srcdir)/src/Geocentric.cpp \ $(top_srcdir)/src/Geodesic.cpp \ $(top_srcdir)/src/GeodesicLine.cpp \ $(top_srcdir)/src/Geohash.cpp \ $(top_srcdir)/src/Geoid.cpp \ + $(top_srcdir)/src/Georef.cpp \ $(top_srcdir)/src/Gnomonic.cpp \ $(top_srcdir)/src/LambertConformalConic.cpp \ $(top_srcdir)/src/LocalCartesian.cpp \ @@ -300,20 +351,9 @@ MANPAGES = \ ../man/Gravity.1.html \ ../man/MagneticField.1.html \ ../man/Planimeter.1.html \ + ../man/RhumbSolve.1.html \ ../man/TransverseMercatorProj.1.html -LEGACYFILES = \ - $(top_srcdir)/legacy/C/geodesic.c \ - $(top_srcdir)/legacy/C/geodesic.h \ - $(top_srcdir)/legacy/C/direct.c \ - $(top_srcdir)/legacy/C/inverse.c \ - $(top_srcdir)/legacy/C/planimeter.c \ - $(top_srcdir)/legacy/Fortran/geodesic.for \ - $(top_srcdir)/legacy/Fortran/geodesic.inc \ - $(top_srcdir)/legacy/Fortran/geoddirect.for \ - $(top_srcdir)/legacy/Fortran/geodinverse.for \ - $(top_srcdir)/legacy/Fortran/planimeter.for - all: all-am .SUFFIXES: @@ -329,7 +369,6 @@ $(srcdir)/Makefile.in: @MAINTAINER_MODE_TRUE@ $(srcdir)/Makefile.am $(am__confi echo ' cd $(top_srcdir) && $(AUTOMAKE) --gnu doc/Makefile'; \ $(am__cd) $(top_srcdir) && \ $(AUTOMAKE) --gnu doc/Makefile -.PRECIOUS: Makefile Makefile: $(srcdir)/Makefile.in $(top_builddir)/config.status @case '$?' in \ *config.status*) \ @@ -353,11 +392,9 @@ mostlyclean-libtool: clean-libtool: -rm -rf .libs _libs -tags: TAGS -TAGS: +tags TAGS: -ctags: CTAGS -CTAGS: +ctags CTAGS: cscope cscopelist: @@ -496,16 +533,19 @@ uninstall-am: .MAKE: install-am install-strip .PHONY: all all-am check check-am clean clean-generic clean-libtool \ - distclean distclean-generic distclean-libtool distdir dvi \ - dvi-am html html-am info info-am install install-am \ - install-data install-data-am install-dvi install-dvi-am \ - install-exec install-exec-am install-html install-html-am \ - install-info install-info-am install-man install-pdf \ - install-pdf-am install-ps install-ps-am install-strip \ - installcheck installcheck-am installdirs maintainer-clean \ - maintainer-clean-generic maintainer-clean-local mostlyclean \ - mostlyclean-generic mostlyclean-libtool pdf pdf-am ps ps-am \ - uninstall uninstall-am + cscopelist-am ctags-am distclean distclean-generic \ + distclean-libtool distdir dvi dvi-am html html-am info info-am \ + install install-am install-data install-data-am install-dvi \ + install-dvi-am install-exec install-exec-am install-html \ + install-html-am install-info install-info-am install-man \ + install-pdf install-pdf-am install-ps install-ps-am \ + install-strip installcheck installcheck-am installdirs \ + maintainer-clean maintainer-clean-generic \ + maintainer-clean-local mostlyclean mostlyclean-generic \ + mostlyclean-libtool pdf pdf-am ps ps-am tags-am uninstall \ + uninstall-am + +.PRECIOUS: Makefile doc: html/index.html @@ -515,21 +555,16 @@ doc: html/index.html @HAVE_DOXYGEN_TRUE@ cp $^ html/ @HAVE_DOXYGEN_TRUE@ touch $@ -@HAVE_DOXYGEN_TRUE@html/index.html: manpages doxyfile.in GeographicLib.dox \ -@HAVE_DOXYGEN_TRUE@ $(HPPFILES) $(ALLSOURCES) $(EXTRAFILES) $(FIGURES) \ -@HAVE_DOXYGEN_TRUE@ doxyfile-c.in geodesic-c.dox doxyfile-for.in geodesic-for.dox \ -@HAVE_DOXYGEN_TRUE@ $(LEGACYFILES) +@HAVE_DOXYGEN_TRUE@html/index.html: manpages doxyfile.in GeographicLib.dox.in \ +@HAVE_DOXYGEN_TRUE@ $(HPPFILES) $(ALLSOURCES) $(EXTRAFILES) $(FIGURES) @HAVE_DOXYGEN_TRUE@ cp -p $(EXTRAFILES) $(top_srcdir)/maxima/*.mac \ @HAVE_DOXYGEN_TRUE@ $(top_srcdir)/LICENSE.txt html/ +@HAVE_DOXYGEN_TRUE@ sed -e "s%@PROJECT_VERSION@%$(VERSION)%g" \ +@HAVE_DOXYGEN_TRUE@ $(srcdir)/GeographicLib.dox.in > GeographicLib.dox @HAVE_DOXYGEN_TRUE@ sed -e "s%@PROJECT_SOURCE_DIR@%$(top_srcdir)%g" \ +@HAVE_DOXYGEN_TRUE@ -e "s%@PROJECT_BINARY_DIR@%..%g" \ @HAVE_DOXYGEN_TRUE@ -e "s%@PROJECT_VERSION@%$(VERSION)%g" \ @HAVE_DOXYGEN_TRUE@ $(srcdir)/doxyfile.in | $(DOXYGEN) - -@HAVE_DOXYGEN_TRUE@ sed -e "s%@PROJECT_SOURCE_DIR@%$(top_srcdir)%g" \ -@HAVE_DOXYGEN_TRUE@ -e "s%@PROJECT_VERSION@%$(VERSION)%g" \ -@HAVE_DOXYGEN_TRUE@ $(srcdir)/doxyfile-c.in | $(DOXYGEN) - -@HAVE_DOXYGEN_TRUE@ sed -e "s%@PROJECT_SOURCE_DIR@%$(top_srcdir)%g" \ -@HAVE_DOXYGEN_TRUE@ -e "s%@PROJECT_VERSION@%$(VERSION)%g" \ -@HAVE_DOXYGEN_TRUE@ $(srcdir)/doxyfile-for.in | $(DOXYGEN) - @HAVE_DOXYGEN_FALSE@html/index.html: index.html.in utilities.html.in @HAVE_DOXYGEN_FALSE@ if test -d html; then rm -rf html/*; else mkdir html; fi @HAVE_DOXYGEN_FALSE@ cp $(top_srcdir)/LICENSE.txt html/ @@ -542,19 +577,11 @@ maintainer-clean-local: rm -rf html manpages install-doc: html/index.html - $(INSTALL) -d $(DESTDIR)$(docdir)/html - $(INSTALL) -m 644 `dirname $<`/*.* $(DESTDIR)$(docdir)/html - -test -f `dirname $<`/C/index.html && \ - $(INSTALL) -d $(DESTDIR)$(docdir)/html/C && \ - $(INSTALL) -m 644 `dirname $<`/C/*.* $(DESTDIR)$(docdir)/html/C - -test -f `dirname $<`/Fortran/index.html && \ - $(INSTALL) -d $(DESTDIR)$(docdir)/html/Fortran && \ - $(INSTALL) -m 644 `dirname $<`/Fortran/*.* \ - $(DESTDIR)$(docdir)/html/Fortran - $(INSTALL) -d $(DESTDIR)$(docdir)/scripts - $(INSTALL) -m 644 $(SCRIPTDRIVERS) $(DESTDIR)$(docdir)/scripts - $(INSTALL) -d $(DESTDIR)$(docdir)/scripts/GeographicLib - $(INSTALL) -m 644 $(JSSCRIPTS) $(DESTDIR)$(docdir)/scripts/GeographicLib + $(INSTALL) -d $(htmldir) + $(INSTALL) -m 644 `dirname $<`/*.* $(htmldir) + -test -f `dirname $<`/search/search.js && \ + $(INSTALL) -d $(htmldir)/search && \ + $(INSTALL) -m 644 `dirname $<`/search/*.* $(htmldir)/search || true # Tell versions [3.59,3.63) of GNU make to not export all variables. # Otherwise a system limit (for SysV at least) may be exceeded. diff --git a/gtsam/3rdparty/GeographicLib/doc/Makefile.mk b/gtsam/3rdparty/GeographicLib/doc/Makefile.mk index ca852d9d0..e6373cec2 100644 --- a/gtsam/3rdparty/GeographicLib/doc/Makefile.mk +++ b/gtsam/3rdparty/GeographicLib/doc/Makefile.mk @@ -1,6 +1,3 @@ -SCRIPTDRIVERS = $(wildcard scripts/[A-Za-z]*.html) -JSSCRIPTS = $(wildcard scripts/GeographicLib/[A-Za-z]*.js) - VERSION:=$(shell grep '\bVERSION=' ../configure | cut -f2 -d\' | head -1) doc: html/index.html @@ -16,15 +13,10 @@ html/index.html: index.html.in utilities.html.in PREFIX = /usr/local DEST = $(PREFIX)/share/doc/GeographicLib DOCDEST = $(DEST)/html -SCRIPTDEST = $(DEST)/scripts INSTALL = install -b install: html/index.html test -d $(DOCDEST) || mkdir -p $(DOCDEST) $(INSTALL) -m 644 html/* $(DOCDEST)/ - test -d $(SCRIPTDEST)/GeographicLib || \ - mkdir -p $(SCRIPTDEST)/GeographicLib - $(INSTALL) -m 644 $(SCRIPTDRIVERS) $(SCRIPTDEST)/ - $(INSTALL) -m 644 $(JSSCRIPTS) $(SCRIPTDEST)/GeographicLib/ .PHONY: doc install clean diff --git a/gtsam/3rdparty/GeographicLib/doc/NETGeographicLib.dox b/gtsam/3rdparty/GeographicLib/doc/NETGeographicLib.dox index fd8f5e057..4009dfd83 100644 --- a/gtsam/3rdparty/GeographicLib/doc/NETGeographicLib.dox +++ b/gtsam/3rdparty/GeographicLib/doc/NETGeographicLib.dox @@ -5,16 +5,20 @@ * * Written by Scott Heiman and licensed under the * MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ /** \mainpage NETGeographicLib library \author Scott Heiman (mrmtdew2@outlook.com) -\version 1.35 -\date 2014-03-13 +\version 1.49 +\date 2017-10-05 -\section abstract Abstract +The documentation for other versions is available at +https://geographiclib.sourceforge.io/m.nn/NET for versions numbers +m.nn ≥ 1.33. + +\section abstract-net Abstract %NETGeographicLib is a .NET wrapper for GeographicLib. It allows .NET developers to access GeographicLib classes within C#, Visual @@ -25,15 +29,15 @@ of the GeographicLib software. It is a container that provides interfaces to the GeographicLib classes. GeographicLib and NETGeographicLib is an integrated product. -The NETGeographic project in the GeographicLib-vc10.sln file located in -\/GeographicLib-1.35/windows will create the NETGeographicLib -DLL. The source code for NETGeographicLib is located in -\/GeographicLib-1.35/dotnet/NETGeographicLib. NETGeographicLib -is not available for older versions of Microsoft Visual Studio. +The NETGeographic solutions and C++ projects are located in the +\/windows folder. The C# Projections projects are located in +the \/dotnet/Projections folder. Solution files have been provided +for VS 2010 and VS 2013 NETGeographicLib is not available for older +versions of Microsoft Visual Studio. NETGeographicLib has been tested with C#, Managed C++, and Visual Basic. Sample code snippets can be found in -\/GeographicLib-1.35/dotnet/examples. +\/GeographicLib-1.49/dotnet/examples. \section differences Differences between NETGeographicLib and GeographicLib @@ -41,14 +45,15 @@ The NETGeographicLib class names are identical to the GeographicLib class names. All NETGeographicLib classes are in the NETGeographicLib namespace. NETGeographicLib exposes most of the GeographicLib classes. The exceptions -are SphericalEngine, GeographicLib::Math, and GeographicLib::Utility. The +are SphericalEngine, GeographicLib::Math, and most of GeographicLib::Utility. The SphericalEngine class is a template class which (according to the comments in the SphericalEngine.h file) is not usually accessible to developers. The GeographicLib::Math class contains several specialized functions required by GeographicLib classes. They have limited use outside GeographicLib. This class may be exposed in a future release if there is demand for it. The functions provided by GeographicLib::Utility duplicate functions provided by existing .NET -controls (DateTime). +controls (DateTime). The GeographicLib::Utility::fractionalyear function is +available to .NET programmers by calling NETGeographicLib::Utility::FractionalYear. The SphericalCoefficients class replaces the SphericalEngine::coeff class. @@ -59,7 +64,10 @@ in the header files contain a section labeled "INTERFACE DIFFERENCES" that detai the differences between the NETGeographicLib interfaces and the GeographicLib interfaces. The differences are summarized in the text that follows. -Default values for function parameters are not supported in .NET. +Default values for function parameters are not supported in .NET. If +the documentation refers to a default value for a parameter, it applies +only to GeographicLib. However, such a "default" value often provides a +reasonable choice for this parameter. Several GeographicLib class functions accept or return a "capabilities mask" as an unsigned integer. The NETGeographicLib classes accept and return the capabilities @@ -135,7 +143,7 @@ to any Visual Basic source that uses NETGeographicLib classes. A C# sample application is provided that demonstrates NETGeographicLib classes. The source code for the sample application is located in -\/GeographicLib-1.35/dotnet/Projections. The sample +\/GeographicLib-1.49/dotnet/Projections. The sample application creates a tabbed dialog. Each tab provides data entry fields that allow the user to exercise one or more NETGeographicLib classes. @@ -153,12 +161,13 @@ The following table lists the source code that demonstrates specific classes. GravityPanel.csNormalGravity, GravityModel, GravityCircle LocalCartesianPanel.csLocalCartesian MagneticPanel.csMagneticModel, MagneticCircle -MiscPanel.csDMS, Geohash +MiscPanel.csDMS, Geohash, GARS, Georef PolarStereoPanel.csPolarStereographic PolyPanel.csPolygonArea ProjectionsPanel.csAzimuthalEquidistant, CassiniSoldner, Gnomonic SphericalHarmonicsPanel.csSphericalHarmonic, SphericalHarmonic1, SphericalHarmonic2, CircularEngine, SphericalCoefficients TypeIIIProjPanel.csUTMUPS, MGRS, OSGB +RhumbPanel.csRhumb, RhumbLine @@ -174,7 +183,7 @@ two ways: application. You can build %GeographicLib as a shared library using -D GEOGRAPHICLIB_LIB_TYPE=SHARED or BOTH. - you have installed %GeographicLib using one of the binary installers (see - \ref windowsbin "Using a binary installer for Windows" in the + \ref binaryinstwin "Using a binary installer for Windows" in the %GeographicLib documentation). In this case, you are restricted to using Visual Studio 10. diff --git a/gtsam/3rdparty/GeographicLib/doc/doxyfile-c.in b/gtsam/3rdparty/GeographicLib/doc/doxyfile-c.in index f77a0b334..611f63e12 100644 --- a/gtsam/3rdparty/GeographicLib/doc/doxyfile-c.in +++ b/gtsam/3rdparty/GeographicLib/doc/doxyfile-c.in @@ -324,30 +324,16 @@ INLINE_SIMPLE_STRUCTS = NO TYPEDEF_HIDES_STRUCT = NO -# The SYMBOL_CACHE_SIZE determines the size of the internal cache use to -# determine which symbols to keep in memory and which to flush to disk. -# When the cache is full, less often used symbols will be written to disk. -# For small to medium size projects (<1000 input files) the default value is -# probably good enough. For larger projects a too small cache size can cause -# doxygen to be busy swapping symbols to and from disk most of the time -# causing a significant performance penalty. -# If the system has enough physical memory increasing the cache will improve the -# performance by keeping more symbols in memory. Note that the value works on -# a logarithmic scale so increasing the size by one will roughly double the -# memory usage. The cache size is given by this formula: -# 2^(16+SYMBOL_CACHE_SIZE). The valid range is 0..9, the default is 0, -# corresponding to a cache size of 2^16 = 65536 symbols. - -SYMBOL_CACHE_SIZE = 0 - -# Similar to the SYMBOL_CACHE_SIZE the size of the symbol lookup cache can be -# set using LOOKUP_CACHE_SIZE. This cache is used to resolve symbols given -# their name and scope. Since this can be an expensive process and often the -# same symbol appear multiple times in the code, doxygen keeps a cache of -# pre-resolved symbols. If the cache is too small doxygen will become slower. -# If the cache is too large, memory is wasted. The cache size is given by this -# formula: 2^(16+LOOKUP_CACHE_SIZE). The valid range is 0..9, the default is 0, -# corresponding to a cache size of 2^16 = 65536 symbols. +# The size of the symbol lookup cache can be set using LOOKUP_CACHE_SIZE. This +# cache is used to resolve symbols given their name and scope. Since this can be +# an expensive process and often the same symbol appears multiple times in the +# code, doxygen keeps a cache of pre-resolved symbols. If the cache is too small +# doxygen will become slower. If the cache is too large, memory is wasted. The +# cache size is given by this formula: 2^(16+LOOKUP_CACHE_SIZE). The valid range +# is 0..9, the default is 0, corresponding to a cache size of 2^16=65536 +# symbols. At the end of a run doxygen will report the cache usage and suggest +# the optimal cache size from a speed point of view. +# Minimum value: 0, maximum value: 9, default value: 0. LOOKUP_CACHE_SIZE = 0 @@ -1200,7 +1186,7 @@ USE_MATHJAX = NO # However, it is strongly recommended to install a local # copy of MathJax from http://www.mathjax.org before deployment. -MATHJAX_RELPATH = http://cdn.mathjax.org/mathjax/latest +MATHJAX_RELPATH = https://geographiclib.sourceforge.io/MathJax-2.7.2 # The MATHJAX_EXTENSIONS tag can be used to specify one or MathJax extension # names that should be enabled during MathJax rendering. @@ -1215,7 +1201,7 @@ MATHJAX_EXTENSIONS = # typically be disabled. For large projects the javascript based search engine # can be slow, then enabling SERVER_BASED_SEARCH may provide a better solution. -SEARCHENGINE = NO +SEARCHENGINE = YES # When the SERVER_BASED_SEARCH tag is enabled the search engine will be # implemented using a PHP enabled web server instead of at the web client @@ -1412,18 +1398,6 @@ GENERATE_XML = NO XML_OUTPUT = xml -# The XML_SCHEMA tag can be used to specify an XML schema, -# which can be used by a validating XML parser to check the -# syntax of the XML files. - -XML_SCHEMA = - -# The XML_DTD tag can be used to specify an XML DTD, -# which can be used by a validating XML parser to check the -# syntax of the XML files. - -XML_DTD = - # If the XML_PROGRAMLISTING tag is set to YES Doxygen will # dump the program listings (including syntax highlighting # and cross-referencing information) to the XML output. Note that diff --git a/gtsam/3rdparty/GeographicLib/doc/doxyfile-for.in b/gtsam/3rdparty/GeographicLib/doc/doxyfile-for.in index 47ef530d7..d18e706e2 100644 --- a/gtsam/3rdparty/GeographicLib/doc/doxyfile-for.in +++ b/gtsam/3rdparty/GeographicLib/doc/doxyfile-for.in @@ -324,30 +324,16 @@ INLINE_SIMPLE_STRUCTS = NO TYPEDEF_HIDES_STRUCT = NO -# The SYMBOL_CACHE_SIZE determines the size of the internal cache use to -# determine which symbols to keep in memory and which to flush to disk. -# When the cache is full, less often used symbols will be written to disk. -# For small to medium size projects (<1000 input files) the default value is -# probably good enough. For larger projects a too small cache size can cause -# doxygen to be busy swapping symbols to and from disk most of the time -# causing a significant performance penalty. -# If the system has enough physical memory increasing the cache will improve the -# performance by keeping more symbols in memory. Note that the value works on -# a logarithmic scale so increasing the size by one will roughly double the -# memory usage. The cache size is given by this formula: -# 2^(16+SYMBOL_CACHE_SIZE). The valid range is 0..9, the default is 0, -# corresponding to a cache size of 2^16 = 65536 symbols. - -SYMBOL_CACHE_SIZE = 0 - -# Similar to the SYMBOL_CACHE_SIZE the size of the symbol lookup cache can be -# set using LOOKUP_CACHE_SIZE. This cache is used to resolve symbols given -# their name and scope. Since this can be an expensive process and often the -# same symbol appear multiple times in the code, doxygen keeps a cache of -# pre-resolved symbols. If the cache is too small doxygen will become slower. -# If the cache is too large, memory is wasted. The cache size is given by this -# formula: 2^(16+LOOKUP_CACHE_SIZE). The valid range is 0..9, the default is 0, -# corresponding to a cache size of 2^16 = 65536 symbols. +# The size of the symbol lookup cache can be set using LOOKUP_CACHE_SIZE. This +# cache is used to resolve symbols given their name and scope. Since this can be +# an expensive process and often the same symbol appears multiple times in the +# code, doxygen keeps a cache of pre-resolved symbols. If the cache is too small +# doxygen will become slower. If the cache is too large, memory is wasted. The +# cache size is given by this formula: 2^(16+LOOKUP_CACHE_SIZE). The valid range +# is 0..9, the default is 0, corresponding to a cache size of 2^16=65536 +# symbols. At the end of a run doxygen will report the cache usage and suggest +# the optimal cache size from a speed point of view. +# Minimum value: 0, maximum value: 9, default value: 0. LOOKUP_CACHE_SIZE = 0 @@ -680,8 +666,7 @@ INPUT_ENCODING = UTF-8 # *.hxx *.hpp *.h++ *.idl *.odl *.cs *.php *.php3 *.inc *.m *.mm *.dox *.py # *.f90 *.f *.for *.vhd *.vhdl -FILE_PATTERNS = *.for \ - *.inc +FILE_PATTERNS = geod*.for planimeter.for geodesic.inc # The RECURSIVE tag can be used to turn specify whether or not subdirectories # should be searched for input files as well. Possible values are YES and NO. @@ -1200,7 +1185,7 @@ USE_MATHJAX = NO # However, it is strongly recommended to install a local # copy of MathJax from http://www.mathjax.org before deployment. -MATHJAX_RELPATH = http://cdn.mathjax.org/mathjax/latest +MATHJAX_RELPATH = https://geographiclib.sourceforge.io/MathJax-2.7.2 # The MATHJAX_EXTENSIONS tag can be used to specify one or MathJax extension # names that should be enabled during MathJax rendering. @@ -1215,7 +1200,7 @@ MATHJAX_EXTENSIONS = # typically be disabled. For large projects the javascript based search engine # can be slow, then enabling SERVER_BASED_SEARCH may provide a better solution. -SEARCHENGINE = NO +SEARCHENGINE = YES # When the SERVER_BASED_SEARCH tag is enabled the search engine will be # implemented using a PHP enabled web server instead of at the web client @@ -1412,18 +1397,6 @@ GENERATE_XML = NO XML_OUTPUT = xml -# The XML_SCHEMA tag can be used to specify an XML schema, -# which can be used by a validating XML parser to check the -# syntax of the XML files. - -XML_SCHEMA = - -# The XML_DTD tag can be used to specify an XML DTD, -# which can be used by a validating XML parser to check the -# syntax of the XML files. - -XML_DTD = - # If the XML_PROGRAMLISTING tag is set to YES Doxygen will # dump the program listings (including syntax highlighting # and cross-referencing information) to the XML output. Note that diff --git a/gtsam/3rdparty/GeographicLib/doc/doxyfile-net.in b/gtsam/3rdparty/GeographicLib/doc/doxyfile-net.in index b9fedb587..2b082c806 100644 --- a/gtsam/3rdparty/GeographicLib/doc/doxyfile-net.in +++ b/gtsam/3rdparty/GeographicLib/doc/doxyfile-net.in @@ -324,30 +324,16 @@ INLINE_SIMPLE_STRUCTS = NO TYPEDEF_HIDES_STRUCT = NO -# The SYMBOL_CACHE_SIZE determines the size of the internal cache use to -# determine which symbols to keep in memory and which to flush to disk. -# When the cache is full, less often used symbols will be written to disk. -# For small to medium size projects (<1000 input files) the default value is -# probably good enough. For larger projects a too small cache size can cause -# doxygen to be busy swapping symbols to and from disk most of the time -# causing a significant performance penalty. -# If the system has enough physical memory increasing the cache will improve the -# performance by keeping more symbols in memory. Note that the value works on -# a logarithmic scale so increasing the size by one will roughly double the -# memory usage. The cache size is given by this formula: -# 2^(16+SYMBOL_CACHE_SIZE). The valid range is 0..9, the default is 0, -# corresponding to a cache size of 2^16 = 65536 symbols. - -SYMBOL_CACHE_SIZE = 0 - -# Similar to the SYMBOL_CACHE_SIZE the size of the symbol lookup cache can be -# set using LOOKUP_CACHE_SIZE. This cache is used to resolve symbols given -# their name and scope. Since this can be an expensive process and often the -# same symbol appear multiple times in the code, doxygen keeps a cache of -# pre-resolved symbols. If the cache is too small doxygen will become slower. -# If the cache is too large, memory is wasted. The cache size is given by this -# formula: 2^(16+LOOKUP_CACHE_SIZE). The valid range is 0..9, the default is 0, -# corresponding to a cache size of 2^16 = 65536 symbols. +# The size of the symbol lookup cache can be set using LOOKUP_CACHE_SIZE. This +# cache is used to resolve symbols given their name and scope. Since this can be +# an expensive process and often the same symbol appears multiple times in the +# code, doxygen keeps a cache of pre-resolved symbols. If the cache is too small +# doxygen will become slower. If the cache is too large, memory is wasted. The +# cache size is given by this formula: 2^(16+LOOKUP_CACHE_SIZE). The valid range +# is 0..9, the default is 0, corresponding to a cache size of 2^16=65536 +# symbols. At the end of a run doxygen will report the cache usage and suggest +# the optimal cache size from a speed point of view. +# Minimum value: 0, maximum value: 9, default value: 0. LOOKUP_CACHE_SIZE = 0 @@ -1201,7 +1187,7 @@ USE_MATHJAX = YES # However, it is strongly recommended to install a local # copy of MathJax from http://www.mathjax.org before deployment. -MATHJAX_RELPATH = http://cdn.mathjax.org/mathjax/latest +MATHJAX_RELPATH = https://geographiclib.sourceforge.io/MathJax-2.7.2 # The MATHJAX_EXTENSIONS tag can be used to specify one or MathJax extension # names that should be enabled during MathJax rendering. @@ -1216,7 +1202,7 @@ MATHJAX_EXTENSIONS = # typically be disabled. For large projects the javascript based search engine # can be slow, then enabling SERVER_BASED_SEARCH may provide a better solution. -SEARCHENGINE = NO +SEARCHENGINE = YES # When the SERVER_BASED_SEARCH tag is enabled the search engine will be # implemented using a PHP enabled web server instead of at the web client @@ -1413,18 +1399,6 @@ GENERATE_XML = NO XML_OUTPUT = xml -# The XML_SCHEMA tag can be used to specify an XML schema, -# which can be used by a validating XML parser to check the -# syntax of the XML files. - -XML_SCHEMA = - -# The XML_DTD tag can be used to specify an XML DTD, -# which can be used by a validating XML parser to check the -# syntax of the XML files. - -XML_DTD = - # If the XML_PROGRAMLISTING tag is set to YES Doxygen will # dump the program listings (including syntax highlighting # and cross-referencing information) to the XML output. Note that diff --git a/gtsam/3rdparty/GeographicLib/doc/doxyfile.in b/gtsam/3rdparty/GeographicLib/doc/doxyfile.in index 448affa1a..eb234e9b9 100644 --- a/gtsam/3rdparty/GeographicLib/doc/doxyfile.in +++ b/gtsam/3rdparty/GeographicLib/doc/doxyfile.in @@ -139,7 +139,8 @@ STRIP_FROM_PATH = @PROJECT_SOURCE_DIR@/ # definition is used. Otherwise one should specify the include paths that # are normally passed to the compiler using the -I flag. -STRIP_FROM_INC_PATH = @PROJECT_SOURCE_DIR@/include/ +STRIP_FROM_INC_PATH = @PROJECT_SOURCE_DIR@/include/ \ + @PROJECT_SOURCE_DIR@/examples/ # If the SHORT_NAMES tag is set to YES, doxygen will generate much shorter # (but less readable) file names. This can be useful if your file system @@ -324,30 +325,16 @@ INLINE_SIMPLE_STRUCTS = NO TYPEDEF_HIDES_STRUCT = NO -# The SYMBOL_CACHE_SIZE determines the size of the internal cache use to -# determine which symbols to keep in memory and which to flush to disk. -# When the cache is full, less often used symbols will be written to disk. -# For small to medium size projects (<1000 input files) the default value is -# probably good enough. For larger projects a too small cache size can cause -# doxygen to be busy swapping symbols to and from disk most of the time -# causing a significant performance penalty. -# If the system has enough physical memory increasing the cache will improve the -# performance by keeping more symbols in memory. Note that the value works on -# a logarithmic scale so increasing the size by one will roughly double the -# memory usage. The cache size is given by this formula: -# 2^(16+SYMBOL_CACHE_SIZE). The valid range is 0..9, the default is 0, -# corresponding to a cache size of 2^16 = 65536 symbols. - -SYMBOL_CACHE_SIZE = 0 - -# Similar to the SYMBOL_CACHE_SIZE the size of the symbol lookup cache can be -# set using LOOKUP_CACHE_SIZE. This cache is used to resolve symbols given -# their name and scope. Since this can be an expensive process and often the -# same symbol appear multiple times in the code, doxygen keeps a cache of -# pre-resolved symbols. If the cache is too small doxygen will become slower. -# If the cache is too large, memory is wasted. The cache size is given by this -# formula: 2^(16+LOOKUP_CACHE_SIZE). The valid range is 0..9, the default is 0, -# corresponding to a cache size of 2^16 = 65536 symbols. +# The size of the symbol lookup cache can be set using LOOKUP_CACHE_SIZE. This +# cache is used to resolve symbols given their name and scope. Since this can be +# an expensive process and often the same symbol appears multiple times in the +# code, doxygen keeps a cache of pre-resolved symbols. If the cache is too small +# doxygen will become slower. If the cache is too large, memory is wasted. The +# cache size is given by this formula: 2^(16+LOOKUP_CACHE_SIZE). The valid range +# is 0..9, the default is 0, corresponding to a cache size of 2^16=65536 +# symbols. At the end of a run doxygen will report the cache usage and suggest +# the optimal cache size from a speed point of view. +# Minimum value: 0, maximum value: 9, default value: 0. LOOKUP_CACHE_SIZE = 0 @@ -664,7 +651,8 @@ WARN_LOGFILE = INPUT = @PROJECT_SOURCE_DIR@/src \ @PROJECT_SOURCE_DIR@/include/GeographicLib \ @PROJECT_SOURCE_DIR@/tools \ - @PROJECT_SOURCE_DIR@/doc/GeographicLib.dox + @PROJECT_BINARY_DIR@/doc/GeographicLib.dox \ + @PROJECT_SOURCE_DIR@/examples/JacobiConformal.hpp # This tag can be used to specify the character encoding of the source files # that doxygen parses. Internally doxygen uses the UTF-8 encoding, which is @@ -1202,7 +1190,7 @@ USE_MATHJAX = YES # However, it is strongly recommended to install a local # copy of MathJax from http://www.mathjax.org before deployment. -MATHJAX_RELPATH = http://cdn.mathjax.org/mathjax/latest +MATHJAX_RELPATH = https://geographiclib.sourceforge.io/MathJax-2.7.2 # The MATHJAX_EXTENSIONS tag can be used to specify one or MathJax extension # names that should be enabled during MathJax rendering. @@ -1217,7 +1205,7 @@ MATHJAX_EXTENSIONS = # typically be disabled. For large projects the javascript based search engine # can be slow, then enabling SERVER_BASED_SEARCH may provide a better solution. -SEARCHENGINE = NO +SEARCHENGINE = YES # When the SERVER_BASED_SEARCH tag is enabled the search engine will be # implemented using a PHP enabled web server instead of at the web client @@ -1414,18 +1402,6 @@ GENERATE_XML = NO XML_OUTPUT = xml -# The XML_SCHEMA tag can be used to specify an XML schema, -# which can be used by a validating XML parser to check the -# syntax of the XML files. - -XML_SCHEMA = - -# The XML_DTD tag can be used to specify an XML DTD, -# which can be used by a validating XML parser to check the -# syntax of the XML files. - -XML_DTD = - # If the XML_PROGRAMLISTING tag is set to YES Doxygen will # dump the program listings (including syntax highlighting # and cross-referencing information) to the XML output. Note that diff --git a/gtsam/3rdparty/GeographicLib/doc/geodesic-c.dox b/gtsam/3rdparty/GeographicLib/doc/geodesic-c.dox index d07fb61ba..2923dcf8a 100644 --- a/gtsam/3rdparty/GeographicLib/doc/geodesic-c.dox +++ b/gtsam/3rdparty/GeographicLib/doc/geodesic-c.dox @@ -5,49 +5,62 @@ * * Written by Charles Karney and licensed under the * MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ /** \mainpage Geodesic routines implemented in C \author Charles F. F. Karney (charles@karney.com) -\version 1.32 +\version 1.49 -\section abstract Abstract +The documentation for other versions is available at +https://geographiclib.sourceforge.io/m.nn/C for versions numbers +m.nn ≥ 1.28. -This is a C implementation of the geodesic algorithms from GeographicLib. This is a -self-contained library (requiring only the standard C math library) +\section abstract-c Abstract + +This is a C implementation of the geodesic algorithms from +GeographicLib. This +is a self-contained library (requiring only the standard C math library) which makes it easy to do geodesic computations for an ellipsoid of -revolution in a C program. It uses ANSI C as described in -B. W. Kernigan and D. M. Ritchie, The C Programming Language, 2nd -Ed. (Prentice Hall, 1988), and so should compile correctly with just -about any C compiler. +revolution in a C program. It is included with version 4.9.0 of +proj.4 and later. +It uses ANSI C as described in B. W. Kernigan and D. M. Ritchie, The C +Programming Language, 2nd Ed. (Prentice Hall, 1988), and so should +compile correctly with just about any C compiler. However, the C99 math +functions are used if they are available. -\section download Downloading the source +\section download-c Downloading the source The C library is part of %GeographicLib which available for download at -- - GeographicLib-1.32.tar.gz -- - GeographicLib-1.32.zip +- + GeographicLib-1.49.tar.gz +- + GeographicLib-1.49.zip . as either a compressed tar file (tar.gz) or a zip file. After unpacking -the source, the C library can be found in GeographicLib-1.32/legacy/C. +the source, the C library can be found in the directory legacy/C. The library consists of two files geodesic.c and geodesic.h. The library is also included as part of -proj.4 starting with version -4.9.0, where is used as the computational backend for -geod(1). +proj.4 starting with +version 4.9.0, where it is used as the computational backend for +geod(1). Instructions for how to use the library via proj.4 are given below. -\section doc Library documentation +Licensed under the +MIT/X11 License; see +LICENSE.txt. -The interface to the library is documented via doxygen in the header -file. To access this, see geodesic.h. +\section doc-c Library documentation -\section samples Sample programs +Here is the +\link geodesic.h application programming interface\endlink +for the library (this is just the documentation for the header file, +geodesic.h). See also the documentation on the structures geod_geodesic, +geod_geodesicline, and geod_polygon. + +\section samples-c Sample programs Also included are 3 small test programs: - direct.c is a simple command line utility for solving the @@ -68,6 +81,7 @@ mkdir BUILD cd BUILD cmake .. make +make test echo 30 0 29.5 179.5 | ./inverse \endverbatim Alternatively, if you have proj.4 installed, you can compile and link @@ -81,38 +95,158 @@ cc -c -I/usr/local/include inverse.c cc -o inverse inverse.o -lproj -L/usr/local/lib -Wl,-rpath=/usr/local/lib echo 30 0 29.5 179.5 | ./inverse \endverbatim -\section library Using the library +\section library-c Using the library -- Put @verbatim - #include "geodesic.h" @endverbatim +- Put @code{.c} + #include "geodesic.h" + @endcode in your source code. If you are using the library via proj.4, change - this to @verbatim - #include @endverbatim -- make calls to the geodesic routines from your code. The interface to + this to @code{.c} + #include + @endcode +- Make calls to the geodesic routines from your code. The interface to the library is documented in geodesic.h. - Compile and link as described above. +- If linking with proj.4, you might want to check that the version of + proj.4 contains the geodesic routines. You can do this with @code{.c} + #include + #if PJ_VERSION >= 490 + #include + #endif + ... + @endcode -\section external External links +- You can check the version of the geodesic library with, e.g., + @code{.c} + #if GEODESIC_VERSION >= GEODESIC_VERSION_NUM(1,40,0) + ... + #endif + @endcode + +\section external-c External links - These algorithms are derived in C. F. F. Karney, - + Algorithms for geodesics, J. Geodesy 87, 43--55 (2013) - ( addenda). + ( addenda). - A longer paper on geodesics: C. F. F. Karney, - Geodesics + Geodesics on an ellipsoid of revolution, Feb. 2011 - ( + ( errata). -- The GeographicLib web site. -- The C++ library. -- The Java library. -- The Fortran library. -- Documentation on the C++ classes: GeographicLib::Geodesic, - GeographicLib::GeodesicLine, GeographicLib::PolygonArea. -- The section in the %GeographicLib documentation on geodesics: \ref - geodesic. -- - An online geodesic bibliography. +- + Main project page +- + GeographicLib web site + - Documentation on the C++ classes: GeographicLib::Geodesic, + GeographicLib::GeodesicLine, GeographicLib::PolygonAreaT. + - The section in the %GeographicLib documentation on geodesics: \ref + geodesic. +- + git repository +- Implementations in various languages + - C++ (complete library): + + documentation, + + download; + - C (geodesic routines): + + documentation, also included with recent versions of + + proj.4; + - Fortran (geodesic routines): + + documentation; + - Java (geodesic routines): + + Maven Central package, + + documentation; + - JavaScript (geodesic routines): + + npm package, + + documentation; + - Python (geodesic routines): + + PyPI package, + + documentation; + - Matlab/Octave (geodesic and some other routines): + + Matlab Central package, + + documentation; + - C# (.NET wrapper for complete C++ library): + + documentation. +- + A geodesic bibliography. +- The wikipedia page, + + Geodesics on an ellipsoid. + +\section changes-c Change log + + - Version 1.49 + (released 2017-10-05) + - Fix more warning messages from some compilers; add tests. + + - Version 1.48 + (released 2017-04-09) + - This is the version slated for the version of proj.4 after 4.9.4 + (tagged v1.48.1-c). + - Fix warnings messages from some compilers. + - Change default range for longitude and azimuth to + (−180°, 180°] (instead of + [−180°, 180°)). + + - Version 1.47 + (released 2017-02-15) + - This is the version incorporated into proj.4 version 4.9.3 (tagged + v1.46.1-c). + - Fix the order of declarations, incorporating the patches in version + 1.46.1. + - Improve accuracy of area calculation (fixing a flaw introduced in + version 1.46). + + - Version 1.46 + (released 2016-02-15) + - Add s13 and a13 to the geod_geodesicline struct. + - Add geod_directline, geod_gendirectline, and geod_inverseline. + - More accurate inverse solution when longitude difference is close + to 180°. + + - Version 1.45 + (released 2015-09-30) + - The solution of the inverse problem now correctly returns NaNs if + one of the latitudes is a NaN. + - Include a test suite that can be run with "make test" after + configuring with cmake. + - Add geod_polygon_clear(). + + - Version 1.44 + (released 2015-08-14) + - This is the version incorporated into proj.4 version 4.9.2. + - Improve accuracy of calculations by evaluating trigonometric + functions more carefully and replacing the series for the reduced + length with one with a smaller truncation error. + - The allowed ranges for longitudes and azimuths is now unlimited; + it used to be [−540°, 540°). + - Enforce the restriction of latitude to [−90°, 90°] by + returning NaNs if the latitude is outside this range. + - The inverse calculation sets \e s12 to zero for coincident points + at pole (instead of returning a tiny quantity). + + - Version 1.40 + (released 2014-12-18) + - This is the version incorporated into proj.4 version 4.9.1. + + - Version 1.32 + (released 2013-07-12) + - This is the version incorporated into proj.4 version 4.9.0. + **********************************************************************/ diff --git a/gtsam/3rdparty/GeographicLib/doc/geodesic-for.dox b/gtsam/3rdparty/GeographicLib/doc/geodesic-for.dox index 1ebc59860..477380e72 100644 --- a/gtsam/3rdparty/GeographicLib/doc/geodesic-for.dox +++ b/gtsam/3rdparty/GeographicLib/doc/geodesic-for.dox @@ -5,42 +5,52 @@ * * Written by Charles Karney and licensed under the * MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ /** \mainpage Geodesic routines implemented in Fortran \author Charles F. F. Karney (charles@karney.com) -\version 1.31 +\version 1.49 -\section abstract Abstract +The documentation for other versions is available at +https://geographiclib.sourceforge.io/m.nn/Fortran for versions numbers +m.nn ≥ 1.28. + +\section abstract-for Abstract This is a Fortran implementation of the geodesic algorithms from GeographicLib. This is a +href="https://geographiclib.sourceforge.io">GeographicLib. This is a self-contained library which makes it easy to do geodesic computations for an ellipsoid of revolution in a Fortran program. It is written in Fortran 77 (avoiding features which are now deprecated) and should compile correctly with just about any Fortran compiler. -\section download Downloading the source +\section download-for Downloading the source The Fortran library is part of %GeographicLib which available for download at -- - GeographicLib-1.31.tar.gz -- - GeographicLib-1.31.zip +- + GeographicLib-1.49.tar.gz +- + GeographicLib-1.49.zip . as either a compressed tar file (tar.gz) or a zip file. After unpacking -the source, the Fortran library can be found in -GeographicLib-1.31/legacy/Fortran. The library consists of the file -geodesic.for. +the source, the Fortran library can be found in the directory +legacy/Fortran. The library consists of the file +geodesic.for. The Fortran-90 interface is defined in geodesic.inc. -\section doc Library documentation +Licensed under the +MIT/X11 License; see +LICENSE.txt. -The interface to the library is documented via doxygen in the source -file. To access this, see geodesic.for. +\section doc-for Library documentation -\section samples Sample programs +Here is the +\link geodesic.for application programming interface\endlink +for the library (this is just the documentation for the source file, +geodesic.for). + +\section samples-for Sample programs Also included are 3 small test programs: - geoddirect.for is a simple command line utility for solving the @@ -61,40 +71,148 @@ mkdir BUILD cd BUILD cmake .. make +make test echo 30 0 29.5 179.5 | ./geodinverse \endverbatim -\section library Using the library +Finally, the two programs + - ngsforward + - ngsinverse + . +which are also built with cmake, provide drop-in replacements for +replacements for the NGS tools FORWARD and INVERSE available from +http://www.ngs.noaa.gov/PC_PROD/Inv_Fwd/. +These cure two problems of the Vincenty algorithms used by NGS: + - the accuracy is "only" 0.1 mm; + - the inverse program sometimes goes into an infinite loop. + . +The corresponding source files + - ngsforward.for + - ngsinverse.for + - ngscommon.for + . +are derived from the NGS source files + - forward.for, version 2.0, dated 2002-08-21 + - inverse.for, version 3.0, dated 2012-11-04 + . +and are therefore in the public domain. -- Optionall put @verbatim - include "geodesic.inc" @endverbatim +\section library-for Using the library + +- Optionally put @code{.for} + include "geodesic.inc" + @endcode in declaration section of your subroutines. - make calls to the geodesic routines from your code. The interface to the library is documented in geodesic.for. - Compile and link as described above. -\section external External links +\section external-for External links - These algorithms are derived in C. F. F. Karney, - + Algorithms for geodesics, J. Geodesy 87, 43--55 (2013) - ( addenda). + ( addenda). - A longer paper on geodesics: C. F. F. Karney, - Geodesics + Geodesics on an ellipsoid of revolution, Feb. 2011 - ( + ( errata). -- The GeographicLib web site. -- The C++ library. -- The C library. -- The Java library. -- Documentation on the C++ classes: GeographicLib::Geodesic, - GeographicLib::GeodesicLine, GeographicLib::PolygonArea. -- The section in the %GeographicLib documentation on geodesics: \ref - geodesic. -- - An online geodesic bibliography. -**********************************************************************/ +- + Main project page +- + GeographicLib web site + - Documentation on the C++ classes: GeographicLib::Geodesic, + GeographicLib::GeodesicLine, GeographicLib::PolygonAreaT. + - The section in the %GeographicLib documentation on geodesics: \ref + geodesic. +- + git repository +- Implementations in various languages + - C++ (complete library): + + documentation, + + download; + - C (geodesic routines): + + documentation, also included with recent versions of + + proj.4; + - Fortran (geodesic routines): + + documentation; + - Java (geodesic routines): + + Maven Central package, + + documentation; + - JavaScript (geodesic routines): + + npm package, + + documentation; + - Python (geodesic routines): + + PyPI package, + + documentation; + - Matlab/Octave (geodesic and some other routines): + + Matlab Central package, + + documentation; + - C# (.NET wrapper for complete C++ library): + + documentation. +- + A geodesic bibliography. +- The wikipedia page, + + Geodesics on an ellipsoid. +\section changes-for Change log + + - Version 1.49 + (released 2017-10-05) + - Fix code formatting and add two tests. + + - Version 1.48 + (released 2017-04-09) + - Change default range for longitude and azimuth to + (−180°, 180°] (instead of + [−180°, 180°)). + + - Version 1.47 + (released 2017-02-15) + - Improve accuracy of area calculation (fixing a flaw introduced in + version 1.46). + + - Version 1.46 + (released 2016-02-15) + - More accurate inverse solution when longitude difference is close + to 180°. + + - Version 1.45 + (released 2015-09-30) + - The solution of the inverse problem now correctly returns NaNs if + one of the latitudes is a NaN. + - Include a test suite that can be run with "make test" after + configuring with cmake. + - The library now treats latitudes outside the range [−90°, + 90°] as NaNs; so the sample programs no longer check for legal + values of latitude. + + - Version 1.44 + (released 2015-08-14) + - Improve accuracy of calculations by evaluating trigonometric + functions more carefully and replacing the series for the reduced + length with one with a smaller truncation error. + - The allowed ranges for longitudes and azimuths is now unlimited; + it used to be [−540°, 540°). + - The sample programs, geoddirect and geodinverse, enforce the + restriction of latitude to [−90°, 90°]. + - The inverse calculation sets \e s12 to zero for coincident points + at pole (instead of returning a tiny quantity). **********************************************************************/ diff --git a/gtsam/3rdparty/GeographicLib/doc/geodseries30.html b/gtsam/3rdparty/GeographicLib/doc/geodseries30.html index 9305117b3..a428749dc 100644 --- a/gtsam/3rdparty/GeographicLib/doc/geodseries30.html +++ b/gtsam/3rdparty/GeographicLib/doc/geodseries30.html @@ -3,6 +3,7 @@ Series for geodesic calculations +

Series for geodesic calculations @@ -12,15 +13,15 @@ This extends the series given flattening. See
Charles F. F. Karney,
- - Algorithms for geodesics,
+ + Algorithms for geodesics,
J. Geodesy 87(1), 43–55 (Jan. 2013);
DOI: - - 10.1007/s00190-012-0578-z - (pdf); - addenda: - geod-addenda.html. + + 10.1007/s00190-012-0578-z + (pdf); + addenda: + geod-addenda.html.
@@ -524,21 +525,21 @@ C1'[28] = + 137344334847260471742767128830849077140799/3817741892241658452955877
 C1'[29] = + 2381352350093111938327626556685002210278872879/37975078602127776631552109325582336000000 * eps^29;
 C1'[30] = + 20034557328168749612075941075238883149/182929433787470496587153418485760 * eps^30;
 
-A2 = (1 + 1/4 * eps^2
-        + 9/64 * eps^4
-        + 25/256 * eps^6
-        + 1225/16384 * eps^8
-        + 3969/65536 * eps^10
-        + 53361/1048576 * eps^12
-        + 184041/4194304 * eps^14
-        + 41409225/1073741824 * eps^16
-        + 147744025/4294967296 * eps^18
-        + 2133423721/68719476736 * eps^20
-        + 7775536041/274877906944 * eps^22
-        + 457028729521/17592186044416 * eps^24
-        + 1690195005625/70368744177664 * eps^26
-        + 25145962430625/1125899906842624 * eps^28
-        + 93990019574025/4503599627370496 * eps^30) * (1 - eps);
+A2 = (1 - 3/4 * eps^2
+        - 7/64 * eps^4
+        - 11/256 * eps^6
+        - 375/16384 * eps^8
+        - 931/65536 * eps^10
+        - 10143/1048576 * eps^12
+        - 29403/4194304 * eps^14
+        - 5705271/1073741824 * eps^16
+        - 17892875/4294967296 * eps^18
+        - 230480679/68719476736 * eps^20
+        - 758158843/274877906944 * eps^22
+        - 40605577103/17592186044416 * eps^24
+        - 137919912459/70368744177664 * eps^26
+        - 1897157659375/1125899906842624 * eps^28
+        - 6593830148475/4503599627370496 * eps^30) / (1 + eps);
 
 C2[1] = + 1/2 * eps
         + 1/16 * eps^3
diff --git a/gtsam/3rdparty/GeographicLib/doc/index.html.in b/gtsam/3rdparty/GeographicLib/doc/index.html.in
index 828a35895..9e0dc78d6 100644
--- a/gtsam/3rdparty/GeographicLib/doc/index.html.in
+++ b/gtsam/3rdparty/GeographicLib/doc/index.html.in
@@ -2,7 +2,7 @@
   
     GeographicLib-@PROJECT_VERSION@ documentation
     
+	  CONTENT="0; URL=https://geographiclib.sourceforge.io/@PROJECT_VERSION@/index.html">
   
   
     

@@ -11,8 +11,8 @@ Online documentation for GeographicLib version @PROJECT_VERSION@ is available at
- - http://geographiclib.sourceforge.net/@PROJECT_VERSION@/index.html. + + https://geographiclib.sourceforge.io/@PROJECT_VERSION@/index.html.

You will be redirected there. Click on the link to go there diff --git a/gtsam/3rdparty/GeographicLib/doc/normal-gravity-potential-1.svg b/gtsam/3rdparty/GeographicLib/doc/normal-gravity-potential-1.svg new file mode 100644 index 000000000..416ef946f --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/doc/normal-gravity-potential-1.svg @@ -0,0 +1,170 @@ + + +0123R012Z diff --git a/gtsam/3rdparty/GeographicLib/doc/scripts/GeographicLib/DMS.js b/gtsam/3rdparty/GeographicLib/doc/scripts/GeographicLib/DMS.js deleted file mode 100644 index e2f339f01..000000000 --- a/gtsam/3rdparty/GeographicLib/doc/scripts/GeographicLib/DMS.js +++ /dev/null @@ -1,364 +0,0 @@ -/** - * DMS.js - * Transcription of DMS.[ch]pp into JavaScript. - * - * See the documentation for the C++ class. The conversion is a literal - * conversion from C++. - * - * Copyright (c) Charles Karney (2011) and licensed - * under the MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ - **********************************************************************/ - -GeographicLib.DMS = {}; - -(function() { - var d = GeographicLib.DMS; - var m = GeographicLib.Math; - d.lookup = function(s, c) { - return s.indexOf(c.toUpperCase()); - } - d.zerofill = function(s, n) { - return String("0000").substr(0, Math.max(0, Math.min(4, n-s.length))) + - s; - } - d.hemispheres_ = "SNWE"; - d.signs_ = "-+"; - d.digits_ = "0123456789"; - d.dmsindicators_ = "D'\":"; - // d.dmsindicatorsu_ = "\u00b0\u2032\u2033"; // Unicode variants - d.dmsindicatorsu_ = "\u00b0'\""; // Use degree symbol - d.components_ = ["degrees", "minutes", "seconds"]; - d.NONE = 0; - d.LATITUDE = 1; - d.LONGITUDE = 2; - d.AZIMUTH = 3; - d.NUMBER = 4; - d.DEGREE = 0; - d.MINUTE = 1; - d.SECOND = 2; - - // return val, ind - d.Decode = function(dms) { - var vals = {}; - var errormsg = new String(""); - var dmsa = dms; - dmsa = dmsa.replace(/\u00b0/g, 'd'); - dmsa = dmsa.replace(/\u00ba/g, 'd'); - dmsa = dmsa.replace(/\u2070/g, 'd'); - dmsa = dmsa.replace(/\u02da/g, 'd'); - dmsa = dmsa.replace(/\u2032/g, '\''); - dmsa = dmsa.replace(/\u00b4/g, '\''); - dmsa = dmsa.replace(/\u2019/g, '\''); - dmsa = dmsa.replace(/\u2033/g, '"'); - dmsa = dmsa.replace(/\u201d/g, '"'); - dmsa = dmsa.replace(/''/g, '"'); - dmsa = dmsa.replace(/^\s+/, ""); - dmsa = dmsa.replace(/\s+$/, ""); - do { // Executed once (provides the ability to break) - var sign = 1; - var beg = 0, end = dmsa.length; - var ind1 = d.NONE; - var k = -1; - if (end > beg && (k = d.lookup(d.hemispheres_, dmsa.charAt(beg))) >= 0) { - ind1 = (k & 2) ? d.LONGITUDE : d.LATITUDE; - sign = (k & 1) ? 1 : -1; - ++beg; - } - if (end > beg && - (k = d.lookup(d.hemispheres_, dmsa.charAt(end-1))) >= 0) { - if (k >= 0) { - if (ind1 != d.NONE) { - if (dmsa.charAt(beg - 1).toUpperCase() == - dmsa.charAt(end - 1).toUpperCase()) - errormsg = "Repeated hemisphere indicators " + - dmsa.charAt(beg - 1) + " in " + - dmsa.substr(beg - 1, end - beg + 1); - else - errormsg = "Contradictory hemisphere indicators " + - dmsa.charAt(beg - 1) + " and " + dmsa.charAt(end - 1) + " in " + - dmsa.substr(beg - 1, end - beg + 1); - break; - } - ind1 = (k & 2) ? d.LONGITUDE : d.LATITUDE; - sign = (k & 1) ? 1 : -1; - --end; - } - } - if (end > beg && (k = d.lookup(d.signs_, dmsa.charAt(beg))) >= 0) { - if (k >= 0) { - sign *= k ? 1 : -1; - ++beg; - } - } - if (end == beg) { - errormsg = "Empty or incomplete DMS string " + dmsa; - break; - } - var ipieces = [0, 0, 0]; - var fpieces = [0, 0, 0]; - var npiece = 0; - var icurrent = 0; - var fcurrent = 0; - var ncurrent = 0, p = beg; - var pointseen = false; - var digcount = 0; - var intcount = 0; - while (p < end) { - var x = dmsa.charAt(p++); - if ((k = d.lookup(d.digits_, x)) >= 0) { - ++ncurrent; - if (digcount > 0) - ++digcount; // Count of decimal digits - else { - icurrent = 10 * icurrent + k; - ++intcount; - } - } else if (x == '.') { - if (pointseen) { - errormsg = "Multiple decimal points in " - + dmsa.substr(beg, end - beg); - break; - } - pointseen = true; - digcount = 1; - } else if ((k = d.lookup(d.dmsindicators_, x)) >= 0) { - if (k >= 3) { - if (p == end) { - errormsg = "Illegal for : to appear at the end of " + - dmsa.substr(beg, end - beg); - break; - } - k = npiece; - } - if (k == npiece - 1) { - errormsg = "Repeated " + d.components_[k] + - " component in " + dmsa.substr(beg, end - beg); - break; - } else if (k < npiece) { - errormsg = d.components_[k] + " component follows " - + d.components_[npiece - 1] + " component in " - + dmsa.substr(beg, end - beg); - break; - } - if (ncurrent == 0) { - errormsg = "Missing numbers in " + d.components_[k] + - " component of " + dmsa.substr(beg, end - beg); - break; - } - if (digcount > 1) { - fcurrent = parseFloat(dmsa.substr(p - intcount - digcount - 1, - intcount + digcount)); - icurrent = 0; - } - ipieces[k] = icurrent; - fpieces[k] = icurrent + fcurrent; - if (p < end) { - npiece = k + 1; - icurrent = fcurrent = 0; - ncurrent = digcount = intcount = 0; - } - } else if (d.lookup(d.signs_, x) >= 0) { - errormsg = "Internal sign in DMS string " - + dmsa.substr(beg, end - beg); - break; - } else { - errormsg = "Illegal character " + x + " in DMS string " - + dmsa.substr(beg, end - beg); - break; - } - } - if (errormsg.length) - break; - if (d.lookup(d.dmsindicators_, dmsa.charAt(p - 1)) < 0) { - if (npiece >= 3) { - errormsg = "Extra text following seconds in DMS string " - + dmsa.substr(beg, end - beg); - break; - } - if (ncurrent == 0) { - errormsg = "Missing numbers in trailing component of " - + dmsa.substr(beg, end - beg); - break; - } - if (digcount > 1) { - fcurrent = parseFloat(dmsa.substr(p - intcount - digcount, - intcount + digcount)); - icurrent = 0; - } - ipieces[npiece] = icurrent; - fpieces[npiece] = icurrent + fcurrent; - } - if (pointseen && digcount == 0) { - errormsg = "Decimal point in non-terminal component of " - + dmsa.substr(beg, end - beg); - break; - } - // Note that we accept 59.999999... even though it rounds to 60. - if (ipieces[1] >= 60) { - errormsg = "Minutes " + fpieces[1] + " not in range [0, 60)"; - break; - } - if (ipieces[2] >= 60) { - errormsg = "Seconds " + fpieces[2] + " not in range [0, 60)"; - break; - } - vals.ind = ind1; - // Assume check on range of result is made by calling routine (which - // might be able to offer a better diagnostic). - vals.val = sign * (fpieces[0] + (fpieces[1] + fpieces[2] / 60) / 60); - return vals; - } while (false); - vals.val = d.NumMatch(dmsa); - if (vals.val == 0) - throw new Error(errormsg); - else - vals.ind = d.NONE; - return vals; - } - - d.NumMatch = function(s) { - if (s.length < 3) - return 0; - var t = s.toUpperCase().replace(/0+$/,""); - var sign = t.charAt(0) == '-' ? -1 : 1; - var p0 = t.charAt(0) == '-' || t.charAt(0) == '+' ? 1 : 0; - var p1 = t.length - 1; - if (p1 + 1 < p0 + 3) - return 0; - // Strip off sign and trailing 0s - t = t.substr(p0, p1 + 1 - p0); // Length at least 3 - if (t == "NAN" || t == "1.#QNAN" || t == "1.#SNAN" || t == "1.#IND" || - t == "1.#R") - return sign * Number.NaN; - else if (t == "INF" || t == "1.#INF") - return sign * Number.POSITIVE_INFINITY; - return 0; - } - - // return lat, lon - d.DecodeLatLon = function(stra, strb, swaplatlong) { - var vals = {}; - if (!swaplatlong) swaplatlong = false; - var valsa = d.Decode(stra); - var valsb = d.Decode(strb); - var a = valsa.val, ia = valsa.ind; - var b = valsb.val, ib = valsb.ind; - if (ia == d.NONE && ib == d.NONE) { - // Default to lat, long unless swaplatlong - ia = swaplatlong ? d.LONGITUDE : d.LATITUDE; - ib = swaplatlong ? d.LATITUDE : d.LONGITUDE; - } else if (ia == d.NONE) - ia = d.LATITUDE + d.LONGITUDE - ib; - else if (ib == d.NONE) - ib = d.LATITUDE + d.LONGITUDE - ia; - if (ia == ib) - throw new Error("Both " + stra + " and " - + strb + " interpreted as " - + (ia == d.LATITUDE ? "latitudes" : "longitudes")); - var lat = ia == d.LATITUDE ? a : b, lon = ia == d.LATITUDE ? b : a; - if (Math.abs(lat) > 90) - throw new Error("Latitude " + lat + "d not in [-90d, 90d]"); - if (lon < -540 || lon >= 540) - throw new Error("Latitude " + lon + "d not in [-540d, 540d)"); - lon = m.AngNormalize(lon); - vals.lat = lat; - vals.lon = lon; - return vals; - } - - d.DecodeAngle = function(angstr) { - var vals = d.Decode(angstr); - var ang = vals.val, ind = vals.ind; - if (ind != d.NONE) - throw new Error("Arc angle " + angstr - + " includes a hemisphere, N/E/W/S"); - return ang; - } - - d.DecodeAzimuth = function(azistr) { - var vals = d.Decode(azistr); - var azi = vals.val, ind = vals.ind; - if (ind == d.LATITUDE) - throw new Error("Azimuth " + azistr - + " has a latitude hemisphere, N/S"); - if (azi < -540 || azi >= 540) - throw new Error("Azimuth " + azistr + " not in range [-540d, 540d)"); - azi = m.AngNormalize(azi); - return azi; - } - - d.Encode = function(angle, trailing, prec, ind) { - // Assume check on range of input angle has been made by calling - // routine (which might be able to offer a better diagnostic). - if (!ind) ind = d.NONE; - if (!isFinite(angle)) - return angle < 0 ? String("-inf") : - (angle > 0 ? String("inf") : String("nan")); - - // 15 - 2 * trailing = ceiling(log10(2^53/90/60^trailing)). - // This suffices to give full real precision for numbers in [-90,90] - prec = Math.min(15 - 2 * trailing, prec); - var scale = 1, i; - for (i = 0; i < trailing; ++i) - scale *= 60; - for (i = 0; i < prec; ++i) - scale *= 10; - if (ind == d.AZIMUTH) - angle -= Math.floor(angle/360) * 360; - var sign = angle < 0 ? -1 : 1; - angle *= sign; - - // Break off integer part to preserve precision in manipulation of - // fractional part. - var - idegree = Math.floor(angle), - fdegree = Math.floor((angle - idegree) * scale + 0.5) / scale; - if (fdegree >= 1) { - idegree += 1; - fdegree -= 1; - } - var pieces = [fdegree, 0, 0]; - for (i = 1; i <= trailing; ++i) { - var - ip = Math.floor(pieces[i - 1]), - fp = pieces[i - 1] - ip; - pieces[i] = fp * 60; - pieces[i - 1] = ip; - } - pieces[0] += idegree; - var s = new String(""); - if (ind == d.NONE && sign < 0) - s += '-'; - switch (trailing) { - case d.DEGREE: - s += d.zerofill(pieces[0].toFixed(prec), - ind == d.NONE ? 0 : - 1 + Math.min(ind, 2) + prec + (prec ? 1 : 0)) + - d.dmsindicatorsu_.charAt(0); - break; - default: - s += d.zerofill(pieces[0].toFixed(0), - ind == d.NONE ? 0 : 1 + Math.min(ind, 2)) + - d.dmsindicatorsu_.charAt(0); - switch (trailing) { - case d.MINUTE: - s += d.zerofill(pieces[1].toFixed(prec), 2 + prec + (prec ? 1 : 0)) + - d.dmsindicatorsu_.charAt(1); - break; - case d.SECOND: - s += d.zerofill(pieces[1].toFixed(0), 2) + d.dmsindicatorsu_.charAt(1); - s += d.zerofill(pieces[2].toFixed(prec), 2 + prec + (prec ? 1 : 0)) + - d.dmsindicatorsu_.charAt(2); - break; - default: - break; - } - } - if (ind != d.NONE && ind != d.AZIMUTH) - s += d.hemispheres_.charAt((ind == d.LATITUDE ? 0 : 2) + - (sign < 0 ? 0 : 1)); - return s; - } - -})(); diff --git a/gtsam/3rdparty/GeographicLib/doc/scripts/GeographicLib/Geodesic.js b/gtsam/3rdparty/GeographicLib/doc/scripts/GeographicLib/Geodesic.js deleted file mode 100644 index cf059126f..000000000 --- a/gtsam/3rdparty/GeographicLib/doc/scripts/GeographicLib/Geodesic.js +++ /dev/null @@ -1,1019 +0,0 @@ -/** - * Geodesic.js - * Transcription of Geodesic.[ch]pp into JavaScript. - * - * See the documentation for the C++ class. The conversion is a literal - * conversion from C++. - * - * The algorithms are derived in - * - * Charles F. F. Karney, - * Algorithms for geodesics, J. Geodesy 87, 43-55 (2013); - * http://dx.doi.org/10.1007/s00190-012-0578-z - * Addenda: http://geographiclib.sf.net/geod-addenda.html - * - * Copyright (c) Charles Karney (2011-2013) and licensed - * under the MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ - **********************************************************************/ - -// Load AFTER Math.js - -GeographicLib.Geodesic = {}; -GeographicLib.GeodesicLine = {}; - -(function() { - var m = GeographicLib.Math; - var g = GeographicLib.Geodesic; - var l = GeographicLib.GeodesicLine; - g.GEOGRAPHICLIB_GEODESIC_ORDER = 6; - g.nA1_ = g.GEOGRAPHICLIB_GEODESIC_ORDER; - g.nC1_ = g.GEOGRAPHICLIB_GEODESIC_ORDER; - g.nC1p_ = g.GEOGRAPHICLIB_GEODESIC_ORDER; - g.nA2_ = g.GEOGRAPHICLIB_GEODESIC_ORDER; - g.nC2_ = g.GEOGRAPHICLIB_GEODESIC_ORDER; - g.nA3_ = g.GEOGRAPHICLIB_GEODESIC_ORDER; - g.nA3x_ = g.nA3_; - g.nC3_ = g.GEOGRAPHICLIB_GEODESIC_ORDER; - g.nC3x_ = (g.nC3_ * (g.nC3_ - 1)) / 2; - g.nC4_ = g.GEOGRAPHICLIB_GEODESIC_ORDER; - g.nC4x_ = (g.nC4_ * (g.nC4_ + 1)) / 2; - g.maxit1_ = 20; - g.maxit2_ = g.maxit1_ + m.digits + 10; - g.tiny_ = Math.sqrt(Number.MIN_VALUE); - g.tol0_ = m.epsilon; - g.tol1_ = 200 * g.tol0_; - g.tol2_ = Math.sqrt(g.tol0_); - g.tolb_ = g.tol0_ * g.tol1_; - g.xthresh_ = 1000 * g.tol2_; - - g.CAP_NONE = 0; - g.CAP_C1 = 1<<0; - g.CAP_C1p = 1<<1; - g.CAP_C2 = 1<<2; - g.CAP_C3 = 1<<3; - g.CAP_C4 = 1<<4; - g.CAP_ALL = 0x1F; - g.OUT_ALL = 0x7F80; - g.NONE = 0; - g.LATITUDE = 1<<7 | g.CAP_NONE; - g.LONGITUDE = 1<<8 | g.CAP_C3; - g.AZIMUTH = 1<<9 | g.CAP_NONE; - g.DISTANCE = 1<<10 | g.CAP_C1; - g.DISTANCE_IN = 1<<11 | g.CAP_C1 | g.CAP_C1p; - g.REDUCEDLENGTH = 1<<12 | g.CAP_C1 | g.CAP_C2; - g.GEODESICSCALE = 1<<13 | g.CAP_C1 | g.CAP_C2; - g.AREA = 1<<14 | g.CAP_C4; - g.ALL = g.OUT_ALL| g.CAP_ALL; - - g.SinCosSeries = function(sinp, sinx, cosx, c, n) { - // Evaluate - // y = sinp ? sum(c[i] * sin( 2*i * x), i, 1, n) : - // sum(c[i] * cos((2*i+1) * x), i, 0, n-1) - // using Clenshaw summation. N.B. c[0] is unused for sin series - // Approx operation count = (n + 5) mult and (2 * n + 2) add - var k = n + (sinp ? 1 : 0); // Point to one beyond last element - var - ar = 2 * (cosx - sinx) * (cosx + sinx), // 2 * cos(2 * x) - y0 = n & 1 ? c[--k] : 0, y1 = 0; // accumulators for sum - // Now n is even - n = Math.floor(n/2); - while (n--) { - // Unroll loop x 2, so accumulators return to their original role - y1 = ar * y0 - y1 + c[--k]; - y0 = ar * y1 - y0 + c[--k]; - } - return (sinp - ? 2 * sinx * cosx * y0 // sin(2 * x) * y0 - : cosx * (y0 - y1)); // cos(x) * (y0 - y1) - } - - g.AngRound = function(x) { - // The makes the smallest gap in x = 1/16 - nextafter(1/16, 0) = 1/2^57 - // for reals = 0.7 pm on the earth if x is an angle in degrees. (This - // is about 1000 times more resolution than we get with angles around 90 - // degrees.) We use this to avoid having to deal with near singular - // cases when x is non-zero but tiny (e.g., 1.0e-200). - var z = 1/16; - var y = Math.abs(x); - // The compiler mustn't "simplify" z - (z - y) to y - y = y < z ? z - (z - y) : y; - return x < 0 ? -y : y; - } - g.Astroid = function(x, y) { - // Solve k^4+2*k^3-(x^2+y^2-1)*k^2-2*y^2*k-y^2 = 0 for positive - // root k. This solution is adapted from Geocentric::Reverse. - var k; - var - p = m.sq(x), - q = m.sq(y), - r = (p + q - 1) / 6; - if ( !(q == 0 && r <= 0) ) { - var - // Avoid possible division by zero when r = 0 by multiplying - // equations for s and t by r^3 and r, resp. - S = p * q / 4, // S = r^3 * s - r2 = m.sq(r), - r3 = r * r2, - // The discrimant of the quadratic equation for T3. This is - // zero on the evolute curve p^(1/3)+q^(1/3) = 1 - disc = S * (S + 2 * r3); - var u = r; - if (disc >= 0) { - var T3 = S + r3; - // Pick the sign on the sqrt to maximize abs(T3). This - // minimizes loss of precision due to cancellation. The - // result is unchanged because of the way the T is used - // in definition of u. - T3 += T3 < 0 ? -Math.sqrt(disc) - : Math.sqrt(disc); // T3 = (r * t)^3 - // N.B. cbrt always returns the real root. cbrt(-8) = -2. - var T = m.cbrt(T3); // T = r * t - // T can be zero; but then r2 / T -> 0. - u += T + (T != 0 ? r2 / T : 0); - } else { - // T is complex, but the way u is defined the result is real. - var ang = Math.atan2(Math.sqrt(-disc), -(S + r3)); - // There are three possible cube roots. We choose the - // root which avoids cancellation. Note that disc < 0 - // implies that r < 0. - u += 2 * r * Math.cos(ang / 3); - } - var - v = Math.sqrt(m.sq(u) + q), // guaranteed positive - // Avoid loss of accuracy when u < 0. - uv = u < 0 ? q / (v - u) : u + v, // u+v, guaranteed positive - w = (uv - q) / (2 * v); // positive? - // Rearrange expression for k to avoid loss of accuracy due to - // subtraction. Division by 0 not possible because uv > 0, w >= 0. - k = uv / (Math.sqrt(uv + m.sq(w)) + w); // guaranteed positive - } else { // q == 0 && r <= 0 - // y = 0 with |x| <= 1. Handle this case directly. - // for y small, positive root is k = abs(y)/sqrt(1-x^2) - k = 0; - } - return k; - } - - g.A1m1f = function(eps) { - var - eps2 = m.sq(eps), - t = eps2*(eps2*(eps2+4)+64)/256; - return (t + eps) / (1 - eps); - } - - g.C1f = function(eps, c) { - var - eps2 = m.sq(eps), - d = eps; - c[1] = d*((6-eps2)*eps2-16)/32; - d *= eps; - c[2] = d*((64-9*eps2)*eps2-128)/2048; - d *= eps; - c[3] = d*(9*eps2-16)/768; - d *= eps; - c[4] = d*(3*eps2-5)/512; - d *= eps; - c[5] = -7*d/1280; - d *= eps; - c[6] = -7*d/2048; - } - - g.C1pf = function(eps, c) { - var - eps2 = m.sq(eps), - d = eps; - c[1] = d*(eps2*(205*eps2-432)+768)/1536; - d *= eps; - c[2] = d*(eps2*(4005*eps2-4736)+3840)/12288; - d *= eps; - c[3] = d*(116-225*eps2)/384; - d *= eps; - c[4] = d*(2695-7173*eps2)/7680; - d *= eps; - c[5] = 3467*d/7680; - d *= eps; - c[6] = 38081*d/61440; - } - - g.A2m1f = function(eps) { - var - eps2 = m.sq(eps), - t = eps2*(eps2*(25*eps2+36)+64)/256; - return t * (1 - eps) - eps; - } - - g.C2f = function(eps, c) { - var - eps2 = m.sq(eps), - d = eps; - c[1] = d*(eps2*(eps2+2)+16)/32; - d *= eps; - c[2] = d*(eps2*(35*eps2+64)+384)/2048; - d *= eps; - c[3] = d*(15*eps2+80)/768; - d *= eps; - c[4] = d*(7*eps2+35)/512; - d *= eps; - c[5] = 63*d/1280; - d *= eps; - c[6] = 77*d/2048; - } - - g.Geodesic = function(a, f) { - this._a = a; - this._f = f <= 1 ? f : 1/f; - this._f1 = 1 - this._f; - this._e2 = this._f * (2 - this._f); - this._ep2 = this._e2 / m.sq(this._f1); // e2 / (1 - e2) - this._n = this._f / ( 2 - this._f); - this._b = this._a * this._f1; - // authalic radius squared - this._c2 = (m.sq(this._a) + m.sq(this._b) * - (this._e2 == 0 ? 1 : - (this._e2 > 0 ? m.atanh(Math.sqrt(this._e2)) : - Math.atan(Math.sqrt(-this._e2))) / - Math.sqrt(Math.abs(this._e2))))/2; - // The sig12 threshold for "really short". Using the auxiliary sphere - // solution with dnm computed at (bet1 + bet2) / 2, the relative error in - // the azimuth consistency check is sig12^2 * abs(f) * min(1, 1-f/2) / 2. - // (Error measured for 1/100 < b/a < 100 and abs(f) >= 1/1000. For a given - // f and sig12, the max error occurs for lines near the pole. If the old - // rule for computing dnm = (dn1 + dn2)/2 is used, then the error increases - // by a factor of 2.) Setting this equal to epsilon gives sig12 = etol2. - // Here 0.1 is a safety factor (error decreased by 100) and max(0.001, - // abs(f)) stops etol2 getting too large in the nearly spherical case. - this._etol2 = 0.1 * g.tol2_ / - Math.sqrt( Math.max(0.001, Math.abs(this._f)) * - Math.min(1.0, 1 - this._f/2) / 2 ); - if (!(isFinite(this._a) && this._a > 0)) - throw new Error("Major radius is not positive"); - if (!(isFinite(this._b) && this._b > 0)) - throw new Error("Minor radius is not positive"); - this._A3x = new Array(g.nA3x_); - this._C3x = new Array(g.nC3x_); - this._C4x = new Array(g.nC4x_); - this.A3coeff(); - this.C3coeff(); - this.C4coeff(); - } - - g.Geodesic.prototype.A3coeff = function() { - var _n = this._n; - this._A3x[0] = 1; - this._A3x[1] = (_n-1)/2; - this._A3x[2] = (_n*(3*_n-1)-2)/8; - this._A3x[3] = ((-_n-3)*_n-1)/16; - this._A3x[4] = (-2*_n-3)/64; - this._A3x[5] = -3/128; - } - - g.Geodesic.prototype.C3coeff = function() { - var _n = this._n; - this._C3x[0] = (1-_n)/4; - this._C3x[1] = (1-_n*_n)/8; - this._C3x[2] = ((3-_n)*_n+3)/64; - this._C3x[3] = (2*_n+5)/128; - this._C3x[4] = 3/128; - this._C3x[5] = ((_n-3)*_n+2)/32; - this._C3x[6] = ((-3*_n-2)*_n+3)/64; - this._C3x[7] = (_n+3)/128; - this._C3x[8] = 5/256; - this._C3x[9] = (_n*(5*_n-9)+5)/192; - this._C3x[10] = (9-10*_n)/384; - this._C3x[11] = 7/512; - this._C3x[12] = (7-14*_n)/512; - this._C3x[13] = 7/512; - this._C3x[14] = 21/2560; - } - - g.Geodesic.prototype.C4coeff = function() { - var _n = this._n; - this._C4x[0] = (_n*(_n*(_n*(_n*(100*_n+208)+572)+3432)-12012)+30030)/45045; - this._C4x[1] = (_n*(_n*(_n*(64*_n+624)-4576)+6864)-3003)/15015; - this._C4x[2] = (_n*((14144-10656*_n)*_n-4576)-858)/45045; - this._C4x[3] = ((-224*_n-4784)*_n+1573)/45045; - this._C4x[4] = (1088*_n+156)/45045; - this._C4x[5] = 97/15015.0; - this._C4x[6] = (_n*(_n*((-64*_n-624)*_n+4576)-6864)+3003)/135135; - this._C4x[7] = (_n*(_n*(5952*_n-11648)+9152)-2574)/135135; - this._C4x[8] = (_n*(5792*_n+1040)-1287)/135135; - this._C4x[9] = (468-2944*_n)/135135; - this._C4x[10] = 1/9009.0; - this._C4x[11] = (_n*((4160-1440*_n)*_n-4576)+1716)/225225; - this._C4x[12] = ((4992-8448*_n)*_n-1144)/225225; - this._C4x[13] = (1856*_n-936)/225225; - this._C4x[14] = 8/10725.0; - this._C4x[15] = (_n*(3584*_n-3328)+1144)/315315; - this._C4x[16] = (1024*_n-208)/105105; - this._C4x[17] = -136/63063.0; - this._C4x[18] = (832-2560*_n)/405405; - this._C4x[19] = -128/135135.0; - this._C4x[20] = 128/99099.0; - } - - g.Geodesic.prototype.A3f = function(eps) { - // Evaluate sum(_A3x[k] * eps^k, k, 0, nA3x_-1) by Horner's method - var v = 0; - for (var i = g.nA3x_; i; ) - v = eps * v + this._A3x[--i]; - return v; - } - - g.Geodesic.prototype.C3f = function(eps, c) { - // Evaluate C3 coeffs by Horner's method - // Elements c[1] thru c[nC3_ - 1] are set - for (var j = g.nC3x_, k = g.nC3_ - 1; k; ) { - var t = 0; - for (var i = g.nC3_ - k; i; --i) - t = eps * t + this._C3x[--j]; - c[k--] = t; - } - - var mult = 1; - for (var k = 1; k < g.nC3_; ) { - mult *= eps; - c[k++] *= mult; - } - } - - g.Geodesic.prototype.C4f = function(eps, c) { - // Evaluate C4 coeffs by Horner's method - // Elements c[0] thru c[nC4_ - 1] are set - for (var j = g.nC4x_, k = g.nC4_; k; ) { - var t = 0; - for (var i = g.nC4_ - k + 1; i; --i) - t = eps * t + this._C4x[--j]; - c[--k] = t; - } - - var mult = 1; - for (var k = 1; k < g.nC4_; ) { - mult *= eps; - c[k++] *= mult; - } - } - - // return s12b, m12b, m0, M12, M21 - g.Geodesic.prototype.Lengths = function(eps, sig12, - ssig1, csig1, dn1, ssig2, csig2, dn2, - cbet1, cbet2, scalep, - C1a, C2a) { - var vals = {}; - // Return m12b = (reduced length)/_b; also calculate s12b = - // distance/_b, and m0 = coefficient of secular term in - // expression for reduced length. - g.C1f(eps, C1a); - g.C2f(eps, C2a); - var - A1m1 = g.A1m1f(eps), - AB1 = (1 + A1m1) * (g.SinCosSeries(true, ssig2, csig2, C1a, g.nC1_) - - g.SinCosSeries(true, ssig1, csig1, C1a, g.nC1_)), - A2m1 = g.A2m1f(eps), - AB2 = (1 + A2m1) * (g.SinCosSeries(true, ssig2, csig2, C2a, g.nC2_) - - g.SinCosSeries(true, ssig1, csig1, C2a, g.nC2_)); - vals.m0 = A1m1 - A2m1; - var J12 = vals.m0 * sig12 + (AB1 - AB2); - // Missing a factor of _b. - // Add parens around (csig1 * ssig2) and (ssig1 * csig2) to - // ensure accurate cancellation in the case of coincident - // points. - vals.m12b = dn2 * (csig1 * ssig2) - dn1 * (ssig1 * csig2) - - csig1 * csig2 * J12; - // Missing a factor of _b - vals.s12b = (1 + A1m1) * sig12 + AB1; - if (scalep) { - var csig12 = csig1 * csig2 + ssig1 * ssig2; - var t = this._ep2 * (cbet1 - cbet2) * (cbet1 + cbet2) / (dn1 + dn2); - vals.M12 = csig12 + (t * ssig2 - csig2 * J12) * ssig1 / dn1; - vals.M21 = csig12 - (t * ssig1 - csig1 * J12) * ssig2 / dn2; - } - return vals; - } - - // return sig12, salp1, calp1, salp2, calp2, dnm - g.Geodesic.prototype.InverseStart = function(sbet1, cbet1, dn1, - sbet2, cbet2, dn2, lam12, - C1a, C2a) { - // Return a starting point for Newton's method in salp1 and calp1 - // (function value is -1). If Newton's method doesn't need to be - // used, return also salp2 and calp2 and function value is sig12. - // salp2, calp2 only updated if return val >= 0. - var - vals = {}, - // bet12 = bet2 - bet1 in [0, pi); bet12a = bet2 + bet1 in (-pi, 0] - sbet12 = sbet2 * cbet1 - cbet2 * sbet1, - cbet12 = cbet2 * cbet1 + sbet2 * sbet1; - vals.sig12 = -1; // Return value - // Volatile declaration needed to fix inverse cases - // 88.202499451857 0 -88.202499451857 179.981022032992859592 - // 89.262080389218 0 -89.262080389218 179.992207982775375662 - // 89.333123580033 0 -89.333123580032997687 179.99295812360148422 - // which otherwise fail with g++ 4.4.4 x86 -O3 - var sbet12a = sbet2 * cbet1; - sbet12a += cbet2 * sbet1; - - var shortline = cbet12 >= 0 && sbet12 < 0.5 && cbet2 * lam12 < 0.5; - var omg12 = lam12; - if (shortline) { - var sbetm2 = m.sq(sbet1 + sbet2); - // sin((bet1+bet2)/2)^2 - // = (sbet1 + sbet2)^2 / ((sbet1 + sbet2)^2 + (cbet1 + cbet2)^2) - sbetm2 /= sbetm2 + m.sq(cbet1 + cbet2); - vals.dnm = Math.sqrt(1 + this._ep2 * sbetm2); - omg12 /= this._f1 * vals.dnm; - } - var somg12 = Math.sin(omg12), comg12 = Math.cos(omg12); - - vals.salp1 = cbet2 * somg12; - vals.calp1 = comg12 >= 0 ? - sbet12 + cbet2 * sbet1 * m.sq(somg12) / (1 + comg12) : - sbet12a - cbet2 * sbet1 * m.sq(somg12) / (1 - comg12); - - var - ssig12 = m.hypot(vals.salp1, vals.calp1), - csig12 = sbet1 * sbet2 + cbet1 * cbet2 * comg12; - - if (shortline && ssig12 < this._etol2) { - // really short lines - vals.salp2 = cbet1 * somg12; - vals.calp2 = sbet12 - cbet1 * sbet2 * - (comg12 >= 0 ? m.sq(somg12) / (1 + comg12) : 1 - comg12); - // SinCosNorm(vals.salp2, vals.calp2); - var t = m.hypot(vals.salp2, vals.calp2); vals.salp2 /= t; vals.calp2 /= t; - // Set return value - vals.sig12 = Math.atan2(ssig12, csig12); - } else if (Math.abs(this._n) > 0.1 || // Skip astroid calc if too eccentric - csig12 >= 0 || - ssig12 >= 6 * Math.abs(this._n) * Math.PI * m.sq(cbet1)) { - // Nothing to do, zeroth order spherical approximation is OK - } else { - // Scale lam12 and bet2 to x, y coordinate system where antipodal - // point is at origin and singular point is at y = 0, x = -1. - var y, lamscale, betscale; - // Volatile declaration needed to fix inverse case - // 56.320923501171 0 -56.320923501171 179.664747671772880215 - // which otherwise fails with g++ 4.4.4 x86 -O3 - var x; - if (this._f >= 0) { // In fact f == 0 does not get here - // x = dlong, y = dlat - { - var - k2 = m.sq(sbet1) * this._ep2, - eps = k2 / (2 * (1 + Math.sqrt(1 + k2)) + k2); - lamscale = this._f * cbet1 * this.A3f(eps) * Math.PI; - } - betscale = lamscale * cbet1; - - x = (lam12 - Math.PI) / lamscale; - y = sbet12a / betscale; - } else { // _f < 0 - // x = dlat, y = dlong - var - cbet12a = cbet2 * cbet1 - sbet2 * sbet1, - bet12a = Math.atan2(sbet12a, cbet12a); - var m12b, m0; - // In the case of lon12 = 180, this repeats a calculation made - // in Inverse. - var nvals = this.Lengths(this._n, Math.PI + bet12a, - sbet1, -cbet1, dn1, sbet2, cbet2, dn2, - cbet1, cbet2, false, C1a, C2a); - m12b = nvals.m12b; m0 = nvals.m0; - x = -1 + m12b / (cbet1 * cbet2 * m0 * Math.PI); - betscale = x < -0.01 ? sbet12a / x : - -this._f * m.sq(cbet1) * Math.PI; - lamscale = betscale / cbet1; - y = (lam12 - Math.PI) / lamscale; - } - - if (y > -g.tol1_ && x > -1 - g.xthresh_) { - // strip near cut - if (this._f >= 0) { - vals.salp1 = Math.min(1, -x); - vals.calp1 = - Math.sqrt(1 - m.sq(vals.salp1)); - } else { - vals.calp1 = Math.max(x > -g.tol1_ ? 0 : -1, x); - vals.salp1 = Math.sqrt(1 - m.sq(vals.calp1)); - } - } else { - // Estimate alp1, by solving the astroid problem. - // - // Could estimate alpha1 = theta + pi/2, directly, i.e., - // calp1 = y/k; salp1 = -x/(1+k); for _f >= 0 - // calp1 = x/(1+k); salp1 = -y/k; for _f < 0 (need to check) - // - // However, it's better to estimate omg12 from astroid and use - // spherical formula to compute alp1. This reduces the mean number of - // Newton iterations for astroid cases from 2.24 (min 0, max 6) to 2.12 - // (min 0 max 5). The changes in the number of iterations are as - // follows: - // - // change percent - // 1 5 - // 0 78 - // -1 16 - // -2 0.6 - // -3 0.04 - // -4 0.002 - // - // The histogram of iterations is (m = number of iterations estimating - // alp1 directly, n = number of iterations estimating via omg12, total - // number of trials = 148605): - // - // iter m n - // 0 148 186 - // 1 13046 13845 - // 2 93315 102225 - // 3 36189 32341 - // 4 5396 7 - // 5 455 1 - // 6 56 0 - // - // Because omg12 is near pi, estimate work with omg12a = pi - omg12 - var k = g.Astroid(x, y); - var - omg12a = lamscale * ( this._f >= 0 ? -x * k/(1 + k) : -y * (1 + k)/k ); - somg12 = Math.sin(omg12a); comg12 = -Math.cos(omg12a); - // Update spherical estimate of alp1 using omg12 instead of - // lam12 - vals.salp1 = cbet2 * somg12; - vals.calp1 = sbet12a - - cbet2 * sbet1 * m.sq(somg12) / (1 - comg12); - } - } - if (vals.salp1 > 0) { // Sanity check on starting guess - // SinCosNorm(vals.salp1, vals.calp1); - var t = m.hypot(vals.salp1, vals.calp1); vals.salp1 /= t; vals.calp1 /= t; - } else { - vals.salp1 = 1; vals.calp1 = 0; - } - return vals; - } - - // return lam12, salp2, calp2, sig12, ssig1, csig1, ssig2, csig2, eps, - // domg12, dlam12, - g.Geodesic.prototype.Lambda12 = function(sbet1, cbet1, dn1, sbet2, cbet2, dn2, - salp1, calp1, diffp, - C1a, C2a, C3a) { - var vals = {}; - if (sbet1 == 0 && calp1 == 0) - // Break degeneracy of equatorial line. This case has already been - // handled. - calp1 = -g.tiny_; - - var - // sin(alp1) * cos(bet1) = sin(alp0) - salp0 = salp1 * cbet1, - calp0 = m.hypot(calp1, salp1 * sbet1); // calp0 > 0 - - var somg1, comg1, somg2, comg2, omg12; - // tan(bet1) = tan(sig1) * cos(alp1) - // tan(omg1) = sin(alp0) * tan(sig1) = tan(omg1)=tan(alp1)*sin(bet1) - vals.ssig1 = sbet1; somg1 = salp0 * sbet1; - vals.csig1 = comg1 = calp1 * cbet1; - // SinCosNorm(vals.ssig1, vals.csig1); - var t = m.hypot(vals.ssig1, vals.csig1); vals.ssig1 /= t; vals.csig1 /= t; - // SinCosNorm(somg1, comg1); -- don't need to normalize! - - // Enforce symmetries in the case abs(bet2) = -bet1. Need to be careful - // about this case, since this can yield singularities in the Newton - // iteration. - // sin(alp2) * cos(bet2) = sin(alp0) - vals.salp2 = cbet2 != cbet1 ? salp0 / cbet2 : salp1; - // calp2 = sqrt(1 - sq(salp2)) - // = sqrt(sq(calp0) - sq(sbet2)) / cbet2 - // and subst for calp0 and rearrange to give (choose positive sqrt - // to give alp2 in [0, pi/2]). - vals.calp2 = cbet2 != cbet1 || Math.abs(sbet2) != -sbet1 ? - Math.sqrt(m.sq(calp1 * cbet1) + (cbet1 < -sbet1 ? - (cbet2 - cbet1) * (cbet1 + cbet2) : - (sbet1 - sbet2) * (sbet1 + sbet2))) - / cbet2 : Math.abs(calp1); - // tan(bet2) = tan(sig2) * cos(alp2) - // tan(omg2) = sin(alp0) * tan(sig2). - vals.ssig2 = sbet2; somg2 = salp0 * sbet2; - vals.csig2 = comg2 = vals.calp2 * cbet2; - // SinCosNorm(vals.ssig2, vals.csig2); - var t = m.hypot(vals.ssig2, vals.csig2); vals.ssig2 /= t; vals.csig2 /= t; - // SinCosNorm(somg2, comg2); -- don't need to normalize! - - // sig12 = sig2 - sig1, limit to [0, pi] - vals.sig12 = Math.atan2(Math.max(vals.csig1 * vals.ssig2 - - vals.ssig1 * vals.csig2, 0), - vals.csig1 * vals.csig2 + vals.ssig1 * vals.ssig2); - - // omg12 = omg2 - omg1, limit to [0, pi] - omg12 = Math.atan2(Math.max(comg1 * somg2 - somg1 * comg2, 0), - comg1 * comg2 + somg1 * somg2); - var B312, h0; - var k2 = m.sq(calp0) * this._ep2; - vals.eps = k2 / (2 * (1 + Math.sqrt(1 + k2)) + k2); - this.C3f(vals.eps, C3a); - B312 = (g.SinCosSeries(true, vals.ssig2, vals.csig2, C3a, g.nC3_-1) - - g.SinCosSeries(true, vals.ssig1, vals.csig1, C3a, g.nC3_-1)); - h0 = -this._f * this.A3f(vals.eps); - vals.domg12 = salp0 * h0 * (vals.sig12 + B312); - vals.lam12 = omg12 + vals.domg12; - - if (diffp) { - if (vals.calp2 == 0) - vals.dlam12 = - 2 * this._f1 * dn1 / sbet1; - else { - var nvals = this.Lengths(vals.eps, vals.sig12, - vals.ssig1, vals.csig1, dn1, - vals.ssig2, vals.csig2, dn2, - cbet1, cbet2, false, C1a, C2a); - vals.dlam12 = nvals.m12b; - vals.dlam12 *= this._f1 / (vals.calp2 * cbet2); - } - } - return vals; - } - - // return a12, s12, azi1, azi2, m12, M12, M21, S12 - g.Geodesic.prototype.GenInverse = function(lat1, lon1, lat2, lon2, outmask) { - var vals = {}; - outmask &= g.OUT_ALL; - // Compute longitude difference (AngDiff does this carefully). Result is - // in [-180, 180] but -180 is only for west-going geodesics. 180 is for - // east-going and meridional geodesics. - var lon12 = m.AngDiff(m.AngNormalize(lon1), m.AngNormalize(lon2)); - // If very close to being on the same half-meridian, then make it so. - lon12 = g.AngRound(lon12); - // Make longitude difference positive. - var lonsign = lon12 >= 0 ? 1 : -1; - lon12 *= lonsign; - // If really close to the equator, treat as on equator. - lat1 = g.AngRound(lat1); - lat2 = g.AngRound(lat2); - // Swap points so that point with higher (abs) latitude is point 1 - var swapp = Math.abs(lat1) >= Math.abs(lat2) ? 1 : -1; - if (swapp < 0) { - lonsign *= -1; - var t = lat1; - lat1 = lat2; - lat2 = t; - // swap(lat1, lat2); - } - // Make lat1 <= 0 - var latsign = lat1 < 0 ? 1 : -1; - lat1 *= latsign; - lat2 *= latsign; - // Now we have - // - // 0 <= lon12 <= 180 - // -90 <= lat1 <= 0 - // lat1 <= lat2 <= -lat1 - // - // longsign, swapp, latsign register the transformation to bring the - // coordinates to this canonical form. In all cases, 1 means no change was - // made. We make these transformations so that there are few cases to - // check, e.g., on verifying quadrants in atan2. In addition, this - // enforces some symmetries in the results returned. - - var phi, sbet1, cbet1, sbet2, cbet2, s12x, m12x; - - phi = lat1 * m.degree; - // Ensure cbet1 = +epsilon at poles - sbet1 = this._f1 * Math.sin(phi); - cbet1 = lat1 == -90 ? g.tiny_ : Math.cos(phi); - // SinCosNorm(sbet1, cbet1); - var t = m.hypot(sbet1, cbet1); sbet1 /= t; cbet1 /= t; - - phi = lat2 * m.degree; - // Ensure cbet2 = +epsilon at poles - sbet2 = this._f1 * Math.sin(phi); - cbet2 = Math.abs(lat2) == 90 ? g.tiny_ : Math.cos(phi); - // SinCosNorm(sbet2, cbet2); - var t = m.hypot(sbet2, cbet2); sbet2 /= t; cbet2 /= t; - - // If cbet1 < -sbet1, then cbet2 - cbet1 is a sensitive measure of the - // |bet1| - |bet2|. Alternatively (cbet1 >= -sbet1), abs(sbet2) + sbet1 is - // a better measure. This logic is used in assigning calp2 in Lambda12. - // Sometimes these quantities vanish and in that case we force bet2 = +/- - // bet1 exactly. An example where is is necessary is the inverse problem - // 48.522876735459 0 -48.52287673545898293 179.599720456223079643 - // which failed with Visual Studio 10 (Release and Debug) - - if (cbet1 < -sbet1) { - if (cbet2 == cbet1) - sbet2 = sbet2 < 0 ? sbet1 : -sbet1; - } else { - if (Math.abs(sbet2) == -sbet1) - cbet2 = cbet1; - } - - var - dn1 = Math.sqrt(1 + this._ep2 * m.sq(sbet1)), - dn2 = Math.sqrt(1 + this._ep2 * m.sq(sbet2)); - - var - lam12 = lon12 * m.degree, - slam12 = lon12 == 180 ? 0 : Math.sin(lam12), - clam12 = Math.cos(lam12); // lon12 == 90 isn't interesting - - var sig12, calp1, salp1, calp2, salp2; - // index zero elements of these arrays are unused - var - C1a = new Array(g.nC1_ + 1), - C2a = new Array(g.nC2_ + 1), - C3a = new Array(g.nC3_); - - var meridian = lat1 == -90 || slam12 == 0; - - if (meridian) { - - // Endpoints are on a single full meridian, so the geodesic might - // lie on a meridian. - - calp1 = clam12; salp1 = slam12; // Head to the target longitude - calp2 = 1; salp2 = 0; // At the target we're heading north - - var - // tan(bet) = tan(sig) * cos(alp) - ssig1 = sbet1, csig1 = calp1 * cbet1, - ssig2 = sbet2, csig2 = calp2 * cbet2; - - // sig12 = sig2 - sig1 - sig12 = Math.atan2(Math.max(csig1 * ssig2 - ssig1 * csig2, 0), - csig1 * csig2 + ssig1 * ssig2); - { - var nvals = this.Lengths(this._n, sig12, - ssig1, csig1, dn1, ssig2, csig2, dn2, - cbet1, cbet2, (outmask & g.GEODESICSCALE) != 0, - C1a, C2a); - s12x = nvals.s12b; - m12x = nvals.m12b; - // Ignore m0 - if ((outmask & g.GEODESICSCALE) != 0) { - vals.M12 = nvals.M12; - vals.M21 = nvals.M21; - } - } - // Add the check for sig12 since zero length geodesics might yield - // m12 < 0. Test case was - // - // echo 20.001 0 20.001 0 | GeodSolve -i - // - // In fact, we will have sig12 > pi/2 for meridional geodesic - // which is not a shortest path. - if (sig12 < 1 || m12x >= 0) { - m12x *= this._b; - s12x *= this._b; - vals.a12 = sig12 / m.degree; - } else - // m12 < 0, i.e., prolate and too close to anti-podal - meridian = false; - } - - var omg12; - if (!meridian && - sbet1 == 0 && // and sbet2 == 0 - // Mimic the way Lambda12 works with calp1 = 0 - (this._f <= 0 || lam12 <= Math.PI - this._f * Math.PI)) { - - // Geodesic runs along equator - calp1 = calp2 = 0; salp1 = salp2 = 1; - s12x = this._a * lam12; - sig12 = omg12 = lam12 / this._f1; - m12x = this._b * Math.sin(sig12); - if (outmask & g.GEODESICSCALE) - vals.M12 = vals.M21 = Math.cos(sig12); - vals.a12 = lon12 / this._f1; - - } else if (!meridian) { - - // Now point1 and point2 belong within a hemisphere bounded by a - // meridian and geodesic is neither meridional or equatorial. - - // Figure a starting point for Newton's method - var nvals = this.InverseStart(sbet1, cbet1, dn1, sbet2, cbet2, dn2, lam12, - C1a, C2a); - sig12 = nvals.sig12; - salp1 = nvals.salp1; - calp1 = nvals.calp1; - - if (sig12 >= 0) { - salp2 = nvals.salp2; - calp2 = nvals.calp2; - // Short lines (InverseStart sets salp2, calp2, dnm) - - var dnm = nvals.dnm; - s12x = sig12 * this._b * dnm; - m12x = m.sq(dnm) * this._b * Math.sin(sig12 / dnm); - if (outmask & g.GEODESICSCALE) - vals.M12 = vals.M21 = Math.cos(sig12 / dnm); - vals.a12 = sig12 / m.degree; - omg12 = lam12 / (this._f1 * dnm); - } else { - - // Newton's method. This is a straightforward solution of f(alp1) = - // lambda12(alp1) - lam12 = 0 with one wrinkle. f(alp) has exactly one - // root in the interval (0, pi) and its derivative is positive at the - // root. Thus f(alp) is positive for alp > alp1 and negative for alp < - // alp1. During the course of the iteration, a range (alp1a, alp1b) is - // maintained which brackets the root and with each evaluation of - // f(alp) the range is shrunk if possible. Newton's method is - // restarted whenever the derivative of f is negative (because the new - // value of alp1 is then further from the solution) or if the new - // estimate of alp1 lies outside (0,pi); in this case, the new starting - // guess is taken to be (alp1a + alp1b) / 2. - var ssig1, csig1, ssig2, csig2, eps; - var numit = 0; - // Bracketing range - var salp1a = g.tiny_, calp1a = 1, salp1b = g.tiny_, calp1b = -1; - for (var tripn = false, tripb = false; numit < g.maxit2_; ++numit) { - // the WGS84 test set: mean = 1.47, sd = 1.25, max = 16 - // WGS84 and random input: mean = 2.85, sd = 0.60 - var dv; - var nvals = this.Lambda12(sbet1, cbet1, dn1, sbet2, cbet2, dn2, - salp1, calp1, numit < g.maxit1_, - C1a, C2a, C3a); - var v = nvals.lam12 - lam12; - salp2 = nvals.salp2; - calp2 = nvals.calp2; - sig12 = nvals.sig12; - ssig1 = nvals.ssig1; - csig1 = nvals.csig1; - ssig2 = nvals.ssig2; - csig2 = nvals.csig2; - eps = nvals.eps; - omg12 = nvals.domg12; - dv = nvals.dlam12; - - // 2 * tol0 is approximately 1 ulp for a number in [0, pi]. - // Reversed test to allow escape with NaNs - if (tripb || !(Math.abs(v) >= (tripn ? 8 : 2) * g.tol0_)) - break; - // Update bracketing values - if (v > 0 && (numit < g.maxit1_ || calp1/salp1 > calp1b/salp1b)) { - salp1b = salp1; calp1b = calp1; - } else if (v < 0 && - (numit < g.maxit1_ || calp1/salp1 < calp1a/salp1a)) { - salp1a = salp1; calp1a = calp1; - } - if (numit < g.maxit1_ && dv > 0) { - var - dalp1 = -v/dv; - var - sdalp1 = Math.sin(dalp1), cdalp1 = Math.cos(dalp1), - nsalp1 = salp1 * cdalp1 + calp1 * sdalp1; - if (nsalp1 > 0 && Math.abs(dalp1) < Math.PI) { - calp1 = calp1 * cdalp1 - salp1 * sdalp1; - salp1 = Math.max(0, nsalp1); - // SinCosNorm(salp1, calp1); - var t = m.hypot(salp1, calp1); salp1 /= t; calp1 /= t; - // In some regimes we don't get quadratic convergence because - // slope -> 0. So use convergence conditions based on epsilon - // instead of sqrt(epsilon). - tripn = Math.abs(v) <= 16 * g.tol0_; - continue; - } - } - // Either dv was not postive or updated value was outside legal - // range. Use the midpoint of the bracket as the next estimate. - // This mechanism is not needed for the WGS84 ellipsoid, but it does - // catch problems with more eccentric ellipsoids. Its efficacy is - // such for the WGS84 test set with the starting guess set to alp1 = - // 90deg: - // the WGS84 test set: mean = 5.21, sd = 3.93, max = 24 - // WGS84 and random input: mean = 4.74, sd = 0.99 - salp1 = (salp1a + salp1b)/2; - calp1 = (calp1a + calp1b)/2; - // SinCosNorm(salp1, calp1); - var t = m.hypot(salp1, calp1); salp1 /= t; calp1 /= t; - tripn = false; - tripb = (Math.abs(salp1a - salp1) + (calp1a - calp1) < g.tolb_ || - Math.abs(salp1 - salp1b) + (calp1 - calp1b) < g.tolb_); - } - { - var nvals = this.Lengths(eps, sig12, - ssig1, csig1, dn1, ssig2, csig2, dn2, - cbet1, cbet2, - (outmask & g.GEODESICSCALE) != 0, - C1a, C2a); - s12x = nvals.s12b; - m12x = nvals.m12b; - // Ignore m0 - if ((outmask & g.GEODESICSCALE) != 0) { - vals.M12 = nvals.M12; - vals.M21 = nvals.M21; - } - } - m12x *= this._b; - s12x *= this._b; - vals.a12 = sig12 / m.degree; - omg12 = lam12 - omg12; - } - } - - if (outmask & g.DISTANCE) - vals.s12 = 0 + s12x; // Convert -0 to 0 - - if (outmask & g.REDUCEDLENGTH) - vals.m12 = 0 + m12x; // Convert -0 to 0 - - if (outmask & g.AREA) { - var - // From Lambda12: sin(alp1) * cos(bet1) = sin(alp0) - salp0 = salp1 * cbet1, - calp0 = m.hypot(calp1, salp1 * sbet1); // calp0 > 0 - var alp12; - if (calp0 != 0 && salp0 != 0) { - var - // From Lambda12: tan(bet) = tan(sig) * cos(alp) - ssig1 = sbet1, csig1 = calp1 * cbet1, - ssig2 = sbet2, csig2 = calp2 * cbet2, - k2 = m.sq(calp0) * this._ep2, - eps = k2 / (2 * (1 + Math.sqrt(1 + k2)) + k2); - // Multiplier = a^2 * e^2 * cos(alpha0) * sin(alpha0). - A4 = m.sq(this._a) * calp0 * salp0 * this._e2; - // SinCosNorm(ssig1, csig1); - var t = m.hypot(ssig1, csig1); ssig1 /= t; csig1 /= t; - // SinCosNorm(ssig2, csig2); - var t = m.hypot(ssig2, csig2); ssig2 /= t; csig2 /= t; - var C4a = new Array(g.nC4_); - this.C4f(eps, C4a); - var - B41 = g.SinCosSeries(false, ssig1, csig1, C4a, g.nC4_), - B42 = g.SinCosSeries(false, ssig2, csig2, C4a, g.nC4_); - vals.S12 = A4 * (B42 - B41); - } else - // Avoid problems with indeterminate sig1, sig2 on equator - vals.S12 = 0; - if (!meridian && - omg12 < 0.75 * Math.PI && // Long difference too big - sbet2 - sbet1 < 1.75) { // Lat difference too big - // Use tan(Gamma/2) = tan(omg12/2) - // * (tan(bet1/2)+tan(bet2/2))/(1+tan(bet1/2)*tan(bet2/2)) - // with tan(x/2) = sin(x)/(1+cos(x)) - var - somg12 = Math.sin(omg12), domg12 = 1 + Math.cos(omg12), - dbet1 = 1 + cbet1, dbet2 = 1 + cbet2; - alp12 = 2 * Math.atan2( somg12 * (sbet1*dbet2 + sbet2*dbet1), - domg12 * (sbet1*sbet2 + dbet1*dbet2) ); - } else { - // alp12 = alp2 - alp1, used in atan2 so no need to normalize - var - salp12 = salp2 * calp1 - calp2 * salp1, - calp12 = calp2 * calp1 + salp2 * salp1; - // The right thing appears to happen if alp1 = +/-180 and alp2 = 0, viz - // salp12 = -0 and alp12 = -180. However this depends on the sign - // being attached to 0 correctly. The following ensures the correct - // behavior. - if (salp12 == 0 && calp12 < 0) { - salp12 = g.tiny_ * calp1; - calp12 = -1; - } - alp12 = Math.atan2(salp12, calp12); - } - vals.S12 += this._c2 * alp12; - vals.S12 *= swapp * lonsign * latsign; - // Convert -0 to 0 - vals.S12 += 0; - } - - // Convert calp, salp to azimuth accounting for lonsign, swapp, latsign. - if (swapp < 0) { - var t = salp1; - salp1 = salp2; - salp2 = t; - // swap(salp1, salp2); - var t = calp1; - calp1 = calp2; - calp2 = t; - // swap(calp1, calp2); - if (outmask & g.GEODESICSCALE) { - var t = vals.M12; - vals.M12 = vals.M21; - vals.M21 = t; - // swap(vals.M12, vals.M21); - } - } - - salp1 *= swapp * lonsign; calp1 *= swapp * latsign; - salp2 *= swapp * lonsign; calp2 *= swapp * latsign; - - if (outmask & g.AZIMUTH) { - // minus signs give range [-180, 180). 0- converts -0 to +0. - vals.azi1 = 0 - Math.atan2(-salp1, calp1) / m.degree; - vals.azi2 = 0 - Math.atan2(-salp2, calp2) / m.degree; - } - - // Returned value in [0, 180] - return vals; - } - - // return a12, lat2, lon2, azi2, s12, m12, M12, M21, S12 - g.Geodesic.prototype.GenDirect = function (lat1, lon1, azi1, - arcmode, s12_a12, outmask) { - var line = new l.GeodesicLine - (this, lat1, lon1, azi1, - // Automatically supply DISTANCE_IN if necessary - outmask | (arcmode ? g.NONE : g.DISTANCE_IN)); - return line.GenPosition(arcmode, s12_a12, outmask); - } - - g.WGS84 = new g.Geodesic(GeographicLib.Constants.WGS84.a, - GeographicLib.Constants.WGS84.f); -})(); diff --git a/gtsam/3rdparty/GeographicLib/doc/scripts/GeographicLib/GeodesicLine.js b/gtsam/3rdparty/GeographicLib/doc/scripts/GeographicLib/GeodesicLine.js deleted file mode 100644 index b2df9c1f6..000000000 --- a/gtsam/3rdparty/GeographicLib/doc/scripts/GeographicLib/GeodesicLine.js +++ /dev/null @@ -1,294 +0,0 @@ -/** - * GeodesicLine.js - * Transcription of GeodesicLine.[ch]pp into JavaScript. - * - * See the documentation for the C++ class. The conversion is a literal - * conversion from C++. - * - * The algorithms are derived in - * - * Charles F. F. Karney, - * Algorithms for geodesics, J. Geodesy 87, 43-55 (2013); - * http://dx.doi.org/10.1007/s00190-012-0578-z - * Addenda: http://geographiclib.sf.net/geod-addenda.html - * - * Copyright (c) Charles Karney (2011-2012) and licensed - * under the MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ - **********************************************************************/ - -// Load AFTER GeographicLib/Math.js and GeographicLib/Geodesic.js - -(function() { - var g = GeographicLib.Geodesic; - var l = GeographicLib.GeodesicLine; - var m = GeographicLib.Math; - - l.GeodesicLine = function(geod, lat1, lon1, azi1, caps) { - this._a = geod._a; - this._f = geod._f; - this._b = geod._b; - this._c2 = geod._c2; - this._f1 = geod._f1; - this._caps = !caps ? g.ALL : (caps | g.LATITUDE | g.AZIMUTH); - - azi1 = g.AngRound(m.AngNormalize(azi1)); - lon1 = m.AngNormalize(lon1); - this._lat1 = lat1; - this._lon1 = lon1; - this._azi1 = azi1; - // alp1 is in [0, pi] - var alp1 = azi1 * m.degree; - // Enforce sin(pi) == 0 and cos(pi/2) == 0. Better to face the ensuing - // problems directly than to skirt them. - this._salp1 = azi1 == -180 ? 0 : Math.sin(alp1); - this._calp1 = Math.abs(azi1) == 90 ? 0 : Math.cos(alp1); - var cbet1, sbet1, phi; - phi = lat1 * m.degree; - // Ensure cbet1 = +epsilon at poles - sbet1 = this._f1 * Math.sin(phi); - cbet1 = Math.abs(lat1) == 90 ? g.tiny_ : Math.cos(phi); - // SinCosNorm(sbet1, cbet1); - var t = m.hypot(sbet1, cbet1); sbet1 /= t; cbet1 /= t; - this._dn1 = Math.sqrt(1 + geod._ep2 * m.sq(sbet1)); - - // Evaluate alp0 from sin(alp1) * cos(bet1) = sin(alp0), - this._salp0 = this._salp1 * cbet1; // alp0 in [0, pi/2 - |bet1|] - // Alt: calp0 = hypot(sbet1, calp1 * cbet1). The following - // is slightly better (consider the case salp1 = 0). - this._calp0 = m.hypot(this._calp1, this._salp1 * sbet1); - // Evaluate sig with tan(bet1) = tan(sig1) * cos(alp1). - // sig = 0 is nearest northward crossing of equator. - // With bet1 = 0, alp1 = pi/2, we have sig1 = 0 (equatorial line). - // With bet1 = pi/2, alp1 = -pi, sig1 = pi/2 - // With bet1 = -pi/2, alp1 = 0 , sig1 = -pi/2 - // Evaluate omg1 with tan(omg1) = sin(alp0) * tan(sig1). - // With alp0 in (0, pi/2], quadrants for sig and omg coincide. - // No atan2(0,0) ambiguity at poles since cbet1 = +epsilon. - // With alp0 = 0, omg1 = 0 for alp1 = 0, omg1 = pi for alp1 = pi. - this._ssig1 = sbet1; this._somg1 = this._salp0 * sbet1; - this._csig1 = this._comg1 = - sbet1 != 0 || this._calp1 != 0 ? cbet1 * this._calp1 : 1; - // SinCosNorm(this._ssig1, this._csig1); // sig1 in (-pi, pi] - var t = m.hypot(this._ssig1, this._csig1); - this._ssig1 /= t; this._csig1 /= t; - // SinCosNorm(this._somg1, this._comg1); -- don't need to normalize! - - this._k2 = m.sq(this._calp0) * geod._ep2; - var eps = this._k2 / (2 * (1 + Math.sqrt(1 + this._k2)) + this._k2); - - if (this._caps & g.CAP_C1) { - this._A1m1 = g.A1m1f(eps); - this._C1a = new Array(g.nC1_ + 1); - g.C1f(eps, this._C1a); - this._B11 = g.SinCosSeries(true, this._ssig1, this._csig1, - this._C1a, g.nC1_); - var s = Math.sin(this._B11), c = Math.cos(this._B11); - // tau1 = sig1 + B11 - this._stau1 = this._ssig1 * c + this._csig1 * s; - this._ctau1 = this._csig1 * c - this._ssig1 * s; - // Not necessary because C1pa reverts C1a - // _B11 = -SinCosSeries(true, _stau1, _ctau1, _C1pa, nC1p_); - } - - if (this._caps & g.CAP_C1p) { - this._C1pa = new Array(g.nC1p_ + 1), - g.C1pf(eps, this._C1pa); - } - - if (this._caps & g.CAP_C2) { - this._A2m1 = g.A2m1f(eps); - this._C2a = new Array(g.nC2_ + 1); - g.C2f(eps, this._C2a); - this._B21 = g.SinCosSeries(true, this._ssig1, this._csig1, - this._C2a, g.nC2_); - } - - if (this._caps & g.CAP_C3) { - this._C3a = new Array(g.nC3_); - geod.C3f(eps, this._C3a); - this._A3c = -this._f * this._salp0 * geod.A3f(eps); - this._B31 = g.SinCosSeries(true, this._ssig1, this._csig1, - this._C3a, g.nC3_-1); - } - - if (this._caps & g.CAP_C4) { - this._C4a = new Array(g.nC4_); // all the elements of _C4a are used - geod.C4f(eps, this._C4a); - // Multiplier = a^2 * e^2 * cos(alpha0) * sin(alpha0) - this._A4 = m.sq(this._a) * this._calp0 * this._salp0 * geod._e2; - this._B41 = g.SinCosSeries(false, this._ssig1, this._csig1, - this._C4a, g.nC4_); - } - } - - // return a12, lat2, lon2, azi2, s12, m12, M12, M21, S12 - l.GeodesicLine.prototype.GenPosition = function(arcmode, s12_a12, - outmask) { - var vals = {}; - outmask &= this._caps & g.OUT_ALL; - if (!( arcmode || (this._caps & g.DISTANCE_IN & g.OUT_ALL) )) { - // Uninitialized or impossible distance calculation requested - vals.a12 = Number.NaN; - return vals; - } - - // Avoid warning about uninitialized B12. - var sig12, ssig12, csig12, B12 = 0, AB1 = 0; - if (arcmode) { - // Interpret s12_a12 as spherical arc length - sig12 = s12_a12 * m.degree; - var s12a = Math.abs(s12_a12); - s12a -= 180 * Math.floor(s12a / 180); - ssig12 = s12a == 0 ? 0 : Math.sin(sig12); - csig12 = s12a == 90 ? 0 : Math.cos(sig12); - } else { - // Interpret s12_a12 as distance - var - tau12 = s12_a12 / (this._b * (1 + this._A1m1)), - s = Math.sin(tau12), - c = Math.cos(tau12); - // tau2 = tau1 + tau12 - B12 = - g.SinCosSeries(true, - this._stau1 * c + this._ctau1 * s, - this._ctau1 * c - this._stau1 * s, - this._C1pa, g.nC1p_); - sig12 = tau12 - (B12 - this._B11); - ssig12 = Math.sin(sig12); csig12 = Math.cos(sig12); - if (Math.abs(this._f) > 0.01) { - // Reverted distance series is inaccurate for |f| > 1/100, so correct - // sig12 with 1 Newton iteration. The following table shows the - // approximate maximum error for a = WGS_a() and various f relative to - // GeodesicExact. - // erri = the error in the inverse solution (nm) - // errd = the error in the direct solution (series only) (nm) - // errda = the error in the direct solution (series + 1 Newton) (nm) - // - // f erri errd errda - // -1/5 12e6 1.2e9 69e6 - // -1/10 123e3 12e6 765e3 - // -1/20 1110 108e3 7155 - // -1/50 18.63 200.9 27.12 - // -1/100 18.63 23.78 23.37 - // -1/150 18.63 21.05 20.26 - // 1/150 22.35 24.73 25.83 - // 1/100 22.35 25.03 25.31 - // 1/50 29.80 231.9 30.44 - // 1/20 5376 146e3 10e3 - // 1/10 829e3 22e6 1.5e6 - // 1/5 157e6 3.8e9 280e6 - var - ssig2 = this._ssig1 * csig12 + this._csig1 * ssig12, - csig2 = this._csig1 * csig12 - this._ssig1 * ssig12; - B12 = g.SinCosSeries(true, ssig2, csig2, this._C1a, g.nC1_); - var serr = (1 + this._A1m1) * (sig12 + (B12 - this._B11)) - - s12_a12 / this._b; - sig12 = sig12 - serr / Math.sqrt(1 + this._k2 * m.sq(ssig2)); - ssig12 = Math.sin(sig12); csig12 = Math.cos(sig12); - // Update B12 below - } - } - - var omg12, lam12, lon12; - var ssig2, csig2, sbet2, cbet2, somg2, comg2, salp2, calp2; - // sig2 = sig1 + sig12 - ssig2 = this._ssig1 * csig12 + this._csig1 * ssig12; - csig2 = this._csig1 * csig12 - this._ssig1 * ssig12; - var dn2 = Math.sqrt(1 + this._k2 * m.sq(ssig2)); - if (outmask & (g.DISTANCE | g.REDUCEDLENGTH | g.GEODESICSCALE)) { - if (arcmode || Math.abs(this._f) > 0.01) - B12 = g.SinCosSeries(true, ssig2, csig2, this._C1a, g.nC1_); - AB1 = (1 + this._A1m1) * (B12 - this._B11); - } - // sin(bet2) = cos(alp0) * sin(sig2) - sbet2 = this._calp0 * ssig2; - // Alt: cbet2 = hypot(csig2, salp0 * ssig2); - cbet2 = m.hypot(this._salp0, this._calp0 * csig2); - if (cbet2 == 0) - // I.e., salp0 = 0, csig2 = 0. Break the degeneracy in this case - cbet2 = csig2 = g.tiny_; - // tan(omg2) = sin(alp0) * tan(sig2) - somg2 = this._salp0 * ssig2; comg2 = csig2; // No need to normalize - // tan(alp0) = cos(sig2)*tan(alp2) - salp2 = this._salp0; calp2 = this._calp0 * csig2; // No need to normalize - // omg12 = omg2 - omg1 - omg12 = Math.atan2(somg2 * this._comg1 - comg2 * this._somg1, - comg2 * this._comg1 + somg2 * this._somg1); - - if (outmask & g.DISTANCE) - vals.s12 = arcmode ? this._b * ((1 + this._A1m1) * sig12 + AB1) : s12_a12; - - if (outmask & g.LONGITUDE) { - lam12 = omg12 + this._A3c * - ( sig12 + (g.SinCosSeries(true, ssig2, csig2, this._C3a, g.nC3_-1) - - this._B31)); - lon12 = lam12 / m.degree; - // Use AngNormalize2 because longitude might have wrapped multiple times. - lon12 = m.AngNormalize2(lon12); - vals.lon2 = m.AngNormalize(this._lon1 + lon12); - } - - if (outmask & g.LATITUDE) - vals.lat2 = Math.atan2(sbet2, this._f1 * cbet2) / m.degree; - - if (outmask & g.AZIMUTH) - // minus signs give range [-180, 180). 0- converts -0 to +0. - vals.azi2 = 0 - Math.atan2(-salp2, calp2) / m.degree; - - if (outmask & (g.REDUCEDLENGTH | g.GEODESICSCALE)) { - var - B22 = g.SinCosSeries(true, ssig2, csig2, this._C2a, g.nC2_), - AB2 = (1 + this._A2m1) * (B22 - this._B21), - J12 = (this._A1m1 - this._A2m1) * sig12 + (AB1 - AB2); - if (outmask & g.REDUCEDLENGTH) - // Add parens around (_csig1 * ssig2) and (_ssig1 * csig2) to ensure - // accurate cancellation in the case of coincident points. - vals.m12 = this._b * (( dn2 * (this._csig1 * ssig2) - - this._dn1 * (this._ssig1 * csig2)) - - this._csig1 * csig2 * J12); - if (outmask & g.GEODESICSCALE) { - var t = this._k2 * (ssig2 - this._ssig1) * (ssig2 + this._ssig1) / - (this._dn1 + dn2); - vals.M12 = csig12 + (t * ssig2 - csig2 * J12) * this._ssig1 / this._dn1; - vals.M21 = csig12 - (t * this._ssig1 - this._csig1 * J12) * ssig2 / dn2; - } - } - - if (outmask & g.AREA) { - var - B42 = g.SinCosSeries(false, ssig2, csig2, this._C4a, g.nC4_); - var salp12, calp12; - if (this._calp0 == 0 || this._salp0 == 0) { - // alp12 = alp2 - alp1, used in atan2 so no need to normalized - salp12 = salp2 * this._calp1 - calp2 * this._salp1; - calp12 = calp2 * this._calp1 + salp2 * this._salp1; - // The right thing appears to happen if alp1 = +/-180 and alp2 = 0, viz - // salp12 = -0 and alp12 = -180. However this depends on the sign being - // attached to 0 correctly. The following ensures the correct behavior. - if (salp12 == 0 && calp12 < 0) { - salp12 = g.tiny_ * this._calp1; - calp12 = -1; - } - } else { - // tan(alp) = tan(alp0) * sec(sig) - // tan(alp2-alp1) = (tan(alp2) -tan(alp1)) / (tan(alp2)*tan(alp1)+1) - // = calp0 * salp0 * (csig1-csig2) / (salp0^2 + calp0^2 * csig1*csig2) - // If csig12 > 0, write - // csig1 - csig2 = ssig12 * (csig1 * ssig12 / (1 + csig12) + ssig1) - // else - // csig1 - csig2 = csig1 * (1 - csig12) + ssig12 * ssig1 - // No need to normalize - salp12 = this._calp0 * this._salp0 * - (csig12 <= 0 ? this._csig1 * (1 - csig12) + ssig12 * this._ssig1 : - ssig12 * (this._csig1 * ssig12 / (1 + csig12) + this._ssig1)); - calp12 = m.sq(this._salp0) + m.sq(this._calp0) * this._csig1 * csig2; - } - vals.S12 = this._c2 * Math.atan2(salp12, calp12) + - this._A4 * (B42 - this._B41); - } - - vals.a12 = arcmode ? s12_a12 : sig12 / m.degree; - return vals; - } - -})(); diff --git a/gtsam/3rdparty/GeographicLib/doc/scripts/GeographicLib/Interface.js b/gtsam/3rdparty/GeographicLib/doc/scripts/GeographicLib/Interface.js deleted file mode 100644 index 55a230888..000000000 --- a/gtsam/3rdparty/GeographicLib/doc/scripts/GeographicLib/Interface.js +++ /dev/null @@ -1,257 +0,0 @@ -/** - * Interface.js - * JavaScript interface routines for the geodesic routines GeographicLib. - * - * This provides JavaScript-style interfaces to Math.js, Geodesic.js, - * GeodesicLine.js, and PolygonArea.js which, in turn, are rather - * literal translations of the following classes from GeographicLib: - * Math, Accumulator, Geodesic, GeodesicLine, PolygonArea. See the - * documentation for the C++ class for more information at - * - * http://geographiclib.sourceforge.net/html/annotated.html - * - * The algorithms are derived in - * - * Charles F. F. Karney, - * Algorithms for geodesics, J. Geodesy 87, 43-55 (2013); - * http://dx.doi.org/10.1007/s00190-012-0578-z - * Addenda: http://geographiclib.sf.net/geod-addenda.html - * - * Copyright (c) Charles Karney (2011) and licensed - * under the MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ - ********************************************************************** - * GeographicLib.Geodesic.WGS84.Inverse(lat1, lon1, lat2, lon2, outmask); - * GeographicLib.Geodesic.WGS84.Direct(lat1, lon1, azi1, s12, outmask); - * - * perform the basic geodesic calculations. These return an object with - * (some) of the following fields: - * - * lat1 latitude of point 1 - * lon1 longitude of point 1 - * azi1 azimuth of line at point 1 - * lat2 latitude of point 2 - * lon2 longitude of point 2 - * azi2 azimuth of line at point 2 - * s12 distance from 1 to 2 - * a12 arc length on auxiliary sphere from 1 to 2 - * m12 reduced length of geodesic - * M12 geodesic scale 2 relative to 1 - * M21 geodesic scale 1 relative to 2 - * S12 area between geodesic and equator - * - * outmask determines which fields get included and if outmask is - * omitted, then only the basic geodesic fields are computed. The mask - * is an or'ed combination of the following values - * - * GeographicLib.Geodesic.LATITUDE - * GeographicLib.Geodesic.LONGITUDE - * GeographicLib.Geodesic.AZIMUTH - * GeographicLib.Geodesic.DISTANCE - * GeographicLib.Geodesic.REDUCEDLENGTH - * GeographicLib.Geodesic.GEODESICSCALE - * GeographicLib.Geodesic.AREA - * GeographicLib.Geodesic.ALL - * - ********************************************************************** - * GeographicLib.Geodesic.WGS84.InversePath(lat1, lon1, lat2, lon2, ds12, maxk); - * GeographicLib.Geodesic.WGS84.DirectPath(lat1, lon1, azi1, s12, ds12, maxk); - * - * splits a geodesic line into k equal pieces which are no longer than - * about ds12 (but k cannot exceed maxk, default 20), and returns an - * array of length k + 1 of objects with fields - * - * lat, lon, azi - * - ********************************************************************** - * GeographicLib.Geodesic.Envelope(lat1, lon1, azi1, s12, k) - * - * return the geodesic circle of radius s12 centered on the point lat1, - * lon1. k equally spaced azimuths starting at azi1 are computed. This - * returns an array of k + 1 points with fields lat and lon (with the - * first and last points matching). - * - ********************************************************************** - * GeographicLib.Geodesic.Envelope(lat1, lon1, k, ord); - * - * returns the ord'th order envelope for geodesics emanating from lat1, - * lon1. This is located approximately circumference * ord/2 from the - * point. Thus odd numbered envelopes are centered at the antipodal - * point and even number envelopes are centered on the point itself. - * This returns an array of k + 1 points with fields lat and lon (with - * the first and last points matching). - * - ********************************************************************** - * GeographicLib.Geodesic.WGS84.Area(points, polyline); - * - * computes the area of a polygon with vertices given by an array - * points, each of whose elements contains lat and lon fields. The - * function returns an object with fields. - * - * number, perimeter, area - * - * There is no need to "close" the polygon. If polyline (default = - * false) is true, then the points denote a polyline and its length is - * returned as the perimeter (and the area is not calculated). - **********************************************************************/ - -(function() { - var m = GeographicLib.Math; - var g = GeographicLib.Geodesic; - var l = GeographicLib.GeodesicLine; - - g.Geodesic.CheckPosition = function(lat, lon) { - if (!(Math.abs(lat) <= 90)) - throw new Error("latitude " + lat + " not in [-90, 90]"); - if (!(lon >= -540 && lon < 540)) - throw new Error("longitude " + lon + " not in [-540, 540)"); - return m.AngNormalize(lon); - } - - g.Geodesic.CheckAzimuth = function(azi) { - if (!(azi >= -540 && azi < 540)) - throw new Error("longitude " + azi + " not in [-540, 540)"); - return m.AngNormalize(azi); - } - - g.Geodesic.CheckDistance = function(s) { - if (!(isFinite(s))) - throw new Error("distance " + s + " not a finite number"); - } - - g.Geodesic.prototype.Inverse = function(lat1, lon1, lat2, lon2, outmask) { - if (!outmask) outmask = g.DISTANCE | g.AZIMUTH; - lon1 = g.Geodesic.CheckPosition(lat1, lon1); - lon2 = g.Geodesic.CheckPosition(lat2, lon2); - - var result = this.GenInverse(lat1, lon1, lat2, lon2, outmask); - result.lat1 = lat1; result.lon1 = lon1; - result.lat2 = lat2; result.lon2 = lon2; - - return result; - } - - g.Geodesic.prototype.Direct = function(lat1, lon1, azi1, s12, outmask) { - if (!outmask) outmask = g.LATITUDE | g.LONGITUDE | g.AZIMUTH; - lon1 = g.Geodesic.CheckPosition(lat1, lon1); - azi1 = g.Geodesic.CheckAzimuth(azi1); - g.Geodesic.CheckDistance(s12); - - var result = this.GenDirect(lat1, lon1, azi1, false, s12, outmask); - result.lat1 = lat1; result.lon1 = lon1; - result.azi1 = azi1; result.s12 = s12; - - return result; - } - - g.Geodesic.prototype.InversePath = - function(lat1, lon1, lat2, lon2, ds12, maxk) { - var t = this.Inverse(lat1, lon1, lat2, lon2); - if (!maxk) maxk = 20; - if (!(ds12 > 0)) - throw new Error("ds12 must be a positive number") - var - k = Math.max(1, Math.min(maxk, Math.ceil(t.s12/ds12))), - points = new Array(k + 1); - points[0] = {lat: t.lat1, lon: t.lon1, azi: t.azi1}; - points[k] = {lat: t.lat2, lon: t.lon2, azi: t.azi2}; - if (k > 1) { - var line = new l.GeodesicLine(this, t.lat1, t.lon1, t.azi1, - g.LATITUDE | g.LONGITUDE | g.AZIMUTH), - da12 = t.a12/k; - var vals; - for (var i = 1; i < k; ++i) { - vals = - line.GenPosition(true, i * da12, g.LATITUDE | g.LONGITUDE | g.AZIMUTH); - points[i] = {lat: vals.lat2, lon: vals.lon2, azi: vals.azi2}; - } - } - return points; - } - - g.Geodesic.prototype.DirectPath = - function(lat1, lon1, azi1, s12, ds12, maxk) { - var t = this.Direct(lat1, lon1, azi1, s12); - if (!maxk) maxk = 20; - if (!(ds12 > 0)) - throw new Error("ds12 must be a positive number") - var - k = Math.max(1, Math.min(maxk, Math.ceil(Math.abs(t.s12)/ds12))), - points = new Array(k + 1); - points[0] = {lat: t.lat1, lon: t.lon1, azi: t.azi1}; - points[k] = {lat: t.lat2, lon: t.lon2, azi: t.azi2}; - if (k > 1) { - var line = new l.GeodesicLine(this, t.lat1, t.lon1, t.azi1, - g.LATITUDE | g.LONGITUDE | g.AZIMUTH), - da12 = t.a12/k; - var vals; - for (var i = 1; i < k; ++i) { - vals = - line.GenPosition(true, i * da12, g.LATITUDE | g.LONGITUDE | g.AZIMUTH); - points[i] = {lat: vals.lat2, lon: vals.lon2, azi: vals.azi2}; - } - } - return points; - } - - g.Geodesic.prototype.Circle = function(lat1, lon1, azi1, s12, k) { - if (!(Math.abs(lat1) <= 90)) - throw new Error("lat1 must be in [-90, 90]"); - if (!(lon1 >= -540 && lon1 < 540)) - throw new Error("lon1 must be in [-540, 540)"); - if (!(azi1 >= -540 && azi1 < 540)) - throw new Error("azi1 must be in [-540, 540)"); - if (!(isFinite(s12))) - throw new Error("s12 must be a finite number"); - lon1 = m.AngNormalize(lon1); - azi1 = m.AngNormalize(azi1); - if (!k || k < 4) k = 24; - var points = new Array(k + 1); - var vals; - for (var i = 0; i <= k; ++i) { - var azi1a = azi1 + (k - i) * 360 / k; // Traverse circle counter-clocwise - if (azi1a >= 180) azi1a -= 360; - vals = - this.GenDirect(lat1, lon1, azi1a, false, s12, g.LATITUDE | g.LONGITUDE); - points[i] = {lat: vals.lat2, lon: vals.lon2}; - } - return points; - } - - g.Geodesic.prototype.Envelope = function(lat1, lon1, k, ord) { - if (!(Math.abs(lat1) <= 90)) - throw new Error("lat1 must be in [-90, 90]"); - if (!(lon1 >= -540 && lon1 < 540)) - throw new Error("lon1 must be in [-540, 540)"); - lon1 = m.AngNormalize(lon1); - if (!k || k < 4) k = 24; - if (!ord) ord = 1; - var points = new Array(k + 1); - var vals, line, s12, j; - for (var i = 0; i <= k; ++i) { - var azi1 = -180 + i * 360 / k; - line = new l.GeodesicLine(this, lat1, lon1, azi1, - g.LATITUDE | g.LONGITUDE | g.DISTANCE_IN | - g.DISTANCE | g.REDUCEDLENGTH | g.GEODESICSCALE); - vals = line.GenPosition(true, 180 * ord, - g.DISTANCE | g.REDUCEDLENGTH | g.GEODESICSCALE); - j = 0; - while (true) { - // Solve m12(s12) = 0 by Newton's method using dm12/ds12 = M21 - s12 = vals.s12 - vals.m12/vals.M21; - if (Math.abs(vals.m12) < line._a * g.tol2_ * 0.1 || ++j > 10) - break; - vals = line.GenPosition(false, s12, - g.DISTANCE | g.REDUCEDLENGTH | g.GEODESICSCALE); - } - vals = line.GenPosition(false, s12, g.LATITUDE | g.LONGITUDE); - points[i] = {lat: vals.lat2, lon: vals.lon2}; - } - return points; - } - - g.Geodesic.prototype.Area = function(points, polyline) { - return GeographicLib.PolygonArea.Area(this, points, polyline); - } - -})(); diff --git a/gtsam/3rdparty/GeographicLib/doc/scripts/GeographicLib/Math.js b/gtsam/3rdparty/GeographicLib/doc/scripts/GeographicLib/Math.js deleted file mode 100644 index c13dd2c93..000000000 --- a/gtsam/3rdparty/GeographicLib/doc/scripts/GeographicLib/Math.js +++ /dev/null @@ -1,172 +0,0 @@ -/** - * Math.js - * Transcription of Math.hpp, Constants.hpp, and Accumulator.hpp into - * JavaScript. - * - * Copyright (c) Charles Karney (2011) and licensed - * under the MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ - **********************************************************************/ - -var GeographicLib; if (!GeographicLib) GeographicLib = {}; - -GeographicLib.Math = {}; - -GeographicLib.Math.sq = function(x) { return x * x; } - -GeographicLib.Math.hypot = function(x, y) { - x = Math.abs(x); - y = Math.abs(y); - var a = Math.max(x, y), b = Math.min(x, y) / (a ? a : 1); - return a * Math.sqrt(1 + b * b); -} - -GeographicLib.Math.cbrt = function(x) { - var y = Math.pow(Math.abs(x), 1/3); - return x < 0 ? -y : y; -} - -GeographicLib.Math.log1p = function(x) { - var - y = 1 + x, - z = y - 1; - // Here's the explanation for this magic: y = 1 + z, exactly, and z - // approx x, thus log(y)/z (which is nearly constant near z = 0) returns - // a good approximation to the true log(1 + x)/x. The multiplication x * - // (log(y)/z) introduces little additional error. - return z == 0 ? x : x * Math.log(y) / z; -} - -GeographicLib.Math.atanh = function(x) { - var y = Math.abs(x); // Enforce odd parity - y = GeographicLib.Math.log1p(2 * y/(1 - y))/2; - return x < 0 ? -y : y; -} - -GeographicLib.Math.sum = function(u, v) { - var - s = u + v, - up = s - v, - vpp = s - up; - up -= u; - vpp -= v; - t = -(up + vpp); - // u + v = s + t - // = round(u + v) + t - return {s: s, t: t}; -} - -GeographicLib.Math.AngNormalize = function(x) { - // Place angle in [-180, 180). Assumes x is in [-540, 540). - return x >= 180 ? x - 360 : (x < -180 ? x + 360 : x); -} - -GeographicLib.Math.AngNormalize2 = function(x) { - // Place arbitrary angle in [-180, 180). - return GeographicLib.Math.AngNormalize(x % 360); -} - -GeographicLib.Math.AngDiff = function(x, y) { - // Compute y - x and reduce to [-180,180] accurately. - // This is the same logic as the Accumulator class uses. - var - d = y - x, - yp = d + x, - xpp = yp - d; - yp -= y; - xpp -= x; - var t = xpp - yp; - // y - x = d + t - // = round(y - x) + t - if ((d - 180) + t > 0) // y - x > 180 - d -= 360; // exact - else if ((d + 180) + t <= 0) // y - x <= -180 - d += 360; // exact - return d + t; -} - -GeographicLib.Math.epsilon = Math.pow(0.5, 52); -GeographicLib.Math.degree = Math.PI/180; -GeographicLib.Math.digits = 53; - -GeographicLib.Constants = {}; -GeographicLib.Constants.WGS84 = { a: 6378137, f: 1/298.257223563 }; - -GeographicLib.Accumulator = {}; -(function() { - a = GeographicLib.Accumulator; - var m = GeographicLib.Math; - - a.Accumulator = function(y) { - this.Set(y); - } - - a.Accumulator.prototype.Set = function(y) { - if (!y) y = 0; - if (y.constructor == a.Accumulator) { - this._s = y._s; - this._t = y._t; - } else { - this._s = y; - this._t = 0; - } - } - - a.Accumulator.prototype.Add = function(y) { - // Here's Shewchuk's solution... - // Accumulate starting at least significant end - var u = m.sum(y, this._t); - var v = m.sum(u.s, this._s); - u = u.t; - this._s = v.s; - this._t = v.t; - // Start is _s, _t decreasing and non-adjacent. Sum is now (s + t + u) - // exactly with s, t, u non-adjacent and in decreasing order (except - // for possible zeros). The following code tries to normalize the - // result. Ideally, we want _s = round(s+t+u) and _u = round(s+t+u - - // _s). The follow does an approximate job (and maintains the - // decreasing non-adjacent property). Here are two "failures" using - // 3-bit floats: - // - // Case 1: _s is not equal to round(s+t+u) -- off by 1 ulp - // [12, -1] - 8 -> [4, 0, -1] -> [4, -1] = 3 should be [3, 0] = 3 - // - // Case 2: _s+_t is not as close to s+t+u as it shold be - // [64, 5] + 4 -> [64, 8, 1] -> [64, 8] = 72 (off by 1) - // should be [80, -7] = 73 (exact) - // - // "Fixing" these problems is probably not worth the expense. The - // representation inevitably leads to small errors in the accumulated - // values. The additional errors illustrated here amount to 1 ulp of - // the less significant word during each addition to the Accumulator - // and an additional possible error of 1 ulp in the reported sum. - // - // Incidentally, the "ideal" representation described above is not - // canonical, because _s = round(_s + _t) may not be true. For - // example, with 3-bit floats: - // - // [128, 16] + 1 -> [160, -16] -- 160 = round(145). - // But [160, 0] - 16 -> [128, 16] -- 128 = round(144). - // - if (this._s == 0) // This implies t == 0, - this._s = u; // so result is u - else - this._t += u; // otherwise just accumulate u to t. - } - - a.Accumulator.prototype.Sum = function(y) { - if (!y) - return this._s; - else { - var b = new a.Accumulator(this); - b.Add(y); - return b._s; - } - } - - a.Accumulator.prototype.Negate = function() { - this._s *= -1; - this._t *= -1; - } - -})(); diff --git a/gtsam/3rdparty/GeographicLib/doc/scripts/GeographicLib/PolygonArea.js b/gtsam/3rdparty/GeographicLib/doc/scripts/GeographicLib/PolygonArea.js deleted file mode 100644 index e1e07f608..000000000 --- a/gtsam/3rdparty/GeographicLib/doc/scripts/GeographicLib/PolygonArea.js +++ /dev/null @@ -1,241 +0,0 @@ -/** - * PolygonArea.js - * Transcription of PolygonArea.[ch]pp into JavaScript. - * - * See the documentation for the C++ class. The conversion is a literal - * conversion from C++. - * - * The algorithms are derived in - * - * Charles F. F. Karney, - * Algorithms for geodesics, J. Geodesy 87, 43-55 (2013); - * http://dx.doi.org/10.1007/s00190-012-0578-z - * Addenda: http://geographiclib.sf.net/geod-addenda.html - * - * Copyright (c) Charles Karney (2011-2013) and licensed - * under the MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ - **********************************************************************/ - -// Load AFTER GeographicLib/Math.js and GeographicLib/Geodesic.js - -GeographicLib.PolygonArea = {}; - -(function() { - var m = GeographicLib.Math; - var a = GeographicLib.Accumulator; - var g = GeographicLib.Geodesic; - var p = GeographicLib.PolygonArea; - - p.transit = function(lon1, lon2) { - // Return 1 or -1 if crossing prime meridian in east or west direction. - // Otherwise return zero. - // Compute lon12 the same way as Geodesic::Inverse. - lon1 = m.AngNormalize(lon1); - lon2 = m.AngNormalize(lon2); - var lon12 = m.AngDiff(lon1, lon2); - var cross = - lon1 < 0 && lon2 >= 0 && lon12 > 0 ? 1 : - (lon2 < 0 && lon1 >= 0 && lon12 < 0 ? -1 : 0); - return cross; - } - - p.PolygonArea = function(earth, polyline) { - this._earth = earth; - this._area0 = 4 * Math.PI * earth._c2; - this._polyline = !polyline ? false : polyline; - this._mask = g.LATITUDE | g.LONGITUDE | g.DISTANCE | - (this._polyline ? g.NONE : g.AREA); - if (!this._polyline) - this._areasum = new a.Accumulator(0); - this._perimetersum = new a.Accumulator(0); - this.Clear(); - } - - p.PolygonArea.prototype.Clear = function() { - this._num = 0; - this._crossings = 0; - if (!this._polyline) - this._areasum.Set(0); - this._perimetersum.Set(0); - this._lat0 = this._lon0 = this._lat1 = this._lon1 = Number.NaN; - } - - p.PolygonArea.prototype.AddPoint = function(lat, lon) { - if (this._num == 0) { - this._lat0 = this._lat1 = lat; - this._lon0 = this._lon1 = lon; - } else { - var t = this._earth.Inverse(this._lat1, this._lon1, lat, lon, this._mask); - this._perimetersum.Add(t.s12); - if (!this._polyline) { - this._areasum.Add(t.S12); - this._crossings += p.transit(this._lon1, lon); - } - this._lat1 = lat; - this._lon1 = lon; - } - ++this._num; - } - - p.PolygonArea.prototype.AddEdge = function(azi, s) { - if (this._num) { - var t = this._earth.Direct(this._lat1, this._lon1, azi, s, this._mask); - this._perimetersum.Add(s); - if (!this._polyline) { - this._areasum.Add(t.S12); - this._crossings += p.transit(this._lon1, t.lon2); - } - this._lat1 = t.lat2; - this._lon1 = t.lon2; - } - ++this._num; - } - - // return number, perimeter, area - p.PolygonArea.prototype.Compute = function(reverse, sign) { - var vals = {number: this._num}; - if (this._num < 2) { - vals.perimeter = 0; - if (!this._polyline) - vals.area = 0; - return vals; - } - if (this._polyline) { - vals.perimeter = this._perimetersum.Sum(); - return vals; - } - var t = this._earth.Inverse(this._lat1, this._lon1, this._lat0, this._lon0, - this._mask); - vals.perimeter = this._perimetersum.Sum(t.s12); - var tempsum = new a.Accumulator(this._areasum); - tempsum.Add(t.S12); - var crossings = this._crossings + p.transit(this._lon1, this._lon0); - if (crossings & 1) - tempsum.Add( (tempsum.Sum() < 0 ? 1 : -1) * this._area0/2 ); - // area is with the clockwise sense. If !reverse convert to - // counter-clockwise convention. - if (!reverse) - tempsum.Negate(); - // If sign put area in (-area0/2, area0/2], else put area in [0, area0) - if (sign) { - if (tempsum.Sum() > this._area0/2) - tempsum.Add( -this._area0 ); - else if (tempsum.Sum() <= -this._area0/2) - tempsum.Add( +this._area0 ); - } else { - if (tempsum.Sum() >= this._area0) - tempsum.Add( -this._area0 ); - else if (tempsum < 0) - tempsum.Add( -this._area0 ); - } - vals.area = tempsum.Sum(); - return vals; - } - - // return number, perimeter, area - p.PolygonArea.prototype.TestPoint = function(lat, lon, reverse, sign) { - var vals = {number: this._num + 1}; - if (this._num == 0) { - vals.perimeter = 0; - if (!this._polyline) - vals.area = 0; - return vals; - } - vals.perimeter = this._perimetersum.Sum(); - var tempsum = this._polyline ? 0 : this._areasum.Sum(); - var crossings = this._crossings; - var t; - for (var i = 0; i < (this._polyline ? 1 : 2); ++i) { - t = this._earth.Inverse - (i == 0 ? this._lat1 : lat, i == 0 ? this._lon1 : lon, - i != 0 ? this._lat0 : lat, i != 0 ? this._lon0 : lon, - this._mask); - vals.perimeter += t.s12; - if (!this._polyline) { - tempsum += t.S12; - crossings += p.transit(i == 0 ? this._lon1 : lon, - i != 0 ? this._lon0 : lon); - } - } - - if (this._polyline) - return vals; - - if (crossings & 1) - tempsum += (tempsum < 0 ? 1 : -1) * this._area0/2; - // area is with the clockwise sense. If !reverse convert to - // counter-clockwise convention. - if (!reverse) - tempsum *= -1; - // If sign put area in (-area0/2, area0/2], else put area in [0, area0) - if (sign) { - if (tempsum > this._area0/2) - tempsum -= this._area0; - else if (tempsum <= -this._area0/2) - tempsum += this._area0; - } else { - if (tempsum >= this._area0) - tempsum -= this._area0; - else if (tempsum < 0) - tempsum += this._area0; - } - vals.area = tempsum; - return vals; - } - - // return number, perimeter, area - p.PolygonArea.prototype.TestEdge = function(azi, s, reverse, sign) { - var vals = {number: this._num ? this._num + 1 : 0}; - if (this._num == 0) - return vals; - vals.perimeter = this._perimetersum.Sum() + s; - if (this._polyline) - return vals; - - var tempsum = this._areasum.Sum(); - var crossings = this._crossings; - var t; - t = this._earth.Direct(this._lat1, this._lon1, azi, s, this._mask); - tempsum += t.S12; - crossings += p.transit(this._lon1, t.lon2); - t = this._earth(t.lat2, t.lon2, this._lat0, this._lon0, this._mask); - perimeter += t.s12; - tempsum += t.S12; - crossings += p.transit(t.lon2, this._lon0); - - if (crossings & 1) - tempsum += (tempsum < 0 ? 1 : -1) * this._area0/2; - // area is with the clockwise sense. If !reverse convert to - // counter-clockwise convention. - if (!reverse) - tempsum *= -1; - // If sign put area in (-area0/2, area0/2], else put area in [0, area0) - if (sign) { - if (tempsum > this._area0/2) - tempsum -= this._area0; - else if (tempsum <= -this._area0/2) - tempsum += this._area0; - } else { - if (tempsum >= this._area0) - tempsum -= this._area0; - else if (tempsum < 0) - tempsum += this._area0; - } - vals.area = tempsum; - return vals; - } - - p.PolygonArea.prototype.CurrentPoint = function() { - var vals = {lat: this._lat1, lon: this._lon1}; - return vals; - } - - p.Area = function(earth, points, polyline) { - var poly = new p.PolygonArea(earth, polyline); - for (var i = 0; i < points.length; ++i) - poly.AddPoint(points[i].lat, points[i].lon); - return poly.Compute(false, true); - } - -})(); diff --git a/gtsam/3rdparty/GeographicLib/doc/scripts/geod-calc.html b/gtsam/3rdparty/GeographicLib/doc/scripts/geod-calc.html deleted file mode 100644 index a6e0b094b..000000000 --- a/gtsam/3rdparty/GeographicLib/doc/scripts/geod-calc.html +++ /dev/null @@ -1,471 +0,0 @@ - - - - Geodesic calculations for an ellipsoid done right - - - - - - - -
-

Geodesic calculations for an ellipsoid done right

-
-

- This page illustrates the geodesic routines available in - GeographicLib. - The C++ code has been converted to JavaScript so the calculations - are carried out on the client. The algorithms are considerably - more accurate than Vincenty's method, and offer more functionality - (an inverse method which never fails to converge, differential - properties of the geodesic, and the area under a geodesic). The - algorithms are derived in -

- Charles F. F. Karney,
- - Algorithms for geodesics,
- J. Geodesy 87(1), 43–55 (Jan. 2013);
- DOI: - - 10.1007/s00190-012-0578-z - (pdf); - addenda: - geod-addenda.html. -
- This page just provides a basic interface. Enter latitudes, - longitudes, and azimuths as degrees and distances as meters using - spaces or commas as separators. (Angles may be entered as decimal - degrees or as degrees, minutes, and seconds, e.g. -20.51125, - 20°30′40.5″S, S20d30'40.5", or - -20:30:40.5.) The results are accurate to about - 15 nanometers (or 0.1 m2 per vertex for - areas). A slicker page where the geodesics are incorporated into - Google Maps is given here. -

- Jump to: -

-

-
-
-

Inverse problem

-

- Find the shortest path between two points on the earth. The - path is characterized by its length s12 and its azimuth - at the two ends azi1 and azi2. The sample - calculation finds the shortest path between Wellington, New - Zealand, and Salamanca, Spain. (For this example, the - NGS - - inverse geodesic calculator returns a result which is 1.2 km - too long with an azimuth which is off by 3 degrees.) To perform - the calculation, press the “COMPUTE” button. -

-

Enter “lat1 lon1 lat2 lon2”:

-

input: - -

-

- Output format:    -
- Output precision:   -

-

- -

-

- status: - -

-

- lat1 lon1 azi1: - -

-

- lat2 lon2 azi2: - -

-

- s12: - -

-
-
-
-

Direct problem

-

- Find the destination traveling a given distance along a geodesic - with a given azimuth at the starting point. The destination is - characterized by its position lat2, lon2 and its azimuth - at the destination azi2. The sample calculation shows - the result of travelling 10000 km NE from JFK airport. To perform - the calculation, press the “COMPUTE” button. -

-

Enter “lat1 lon1 azi1 s12”:

-

input: - -

-

- Output format:    -
- Output precision:   -

-

- -

-

- status: - -

-

- lat1 lon1 azi1: - -

-

- lat2 lon2 azi2: - -

-

- s12: - -

- -
-
-

Geodesic path

-

- Find intermediate points along a geodesic. In addition to - specifying the endpoints, give ds12, the maximum distance - between the intermediate points and maxk, the maximum - number of intervals the geodesic is broken into. The output - gives a sequence of positions lat, lon together with the - corresponding azimuths azi. The sample shows the path - from JFK to Singapore's Changi Airport at about 1000 km - intervals. (In this example, the path taken by Google Earth - deviates from the shortest path by about 2.9 km.) To perform - the calculation, press the “COMPUTE” button. -

-

Enter “lat1 lon1 lat2 lon2 ds12 maxk”:

-

input: - -

-

- Output format:    -
- Output precision:   -

-

- -

-

- status: - -

-

- points (lat lon azi):
- -

- -
-
-

Polygon area

-

- Find the perimeter and area of a polygon whose sides are - geodesics. The polygon must be simple (i.e., must not intersect - itself). (There's no need to ensure that the polygon is - closed.) Counter-clockwise traversal of the polygon results in - a positive area. The polygon can encircle one or both poles. - The sample gives the approximate perimeter (in m) and area (in - m2) of Antarctica. (For this example, Google Earth - Pro returns an area which is 30 times too large! However this - is a little unfair, since Google Earth has no concept of - polygons which encircle a pole.) If the polyline option - is selected then just the length of the line joining the points - is is returned. To perform the calculation, press the - “COMPUTE” button. -

-

Enter points, one per line, as “lat lon”:

-

points (lat lon):
- -

-

- Treat points as:    - -

-

- -

-

- status: - -

-

- number perimeter area: - -

- -
-
Charles Karney - <charles@karney.com> - (2011-08-04)
-
- - SourceForge.net - - - diff --git a/gtsam/3rdparty/GeographicLib/doc/scripts/geod-google-instructions.html b/gtsam/3rdparty/GeographicLib/doc/scripts/geod-google-instructions.html deleted file mode 100644 index 89c2e5605..000000000 --- a/gtsam/3rdparty/GeographicLib/doc/scripts/geod-google-instructions.html +++ /dev/null @@ -1,118 +0,0 @@ - - - - - Geodesic lines, circles, envelopes in Google Maps (instructions) - - - - - - -

- Geodesic lines, circles, envelopes in Google Maps (instructions) -

-

- The page allows you to draw - accurate ellipsoidal geodesics on Google Maps. You can specify the - geodesic in one of two forms: -

    -
  • - The direct problem: specify a starting point, an - azimuth and a distance as lat1 lon1 azi1 s12 as degrees - and meters. -
  • - The inverse problem: specify the two end points - as lat1 lon1 lat2 lon2 as degrees; this finds the - shortest path between the two points. -
- (Angles may be entered as decimal degrees or as degrees, minutes, - and seconds, e.g. -20.51125, 20°30′40.5″S, - S20d30'40.5", or -20:30:40.5.) Click on the - corresponding "compute" button. The display then shows -
    -
  • The requested geodesic as a blue - line; the WGS84 ellipsoid model is used. -
  • The geodesic circle as a green - curve; this shows the locus of points a - distance s12 from lat1, lon1. -
  • The geodesic envelopes as red - curves; all the geodesics emanating from lat1, - lon1 are tangent to the envelopes (providing they are - extended far enough). The number of solutions to the inverse - problem changes depending on whether lat2, lon2 lies - inside the envelopes. For example, there are four (resp. two) - approximately hemispheroidal geodesics if this point lies - inside (resp. outside) the inner envelope (only one of which - is a shortest path). -
-

-

- The sample data has lat1, lon1 in Wellington, New - Zealand, lat2, lon2 in Salamanca, Spain, and s12 - about 1.5 times the earth's circumference. Try clicking on the - "compute" button next to the "Direct:" input box when the page - first loads. You can navigate around the map using the normal - Google Map controls. -

-

- The precision of output for the geodesic is 0.1" or 1 m. - A text-only geodesic calculator based - on the same JavaScript library is also available; this calculator - solves the inverse and direct geodesic problems, computes - intermediate points on a geodesic, and finds the area of a - geodesic polygon; it allows you to specify the precision of the - output and choose between decimal degrees and degress, minutes, - and seconds. -

- The Javascipt code for computing the geodesic lines, circles, and - envelopes is part of - GeographicLib. - The algorithms are derived in -

- Charles F. F. Karney,
- - Algorithms for geodesics,
- J. Geodesy 87(1), 43–55 (Jan. 2013);
- DOI: - - 10.1007/s00190-012-0578-z - (pdf);
- addenda: - geod-addenda.html. -
- In putting together this Google Maps demonstration, I started with - the sample code - - geometry-headings. -

-
-
Charles Karney - <charles@karney.com> - (2011-08-02)
-
- - SourceForge.net - - - diff --git a/gtsam/3rdparty/GeographicLib/doc/scripts/geod-google.html b/gtsam/3rdparty/GeographicLib/doc/scripts/geod-google.html deleted file mode 100644 index 5a48d7e2e..000000000 --- a/gtsam/3rdparty/GeographicLib/doc/scripts/geod-google.html +++ /dev/null @@ -1,226 +0,0 @@ - - - - - - Geodesic lines, circles, envelopes in Google Maps - - - - - - - - - -
-
-
-

-  Direct:   - - -

-

-  Inverse: - - -

-

-  lat1 lon1 azi1: -

-

-  lat2 lon2 azi2: -

-

-  s12: -    status: -    - INSTRUCTIONS HERE -

-
- - diff --git a/gtsam/3rdparty/GeographicLib/doc/tmseries30.html b/gtsam/3rdparty/GeographicLib/doc/tmseries30.html index 26b1f9341..0d0ee7971 100644 --- a/gtsam/3rdparty/GeographicLib/doc/tmseries30.html +++ b/gtsam/3rdparty/GeographicLib/doc/tmseries30.html @@ -3,6 +3,7 @@ Krueger's series for the transverse Mercator projection +

Krueger's series for the transverse Mercator projection @@ -12,22 +13,22 @@ order in the flattening. See
Louis Krueger, - + Konforme Abbildung des Erdellipsoids in der Ebene, Royal Prussian Geodetic Institute, New Series 52, 172 pp. (1912), DOI: - + 10.2312/GFZ.b103-krueger28
and
Charles F. F. Karney, - + Transverse Mercator with an accuracy of a few nanometers, J. Geodesy 85(8), 475–485 (Aug. 2011); preprint - arXiv:1002.1417; + arXiv:1002.1417; resource page - tm.html. + tm.html.
 
diff --git a/gtsam/3rdparty/GeographicLib/doc/utilities.html.in b/gtsam/3rdparty/GeographicLib/doc/utilities.html.in
index adadcb915..740a70c56 100644
--- a/gtsam/3rdparty/GeographicLib/doc/utilities.html.in
+++ b/gtsam/3rdparty/GeographicLib/doc/utilities.html.in
@@ -2,7 +2,7 @@
   
     GeographicLib-@PROJECT_VERSION@ utilities
     
+	  CONTENT="0; URL=https://geographiclib.sourceforge.io/@PROJECT_VERSION@/utilities.html">
   
   
     

@@ -11,8 +11,8 @@ Online documentation for utilities for GeographicLib version @PROJECT_VERSION@ is available at
- - http://geographiclib.sourceforge.net/@PROJECT_VERSION@/utilities.html. + + https://geographiclib.sourceforge.io/@PROJECT_VERSION@/utilities.html.

You will be redirected there. Click on the link to go there diff --git a/gtsam/3rdparty/GeographicLib/doc/vptree.gif b/gtsam/3rdparty/GeographicLib/doc/vptree.gif new file mode 100644 index 000000000..4f70cce6b Binary files /dev/null and b/gtsam/3rdparty/GeographicLib/doc/vptree.gif differ diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Accumulator.cpp b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Accumulator.cpp index fda88f606..9a249617a 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Accumulator.cpp +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Accumulator.cpp @@ -6,7 +6,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #include "stdafx.h" #include "GeographicLib/Accumulator.hpp" diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Accumulator.h b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Accumulator.h index 825306f32..4b8b1d093 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Accumulator.h +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Accumulator.h @@ -7,7 +7,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ namespace NETGeographicLib @@ -22,7 +22,7 @@ namespace NETGeographicLib precision of the sum is 106 bits or about 32 decimal places. The implementation follows J. R. Shewchuk, - Adaptive Precision + Adaptive Precision Floating-Point Arithmetic and Fast Robust Geometric Predicates, Discrete & Computational Geometry 18(3) 305--363 (1997). diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/AlbersEqualArea.cpp b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/AlbersEqualArea.cpp index 87a3160e8..9d0d251d7 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/AlbersEqualArea.cpp +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/AlbersEqualArea.cpp @@ -6,7 +6,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #include "stdafx.h" #include "GeographicLib/AlbersEqualArea.hpp" @@ -33,13 +33,13 @@ AlbersEqualArea::AlbersEqualArea( StandardTypes type ) switch ( type ) { case StandardTypes::CylindricalEqualArea: - m_pAlbersEqualArea = new GeographicLib::AlbersEqualArea( GeographicLib::AlbersEqualArea::CylindricalEqualArea ); + m_pAlbersEqualArea = new GeographicLib::AlbersEqualArea( GeographicLib::AlbersEqualArea::CylindricalEqualArea() ); break; case StandardTypes::AzimuthalEqualAreaNorth: - m_pAlbersEqualArea = new GeographicLib::AlbersEqualArea( GeographicLib::AlbersEqualArea::AzimuthalEqualAreaNorth ); + m_pAlbersEqualArea = new GeographicLib::AlbersEqualArea( GeographicLib::AlbersEqualArea::AzimuthalEqualAreaNorth() ); break; case StandardTypes::AzimuthalEqualAreaSouth: - m_pAlbersEqualArea = new GeographicLib::AlbersEqualArea( GeographicLib::AlbersEqualArea::AzimuthalEqualAreaSouth ); + m_pAlbersEqualArea = new GeographicLib::AlbersEqualArea( GeographicLib::AlbersEqualArea::AzimuthalEqualAreaSouth() ); break; } } diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/AlbersEqualArea.h b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/AlbersEqualArea.h index c1105173a..6c1ac0244 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/AlbersEqualArea.h +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/AlbersEqualArea.h @@ -7,7 +7,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ namespace NETGeographicLib @@ -97,8 +97,7 @@ namespace NETGeographicLib * * @param[in] a equatorial radius of ellipsoid (meters). * @param[in] f flattening of ellipsoid. Setting \e f = 0 gives a sphere. - * Negative \e f gives a prolate ellipsoid. If \e f > 1, set flattening - * to 1/\e f. + * Negative \e f gives a prolate ellipsoid. * @param[in] stdlat standard parallel (degrees), the circle of tangency. * @param[in] k0 azimuthal scale on the standard parallel. * @exception GeographicErr if \e a, (1 − \e f ) \e a, or \e k0 is @@ -113,8 +112,7 @@ namespace NETGeographicLib * * @param[in] a equatorial radius of ellipsoid (meters). * @param[in] f flattening of ellipsoid. Setting \e f = 0 gives a sphere. - * Negative \e f gives a prolate ellipsoid. If \e f > 1, set flattening - * to 1/\e f. + * Negative \e f gives a prolate ellipsoid. * @param[in] stdlat1 first standard parallel (degrees). * @param[in] stdlat2 second standard parallel (degrees). * @param[in] k1 azimuthal scale on the standard parallels. @@ -131,8 +129,7 @@ namespace NETGeographicLib * * @param[in] a equatorial radius of ellipsoid (meters). * @param[in] f flattening of ellipsoid. Setting \e f = 0 gives a sphere. - * Negative \e f gives a prolate ellipsoid. If \e f > 1, set flattening - * to 1/\e f. + * Negative \e f gives a prolate ellipsoid. * @param[in] sinlat1 sine of first standard parallel. * @param[in] coslat1 cosine of first standard parallel. * @param[in] sinlat2 sine of second standard parallel. @@ -180,12 +177,11 @@ namespace NETGeographicLib * @param[out] k azimuthal scale of projection at point; the radial * scale is the 1/\e k. * - * The latitude origin is given by AlbersEqualArea::LatitudeOrigin(). No - * false easting or northing is added and \e lat should be in the range - * [−90°, 90°]; \e lon and \e lon0 should be in the - * range [−540°, 540°). The values of \e x and \e y - * returned for points which project to infinity (i.e., one or both of the - * poles) will be large but finite. + * The latitude origin is given by AlbersEqualArea::LatitudeOrigin(). + * No false easting or northing is added and \e lat should be in the + * range [−90°, 90°]. The values of \e x and \e y + * returned for points which project to infinity (i.e., one or both of + * the poles) will be large but finite. **********************************************************************/ void Forward(double lon0, double lat, double lon, [System::Runtime::InteropServices::Out] double% x, @@ -205,12 +201,11 @@ namespace NETGeographicLib * @param[out] k azimuthal scale of projection at point; the radial * scale is the 1/\e k. * - * The latitude origin is given by AlbersEqualArea::LatitudeOrigin(). No - * false easting or northing is added. \e lon0 should be in the range - * [−540°, 540°). The value of \e lon returned is in - * the range [−180°, 180°). The value of \e lat - * returned is in the range [−90°, 90°]. If the - * input point is outside the legal projected space the nearest pole is + * The latitude origin is given by AlbersEqualArea::LatitudeOrigin(). + * No false easting or northing is added. The value of \e lon returned + * is in the range [−180°, 180°). The value of \e lat + * returned is in the range [−90°, 90°]. If the input + * point is outside the legal projected space the nearest pole is * returned. **********************************************************************/ void Reverse(double lon0, double x, double y, diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/AzimuthalEquidistant.cpp b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/AzimuthalEquidistant.cpp index 5279ee938..c4b091941 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/AzimuthalEquidistant.cpp +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/AzimuthalEquidistant.cpp @@ -6,7 +6,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #include "stdafx.h" #include "GeographicLib/AzimuthalEquidistant.hpp" @@ -32,7 +32,7 @@ AzimuthalEquidistant::AzimuthalEquidistant(void) { try { - m_pAzimuthalEquidistant = new GeographicLib::AzimuthalEquidistant( GeographicLib::Geodesic::WGS84 ); + m_pAzimuthalEquidistant = new GeographicLib::AzimuthalEquidistant( GeographicLib::Geodesic::WGS84() ); } catch ( std::bad_alloc ) { diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/AzimuthalEquidistant.h b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/AzimuthalEquidistant.h index ab0643fc4..b28431c92 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/AzimuthalEquidistant.h +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/AzimuthalEquidistant.h @@ -6,7 +6,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #pragma once #include "Geodesic.h" @@ -86,13 +86,12 @@ namespace NETGeographicLib * @param[out] azi azimuth of geodesic at point (degrees). * @param[out] rk reciprocal of azimuthal scale at point. * - * \e lat0 and \e lat should be in the range [−90°, - * 90°] and \e lon0 and \e lon should be in the range - * [−540°, 540°). The scale of the projection is 1 - * in the "radial" direction, \e azi clockwise from true north, and is 1/\e - * rk in the direction perpendicular to this. A call to Forward followed - * by a call to Reverse will return the original (\e lat, \e lon) (to - * within roundoff). + * \e lat0 and \e lat should be in the range [−90°, 90°]. + * The scale of the projection is 1 in the "radial" direction, \e azi + * clockwise from true north, and is 1/\e rk in the direction + * perpendicular to this. A call to Forward followed by a call to + * Reverse will return the original (\e lat, \e lon) (to within + * roundoff). **********************************************************************/ void Forward(double lat0, double lon0, double lat, double lon, [System::Runtime::InteropServices::Out] double% x, @@ -112,15 +111,14 @@ namespace NETGeographicLib * @param[out] azi azimuth of geodesic at point (degrees). * @param[out] rk reciprocal of azimuthal scale at point. * - * \e lat0 should be in the range [−90°, 90°] and \e - * lon0 should be in the range [−540°, 540°). \e lat - * will be in the range [−90°, 90°] and \e lon will - * be in the range [−180°, 180°). The scale of the - * projection is 1 in the "radial" direction, \e azi clockwise from true - * north, and is 1/\e rk in the direction perpendicular to this. A call to - * Reverse followed by a call to Forward will return the original (\e x, \e - * y) (to roundoff) only if the geodesic to (\e x, \e y) is a shortest - * path. + * \e lat0 should be in the range [−90°, 90°]. \e lat + * will be in the range [−90°, 90°] and \e lon will be in + * the range [−180°, 180°). The scale of the projection + * is 1 in the "radial" direction, \e azi clockwise from true north, + * and is 1/\e rk in the direction perpendicular to this. A call to + * Reverse followed by a call to Forward will return the original (\e + * x, \e y) (to roundoff) only if the geodesic to (\e x, \e y) is a + * shortest path. **********************************************************************/ void Reverse(double lat0, double lon0, double x, double y, [System::Runtime::InteropServices::Out] double% lat, diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/CMakeLists.txt b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/CMakeLists.txt index 664b1bc07..d83d06462 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/CMakeLists.txt +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/CMakeLists.txt @@ -11,32 +11,44 @@ set_target_properties (${NETGEOGRAPHICLIB_LIBRARIES} string (REPLACE "/RTC1" "" CMAKE_CXX_FLAGS_DEBUG "${CMAKE_CXX_FLAGS_DEBUG}") string (REPLACE "/EHsc" "" CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS}") +if (MSVC AND NOT MSVC_VERSION GREATER 1600) + # Disable "already imported" and "unsupported default parameter" + # warnings with VS 10 + set (CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} /wd4945 /wd4564") +endif () + add_definitions (${PROJECT_DEFINITIONS}) target_link_libraries (${NETGEOGRAPHICLIB_LIBRARIES} ${PROJECT_LIBRARIES}) # Set the version number on the library set_target_properties (${NETGEOGRAPHICLIB_LIBRARIES} PROPERTIES - VERSION "${LIBVERSIONFULL}" OUTPUT_NAME ${NETLIBNAME} - PDB_NAME ${NETLIBNAME}${CMAKE_DEBUG_POSTFIX}) + VERSION "${LIBVERSIONFULL}" OUTPUT_NAME ${NETLIBNAME}) -# Specify where the library is installed, adding it to the export depends +# Specify where the library is installed, adding it to the export targets install (TARGETS ${NETGEOGRAPHICLIB_LIBRARIES} - EXPORT depends + EXPORT targets RUNTIME DESTINATION bin) if (PACKAGE_DEBUG_LIBS) install (PROGRAMS - "${CMAKE_CURRENT_BINARY_DIR}/Debug/${NETLIBNAME}${CMAKE_DEBUG_POSTFIX}.dll" + "${PROJECT_BINARY_DIR}/bin/Debug/${NETLIBNAME}${CMAKE_DEBUG_POSTFIX}.dll" DESTINATION bin CONFIGURATIONS Release) endif () -# Install pdb file in debug mode. -get_target_property (_P ${NETGEOGRAPHICLIB_LIBRARIES} LOCATION_DEBUG) -get_filename_component (_P ${_P} PATH) -get_target_property (_N ${NETGEOGRAPHICLIB_LIBRARIES} PDB_NAME) -set (_PDB ${_P}/${_N}.pdb) -install (FILES ${_PDB} DESTINATION bin - RENAME ${NETLIBNAME}${CMAKE_DEBUG_POSTFIX}.pdb CONFIGURATIONS Debug) +if (NOT CMAKE_VERSION VERSION_LESS 3.0) + # Suppress 3.0 warnings about use of the LOCATION target property + cmake_policy (SET CMP0026 OLD) +endif () + +# Install pdb file. +foreach (_c ${CMAKE_CONFIGURATION_TYPES}) + string (TOUPPER ${_c} _C) + get_target_property (_P ${NETGEOGRAPHICLIB_LIBRARIES} LOCATION_${_C}) + get_filename_component (_D ${_P} PATH) + get_filename_component (_N ${_P} NAME_WE) + set (_PDB ${_D}/${_N}.pdb) + install (FILES ${_PDB} DESTINATION bin CONFIGURATIONS ${_c} OPTIONAL) +endforeach () # Put all the library into a folder in the IDE set_property (TARGET ${NETGEOGRAPHICLIB_LIBRARIES} PROPERTY FOLDER library) diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/CassiniSoldner.cpp b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/CassiniSoldner.cpp index cfaa96aea..29a7327af 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/CassiniSoldner.cpp +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/CassiniSoldner.cpp @@ -6,7 +6,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #include "stdafx.h" #include "GeographicLib/CassiniSoldner.hpp" @@ -33,7 +33,7 @@ CassiniSoldner::CassiniSoldner(double lat0, double lon0) { try { - m_pCassiniSoldner = new GeographicLib::CassiniSoldner( GeographicLib::Geodesic::WGS84 ); + m_pCassiniSoldner = new GeographicLib::CassiniSoldner( GeographicLib::Geodesic::WGS84() ); m_pCassiniSoldner->Reset(lat0, lon0); } catch ( std::bad_alloc ) diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/CassiniSoldner.h b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/CassiniSoldner.h index 7150da02d..c6de0e402 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/CassiniSoldner.h +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/CassiniSoldner.h @@ -6,7 +6,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #pragma once @@ -93,8 +93,7 @@ namespace NETGeographicLib * @param[in] earth the Geodesic object to use for geodesic calculations. * By default this uses the WGS84 ellipsoid. * - * \e lat0 should be in the range [−90°, 90°] and \e - * lon0 should be in the range [−540°, 540°). + * \e lat0 should be in the range [−90°, 90°]. **********************************************************************/ CassiniSoldner(double lat0, double lon0, Geodesic^ earth ); @@ -110,8 +109,7 @@ namespace NETGeographicLib * @param[in] lat0 latitude of center point of projection (degrees). * @param[in] lon0 longitude of center point of projection (degrees). * - * \e lat0 should be in the range [−90°, 90°] and \e - * lon0 should be in the range [−540°, 540°). + * \e lat0 should be in the range [−90°, 90°]. **********************************************************************/ void Reset(double lat0, double lon0); @@ -125,9 +123,8 @@ namespace NETGeographicLib * @param[out] azi azimuth of easting direction at point (degrees). * @param[out] rk reciprocal of azimuthal northing scale at point. * - * \e lat should be in the range [−90°, 90°] and \e - * lon should be in the range [−540°, 540°). A call - * to Forward followed by a call to Reverse will return the original (\e + * \e lat should be in the range [−90°, 90°]. A call to + * Forward followed by a call to Reverse will return the original (\e * lat, \e lon) (to within roundoff). The routine does nothing if the * origin has not been set. **********************************************************************/ diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/CircularEngine.cpp b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/CircularEngine.cpp index 37aae2150..1ac48d28c 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/CircularEngine.cpp +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/CircularEngine.cpp @@ -6,7 +6,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #include "stdafx.h" #include "GeographicLib/CircularEngine.hpp" diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/CircularEngine.h b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/CircularEngine.h index febed2bf9..9bf1014a3 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/CircularEngine.h +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/CircularEngine.h @@ -6,7 +6,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #pragma once diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/DMS.cpp b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/DMS.cpp index 8271b7fd2..89deb3f5d 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/DMS.cpp +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/DMS.cpp @@ -6,7 +6,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #include "stdafx.h" #include "GeographicLib/DMS.hpp" @@ -32,30 +32,17 @@ double DMS::Decode( System::String^ dms, } } -//***************************************************************************** -double DMS::Decode(System::String^ str) -{ - try - { - return GeographicLib::DMS::Decode(StringConvert::ManagedToUnmanaged(str)); - } - catch ( const std::exception& xcpt ) - { - throw gcnew GeographicErr( xcpt.what() ); - } -} - //***************************************************************************** void DMS::DecodeLatLon(System::String^ dmsa, System::String^ dmsb, [System::Runtime::InteropServices::Out] double% lat, [System::Runtime::InteropServices::Out] double% lon, - bool swaplatlong ) + bool longfirst ) { try { double llat, llon; GeographicLib::DMS::DecodeLatLon( StringConvert::ManagedToUnmanaged( dmsa ), - StringConvert::ManagedToUnmanaged( dmsb ), llat, llon, swaplatlong ); + StringConvert::ManagedToUnmanaged( dmsb ), llat, llon, longfirst ); lat = llat; lon = llon; } diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/DMS.h b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/DMS.h index a0c37fe4e..c68622ac3 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/DMS.h +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/DMS.h @@ -6,7 +6,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #pragma once @@ -95,37 +95,62 @@ public: * Degrees, minutes, and seconds are indicated by the characters d, ' * (single quote), " (double quote), and these components may only be * given in this order. Any (but not all) components may be omitted and - * other symbols (e.g., the ° symbol for degrees and the unicode - * prime and double prime symbols for minutes and seconds) may be - * substituted. The last component indicator may be omitted and is assumed - * to be the next smallest unit (thus 33d10 is interpreted as 33d10'). The - * final component may be a decimal fraction but the non-final components - * must be integers. Instead of using d, ', and " to indicate - * degrees, minutes, and seconds, : (colon) may be used to separate - * these components (numbers must appear before and after each colon); thus - * 50d30'10.3" may be written as 50:30:10.3, 5.5' may be written - * 0:5.5, and so on. The integer parts of the minutes and seconds - * components must be less than 60. A single leading sign is permitted. A - * hemisphere designator (N, E, W, S) may be added to the beginning or end - * of the string. The result is multiplied by the implied sign of the - * hemisphere designator (negative for S and W). In addition \e ind is set - * to DMS::LATITUDE if N or S is present, to DMS::LONGITUDE if E or W is - * present, and to DMS::NONE otherwise. Throws an error on a malformed - * string. No check is performed on the range of the result. Examples of - * legal and illegal strings are + * other symbols (e.g., the ° symbol for degrees and the unicode prime + * and double prime symbols for minutes and seconds) may be substituted; + * two single quotes can be used instead of ". The last component + * indicator may be omitted and is assumed to be the next smallest unit + * (thus 33d10 is interpreted as 33d10'). The final component may be a + * decimal fraction but the non-final components must be integers. Instead + * of using d, ', and " to indicate degrees, minutes, and seconds, : + * (colon) may be used to separate these components (numbers must + * appear before and after each colon); thus 50d30'10.3" may be + * written as 50:30:10.3, 5.5' may be written 0:5.5, and so on. The + * integer parts of the minutes and seconds components must be less + * than 60. A single leading sign is permitted. A hemisphere designator + * (N, E, W, S) may be added to the beginning or end of the string. The + * result is multiplied by the implied sign of the hemisphere designator + * (negative for S and W). In addition \e ind is set to DMS::LATITUDE if N + * or S is present, to DMS::LONGITUDE if E or W is present, and to + * DMS::NONE otherwise. Throws an error on a malformed string. No check + * is performed on the range of the result. Examples of legal and illegal + * strings are * - LEGAL (all the entries on each line are equivalent) * - -20.51125, 20d30'40.5"S, -20°30'40.5, -20d30.675, * N-20d30'40.5", -20:30:40.5 * - 4d0'9, 4d9", 4d9'', 4:0:9, 004:00:09, 4.0025, 4.0025d, 4d0.15, * 04:.15 + * - 4:59.99999999999999, 4:60.0, 4:59:59.9999999999999, 4:59:60.0, 5 * - ILLEGAL (the exception thrown explains the problem) * - 4d5"4', 4::5, 4:5:, :4:5, 4d4.5'4", -N20.5, 1.8e2d, 4:60, - * 4d-5' + * 4:59:60 + * + * The decoding operation can also perform addition and subtraction + * operations. If the string includes internal signs (i.e., not at + * the beginning nor immediately after an initial hemisphere designator), + * then the string is split immediately before such signs and each piece is + * decoded according to the above rules and the results added; thus + * S3-2.5+4.1N is parsed as the sum of S3, + * -2.5, +4.1N. Any piece can include a + * hemisphere designator; however, if multiple designators are given, they + * must compatible; e.g., you cannot mix N and E. In addition, the + * designator can appear at the beginning or end of the first piece, but + * must be at the end of all subsequent pieces (a hemisphere designator is + * not allowed after the initial sign). Examples of legal and illegal + * combinations are + * - LEGAL (these are all equivalent) + * - 070:00:45, 70:01:15W+0:0.5, 70:01:15W-0:0:30W, W70:01:15+0:0:30E + * - ILLEGAL (the exception thrown explains the problem) + * - 70:01:15W+0:0:15N, W70:01:15+W0:0:15 + * + * WARNING: "Exponential" notation is not recognized. Thus + * 7.0E1 is illegal, while 7.0E+1 is parsed as + * (7.0E) + (+1), yielding the same result as + * 8.0E. * * NOTE: At present, all the string handling in the C++ * implementation %GeographicLib is with 8-bit characters. The support for * unicode symbols for degrees, minutes, and seconds is therefore via the - * UTF-8 encoding. (The + * UTF-8 encoding. (The * JavaScript implementation of this class uses unicode natively, of * course.) * @@ -169,27 +194,14 @@ public: static double Decode(double d, double m, double s ) { return d + (m + s/double(60))/double(60); } - /// \cond SKIP - /** - * DEPRECATED (use Utility::num, instead). - * Convert a string to a double number. - * - * @param[in] str string input. - * @exception GeographicErr if \e str is malformed. - * @return decoded number. - **********************************************************************/ - static double Decode(System::String^ str); - /// \endcond - /** * Convert a pair of strings to latitude and longitude. * * @param[in] dmsa first string. * @param[in] dmsb second string. - * @param[out] lat latitude. - * @param[out] lon longitude reduced to the range [−180°, - * 180°). - * @param[in] swaplatlong if true assume longitude is given before latitude + * @param[out] lat latitude (degrees). + * @param[out] lon longitude (degrees). + * @param[in] longfirst if true assume longitude is given before latitude * in the absence of hemisphere designators (default false). * @exception GeographicErr if \e dmsa or \e dmsb is malformed. * @exception GeographicErr if \e dmsa and \e dmsb are both interpreted as @@ -198,8 +210,6 @@ public: * longitudes. * @exception GeographicErr if decoded latitude is not in [−90°, * 90°]. - * @exception GeographicErr if decoded longitude is not in - * [−540°, 540°). * * By default, the \e lat (resp., \e lon) is assigned to the results of * decoding \e dmsa (resp., \e dmsb). However this is overridden if either @@ -210,7 +220,7 @@ public: static void DecodeLatLon(System::String^ dmsa, System::String^ dmsb, [System::Runtime::InteropServices::Out] double% lat, [System::Runtime::InteropServices::Out] double% lon, - bool swaplatlong ); + bool longfirst ); /** * Convert a string to an angle in degrees. @@ -231,8 +241,6 @@ public: * @param[in] azistr input string. * @exception GeographicErr if \e azistr is malformed. * @exception GeographicErr if \e azistr includes a N/S designator. - * @exception GeographicErr if decoded azimuth is not in - * [−540°, 540°). * @return azimuth (degrees) reduced to the range [−180°, * 180°). * diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Ellipsoid.cpp b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Ellipsoid.cpp index 8f5acd6e0..a6abdaea8 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Ellipsoid.cpp +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Ellipsoid.cpp @@ -6,7 +6,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #include "stdafx.h" #include "GeographicLib/Ellipsoid.hpp" @@ -32,7 +32,7 @@ Ellipsoid::Ellipsoid() { try { - m_pEllipsoid = new GeographicLib::Ellipsoid( GeographicLib::Ellipsoid::WGS84 ); + m_pEllipsoid = new GeographicLib::Ellipsoid( GeographicLib::Ellipsoid::WGS84() ); } catch ( std::bad_alloc ) { diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Ellipsoid.h b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Ellipsoid.h index 751bf6c5a..e94dc751b 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Ellipsoid.h +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Ellipsoid.h @@ -6,7 +6,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #pragma once @@ -50,7 +50,7 @@ namespace NETGeographicLib // A pointer to the unmanaged GeographicLib::Ellipsoid GeographicLib::Ellipsoid* m_pEllipsoid; - // Th efinalizer frees the unmanaged memory when the object is destroyed. + // The finalizer frees the unmanaged memory when the object is destroyed. !Ellipsoid(); public: /** \name Constructor @@ -67,8 +67,7 @@ namespace NETGeographicLib * * @param[in] a equatorial radius (meters). * @param[in] f flattening of ellipsoid. Setting \e f = 0 gives a sphere. - * Negative \e f gives a prolate ellipsoid. If \e f > 1, set flattening - * to 1/\e f. + * Negative \e f gives a prolate ellipsoid. * @exception GeographicErr if \e a or (1 − \e f ) \e a is not * positive. **********************************************************************/ @@ -402,9 +401,8 @@ namespace NETGeographicLib * section at latitude φ inclined at an angle \e azi to the * meridian (meters). * - * φ must lie in the range [−90°, 90°] and \e - * azi must lie in the range [−540°, 540°); the - * result is undefined if either of conditions does not hold. + * φ must lie in the range [−90°, 90°]; the + * result is undefined if this condition does not hold. **********************************************************************/ double NormalCurvatureRadius(double phi, double azi); ///@} diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/EllipticFunction.cpp b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/EllipticFunction.cpp index 1a05b8a56..29e32eb8b 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/EllipticFunction.cpp +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/EllipticFunction.cpp @@ -6,7 +6,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #include "stdafx.h" #include "GeographicLib/EllipticFunction.hpp" diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/EllipticFunction.h b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/EllipticFunction.h index e62442a49..07b3eb703 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/EllipticFunction.h +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/EllipticFunction.h @@ -6,7 +6,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #pragma once @@ -43,14 +43,14 @@ namespace NETGeographicLib * * The computation of the elliptic integrals uses the algorithms given in * - B. C. Carlson, - * Computation of real or + * Computation of real or * complex elliptic integrals, Numerical Algorithms 10, 13--26 (1995) * . * with the additional optimizations given in http://dlmf.nist.gov/19.36.i. * The computation of the Jacobi elliptic functions uses the algorithm given * in * - R. Bulirsch, - * Numerical Calculation of + * Numerical Calculation of * Elliptic Integrals and Elliptic Functions, Numericshe Mathematik 7, * 78--90 (1965). * . @@ -365,7 +365,7 @@ namespace NETGeographicLib * Legendre expresses the longitude of a point on the geodesic in terms of * this combination of elliptic integrals in Exercices de Calcul * Intégral, Vol. 1 (1811), p. 181, - * http://books.google.com/books?id=riIOAAAAQAAJ&pg=PA181. + * https://books.google.com/books?id=riIOAAAAQAAJ&pg=PA181. * * See \ref geodellip for the expression for the longitude in terms of this * function. @@ -392,7 +392,7 @@ namespace NETGeographicLib * * Cayley expresses the longitude difference of a point on the geodesic in * terms of this combination of elliptic integrals in Phil. Mag. 40 - * (1870), p. 333, http://books.google.com/books?id=Zk0wAAAAIAAJ&pg=PA333. + * (1870), p. 333, https://books.google.com/books?id=Zk0wAAAAIAAJ&pg=PA333. * * See \ref geodellip for the expression for the longitude in terms of this * function. diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/GARS.cpp b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/GARS.cpp new file mode 100644 index 000000000..82dd06647 --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/GARS.cpp @@ -0,0 +1,57 @@ +/** + * \file NETGeographicLib/GARS.cpp + * \brief Source for NETGeographicLib::GARS class + * + * NETGeographicLib is copyright (c) Scott Heiman (2013-2015) + * GeographicLib is Copyright (c) Charles Karney (2010-2012) + * and licensed under the MIT/X11 License. + * For more information, see + * https://geographiclib.sourceforge.io/ + **********************************************************************/ +#include "stdafx.h" +#include "GeographicLib/GARS.hpp" +#include "GARS.h" +#include "NETGeographicLib.h" + +using namespace NETGeographicLib; + +//***************************************************************************** +void GARS::Forward(double lat, double lon, int prec, System::String^% gars) +{ + try + { + std::string l; + GeographicLib::GARS::Forward( lat, lon, prec, l ); + gars = gcnew System::String( l.c_str() ); + } + catch ( const std::exception& xcpt ) + { + throw gcnew GeographicErr( xcpt.what() ); + } +} + +//***************************************************************************** +void GARS::Reverse( System::String^ gars, double% lat, double% lon, + int% prec, bool centerp) +{ + try + { + double llat, llon; + int lprec; + GeographicLib::GARS::Reverse( StringConvert::ManagedToUnmanaged( gars ), + llat, llon, lprec, centerp ); + lat = llat; + lon = llon; + prec = lprec; + } + catch ( const std::exception& err ) + { + throw gcnew GeographicErr( err.what() ); + } +} + +//***************************************************************************** +double GARS::Resolution(int prec) { return GeographicLib::GARS::Resolution(prec); } + +//***************************************************************************** +int GARS::Precision(double res) { return GeographicLib::GARS::Precision(res); } diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/GARS.h b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/GARS.h new file mode 100644 index 000000000..dde365f4c --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/GARS.h @@ -0,0 +1,109 @@ +/** + * \file NETGeographicLib/GARS.h + * \brief Header for NETGeographicLib::GARS class + * + * NETGeographicLib is copyright (c) Scott Heiman (2013-2015) + * GeographicLib is Copyright (c) Charles Karney (2010-2012) + * and licensed under the MIT/X11 License. + * For more information, see + * https://geographiclib.sourceforge.io/ + **********************************************************************/ +#pragma once + +namespace NETGeographicLib +{ + /** + * \brief .NET Wrapper for GeographicLib::GARS + * + * This class allows .NET applications to access GeographicLib::GARS. + * + * The Global Area Reference System is described in + * - https://en.wikipedia.org/wiki/Global_Area_Reference_System + * - http://earth-info.nga.mil/GandG/coordsys/grids/gars.html + * . + * It provides a compact string representation of a geographic area + * (expressed as latitude and longitude). The classes Georef and Geohash + * implement similar compact representations. + * + * C# Example: + * \include example-GARS.cs + * Managed C++ Example: + * \include example-GARS.cpp + * Visual Basic Example: + * \include example-GARS.vb + **********************************************************************/ + public ref class GARS + { + // all memebers of this class are static so the constructor is hidden. + GARS() {} + + public: + + /** + * Convert from geographic coordinates to GARS. + * + * @param[in] lat latitude of point (degrees). + * @param[in] lon longitude of point (degrees). + * @param[in] prec the precision of the resulting GARS. + * @param[out] gars the GARS string. + * @exception GeographicErr if \e lat is not in [−90°, + * 90°] or if memory for \e gars can't be allocated. + * + * \e prec specifies the precision of \e gars as follows: + * - \e prec = 0 (min), 30' precision, e.g., 006AG; + * - \e prec = 1, 15' precision, e.g., 006AG3; + * - \e prec = 2 (max), 5' precision, e.g., 006AG39. + * + * If \e lat or \e lon is NaN, then \e gars is set to "INVALID". + **********************************************************************/ + static void Forward(double lat, double lon, int prec, + [System::Runtime::InteropServices::Out] System::String^% gars); + + /** + * Convert from GARS to geographic coordinates. + * + * @param[in] gars the GARS. + * @param[out] lat latitude of point (degrees). + * @param[out] lon longitude of point (degrees). + * @param[out] prec the precision of \e gars. + * @param[in] centerp if true (the default) return the center of the + * \e gars, otherwise return the south-west corner. + * @exception GeographicErr if \e gars is illegal. + * + * The case of the letters in \e gars is ignored. \e prec is in the range + * [0, 2] and gives the precision of \e gars as follows: + * - \e prec = 0 (min), 30' precision, e.g., 006AG; + * - \e prec = 1, 15' precision, e.g., 006AG3; + * - \e prec = 2 (max), 5' precision, e.g., 006AG39. + * + * If the first 3 characters of \e gars are "INV", then \e lat and \e lon + * are set to NaN and \e prec is unchanged. + **********************************************************************/ + static void Reverse( System::String^ gars, + [System::Runtime::InteropServices::Out] double% lat, + [System::Runtime::InteropServices::Out] double% lon, + [System::Runtime::InteropServices::Out] int% prec, + bool centerp); + + /** + * The angular resolution of a GARS. + * + * @param[in] prec the precision of the GARS. + * @return the latitude-longitude resolution (degrees). + * + * Internally, \e prec is first put in the range [0, 2]. + **********************************************************************/ + static double Resolution(int prec); + + /** + * The GARS precision required to meet a given geographic resolution. + * + * @param[in] res the minimum of resolution in latitude and longitude + * (degrees). + * @return GARS precision. + * + * The returned length is in the range [0, 2]. + **********************************************************************/ + static int Precision(double res); + }; +} // namespace NETGeographicLib diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/GeoCoords.cpp b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/GeoCoords.cpp index a060068a1..60bbd577a 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/GeoCoords.cpp +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/GeoCoords.cpp @@ -6,7 +6,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #include "stdafx.h" #include "GeographicLib/GeoCoords.hpp" @@ -42,11 +42,11 @@ GeoCoords::GeoCoords() } //***************************************************************************** -GeoCoords::GeoCoords(System::String^ s, bool centerp, bool swaplatlong ) +GeoCoords::GeoCoords(System::String^ s, bool centerp, bool longfirst ) { try { - m_pGeoCoords = new GeographicLib::GeoCoords(StringConvert::ManagedToUnmanaged(s), centerp, swaplatlong); + m_pGeoCoords = new GeographicLib::GeoCoords(StringConvert::ManagedToUnmanaged(s), centerp, longfirst); } catch ( std::bad_alloc ) { @@ -93,11 +93,11 @@ GeoCoords::GeoCoords(int zone, bool northp, double easting, double northing) } //***************************************************************************** -void GeoCoords::Reset( System::String^ s, bool centerp, bool swaplatlong ) +void GeoCoords::Reset( System::String^ s, bool centerp, bool longfirst ) { try { - m_pGeoCoords->Reset(StringConvert::ManagedToUnmanaged(s), centerp, swaplatlong); + m_pGeoCoords->Reset(StringConvert::ManagedToUnmanaged(s), centerp, longfirst); } catch ( const std::exception& err ) { @@ -194,16 +194,16 @@ double GeoCoords::MajorRadius::get() { return UTMUPS::MajorRadius(); } double GeoCoords::Flattening::get() { return UTMUPS::Flattening(); } //***************************************************************************** -System::String^ GeoCoords::GeoRepresentation(int prec, bool swaplatlong ) +System::String^ GeoCoords::GeoRepresentation(int prec, bool longfirst ) { - return gcnew System::String( m_pGeoCoords->GeoRepresentation(prec, swaplatlong).c_str() ); + return gcnew System::String( m_pGeoCoords->GeoRepresentation(prec, longfirst).c_str() ); } //***************************************************************************** -System::String^ GeoCoords::DMSRepresentation(int prec, bool swaplatlong, +System::String^ GeoCoords::DMSRepresentation(int prec, bool longfirst, char dmssep ) { - return gcnew System::String( m_pGeoCoords->DMSRepresentation(prec, swaplatlong, dmssep).c_str() ); + return gcnew System::String( m_pGeoCoords->DMSRepresentation(prec, longfirst, dmssep).c_str() ); } //***************************************************************************** @@ -213,15 +213,15 @@ System::String^ GeoCoords::MGRSRepresentation(int prec) } //***************************************************************************** -System::String^ GeoCoords::UTMUPSRepresentation(int prec) +System::String^ GeoCoords::UTMUPSRepresentation(int prec, bool abbrev) { - return gcnew System::String( m_pGeoCoords->UTMUPSRepresentation(prec).c_str() ); + return gcnew System::String( m_pGeoCoords->UTMUPSRepresentation(prec, abbrev).c_str() ); } //***************************************************************************** -System::String^ GeoCoords::UTMUPSRepresentation(bool northp, int prec) +System::String^ GeoCoords::UTMUPSRepresentation(bool northp, int prec, bool abbrev) { - return gcnew System::String( m_pGeoCoords->UTMUPSRepresentation(northp, prec).c_str() ); + return gcnew System::String( m_pGeoCoords->UTMUPSRepresentation(northp, prec, abbrev).c_str() ); } //***************************************************************************** @@ -231,13 +231,13 @@ System::String^ GeoCoords::AltMGRSRepresentation(int prec) } //***************************************************************************** -System::String^ GeoCoords::AltUTMUPSRepresentation(int prec) +System::String^ GeoCoords::AltUTMUPSRepresentation(int prec, bool abbrev) { - return gcnew System::String( m_pGeoCoords->AltUTMUPSRepresentation(prec).c_str() ); + return gcnew System::String( m_pGeoCoords->AltUTMUPSRepresentation(prec, abbrev).c_str() ); } //***************************************************************************** -System::String^ GeoCoords::AltUTMUPSRepresentation(bool northp, int prec) +System::String^ GeoCoords::AltUTMUPSRepresentation(bool northp, int prec, bool abbrev) { - return gcnew System::String( m_pGeoCoords->AltUTMUPSRepresentation(northp, prec).c_str() ); + return gcnew System::String( m_pGeoCoords->AltUTMUPSRepresentation(northp, prec, abbrev).c_str() ); } diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/GeoCoords.h b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/GeoCoords.h index bbc012a17..1921d4d25 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/GeoCoords.h +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/GeoCoords.h @@ -6,7 +6,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #pragma once @@ -65,8 +65,7 @@ namespace NETGeographicLib **********************************************************************/ ///@{ /** - * The default constructor is equivalent to \e latitude = 90°, - * \e longitude = 0°. + * The default constructor sets the coordinate as undefined. **********************************************************************/ GeoCoords(); @@ -77,7 +76,7 @@ namespace NETGeographicLib * the position. * @param[in] centerp governs the interpretation of MGRS coordinates (see * below). - * @param[in] swaplatlong governs the interpretation of geographic + * @param[in] longfirst governs the interpretation of geographic * coordinates (see below). * @exception GeographicErr if the \e s is malformed (see below). * @@ -95,7 +94,7 @@ namespace NETGeographicLib * - 43d16'12"E 33d26'24"N * - 43:16:12E 33:26:24 * - MGRS - * - 38SLC301 + * - 38SLC30 * - 38SLC391014 * - 38SLC3918701405 * - 37SHT9708 @@ -105,9 +104,9 @@ namespace NETGeographicLib * * Latitude and Longitude parsing: Latitude precedes longitude, * unless a N, S, E, W hemisphere designator is used on one or both - * coordinates. If \e swaplatlong = true (default is false), then + * coordinates. If \e longfirst = true (default is false), then * longitude precedes latitude in the absence of a hemisphere designator. - * Thus (with \e swaplatlong = false) + * Thus (with \e longfirst = false) * - 40 -75 * - N40 W75 * - -75 N40 @@ -129,10 +128,9 @@ namespace NETGeographicLib * - 40:30.5 * - 40.508333333 * . - * all specify the same angle. The leading sign applies to all components - * so -1d30 is -(1+30/60) = -1.5. Latitudes must be in the range - * [−90°, 90°] and longitudes in the range - * [−540°, 540°). Internally longitudes are reduced + * all specify the same angle. The leading sign applies to all + * components so -1d30 is -(1+30/60) = -1.5. Latitudes must be in the + * range [−90°, 90°]. Internally longitudes are reduced * to the range [−180°, 180°). * * UTM/UPS parsing: For UTM zones (−80° ≤ Lat < @@ -156,7 +154,7 @@ namespace NETGeographicLib * - 38SMB4484 = 38N 444000 3684000 * - 38SMB44148470 = 38N 444140 3684700 **********************************************************************/ - GeoCoords(System::String^ s, bool centerp, bool swaplatlong ); + GeoCoords(System::String^ s, bool centerp, bool longfirst ); /** * Construct from geographic coordinates. @@ -167,8 +165,6 @@ namespace NETGeographicLib * specified zone using the rules given in UTMUPS::zonespec. * @exception GeographicErr if \e latitude is not in [−90°, * 90°]. - * @exception GeographicErr if \e longitude is not in [−540°, - * 540°). * @exception GeographicErr if \e zone cannot be used for this location. **********************************************************************/ GeoCoords(double latitude, double longitude, int zone ); @@ -192,16 +188,16 @@ namespace NETGeographicLib /** * Reset the location from a string. See - * GeoCoords(const std::string& s, bool centerp, bool swaplatlong). + * GeoCoords(const std::string& s, bool centerp, bool longfirst). * * @param[in] s 1-element, 2-element, or 3-element string representation of * the position. * @param[in] centerp governs the interpretation of MGRS coordinates. - * @param[in] swaplatlong governs the interpretation of geographic + * @param[in] longfirst governs the interpretation of geographic * coordinates. * @exception GeographicErr if the \e s is malformed. **********************************************************************/ - void Reset( System::String^ s, bool centerp, bool swaplatlong); + void Reset( System::String^ s, bool centerp, bool longfirst); /** * Reset the location in terms of geographic coordinates. See @@ -213,8 +209,6 @@ namespace NETGeographicLib * specified zone using the rules given in UTMUPS::zonespec. * @exception GeographicErr if \e latitude is not in [−90°, * 90°]. - * @exception GeographicErr if \e longitude is not in [−540°, - * 540°). * @exception GeographicErr if \e zone cannot be used for this location. **********************************************************************/ void Reset(double latitude, double longitude, int zone ) ; @@ -327,7 +321,7 @@ namespace NETGeographicLib * degrees. * * @param[in] prec precision (relative to about 1m). - * @param[in] swaplatlong if true give longitude first (default = false) + * @param[in] longfirst if true give longitude first (default = false) * @exception std::bad_alloc if memory for the string can't be allocated. * @return decimal latitude/longitude string representation. * @@ -337,14 +331,14 @@ namespace NETGeographicLib * - prec = 3, 10−8° * - prec = 9 (max), 10−14° **********************************************************************/ - System::String^ GeoRepresentation(int prec, bool swaplatlong ); + System::String^ GeoRepresentation(int prec, bool longfirst ); /** * String representation with latitude and longitude as degrees, minutes, * seconds, and hemisphere. * * @param[in] prec precision (relative to about 1m) - * @param[in] swaplatlong if true give longitude first (default = false) + * @param[in] longfirst if true give longitude first (default = false) * @param[in] dmssep if non-null, use as the DMS separator character * (instead of d, ', " delimiters). * @exception std::bad_alloc if memory for the string can't be allocated. @@ -360,7 +354,7 @@ namespace NETGeographicLib * - prec = 1, 0.01" * - prec = 10 (max), 10−11" **********************************************************************/ - System::String^ DMSRepresentation(int prec, bool swaplatlong, + System::String^ DMSRepresentation(int prec, bool longfirst, char dmssep ); /** @@ -390,6 +384,8 @@ namespace NETGeographicLib * UTM/UPS string. * * @param[in] prec precision (relative to about 1m) + * @param[in] abbrev if true (the default) use abbreviated (n/s) notation + * for hemisphere; otherwise spell out the hemisphere (north/south) * @exception std::bad_alloc if memory for the string can't be allocated. * @return UTM/UPS string representation: zone designator, easting, and * northing. @@ -402,20 +398,22 @@ namespace NETGeographicLib * - prec = 6, 1μm * - prec = 9 (max), 1nm **********************************************************************/ - System::String^ UTMUPSRepresentation(int prec); + System::String^ UTMUPSRepresentation(int prec, bool abbrev); /** * UTM/UPS string with hemisphere override. * - * @param[in] prec precision (relative to about 1m) * @param[in] northp hemisphere override + * @param[in] prec precision (relative to about 1m) + * @param[in] abbrev if true (the default) use abbreviated (n/s) notation + * for hemisphere; otherwise spell out the hemisphere (north/south) * @exception GeographicErr if the hemisphere override attempts to change - * UPS N to UPS S or vice verse. + * UPS N to UPS S or vice versa. * @exception std::bad_alloc if memory for the string can't be allocated. * @return UTM/UPS string representation: zone designator, easting, and * northing. **********************************************************************/ - System::String^ UTMUPSRepresentation(bool northp, int prec); + System::String^ UTMUPSRepresentation(bool northp, int prec, bool abbrev); /** * MGRS string for the alternate zone. See GeoCoords::MGRSRepresentation. @@ -431,24 +429,28 @@ namespace NETGeographicLib * GeoCoords::UTMUPSRepresentation. * * @param[in] prec precision (relative to about 1m) + * @param[in] abbrev if true (the default) use abbreviated (n/s) notation + * for hemisphere; otherwise spell out the hemisphere (north/south) * @exception std::bad_alloc if memory for the string can't be allocated. * @return UTM/UPS string representation: zone designator, easting, and * northing. **********************************************************************/ - System::String^ AltUTMUPSRepresentation(int prec); + System::String^ AltUTMUPSRepresentation(int prec, bool abbrev); /** * UTM/UPS string for the alternate zone, with hemisphere override. * - * @param[in] prec precision (relative to about 1m) * @param[in] northp hemisphere override + * @param[in] prec precision (relative to about 1m) + * @param[in] abbrev if true (the default) use abbreviated (n/s) notation + * for hemisphere; otherwise spell out the hemisphere (north/south) * @exception GeographicErr if the hemisphere override attempts to change - * UPS N to UPS S or vice verse. + * UPS n to UPS s or vice verse. * @exception std::bad_alloc if memory for the string can't be allocated. * @return UTM/UPS string representation: zone designator, easting, and * northing. **********************************************************************/ - System::String^ AltUTMUPSRepresentation(bool northp, int prec); + System::String^ AltUTMUPSRepresentation(bool northp, int prec, bool abbrev); ///@} /** \name Inspector functions diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Geocentric.cpp b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Geocentric.cpp index 2bbfade68..e99d0db96 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Geocentric.cpp +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Geocentric.cpp @@ -6,7 +6,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #include "stdafx.h" #include "GeographicLib/Geocentric.hpp" @@ -33,7 +33,7 @@ Geocentric::Geocentric(void) try { m_pGeocentric = new GeographicLib::Geocentric( - GeographicLib::Geocentric::WGS84 ); + GeographicLib::Geocentric::WGS84() ); } catch (std::bad_alloc) { diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Geocentric.h b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Geocentric.h index 2052ac418..c865463d0 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Geocentric.h +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Geocentric.h @@ -6,7 +6,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #pragma once @@ -28,7 +28,7 @@ namespace NETGeographicLib * The conversion from geographic to geocentric coordinates is * straightforward. For the reverse transformation we use * - H. Vermeille, - * Direct + * Direct * transformation from geocentric coordinates to geodetic coordinates, * J. Geodesy 76, 451--454 (2002). * . @@ -36,11 +36,11 @@ namespace NETGeographicLib * results for all finite inputs (even if \e h is infinite). The changes are * described in Appendix B of * - C. F. F. Karney, - * Geodesics + * Geodesics * on an ellipsoid of revolution, * Feb. 2011; * preprint - * arxiv:1102.1215v1. + * arxiv:1102.1215v1. * . * See \ref geocentric for more information. * @@ -79,8 +79,7 @@ namespace NETGeographicLib * * @param[in] a equatorial radius (meters). * @param[in] f flattening of ellipsoid. Setting \e f = 0 gives a sphere. - * Negative \e f gives a prolate ellipsoid. If \e f > 1, set flattening - * to 1/\e f. + * Negative \e f gives a prolate ellipsoid. * @exception GeographicErr if \e a or (1 − \e f ) \e a is not * positive. **********************************************************************/ @@ -114,8 +113,7 @@ namespace NETGeographicLib * @param[out] Y geocentric coordinate (meters). * @param[out] Z geocentric coordinate (meters). * - * \e lat should be in the range [−90°, 90°]; \e lon - * should be in the range [−540°, 540°). + * \e lat should be in the range [−90°, 90°]. **********************************************************************/ void Forward(double lat, double lon, double h, [System::Runtime::InteropServices::Out] double% X, diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Geodesic.cpp b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Geodesic.cpp index dadd022c4..89fd01d59 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Geodesic.cpp +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Geodesic.cpp @@ -6,10 +6,11 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #include "stdafx.h" #include +#include #include "Geodesic.h" #include "GeodesicLine.h" #include "NETGeographicLib.h" @@ -50,7 +51,7 @@ Geodesic::Geodesic() { try { - m_pGeodesic = new GeographicLib::Geodesic( GeographicLib::Geodesic::WGS84 ); + m_pGeodesic = new GeographicLib::Geodesic( GeographicLib::Geodesic::WGS84() ); } catch ( std::bad_alloc ) { @@ -293,7 +294,7 @@ void Geodesic::ArcDirect(double lat1, double lon1, double azi1, double a12, //***************************************************************************** double Geodesic::GenDirect(double lat1, double lon1, double azi1, bool arcmode, double s12_a12, - NETGeographicLib::Mask outmask, + Geodesic::mask outmask, [System::Runtime::InteropServices::Out] double% lat2, [System::Runtime::InteropServices::Out] double% lon2, [System::Runtime::InteropServices::Out] double% azi2, @@ -437,7 +438,7 @@ double Geodesic::Inverse(double lat1, double lon1, double lat2, double lon2, //***************************************************************************** double Geodesic::GenInverse(double lat1, double lon1, double lat2, double lon2, - NETGeographicLib::Mask outmask, + Geodesic::mask outmask, [System::Runtime::InteropServices::Out] double% s12, [System::Runtime::InteropServices::Out] double% azi1, [System::Runtime::InteropServices::Out] double% azi2, @@ -473,6 +474,38 @@ GeodesicLine^ Geodesic::Line(double lat1, double lon1, double azi1, return gcnew GeodesicLine( this, lat1, lon1, azi1, caps ); } +//***************************************************************************** +GeodesicLine^ Geodesic::InverseLine(double lat1, double lon1, double lat2, + double lon2, NETGeographicLib::Mask caps) +{ + return gcnew GeodesicLine(m_pGeodesic->InverseLine(lat1, lon1, lat2, + lon2, static_cast(caps))); +} + +//***************************************************************************** +GeodesicLine^ Geodesic::DirectLine(double lat1, double lon1, double azi1, + double s12, NETGeographicLib::Mask caps) +{ + return gcnew GeodesicLine(m_pGeodesic->DirectLine(lat1, lon1, azi1, + s12, static_cast(caps))); +} + +//***************************************************************************** +GeodesicLine^ Geodesic::ArcDirectLine(double lat1, double lon1, double azi1, + double a12, NETGeographicLib::Mask caps) +{ + return gcnew GeodesicLine(m_pGeodesic->ArcDirectLine(lat1, lon1, azi1, + a12, static_cast(caps))); +} + +//***************************************************************************** +GeodesicLine^ Geodesic::GenDirectLine(double lat1, double lon1, double azi1, + bool arcmode, double s12_a12, NETGeographicLib::Mask caps) +{ + return gcnew GeodesicLine(m_pGeodesic->GenDirectLine(lat1, lon1, azi1, + arcmode, s12_a12, static_cast(caps))); +} + //***************************************************************************** double Geodesic::MajorRadius::get() { return m_pGeodesic->MajorRadius(); } diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Geodesic.h b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Geodesic.h index aba97e1ab..822087d87 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Geodesic.h +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Geodesic.h @@ -6,7 +6,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #pragma once #include "NETGeographicLib.h" @@ -24,7 +24,11 @@ namespace NETGeographicLib * the geodesic from point 1 to point 2 has azimuths \e azi1 and \e azi2 at * the two end points. (The azimuth is the heading measured clockwise from * north. \e azi2 is the "forward" azimuth, i.e., the heading that takes you - * beyond point 2 not back to point 1.) + * beyond point 2 not back to point 1.) In the figure below, latitude if + * labeled φ, longitude λ (with λ12 = + * λ2 − λ1), and azimuth α. + * + * spheroidal triangle * * Given \e lat1, \e lon1, \e azi1, and \e s12, we can determine \e lat2, \e * lon2, and \e azi2. This is the \e direct geodesic problem and its @@ -67,7 +71,6 @@ namespace NETGeographicLib * defined similarly (with the geodesics being parallel at point 2). On a * flat surface, we have \e M12 = \e M21 = 1. The quantity 1/\e M12 gives * the scale of the Cassini-Soldner projection. - * - area. The area between the geodesic from point 1 to point 2 and * the equation is represented by \e S12; it is the area, measured * counter-clockwise, of the geodesic quadrilateral with corners @@ -96,29 +99,29 @@ namespace NETGeographicLib * (obviously) uniquely defined. However, in a few special cases there are * multiple azimuths which yield the same shortest distance. Here is a * catalog of those cases: - * - \e lat1 = −\e lat2 (with neither at a pole). If \e azi1 = \e - * azi2, the geodesic is unique. Otherwise there are two geodesics and the - * second one is obtained by setting [\e azi1, \e azi2] = [\e azi2, \e - * azi1], [\e M12, \e M21] = [\e M21, \e M12], \e S12 = −\e S12. - * (This occurs when the longitude difference is near ±180° for - * oblate ellipsoids.) - * - \e lon2 = \e lon1 ± 180° (with neither at a pole). If \e - * azi1 = 0° or ±180°, the geodesic is unique. Otherwise + * - \e lat1 = −\e lat2 (with neither point at a pole). If \e azi1 = + * \e azi2, the geodesic is unique. Otherwise there are two geodesics and + * the second one is obtained by setting [\e azi1, \e azi2] → [\e + * azi2, \e azi1], [\e M12, \e M21] → [\e M21, \e M12], \e S12 → + * −\e S12. (This occurs when the longitude difference is near + * ±180° for oblate ellipsoids.) + * - \e lon2 = \e lon1 ± 180° (with neither point at a pole). If + * \e azi1 = 0° or ±180°, the geodesic is unique. Otherwise * there are two geodesics and the second one is obtained by setting [\e - * azi1, \e azi2] = [−\e azi1, −\e azi2], \e S12 = −\e - * S12. (This occurs when the \e lat2 is near −\e lat1 for prolate - * ellipsoids.) + * azi1, \e azi2] → [−\e azi1, −\e azi2], \e S12 → + * −\e S12. (This occurs when \e lat2 is near −\e lat1 for + * prolate ellipsoids.) * - Points 1 and 2 at opposite poles. There are infinitely many geodesics - * which can be generated by setting [\e azi1, \e azi2] = [\e azi1, \e + * which can be generated by setting [\e azi1, \e azi2] → [\e azi1, \e * azi2] + [\e d, −\e d], for arbitrary \e d. (For spheres, this * prescription applies when points 1 and 2 are antipodal.) - * - s12 = 0 (coincident points). There are infinitely many geodesics which - * can be generated by setting [\e azi1, \e azi2] = [\e azi1, \e azi2] + - * [\e d, \e d], for arbitrary \e d. + * - \e s12 = 0 (coincident points). There are infinitely many geodesics + * which can be generated by setting [\e azi1, \e azi2] → + * [\e azi1, \e azi2] + [\e d, \e d], for arbitrary \e d. * * The calculations are accurate to better than 15 nm (15 nanometers) for the * WGS84 ellipsoid. See Sec. 9 of - * arXiv:1102.1215v1 for + * arXiv:1102.1215v1 for * details. The algorithms used by this class are based on series expansions * using the flattening \e f as a small parameter. These are only accurate * for |f| < 0.02; however reasonably accurate results will be @@ -137,12 +140,12 @@ namespace NETGeographicLib * * The algorithms are described in * - C. F. F. Karney, - * + * * Algorithms for geodesics, * J. Geodesy 87, 43--55 (2013); - * DOI: + * DOI: * 10.1007/s00190-012-0578-z; - * addenda: + * addenda: * geod-addenda.html. * . * For more information on geodesics see \ref geodesic. @@ -173,7 +176,77 @@ namespace NETGeographicLib // Frees the unmanaged memory when this object is destroyed. !Geodesic(); public: - /** \name Constructor + /** + * Bit masks for what calculations to do. These masks do double duty. + * They signify to the GeodesicLine::GeodesicLine constructor and to + * Geodesic::Line what capabilities should be included in the GeodesicLine + * object. They also specify which results to return in the general + * routines Geodesic::GenDirect and Geodesic::GenInverse routines. + * GeodesicLine::mask is a duplication of this enum. + **********************************************************************/ + enum class mask { + /** + * No capabilities, no output. + * @hideinitializer + **********************************************************************/ + NONE = 0U, + /** + * Calculate latitude \e lat2. (It's not necessary to include this as a + * capability to GeodesicLine because this is included by default.) + * @hideinitializer + **********************************************************************/ + LATITUDE = 1U<<7 | unsigned(captype::CAP_NONE), + /** + * Calculate longitude \e lon2. + * @hideinitializer + **********************************************************************/ + LONGITUDE = 1U<<8 | unsigned(captype::CAP_C3), + /** + * Calculate azimuths \e azi1 and \e azi2. (It's not necessary to + * include this as a capability to GeodesicLine because this is included + * by default.) + * @hideinitializer + **********************************************************************/ + AZIMUTH = 1U<<9 | unsigned(captype::CAP_NONE), + /** + * Calculate distance \e s12. + * @hideinitializer + **********************************************************************/ + DISTANCE = 1U<<10 | unsigned(captype::CAP_C1), + /** + * Allow distance \e s12 to be used as input in the direct geodesic + * problem. + * @hideinitializer + **********************************************************************/ + DISTANCE_IN = 1U<<11 | unsigned(captype::CAP_C1) | unsigned(captype::CAP_C1p), + /** + * Calculate reduced length \e m12. + * @hideinitializer + **********************************************************************/ + REDUCEDLENGTH = 1U<<12 | unsigned(captype::CAP_C1) | unsigned(captype::CAP_C2), + /** + * Calculate geodesic scales \e M12 and \e M21. + * @hideinitializer + **********************************************************************/ + GEODESICSCALE = 1U<<13 | unsigned(captype::CAP_C1) | unsigned(captype::CAP_C2), + /** + * Calculate area \e S12. + * @hideinitializer + **********************************************************************/ + AREA = 1U<<14 | unsigned(captype::CAP_C4), + /** + * Unroll \e lon2 in the direct calculation. + * @hideinitializer + **********************************************************************/ + LONG_UNROLL = 1U<<15, + /** + * All capabilities, calculate everything. (LONG_UNROLL is not + * included in this mask.) + * @hideinitializer + **********************************************************************/ + ALL = unsigned(captype::OUT_ALL)| unsigned(captype::CAP_ALL), + }; + /** \name Constructor **********************************************************************/ ///@{ /** @@ -181,8 +254,7 @@ namespace NETGeographicLib * * @param[in] a equatorial radius (meters). * @param[in] f flattening of ellipsoid. Setting \e f = 0 gives a sphere. - * Negative \e f gives a prolate ellipsoid. If \e f > 1, set flattening - * to 1/\e f. + * Negative \e f gives a prolate ellipsoid. * @exception GeographicErr if \e a or (1 − \e f ) \e a is not * positive. **********************************************************************/ @@ -222,10 +294,9 @@ namespace NETGeographicLib * @param[out] S12 area under the geodesic (meters2). * @return \e a12 arc length of between point 1 and point 2 (degrees). * - * \e lat1 should be in the range [−90°, 90°]; \e lon1 and \e - * azi1 should be in the range [−540°, 540°). The values of - * \e lon2 and \e azi2 returned are in the range [−180°, - * 180°). + * \e lat1 should be in the range [−90°, 90°]. The + * values of \e lon2 and \e azi2 returned are in the range + * [−180°, 180°). * * If either point is at a pole, the azimuth is defined by keeping the * longitude fixed, writing \e lat = ±(90° − ε), @@ -316,10 +387,9 @@ namespace NETGeographicLib * (dimensionless). * @param[out] S12 area under the geodesic (meters2). * - * \e lat1 should be in the range [−90°, 90°]; \e lon1 and \e - * azi1 should be in the range [−540°, 540°). The values of - * \e lon2 and \e azi2 returned are in the range [−180°, - * 180°). + * \e lat1 should be in the range [−90°, 90°]. The + * values of \e lon2 and \e azi2 returned are in the range + * [−180°, 180°). * * If either point is at a pole, the azimuth is defined by keeping the * longitude fixed, writing \e lat = ±(90° − ε), @@ -415,7 +485,7 @@ namespace NETGeographicLib * @param[in] s12_a12 if \e arcmode is false, this is the distance between * point 1 and point 2 (meters); otherwise it is the arc length between * point 1 and point 2 (degrees); it can be negative. - * @param[in] outmask a bitor'ed combination of NETGeographicLib::Mask values + * @param[in] outmask a bitor'ed combination of Geodesic::mask values * specifying which of the following parameters should be set. * @param[out] lat2 latitude of point 2 (degrees). * @param[out] lon2 longitude of point 2 (degrees). @@ -429,28 +499,33 @@ namespace NETGeographicLib * @param[out] S12 area under the geodesic (meters2). * @return \e a12 arc length of between point 1 and point 2 (degrees). * - * The NETGeographicLib::Mask values possible for \e outmask are - * - \e outmask |= NETGeographicLib::Mask::LATITUDE for the latitude \e lat2; - * - \e outmask |= NETGeographicLib::Mask::LONGITUDE for the latitude \e lon2; - * - \e outmask |= NETGeographicLib::Mask::AZIMUTH for the latitude \e azi2; - * - \e outmask |= NETGeographicLib::Mask::DISTANCE for the distance \e s12; - * - \e outmask |= NETGeographicLib::Mask::REDUCEDLENGTH for the reduced length \e + * The Geodesic::mask values possible for \e outmask are + * - \e outmask |= Geodesic::LATITUDE for the latitude \e lat2; + * - \e outmask |= Geodesic::LONGITUDE for the latitude \e lon2; + * - \e outmask |= Geodesic::AZIMUTH for the latitude \e azi2; + * - \e outmask |= Geodesic::DISTANCE for the distance \e s12; + * - \e outmask |= Geodesic::REDUCEDLENGTH for the reduced length \e * m12; - * - \e outmask |= NETGeographicLib::Mask::GEODESICSCALE for the geodesic scales \e + * - \e outmask |= Geodesic::GEODESICSCALE for the geodesic scales \e * M12 and \e M21; - * - \e outmask |= NETGeographicLib::Mask::AREA for the area \e S12; - * - \e outmask |= NETGeographicLib::Mask::ALL for all of the above. + * - \e outmask |= Geodesic::AREA for the area \e S12; + * - \e outmask |= Geodesic::ALL for all of the above; + * - \e outmask |= Geodesic::LONG_UNROLL to unroll \e lon2 instead of + * wrapping it into the range [−180°, 180°). * . * The function value \e a12 is always computed and returned and this * equals \e s12_a12 is \e arcmode is true. If \e outmask includes - * NETGeographicLib::Mask::DISTANCE and \e arcmode is false, then - * \e s12 = \e s12_a12. It is not necessary to include - * NETGeographicLib::Mask::DISTANCE_IN in \e outmask; this is - * automatically included is \e arcmode is false. + * Geodesic::DISTANCE and \e arcmode is false, then \e s12 = \e s12_a12. + * It is not necessary to include Geodesic::DISTANCE_IN in \e outmask; this + * is automatically included is \e arcmode is false. + * + * With the LONG_UNROLL bit set, the quantity \e lon2 − \e lon1 + * indicates how many times and in what sense the geodesic encircles + * the ellipsoid. **********************************************************************/ double GenDirect(double lat1, double lon1, double azi1, bool arcmode, double s12_a12, - NETGeographicLib::Mask outmask, + Geodesic::mask outmask, [System::Runtime::InteropServices::Out] double% lat2, [System::Runtime::InteropServices::Out] double% lon2, [System::Runtime::InteropServices::Out] double% azi2, @@ -482,10 +557,9 @@ namespace NETGeographicLib * @param[out] S12 area under the geodesic (meters2). * @return \e a12 arc length of between point 1 and point 2 (degrees). * - * \e lat1 and \e lat2 should be in the range [−90°, 90°]; \e - * lon1 and \e lon2 should be in the range [−540°, 540°). - * The values of \e azi1 and \e azi2 returned are in the range - * [−180°, 180°). + * \e lat1 and \e lat2 should be in the range [−90°, + * 90°]. The values of \e azi1 and \e azi2 returned are in the + * range [−180°, 180°). * * If either point is at a pole, the azimuth is defined by keeping the * longitude fixed, writing \e lat = ±(90° − ε), @@ -598,7 +672,7 @@ namespace NETGeographicLib * The arc length is always computed and returned as the function value. **********************************************************************/ double GenInverse(double lat1, double lon1, double lat2, double lon2, - NETGeographicLib::Mask outmask, + Geodesic::mask outmask, [System::Runtime::InteropServices::Out] double% s12, [System::Runtime::InteropServices::Out] double% azi1, [System::Runtime::InteropServices::Out] double% azi2, @@ -624,8 +698,7 @@ namespace NETGeographicLib * GeodesicLine::Position. * @return a GeodesicLine object. * - * \e lat1 should be in the range [−90°, 90°]; \e lon1 and \e - * azi1 should be in the range [−540°, 540°). + * \e lat1 should be in the range [−90°, 90°]. * * The NETGeographicLib::Mask values are * - \e caps |= NETGeographicLib::Mask::LATITUDE for the latitude \e lat2; this is @@ -651,6 +724,99 @@ namespace NETGeographicLib GeodesicLine^ Line(double lat1, double lon1, double azi1, NETGeographicLib::Mask caps ); + /** + * Define a GeodesicLine in terms of the inverse geodesic problem. + * + * @param[in] lat1 latitude of point 1 (degrees). + * @param[in] lon1 longitude of point 1 (degrees). + * @param[in] lat2 latitude of point 2 (degrees). + * @param[in] lon2 longitude of point 2 (degrees). + * @param[in] caps bitor'ed combination of Geodesic::mask values + * specifying the capabilities the GeodesicLine object should possess, + * i.e., which quantities can be returned in calls to + * GeodesicLine::Position. + * @return a GeodesicLine object. + * + * This function sets point 3 of the GeodesicLine to correspond to point 2 + * of the inverse geodesic problem. + * + * \e lat1 and \e lat2 should be in the range [−90°, 90°]. + **********************************************************************/ + GeodesicLine^ InverseLine(double lat1, double lon1, double lat2, + double lon2, NETGeographicLib::Mask caps); + + /** + * Define a GeodesicLine in terms of the direct geodesic problem specified + * in terms of distance. + * + * @param[in] lat1 latitude of point 1 (degrees). + * @param[in] lon1 longitude of point 1 (degrees). + * @param[in] azi1 azimuth at point 1 (degrees). + * @param[in] s12 distance between point 1 and point 2 (meters); it can be + * negative. + * @param[in] caps bitor'ed combination of Geodesic::mask values + * specifying the capabilities the GeodesicLine object should possess, + * i.e., which quantities can be returned in calls to + * GeodesicLine::Position. + * @return a GeodesicLine object. + * + * This function sets point 3 of the GeodesicLine to correspond to point 2 + * of the direct geodesic problem. + * + * \e lat1 should be in the range [−90°, 90°]. + **********************************************************************/ + GeodesicLine^ DirectLine(double lat1, double lon1, double azi1, + double s12, NETGeographicLib::Mask caps); + + /** + * Define a GeodesicLine in terms of the direct geodesic problem specified + * in terms of arc length. + * + * @param[in] lat1 latitude of point 1 (degrees). + * @param[in] lon1 longitude of point 1 (degrees). + * @param[in] azi1 azimuth at point 1 (degrees). + * @param[in] a12 arc length between point 1 and point 2 (degrees); it can + * be negative. + * @param[in] caps bitor'ed combination of Geodesic::mask values + * specifying the capabilities the GeodesicLine object should possess, + * i.e., which quantities can be returned in calls to + * GeodesicLine::Position. + * @return a GeodesicLine object. + * + * This function sets point 3 of the GeodesicLine to correspond to point 2 + * of the direct geodesic problem. + * + * \e lat1 should be in the range [−90°, 90°]. + **********************************************************************/ + GeodesicLine^ ArcDirectLine(double lat1, double lon1, double azi1, + double a12, NETGeographicLib::Mask caps); + + /** + * Define a GeodesicLine in terms of the direct geodesic problem specified + * in terms of either distance or arc length. + * + * @param[in] lat1 latitude of point 1 (degrees). + * @param[in] lon1 longitude of point 1 (degrees). + * @param[in] azi1 azimuth at point 1 (degrees). + * @param[in] arcmode boolean flag determining the meaning of the \e + * s12_a12. + * @param[in] s12_a12 if \e arcmode is false, this is the distance between + * point 1 and point 2 (meters); otherwise it is the arc length between + * point 1 and point 2 (degrees); it can be negative. + * @param[in] caps bitor'ed combination of Geodesic::mask values + * specifying the capabilities the GeodesicLine object should possess, + * i.e., which quantities can be returned in calls to + * GeodesicLine::Position. + * @return a GeodesicLine object. + * + * This function sets point 3 of the GeodesicLine to correspond to point 2 + * of the direct geodesic problem. + * + * \e lat1 should be in the range [−90°, 90°]. + **********************************************************************/ + GeodesicLine^ GenDirectLine(double lat1, double lon1, double azi1, + bool arcmode, double s12_a12, + NETGeographicLib::Mask caps); ///@} /** \name Inspector functions. diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/GeodesicExact.cpp b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/GeodesicExact.cpp index aa4534761..abd70f54c 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/GeodesicExact.cpp +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/GeodesicExact.cpp @@ -6,10 +6,11 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #include "stdafx.h" #include "GeographicLib/GeodesicExact.hpp" +#include "GeographicLib/GeodesicLineExact.hpp" #include "GeodesicExact.h" #include "GeodesicLineExact.h" @@ -32,7 +33,7 @@ GeodesicExact::GeodesicExact() { try { - m_pGeodesicExact = new GeographicLib::GeodesicExact( GeographicLib::GeodesicExact::WGS84 ); + m_pGeodesicExact = new GeographicLib::GeodesicExact( GeographicLib::GeodesicExact::WGS84() ); } catch ( std::bad_alloc err ) { @@ -294,7 +295,7 @@ void GeodesicExact::ArcDirect(double lat1, double lon1, double azi1, double a12, //***************************************************************************** double GeodesicExact::GenDirect(double lat1, double lon1, double azi1, bool arcmode, double s12_a12, - NETGeographicLib::Mask outmask, + GeodesicExact::mask outmask, [System::Runtime::InteropServices::Out] double% lat2, [System::Runtime::InteropServices::Out] double% lon2, [System::Runtime::InteropServices::Out] double% azi2, @@ -439,7 +440,7 @@ double GeodesicExact::Inverse(double lat1, double lon1, double lat2, double lon2 //***************************************************************************** double GeodesicExact::GenInverse(double lat1, double lon1, double lat2, double lon2, - NETGeographicLib::Mask outmask, + GeodesicExact::mask outmask, [System::Runtime::InteropServices::Out] double% s12, [System::Runtime::InteropServices::Out] double% azi1, [System::Runtime::InteropServices::Out] double% azi2, @@ -476,6 +477,38 @@ GeodesicLineExact^ GeodesicExact::Line(double lat1, double lon1, double azi1, return gcnew GeodesicLineExact( this, lat1, lon1, azi1, caps ); } +//***************************************************************************** +GeodesicLineExact^ GeodesicExact::InverseLine(double lat1, double lon1, + double lat2, double lon2, NETGeographicLib::Mask caps) +{ + return gcnew GeodesicLineExact(m_pGeodesicExact->InverseLine( + lat1, lon1, lat2, lon2, static_cast(caps))); +} + +//***************************************************************************** +GeodesicLineExact^ GeodesicExact::DirectLine(double lat1, double lon1, + double azi1, double s12, NETGeographicLib::Mask caps) +{ + return gcnew GeodesicLineExact(m_pGeodesicExact->DirectLine( + lat1, lon1, azi1, s12, static_cast(caps))); +} + +//***************************************************************************** +GeodesicLineExact^ GeodesicExact::ArcDirectLine(double lat1, double lon1, + double azi1, double a12, NETGeographicLib::Mask caps) +{ + return gcnew GeodesicLineExact(m_pGeodesicExact->ArcDirectLine( + lat1, lon1, azi1, a12, static_cast(caps))); +} + +//***************************************************************************** +GeodesicLineExact^ GeodesicExact::GenDirectLine(double lat1, double lon1, + double azi1, bool arcmode, double s12_a12, NETGeographicLib::Mask caps) +{ + return gcnew GeodesicLineExact(m_pGeodesicExact->GenDirectLine( + lat1, lon1, azi1, arcmode, s12_a12, static_cast(caps))); +} + //***************************************************************************** double GeodesicExact::MajorRadius::get() { return m_pGeodesicExact->MajorRadius(); } diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/GeodesicExact.h b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/GeodesicExact.h index f52a0eb94..ab03a5c80 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/GeodesicExact.h +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/GeodesicExact.h @@ -7,7 +7,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #include "NETGeographicLib.h" @@ -85,13 +85,97 @@ namespace NETGeographicLib **********************************************************************/ public ref class GeodesicExact { - private: + private: + enum class captype { + CAP_NONE = 0U, + CAP_E = 1U<<0, + // Skip 1U<<1 for compatibility with Geodesic (not required) + CAP_D = 1U<<2, + CAP_H = 1U<<3, + CAP_C4 = 1U<<4, + CAP_ALL = 0x1FU, + CAP_MASK = CAP_ALL, + OUT_ALL = 0x7F80U, + OUT_MASK = 0xFF80U, // Includes LONG_UNROLL + }; // pointer to the unmanaged GeographicLib::GeodesicExact. const GeographicLib::GeodesicExact* m_pGeodesicExact; // the finalizer deletes the unmanaged memory. !GeodesicExact(); public: + /** + * Bit masks for what calculations to do. These masks do double duty. + * They signify to the GeodesicLineExact::GeodesicLineExact constructor and + * to GeodesicExact::Line what capabilities should be included in the + * GeodesicLineExact object. They also specify which results to return in + * the general routines GeodesicExact::GenDirect and + * GeodesicExact::GenInverse routines. GeodesicLineExact::mask is a + * duplication of this enum. + **********************************************************************/ + enum class mask { + /** + * No capabilities, no output. + * @hideinitializer + **********************************************************************/ + NONE = 0U, + /** + * Calculate latitude \e lat2. (It's not necessary to include this as a + * capability to GeodesicLineExact because this is included by default.) + * @hideinitializer + **********************************************************************/ + LATITUDE = 1U<<7 | unsigned(captype::CAP_NONE), + /** + * Calculate longitude \e lon2. + * @hideinitializer + **********************************************************************/ + LONGITUDE = 1U<<8 | unsigned(captype::CAP_H), + /** + * Calculate azimuths \e azi1 and \e azi2. (It's not necessary to + * include this as a capability to GeodesicLineExact because this is + * included by default.) + * @hideinitializer + **********************************************************************/ + AZIMUTH = 1U<<9 | unsigned(captype::CAP_NONE), + /** + * Calculate distance \e s12. + * @hideinitializer + **********************************************************************/ + DISTANCE = 1U<<10 | unsigned(captype::CAP_E), + /** + * Allow distance \e s12 to be used as input in the direct geodesic + * problem. + * @hideinitializer + **********************************************************************/ + DISTANCE_IN = 1U<<11 | unsigned(captype::CAP_E), + /** + * Calculate reduced length \e m12. + * @hideinitializer + **********************************************************************/ + REDUCEDLENGTH = 1U<<12 | unsigned(captype::CAP_D), + /** + * Calculate geodesic scales \e M12 and \e M21. + * @hideinitializer + **********************************************************************/ + GEODESICSCALE = 1U<<13 | unsigned(captype::CAP_D), + /** + * Calculate area \e S12. + * @hideinitializer + **********************************************************************/ + AREA = 1U<<14 | unsigned(captype::CAP_C4), + /** + * Unroll \e lon2 in the direct calculation. + * @hideinitializer + **********************************************************************/ + LONG_UNROLL = 1U<<15, + /** + * All capabilities, calculate everything. (LONG_UNROLL is not + * included in this mask.) + * @hideinitializer + **********************************************************************/ + ALL = unsigned(captype::OUT_ALL)| unsigned(captype::CAP_ALL), + }; + /** \name Constructor **********************************************************************/ ///@{ @@ -105,8 +189,7 @@ namespace NETGeographicLib * * @param[in] a equatorial radius (meters). * @param[in] f flattening of ellipsoid. Setting \e f = 0 gives a sphere. - * Negative \e f gives a prolate ellipsoid. If \e f > 1, set flattening - * to 1/\e f. + * Negative \e f gives a prolate ellipsoid. * @exception GeographicErr if \e a or (1 − \e f ) \e a is not * positive. **********************************************************************/ @@ -142,10 +225,9 @@ namespace NETGeographicLib * @param[out] S12 area under the geodesic (meters2). * @return \e a12 arc length of between point 1 and point 2 (degrees). * - * \e lat1 should be in the range [−90°, 90°]; \e lon1 and \e - * azi1 should be in the range [−540°, 540°). The values of - * \e lon2 and \e azi2 returned are in the range [−180°, - * 180°). + * \e lat1 should be in the range [−90°, 90°];. The + * values of \e lon2 and \e azi2 returned are in the range + * [−180°, 180°). * * If either point is at a pole, the azimuth is defined by keeping the * longitude fixed, writing \e lat = ±(90° − ε), @@ -236,10 +318,9 @@ namespace NETGeographicLib * (dimensionless). * @param[out] S12 area under the geodesic (meters2). * - * \e lat1 should be in the range [−90°, 90°]; \e lon1 and \e - * azi1 should be in the range [−540°, 540°). The values of - * \e lon2 and \e azi2 returned are in the range [−180°, - * 180°). + * \e lat1 should be in the range [−90°, 90°]. The + * values of \e lon2 and \e azi2 returned are in the range + * [−180°, 180°). * * If either point is at a pole, the azimuth is defined by keeping the * longitude fixed, writing \e lat = ±(90° − ε), @@ -335,7 +416,7 @@ namespace NETGeographicLib * @param[in] s12_a12 if \e arcmode is false, this is the distance between * point 1 and point 2 (meters); otherwise it is the arc length between * point 1 and point 2 (degrees); it can be signed. - * @param[in] outmask a bitor'ed combination of NETGeographicLib::Mask values + * @param[in] outmask a bitor'ed combination of GeodesicExact::mask values * specifying which of the following parameters should be set. * @param[out] lat2 latitude of point 2 (degrees). * @param[out] lon2 longitude of point 2 (degrees). @@ -349,26 +430,32 @@ namespace NETGeographicLib * @param[out] S12 area under the geodesic (meters2). * @return \e a12 arc length of between point 1 and point 2 (degrees). * - * The NETGeographicLib::Mask values possible for \e outmask are - * - \e outmask |= NETGeographicLib::Mask::LATITUDE for the latitude \e lat2; - * - \e outmask |= NETGeographicLib::Mask::LONGITUDE for the latitude \e lon2; - * - \e outmask |= NETGeographicLib::Mask::AZIMUTH for the latitude \e azi2; - * - \e outmask |= NETGeographicLib::Mask::DISTANCE for the distance \e s12; - * - \e outmask |= NETGeographicLib::Mask::REDUCEDLENGTH for the reduced length \e + * The GeodesicExact::mask values possible for \e outmask are + * - \e outmask |= GeodesicExact::LATITUDE for the latitude \e lat2; + * - \e outmask |= GeodesicExact::LONGITUDE for the latitude \e lon2; + * - \e outmask |= GeodesicExact::AZIMUTH for the latitude \e azi2; + * - \e outmask |= GeodesicExact::DISTANCE for the distance \e s12; + * - \e outmask |= GeodesicExact::REDUCEDLENGTH for the reduced length \e * m12; - * - \e outmask |= NETGeographicLib::Mask::GEODESICSCALE for the geodesic scales \e + * - \e outmask |= GeodesicExact::GEODESICSCALE for the geodesic scales \e * M12 and \e M21; - * - \e outmask |= NETGeographicLib::Mask::AREA for the area \e S12; - * - \e outmask |= NETGeographicLib::Mask::ALL for all of the above. + * - \e outmask |= GeodesicExact::AREA for the area \e S12; + * - \e outmask |= GeodesicExact::ALL for all of the above; + * - \e outmask |= GeodesicExact::LONG_UNROLL to unroll \e lon2 instead of + * wrapping it into the range [−180°, 180°). * . * The function value \e a12 is always computed and returned and this * equals \e s12_a12 is \e arcmode is true. If \e outmask includes * GeodesicExact::DISTANCE and \e arcmode is false, then \e s12 = \e - * s12_a12. It is not necessary to include NETGeographicLib::Mask::DISTANCE_IN in + * s12_a12. It is not necessary to include GeodesicExact::DISTANCE_IN in * \e outmask; this is automatically included is \e arcmode is false. + * + * With the LONG_UNROLL bit set, the quantity \e lon2 − \e lon1 + * indicates how many times and in what sense the geodesic encircles + * the ellipsoid. **********************************************************************/ double GenDirect(double lat1, double lon1, double azi1, - bool arcmode, double s12_a12, NETGeographicLib::Mask outmask, + bool arcmode, double s12_a12, GeodesicExact::mask outmask, [System::Runtime::InteropServices::Out] double% lat2, [System::Runtime::InteropServices::Out] double% lon2, [System::Runtime::InteropServices::Out] double% azi2, @@ -400,10 +487,9 @@ namespace NETGeographicLib * @param[out] S12 area under the geodesic (meters2). * @return \e a12 arc length of between point 1 and point 2 (degrees). * - * \e lat1 and \e lat2 should be in the range [−90°, 90°]; \e - * lon1 and \e lon2 should be in the range [−540°, 540°). - * The values of \e azi1 and \e azi2 returned are in the range - * [−180°, 180°). + * \e lat1 and \e lat2 should be in the range [−90°, + * 90°]. The values of \e azi1 and \e azi2 returned are in the + * range [−180°, 180°). * * If either point is at a pole, the azimuth is defined by keeping the * longitude fixed, writing \e lat = ±(90° − ε), @@ -485,7 +571,7 @@ namespace NETGeographicLib * @param[in] lon1 longitude of point 1 (degrees). * @param[in] lat2 latitude of point 2 (degrees). * @param[in] lon2 longitude of point 2 (degrees). - * @param[in] outmask a bitor'ed combination of NETGeographicLib::Mask values + * @param[in] outmask a bitor'ed combination of GeodesicExact::mask values * specifying which of the following parameters should be set. * @param[out] s12 distance between point 1 and point 2 (meters). * @param[out] azi1 azimuth at point 1 (degrees). @@ -498,20 +584,20 @@ namespace NETGeographicLib * @param[out] S12 area under the geodesic (meters2). * @return \e a12 arc length of between point 1 and point 2 (degrees). * - * The NETGeographicLib::Mask values possible for \e outmask are - * - \e outmask |= NETGeographicLib::Mask::DISTANCE for the distance \e s12; - * - \e outmask |= NETGeographicLib::Mask::AZIMUTH for the latitude \e azi2; - * - \e outmask |= NETGeographicLib::Mask::REDUCEDLENGTH for the reduced length \e + * The GeodesicExact::mask values possible for \e outmask are + * - \e outmask |= GeodesicExact::DISTANCE for the distance \e s12; + * - \e outmask |= GeodesicExact::AZIMUTH for the latitude \e azi2; + * - \e outmask |= GeodesicExact::REDUCEDLENGTH for the reduced length \e * m12; - * - \e outmask |= NETGeographicLib::Mask::GEODESICSCALE for the geodesic scales \e + * - \e outmask |= GeodesicExact::GEODESICSCALE for the geodesic scales \e * M12 and \e M21; - * - \e outmask |= NETGeographicLib::Mask::AREA for the area \e S12; - * - \e outmask |= NETGeographicLib::Mask::ALL for all of the above. + * - \e outmask |= GeodesicExact::AREA for the area \e S12; + * - \e outmask |= GeodesicExact::ALL for all of the above. * . * The arc length is always computed and returned as the function value. **********************************************************************/ double GenInverse(double lat1, double lon1, double lat2, double lon2, - NETGeographicLib::Mask outmask, + GeodesicExact::mask outmask, [System::Runtime::InteropServices::Out] double% s12, [System::Runtime::InteropServices::Out] double% azi1, [System::Runtime::InteropServices::Out] double% azi2, @@ -537,8 +623,7 @@ namespace NETGeographicLib * GeodesicLineExact::Position. * @return a GeodesicLineExact object. * - * \e lat1 should be in the range [−90°, 90°]; \e lon1 and \e - * azi1 should be in the range [−540°, 540°). + * \e lat1 should be in the range [−90°, 90°]. * * The GeodesicExact::mask values are * - \e caps |= NETGeographicLib::Mask::LATITUDE for the latitude \e lat2; this is @@ -566,6 +651,98 @@ namespace NETGeographicLib GeodesicLineExact^ Line(double lat1, double lon1, double azi1, NETGeographicLib::Mask caps ); + /** + * Define a GeodesicLineExact in terms of the inverse geodesic problem. + * + * @param[in] lat1 latitude of point 1 (degrees). + * @param[in] lon1 longitude of point 1 (degrees). + * @param[in] lat2 latitude of point 2 (degrees). + * @param[in] lon2 longitude of point 2 (degrees). + * @param[in] caps bitor'ed combination of GeodesicExact::mask values + * specifying the capabilities the GeodesicLineExact object should + * possess, i.e., which quantities can be returned in calls to + * GeodesicLineExact::Position. + * @return a GeodesicLineExact object. + * + * This function sets point 3 of the GeodesicLineExact to correspond to + * point 2 of the inverse geodesic problem. + * + * \e lat1 and \e lat2 should be in the range [−90°, 90°]. + **********************************************************************/ + GeodesicLineExact^ InverseLine(double lat1, double lon1, double lat2, + double lon2, NETGeographicLib::Mask caps ); + + /** + * Define a GeodesicLineExact in terms of the direct geodesic problem + * specified in terms of distance. + * + * @param[in] lat1 latitude of point 1 (degrees). + * @param[in] lon1 longitude of point 1 (degrees). + * @param[in] azi1 azimuth at point 1 (degrees). + * @param[in] s12 distance between point 1 and point 2 (meters); it can be + * negative. + * @param[in] caps bitor'ed combination of GeodesicExact::mask values + * specifying the capabilities the GeodesicLineExact object should + * possess, i.e., which quantities can be returned in calls to + * GeodesicLineExact::Position. + * @return a GeodesicLineExact object. + * + * This function sets point 3 of the GeodesicLineExact to correspond to + * point 2 of the direct geodesic problem. + * + * \e lat1 should be in the range [−90°, 90°]. + **********************************************************************/ + GeodesicLineExact^ DirectLine(double lat1, double lon1, double azi1, + double s12, NETGeographicLib::Mask caps); + + /** + * Define a GeodesicLineExact in terms of the direct geodesic problem + * specified in terms of arc length. + * + * @param[in] lat1 latitude of point 1 (degrees). + * @param[in] lon1 longitude of point 1 (degrees). + * @param[in] azi1 azimuth at point 1 (degrees). + * @param[in] a12 arc length between point 1 and point 2 (degrees); it can + * be negative. + * @param[in] caps bitor'ed combination of GeodesicExact::mask values + * specifying the capabilities the GeodesicLineExact object should + * possess, i.e., which quantities can be returned in calls to + * GeodesicLineExact::Position. + * @return a GeodesicLineExact object. + * + * This function sets point 3 of the GeodesicLineExact to correspond to + * point 2 of the direct geodesic problem. + * + * \e lat1 should be in the range [−90°, 90°]. + **********************************************************************/ + GeodesicLineExact^ ArcDirectLine(double lat1, double lon1, double azi1, + double a12, NETGeographicLib::Mask caps); + + /** + * Define a GeodesicLineExact in terms of the direct geodesic problem + * specified in terms of either distance or arc length. + * + * @param[in] lat1 latitude of point 1 (degrees). + * @param[in] lon1 longitude of point 1 (degrees). + * @param[in] azi1 azimuth at point 1 (degrees). + * @param[in] arcmode boolean flag determining the meaning of the \e + * s12_a12. + * @param[in] s12_a12 if \e arcmode is false, this is the distance between + * point 1 and point 2 (meters); otherwise it is the arc length between + * point 1 and point 2 (degrees); it can be negative. + * @param[in] caps bitor'ed combination of GeodesicExact::mask values + * specifying the capabilities the GeodesicLineExact object should + * possess, i.e., which quantities can be returned in calls to + * GeodesicLineExact::Position. + * @return a GeodesicLineExact object. + * + * This function sets point 3 of the GeodesicLineExact to correspond to + * point 2 of the direct geodesic problem. + * + * \e lat1 should be in the range [−90°, 90°]. + **********************************************************************/ + GeodesicLineExact^ GenDirectLine(double lat1, double lon1, double azi1, + bool arcmode, double s12_a12, NETGeographicLib::Mask caps); ///@} /** \name Inspector functions. diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/GeodesicLine.cpp b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/GeodesicLine.cpp index 2c6d683f4..1d92fbcdb 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/GeodesicLine.cpp +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/GeodesicLine.cpp @@ -6,7 +6,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #include "stdafx.h" #include "GeographicLib/GeodesicLine.hpp" @@ -45,6 +45,19 @@ GeodesicLine::GeodesicLine( Geodesic^ g, double lat1, double lon1, double azi1, } } +//***************************************************************************** +GeodesicLine::GeodesicLine(const GeographicLib::GeodesicLine& gl) +{ + try + { + m_pGeodesicLine = new GeographicLib::GeodesicLine(gl); + } + catch (std::bad_alloc) + { + throw gcnew GeographicErr(BADALLOC); + } +} + //***************************************************************************** GeodesicLine::GeodesicLine(double lat1, double lon1, double azi1, NETGeographicLib::Mask caps) @@ -52,7 +65,7 @@ GeodesicLine::GeodesicLine(double lat1, double lon1, double azi1, try { m_pGeodesicLine = new GeographicLib::GeodesicLine( - GeographicLib::Geodesic::WGS84, lat1, lon1, azi1, + GeographicLib::Geodesic::WGS84(), lat1, lon1, azi1, static_cast(caps) ); } catch ( std::bad_alloc ) @@ -291,7 +304,7 @@ void GeodesicLine::ArcPosition(double a12, //***************************************************************************** double GeodesicLine::GenPosition(bool arcmode, double s12_a12, - NETGeographicLib::Mask outmask, + GeodesicLine::mask outmask, [System::Runtime::InteropServices::Out] double% lat2, [System::Runtime::InteropServices::Out] double% lon2, [System::Runtime::InteropServices::Out] double% azi2, @@ -341,10 +354,52 @@ double GeodesicLine::MajorRadius::get() double GeodesicLine::Flattening::get() { return m_pGeodesicLine->Flattening(); } +//***************************************************************************** +double GeodesicLine::Distance::get() +{ return m_pGeodesicLine->Distance(); } + +//***************************************************************************** +double GeodesicLine::Arc::get() +{ return m_pGeodesicLine->Arc(); } + //***************************************************************************** NETGeographicLib::Mask GeodesicLine::Capabilities() { return static_cast(m_pGeodesicLine->Capabilities()); } //***************************************************************************** -bool GeodesicLine::Capabilities(NETGeographicLib::Mask testcaps) +bool GeodesicLine::Capabilities(GeodesicLine::mask testcaps) { return m_pGeodesicLine->Capabilities( static_cast(testcaps) ); } + +//***************************************************************************** +void GeodesicLine::SetDistance(double s13) +{ m_pGeodesicLine->SetDistance(s13); } + +//***************************************************************************** +void GeodesicLine::SetArc(double a13) +{ m_pGeodesicLine->SetArc(a13); } + +//***************************************************************************** +void GeodesicLine::GenSetDistance(bool arcmode, double s13_a13) +{ m_pGeodesicLine->GenSetDistance(arcmode, s13_a13); } + +//***************************************************************************** +void GeodesicLine::AzimuthSinCos(double% sazi1, double% cazi1) +{ + double x1, x2; + m_pGeodesicLine->Azimuth(x1, x2); + sazi1 = x1; + cazi1 = x2; +} + +//***************************************************************************** +void GeodesicLine::EquatorialAzimuthSinCos(double% sazi0, double% cazi0) +{ + double x1, x2; + m_pGeodesicLine->EquatorialAzimuth(x1, x2); + sazi0 = x1; + cazi0 = x2; +} + +//***************************************************************************** +double GeodesicLine::GenDistance(bool arcmode) +{ return m_pGeodesicLine->GenDistance(arcmode); } diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/GeodesicLine.h b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/GeodesicLine.h index b2a916caf..5e59687c5 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/GeodesicLine.h +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/GeodesicLine.h @@ -7,7 +7,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #include "NETGeographicLib.h" @@ -30,7 +30,7 @@ namespace NETGeographicLib * * The calculations are accurate to better than 15 nm (15 nanometers). See * Sec. 9 of - * arXiv:1102.1215v1 for + * arXiv:1102.1215v1 for * details. The algorithms used by this class are based on series expansions * using the flattening \e f as a small parameter. These are only accurate * for |f| < 0.02; however reasonably accurate results will be @@ -39,12 +39,12 @@ namespace NETGeographicLib * * The algorithms are described in * - C. F. F. Karney, - * + * * Algorithms for geodesics, * J. Geodesy 87, 43--55 (2013); - * DOI: + * DOI: * 10.1007/s00190-012-0578-z; - * addenda: + * addenda: * geod-addenda.html. * . * For more information on geodesics see \ref geodesic. @@ -61,22 +61,95 @@ namespace NETGeographicLib * * The following functions are implemented as properties: * Latitude, Longitude, Azimuth, EquatorialAzimuth, EquatorialArc, - * MajorRadius, and Flattening. + * MajorRadius, Distance, Arc, and Flattening. * * The constructors, Capabilities, and GenPosition functions accept the * "capabilities mask" as a NETGeographicLib::Mask rather than an * unsigned. The Capabilities function returns a NETGeographicLib::Mask * rather than an unsigned. + * + * The overloaded Azimuth and EquatorialAzimuth functions that return + * the sin and cosine terms have been renamed AzimuthSinCos and + * EquatorialAzimuthSinCos, repectively. **********************************************************************/ public ref class GeodesicLine { private: // pointer to the unmanaged GeographicLib::GeodesicLine. - const GeographicLib::GeodesicLine* m_pGeodesicLine; + GeographicLib::GeodesicLine* m_pGeodesicLine; // The finalizer frees the unmanaged memory when this object is destroyed. !GeodesicLine(void); public: + + /** + * Bit masks for what calculations to do. They signify to the + * GeodesicLine::GeodesicLine constructor and to Geodesic::Line what + * capabilities should be included in the GeodesicLine object. This is + * merely a duplication of Geodesic::mask. + **********************************************************************/ + enum class mask { + /** + * No capabilities, no output. + * @hideinitializer + **********************************************************************/ + NONE = 0U, + /** + * Calculate latitude \e lat2. (It's not necessary to include this as a + * capability to GeodesicLine because this is included by default.) + * @hideinitializer + **********************************************************************/ + LATITUDE = 1U<<7 | unsigned(captype::CAP_NONE), + /** + * Calculate longitude \e lon2. + * @hideinitializer + **********************************************************************/ + LONGITUDE = 1U<<8 | unsigned(captype::CAP_C3), + /** + * Calculate azimuths \e azi1 and \e azi2. (It's not necessary to + * include this as a capability to GeodesicLine because this is included + * by default.) + * @hideinitializer + **********************************************************************/ + AZIMUTH = 1U<<9 | unsigned(captype::CAP_NONE), + /** + * Calculate distance \e s12. + * @hideinitializer + **********************************************************************/ + DISTANCE = 1U<<10 | unsigned(captype::CAP_C1), + /** + * Allow distance \e s12 to be used as input in the direct geodesic + * problem. + * @hideinitializer + **********************************************************************/ + DISTANCE_IN = 1U<<11 | unsigned(captype::CAP_C1) | unsigned(captype::CAP_C1p), + /** + * Calculate reduced length \e m12. + * @hideinitializer + **********************************************************************/ + REDUCEDLENGTH = 1U<<12 | unsigned(captype::CAP_C1) | unsigned(captype::CAP_C2), + /** + * Calculate geodesic scales \e M12 and \e M21. + * @hideinitializer + **********************************************************************/ + GEODESICSCALE = 1U<<13 | unsigned(captype::CAP_C1) | unsigned(captype::CAP_C2), + /** + * Calculate area \e S12. + * @hideinitializer + **********************************************************************/ + AREA = 1U<<14 | unsigned(captype::CAP_C4), + /** + * Unroll \e lon2 in the direct calculation. + * @hideinitializer + **********************************************************************/ + LONG_UNROLL = 1U<<15, + /** + * All capabilities, calculate everything. (LONG_UNROLL is not + * included in this mask.) + * @hideinitializer + **********************************************************************/ + ALL = unsigned(captype::OUT_ALL)| unsigned(captype::CAP_ALL), + }; /** \name Constructors **********************************************************************/ ///@{ @@ -95,8 +168,7 @@ namespace NETGeographicLib * i.e., which quantities can be returned in calls to * GeodesicLine::Position. * - * \e lat1 should be in the range [−90°, 90°]; \e lon1 and \e - * azi1 should be in the range [−540°, 540°). + * \e lat1 should be in the range [−90°, 90°]. * * The NETGeographicLib::Mask values are * - \e caps |= GeodesicLine::LATITUDE for the latitude \e lat2; this is @@ -128,6 +200,12 @@ namespace NETGeographicLib **********************************************************************/ GeodesicLine(double lat1, double lon1, double azi1, NETGeographicLib::Mask caps); + + /** + * A constructoe that accepts a reference to an unmanages GeodesicLin. + * FOR INTERNAL USE ONLY + **********************************************************************/ + GeodesicLine(const GeographicLib::GeodesicLine& gl); ///@} /** @@ -358,49 +436,55 @@ namespace NETGeographicLib * @param[in] s12_a12 if \e arcmode is false, this is the distance between * point 1 and point 2 (meters); otherwise it is the arc length between * point 1 and point 2 (degrees); it can be negative. - * @param[in] outmask a bitor'ed combination of NETGeographicLib::Mask values + * @param[in] outmask a bitor'ed combination of GeodesicLine::mask values * specifying which of the following parameters should be set. * @param[out] lat2 latitude of point 2 (degrees). * @param[out] lon2 longitude of point 2 (degrees); requires that the * GeodesicLine object was constructed with \e caps |= - * NETGeographicLib::Mask::LONGITUDE. + * GeodesicLine::LONGITUDE. * @param[out] azi2 (forward) azimuth at point 2 (degrees). * @param[out] s12 distance between point 1 and point 2 (meters); requires * that the GeodesicLine object was constructed with \e caps |= - * NETGeographicLib::Mask::DISTANCE. + * GeodesicLine::DISTANCE. * @param[out] m12 reduced length of geodesic (meters); requires that the * GeodesicLine object was constructed with \e caps |= - * NETGeographicLib::Mask::REDUCEDLENGTH. + * GeodesicLine::REDUCEDLENGTH. * @param[out] M12 geodesic scale of point 2 relative to point 1 * (dimensionless); requires that the GeodesicLine object was constructed - * with \e caps |= NETGeographicLib::Mask::GEODESICSCALE. + * with \e caps |= GeodesicLine::GEODESICSCALE. * @param[out] M21 geodesic scale of point 1 relative to point 2 * (dimensionless); requires that the GeodesicLine object was constructed - * with \e caps |= NETGeographicLib::Mask::GEODESICSCALE. + * with \e caps |= GeodesicLine::GEODESICSCALE. * @param[out] S12 area under the geodesic (meters2); requires * that the GeodesicLine object was constructed with \e caps |= - * NETGeographicLib::Mask::AREA. + * GeodesicLine::AREA. * @return \e a12 arc length of between point 1 and point 2 (degrees). * * The GeodesicLine::mask values possible for \e outmask are - * - \e outmask |= NETGeographicLib::Mask::LATITUDE for the latitude \e lat2; - * - \e outmask |= NETGeographicLib::Mask::LONGITUDE for the latitude \e lon2; - * - \e outmask |= NETGeographicLib::Mask::AZIMUTH for the latitude \e azi2; - * - \e outmask |= NETGeographicLib::Mask::DISTANCE for the distance \e s12; - * - \e outmask |= NETGeographicLib::Mask::REDUCEDLENGTH for the reduced length \e + * - \e outmask |= GeodesicLine::LATITUDE for the latitude \e lat2; + * - \e outmask |= GeodesicLine::LONGITUDE for the latitude \e lon2; + * - \e outmask |= GeodesicLine::AZIMUTH for the latitude \e azi2; + * - \e outmask |= GeodesicLine::DISTANCE for the distance \e s12; + * - \e outmask |= GeodesicLine::REDUCEDLENGTH for the reduced length \e * m12; - * - \e outmask |= NETGeographicLib::Mask::GEODESICSCALE for the geodesic scales \e + * - \e outmask |= GeodesicLine::GEODESICSCALE for the geodesic scales \e * M12 and \e M21; - * - \e outmask |= NETGeographicLib::Mask::AREA for the area \e S12; - * - \e outmask |= NETGeographicLib::Mask::ALL for all of the above. + * - \e outmask |= GeodesicLine::AREA for the area \e S12; + * - \e outmask |= GeodesicLine::ALL for all of the above; + * - \e outmask |= GeodesicLine::LONG_UNROLL to unroll \e lon2 instead of + * wrapping it into the range [−180°, 180°). * . * Requesting a value which the GeodesicLine object is not capable of * computing is not an error; the corresponding argument will not be * altered. Note, however, that the arc length is always computed and * returned as the function value. + * + * With the LONG_UNROLL bit set, the quantity \e lon2 − \e lon1 + * indicates how many times and in what sense the geodesic encircles + * the ellipsoid. **********************************************************************/ double GenPosition(bool arcmode, double s12_a12, - NETGeographicLib::Mask outmask, + GeodesicLine::mask outmask, [System::Runtime::InteropServices::Out] double% lat2, [System::Runtime::InteropServices::Out] double% lon2, [System::Runtime::InteropServices::Out] double% azi2, @@ -412,6 +496,77 @@ namespace NETGeographicLib ///@} + /** \name Setting point 3 + **********************************************************************/ + ///@{ + + /** + * Specify position of point 3 in terms of distance. + * + * @param[in] s13 the distance from point 1 to point 3 (meters); it + * can be negative. + * + * This is only useful if the GeodesicLine object has been constructed + * with \e caps |= GeodesicLine::DISTANCE_IN. + **********************************************************************/ + void SetDistance(double s13); + + /** + * Specify position of point 3 in terms of arc length. + * + * @param[in] a13 the arc length from point 1 to point 3 (degrees); it + * can be negative. + * + * The distance \e s13 is only set if the GeodesicLine object has been + * constructed with \e caps |= GeodesicLine::DISTANCE. + **********************************************************************/ + void SetArc(double a13); + + /** + * Specify position of point 3 in terms of either distance or arc length. + * + * @param[in] arcmode boolean flag determining the meaning of the second + * parameter; if \e arcmode is false, then the GeodesicLine object must + * have been constructed with \e caps |= GeodesicLine::DISTANCE_IN. + * @param[in] s13_a13 if \e arcmode is false, this is the distance from + * point 1 to point 3 (meters); otherwise it is the arc length from + * point 1 to point 3 (degrees); it can be negative. + **********************************************************************/ + void GenSetDistance(bool arcmode, double s13_a13); + ///@} + + /** \name Trigonometric accessor functions + **********************************************************************/ + ///@{ + /** + * The sine and cosine of \e azi1. + * + * @param[out] sazi1 the sine of \e azi1. + * @param[out] cazi1 the cosine of \e azi1. + **********************************************************************/ + void AzimuthSinCos([System::Runtime::InteropServices::Out] double% sazi1, + [System::Runtime::InteropServices::Out] double% cazi1); + + /** + * The sine and cosine of \e azi0. + * + * @param[out] sazi0 the sine of \e azi0. + * @param[out] cazi0 the cosine of \e azi0. + **********************************************************************/ + void EquatorialAzimuthSinCos( + [System::Runtime::InteropServices::Out] double% sazi0, + [System::Runtime::InteropServices::Out] double% cazi0); + + /** + * The distance or arc length to point 3. + * + * @param[in] arcmode boolean flag determining the meaning of returned + * value. + * @return \e s13 if \e arcmode is false; \e a13 if \e arcmode is true. + **********************************************************************/ + double GenDistance(bool arcmode); + ///@} + /** \name Inspector functions **********************************************************************/ ///@{ @@ -455,6 +610,16 @@ namespace NETGeographicLib **********************************************************************/ property double Flattening { double get(); } + /** + * @return \e s13, the distance to point 3 (meters). + **********************************************************************/ + property double Distance { double get(); } + + /** + * @return \e a13, the arc length to point 3 (degrees). + **********************************************************************/ + property double Arc { double get(); } + /** * @return \e caps the computational capabilities that this object was * constructed with. LATITUDE and AZIMUTH are always included. @@ -465,7 +630,7 @@ namespace NETGeographicLib * @param[in] testcaps a set of bitor'ed GeodesicLine::mask values. * @return true if the GeodesicLine object has all these capabilities. **********************************************************************/ - bool Capabilities(NETGeographicLib::Mask testcaps); + bool Capabilities(GeodesicLine::mask testcaps); ///@} }; } // namespace NETGeographicLib diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/GeodesicLineExact.cpp b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/GeodesicLineExact.cpp index fb8ab72fc..d332745ab 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/GeodesicLineExact.cpp +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/GeodesicLineExact.cpp @@ -6,7 +6,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #include "stdafx.h" #include "GeographicLib/GeodesicLineExact.hpp" @@ -45,6 +45,20 @@ GeodesicLineExact::GeodesicLineExact(GeodesicExact^ g, double lat1, } } +//***************************************************************************** +GeodesicLineExact::GeodesicLineExact( + const GeographicLib::GeodesicLineExact& gle) +{ + try + { + m_pGeodesicLineExact = new GeographicLib::GeodesicLineExact(gle); + } + catch (std::bad_alloc) + { + throw gcnew GeographicErr(BADALLOC); + } +} + //***************************************************************************** GeodesicLineExact::GeodesicLineExact(double lat1, double lon1, double azi1, NETGeographicLib::Mask caps) @@ -52,7 +66,7 @@ GeodesicLineExact::GeodesicLineExact(double lat1, double lon1, double azi1, try { m_pGeodesicLineExact = new GeographicLib::GeodesicLineExact( - GeographicLib::GeodesicExact::WGS84, lat1, lon1, azi1, + GeographicLib::GeodesicExact::WGS84(), lat1, lon1, azi1, static_cast(caps) ); } catch ( std::bad_alloc ) @@ -292,7 +306,7 @@ void GeodesicLineExact::ArcPosition(double a12, //***************************************************************************** double GeodesicLineExact::GenPosition(bool arcmode, double s12_a12, - NETGeographicLib::Mask outmask, + GeodesicLineExact::mask outmask, [System::Runtime::InteropServices::Out] double% lat2, [System::Runtime::InteropServices::Out] double% lon2, [System::Runtime::InteropServices::Out] double% azi2, @@ -345,6 +359,14 @@ double GeodesicLineExact::MajorRadius::get() double GeodesicLineExact::Flattening::get() { return m_pGeodesicLineExact->Flattening(); } +//***************************************************************************** +double GeodesicLineExact::Distance::get() +{ return m_pGeodesicLineExact->Distance(); } + +//***************************************************************************** +double GeodesicLineExact::Arc::get() +{ return m_pGeodesicLineExact->Arc(); } + //***************************************************************************** NETGeographicLib::Mask GeodesicLineExact::Capabilities() { return static_cast(m_pGeodesicLineExact->Capabilities()); } @@ -352,3 +374,37 @@ NETGeographicLib::Mask GeodesicLineExact::Capabilities() //***************************************************************************** bool GeodesicLineExact::Capabilities(NETGeographicLib::Mask testcaps) { return m_pGeodesicLineExact->Capabilities(static_cast(testcaps)); } + +//***************************************************************************** +void GeodesicLineExact::SetDistance(double s13) +{ m_pGeodesicLineExact->SetDistance(s13); } + +//***************************************************************************** +void GeodesicLineExact::SetArc(double a13) +{ m_pGeodesicLineExact->SetArc(a13); } + +//***************************************************************************** +void GeodesicLineExact::GenSetDistance(bool arcmode, double s13_a13) +{ m_pGeodesicLineExact->GenSetDistance(arcmode, s13_a13); } + +//***************************************************************************** +void GeodesicLineExact::AzimuthSinCos(double% sazi1, double% cazi1) +{ + double x1, x2; + m_pGeodesicLineExact->Azimuth(x1, x2); + sazi1 = x1; + cazi1 = x2; +} + +//***************************************************************************** +void GeodesicLineExact::EquatorialAzimuthSinCos(double% sazi0, double% cazi0) +{ + double x1, x2; + m_pGeodesicLineExact->EquatorialAzimuth(x1, x2); + sazi0 = x1; + cazi0 = x2; +} + +//***************************************************************************** +double GeodesicLineExact::GenDistance(bool arcmode) +{ return m_pGeodesicLineExact->GenDistance(arcmode); } diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/GeodesicLineExact.h b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/GeodesicLineExact.h index 750bf8ac9..fe804eda8 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/GeodesicLineExact.h +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/GeodesicLineExact.h @@ -7,7 +7,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #include "NETGeographicLib.h" @@ -36,22 +36,109 @@ namespace NETGeographicLib * * The following functions are implemented as properties: * Latitude, Longitude, Azimuth, EquatorialAzimuth, EquatorialArc, - * MajorRadius, and Flattening. + * MajorRadius, Distance, Arc, and Flattening. * * The constructors, GenPosition, and Capabilities functions accept the * "capabilities mask" as a NETGeographicLib::Mask rather than an * unsigned. The Capabilities function returns a NETGeographicLib::Mask * rather than an unsigned. + * + * The overloaded Azimuth and EquatorialAzimuth functions that return + * the sin and cosine terms have been renamed AzimuthSinCos and + * EquatorialAzimuthSinCos, repectively. **********************************************************************/ public ref class GeodesicLineExact { - private: + private: + enum class captype { + CAP_NONE = 0U, + CAP_E = 1U<<0, + // Skip 1U<<1 for compatibility with Geodesic (not required) + CAP_D = 1U<<2, + CAP_H = 1U<<3, + CAP_C4 = 1U<<4, + CAP_ALL = 0x1FU, + CAP_MASK = CAP_ALL, + OUT_ALL = 0x7F80U, + OUT_MASK = 0xFF80U, // Includes LONG_UNROLL + }; // a pointer to the GeographicLib::GeodesicLineExact. - const GeographicLib::GeodesicLineExact* m_pGeodesicLineExact; + GeographicLib::GeodesicLineExact* m_pGeodesicLineExact; // the finalizer frees the unmanaged memory when the object is destroyed. !GeodesicLineExact(void); public: + /** + * Bit masks for what calculations to do. These masks do double duty. + * They signify to the GeodesicLineExact::GeodesicLineExact constructor and + * to GeodesicExact::Line what capabilities should be included in the + * GeodesicLineExact object. They also specify which results to return in + * the general routines GeodesicExact::GenDirect and + * GeodesicExact::GenInverse routines. GeodesicLineExact::mask is a + * duplication of this enum. + **********************************************************************/ + enum class mask { + /** + * No capabilities, no output. + * @hideinitializer + **********************************************************************/ + NONE = 0U, + /** + * Calculate latitude \e lat2. (It's not necessary to include this as a + * capability to GeodesicLineExact because this is included by default.) + * @hideinitializer + **********************************************************************/ + LATITUDE = 1U<<7 | unsigned(captype::CAP_NONE), + /** + * Calculate longitude \e lon2. + * @hideinitializer + **********************************************************************/ + LONGITUDE = 1U<<8 | unsigned(captype::CAP_H), + /** + * Calculate azimuths \e azi1 and \e azi2. (It's not necessary to + * include this as a capability to GeodesicLineExact because this is + * included by default.) + * @hideinitializer + **********************************************************************/ + AZIMUTH = 1U<<9 | unsigned(captype::CAP_NONE), + /** + * Calculate distance \e s12. + * @hideinitializer + **********************************************************************/ + DISTANCE = 1U<<10 | unsigned(captype::CAP_E), + /** + * Allow distance \e s12 to be used as input in the direct geodesic + * problem. + * @hideinitializer + **********************************************************************/ + DISTANCE_IN = 1U<<11 | unsigned(captype::CAP_E), + /** + * Calculate reduced length \e m12. + * @hideinitializer + **********************************************************************/ + REDUCEDLENGTH = 1U<<12 | unsigned(captype::CAP_D), + /** + * Calculate geodesic scales \e M12 and \e M21. + * @hideinitializer + **********************************************************************/ + GEODESICSCALE = 1U<<13 | unsigned(captype::CAP_D), + /** + * Calculate area \e S12. + * @hideinitializer + **********************************************************************/ + AREA = 1U<<14 | unsigned(captype::CAP_C4), + /** + * Unroll \e lon2 in the direct calculation. + * @hideinitializer + **********************************************************************/ + LONG_UNROLL = 1U<<15, + /** + * All capabilities, calculate everything. (LONG_UNROLL is not + * included in this mask.) + * @hideinitializer + **********************************************************************/ + ALL = unsigned(captype::OUT_ALL)| unsigned(captype::CAP_ALL), + }; /** \name Constructors **********************************************************************/ @@ -71,8 +158,7 @@ namespace NETGeographicLib * possess, i.e., which quantities can be returned in calls to * GeodesicLine::Position. * - * \e lat1 should be in the range [−90°, 90°]; \e lon1 and \e - * azi1 should be in the range [−540°, 540°). + * \e lat1 should be in the range [−90°, 90°]. * * The NETGeographicLib::Mask values are * - \e caps |= GeodesicLineExact::LATITUDE for the latitude \e lat2; this @@ -105,6 +191,13 @@ namespace NETGeographicLib **********************************************************************/ GeodesicLineExact(double lat1, double lon1, double azi1, NETGeographicLib::Mask caps); + + /** + * This constructor accepts a reference to an unmanaged + * GeodesicLineExact. + * FOR INTERNAL USE ONLY. + **********************************************************************/ + GeodesicLineExact(const GeographicLib::GeodesicLineExact& gle); ///@} /** @@ -335,7 +428,7 @@ namespace NETGeographicLib * @param[in] s12_a12 if \e arcmode is false, this is the distance between * point 1 and point 2 (meters); otherwise it is the arc length between * point 1 and point 2 (degrees); it can be signed. - * @param[in] outmask a bitor'ed combination of NETGeographicLib::Mask + * @param[in] outmask a bitor'ed combination of GeodesicLineExact::mask * values specifying which of the following parameters should be set. * @param[out] lat2 latitude of point 2 (degrees). * @param[out] lon2 longitude of point 2 (degrees); requires that the @@ -359,25 +452,31 @@ namespace NETGeographicLib * GeodesicLineExact::AREA. * @return \e a12 arc length of between point 1 and point 2 (degrees). * - * The NETGeographicLib::Mask values possible for \e outmask are - * - \e outmask |= NETGeographicLib::Mask::LATITUDE for the latitude \e lat2; - * - \e outmask |= NETGeographicLib::Mask::LONGITUDE for the latitude \e lon2; - * - \e outmask |= NETGeographicLib::Mask::AZIMUTH for the latitude \e azi2; - * - \e outmask |= NETGeographicLib::Mask::DISTANCE for the distance \e s12; - * - \e outmask |= NETGeographicLib::Mask::REDUCEDLENGTH for the reduced length + * The GeodesicLineExact::mask values possible for \e outmask are + * - \e outmask |= GeodesicLineExact::LATITUDE for the latitude \e lat2; + * - \e outmask |= GeodesicLineExact::LONGITUDE for the latitude \e lon2; + * - \e outmask |= GeodesicLineExact::AZIMUTH for the latitude \e azi2; + * - \e outmask |= GeodesicLineExact::DISTANCE for the distance \e s12; + * - \e outmask |= GeodesicLineExact::REDUCEDLENGTH for the reduced length * \e m12; - * - \e outmask |= NETGeographicLib::Mask::GEODESICSCALE for the geodesic scales + * - \e outmask |= GeodesicLineExact::GEODESICSCALE for the geodesic scales * \e M12 and \e M21; - * - \e outmask |= NETGeographicLib::Mask::AREA for the area \e S12; - * - \e outmask |= NETGeographicLib::Mask::ALL for all of the above. + * - \e outmask |= GeodesicLineExact::AREA for the area \e S12; + * - \e outmask |= GeodesicLineExact::ALL for all of the above; + * - \e outmask |= GeodesicLineExact::LONG_UNROLL to unroll \e lon2 instead + * of wrapping it into the range [−180°, 180°). * . * Requesting a value which the GeodesicLineExact object is not capable of * computing is not an error; the corresponding argument will not be * altered. Note, however, that the arc length is always computed and * returned as the function value. + * + * With the LONG_UNROLL bit set, the quantity \e lon2 − \e lon1 + * indicates how many times and in what sense the geodesic encircles + * the ellipsoid. **********************************************************************/ double GenPosition(bool arcmode, double s12_a12, - NETGeographicLib::Mask outmask, + GeodesicLineExact::mask outmask, [System::Runtime::InteropServices::Out] double% lat2, [System::Runtime::InteropServices::Out] double% lon2, [System::Runtime::InteropServices::Out] double% azi2, @@ -389,6 +488,79 @@ namespace NETGeographicLib ///@} + /** \name Setting point 3 + **********************************************************************/ + ///@{ + + /** + * Specify position of point 3 in terms of distance. + * + * @param[in] s13 the distance from point 1 to point 3 (meters); it + * can be negative. + * + * This is only useful if the GeodesicLineExact object has been constructed + * with \e caps |= GeodesicLineExact::DISTANCE_IN. + **********************************************************************/ + void SetDistance(double s13); + + /** + * Specify position of point 3 in terms of arc length. + * + * @param[in] a13 the arc length from point 1 to point 3 (degrees); it + * can be negative. + * + * The distance \e s13 is only set if the GeodesicLineExact object has been + * constructed with \e caps |= GeodesicLineExact::DISTANCE. + **********************************************************************/ + void SetArc(double a13); + + /** + * Specify position of point 3 in terms of either distance or arc length. + * + * @param[in] arcmode boolean flag determining the meaning of the second + * parameter; if \e arcmode is false, then the GeodesicLineExact object + * must have been constructed with \e caps |= + * GeodesicLineExact::DISTANCE_IN. + * @param[in] s13_a13 if \e arcmode is false, this is the distance from + * point 1 to point 3 (meters); otherwise it is the arc length from + * point 1 to point 3 (degrees); it can be negative. + **********************************************************************/ + void GenSetDistance(bool arcmode, double s13_a13); + + /** + * The distance or arc length to point 3. + * + * @param[in] arcmode boolean flag determining the meaning of returned + * value. + * @return \e s13 if \e arcmode is false; \e a13 if \e arcmode is true. + **********************************************************************/ + double GenDistance(bool arcmode); + ///@} + + /** \name Trigonometric accessor functions + **********************************************************************/ + ///@{ + /** + * The sine and cosine of \e azi1. + * + * @param[out] sazi1 the sine of \e azi1. + * @param[out] cazi1 the cosine of \e azi1. + **********************************************************************/ + void AzimuthSinCos( + [System::Runtime::InteropServices::Out] double% sazi1, + [System::Runtime::InteropServices::Out] double% cazi1); + + /** + * The sine and cosine of \e azi0. + * + * @param[out] sazi0 the sine of \e azi0. + * @param[out] cazi0 the cosine of \e azi0. + **********************************************************************/ + void EquatorialAzimuthSinCos( + [System::Runtime::InteropServices::Out] double% sazi0, + [System::Runtime::InteropServices::Out] double% cazi0); + ///@} + /** \name Inspector functions **********************************************************************/ ///@{ @@ -432,6 +604,16 @@ namespace NETGeographicLib **********************************************************************/ property double Flattening { double get(); } + /** + * @return \e s13, the distance to point 3 (meters). + **********************************************************************/ + property double Distance { double get(); } + + /** + * @return \e a13, the arc length to point 3 (degrees). + **********************************************************************/ + property double Arc { double get(); } + /** * @return \e caps the computational capabilities that this object was * constructed with. LATITUDE and AZIMUTH are always included. diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Geohash.cpp b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Geohash.cpp index 08c31c8db..438a1d328 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Geohash.cpp +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Geohash.cpp @@ -6,7 +6,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #include "stdafx.h" #include "GeographicLib/Geohash.hpp" diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Geohash.h b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Geohash.h index c198776a1..116867d0d 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Geohash.h +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Geohash.h @@ -7,7 +7,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ namespace NETGeographicLib @@ -16,8 +16,8 @@ namespace NETGeographicLib * \brief .NET wrapper for GeographicLib::Geohash. * * Geohashes are described in - * - http://en.wikipedia.org/wiki/Geohash - * - http://geohash.org/ + * - https://en.wikipedia.org/wiki/Geohash + * - http://geohash.org/ (this link is broken as of 2012-12-11) * . * They provide a compact string representation of a particular geographic * location (expressed as latitude and longitude), with the property that if @@ -45,10 +45,8 @@ namespace NETGeographicLib * @param[in] lon longitude of point (degrees). * @param[in] len the length of the resulting geohash. * @param[out] geohash the geohash. - * @exception GeographicErr if \e la is not in [−90°, + * @exception GeographicErr if \e lat is not in [−90°, * 90°]. - * @exception GeographicErr if \e lon is not in [−540°, - * 540°). * @exception std::bad_alloc if memory for \e geohash can't be allocated. * * Internally, \e len is first put in the range [0, 18]. diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Geoid.cpp b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Geoid.cpp index 9814d166d..f7dff9778 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Geoid.cpp +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Geoid.cpp @@ -6,7 +6,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #include "stdafx.h" #include "GeographicLib/Geoid.hpp" @@ -92,25 +92,6 @@ double Geoid::Height(double lat, double lon) } } -//***************************************************************************** -double Geoid::Height(double lat, double lon, - [System::Runtime::InteropServices::Out] double% gradn, - [System::Runtime::InteropServices::Out] double% grade) -{ - try - { - double lgradn, lgrade; - double out = m_pGeoid->operator()( lat, lon, lgradn, lgrade ); - gradn = lgradn; - grade = lgrade; - return out; - } - catch ( const std::exception& err ) - { - throw gcnew GeographicErr( err.what() ); - } -} - //***************************************************************************** double Geoid::ConvertHeight(double lat, double lon, double h, ConvertFlag d) diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Geoid.h b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Geoid.h index a3b9b81f8..1387bf874 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Geoid.h +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Geoid.h @@ -7,7 +7,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ namespace NETGeographicLib @@ -32,18 +32,16 @@ namespace NETGeographicLib * this class evaluates the height by interpolation into a grid of * precomputed values. * + * The geoid height, \e N, can be used to convert a height above the + * ellipsoid, \e h, to the corresponding height above the geoid (roughly the + * height above mean sea level), \e H, using the relations + * + *    \e h = \e N + \e H; + *   \e H = −\e N + \e h. + * * See \ref geoid for details of how to install the data sets, the data * format, estimates of the interpolation errors, and how to use caching. * - * In addition to returning the geoid height, the gradient of the geoid can - * be calculated. The gradient is defined as the rate of change of the geoid - * as a function of position on the ellipsoid. This uses the parameters for - * the WGS84 ellipsoid. The gradient defined in terms of the interpolated - * heights. As a result of the way that the geoid data is stored, the - * calculation of gradients can result in large quantization errors. This is - * particularly acute for fine grids, at high latitudes, and for the easterly - * gradient. - * * This class is typically \e not thread safe in that a single instantiation * cannot be safely used by multiple threads because of the way the object * reads the data set and because it maintains a single-cell cache. If @@ -149,8 +147,7 @@ namespace NETGeographicLib * parallels \e south and \e north and the meridians \e west and \e east. * \e east is always interpreted as being east of \e west, if necessary by * adding 360° to its value. \e south and \e north should be in - * the range [−90°, 90°]; \e west and \e east should - * be in the range [−540°, 540°). + * the range [−90°, 90°]. **********************************************************************/ void CacheArea(double south, double west, double north, double east); @@ -189,34 +186,10 @@ namespace NETGeographicLib * never happens if (\e lat, \e lon) is within a successfully cached area. * @return geoid height (meters). * - * The latitude should be in [−90°, 90°] and - * longitude should be in [−540°, 540°). + * The latitude should be in [−90°, 90°]. **********************************************************************/ double Height(double lat, double lon); - /** - * Compute the geoid height and gradient at a point - * - * @param[in] lat latitude of the point (degrees). - * @param[in] lon longitude of the point (degrees). - * @param[out] gradn northerly gradient (dimensionless). - * @param[out] grade easterly gradient (dimensionless). - * @exception GeographicErr if there's a problem reading the data; this - * never happens if (\e lat, \e lon) is within a successfully cached area. - * @return geoid height (meters). - * - * The latitude should be in [−90°, 90°] and - * longitude should be in [−540°, 540°). As a result - * of the way that the geoid data is stored, the calculation of gradients - * can result in large quantization errors. This is particularly acute for - * fine grids, at high latitudes, and for the easterly gradient. If you - * need to compute the direction of the acceleration due to gravity - * accurately, you should use GravityModel::Gravity. - **********************************************************************/ - double Height(double lat, double lon, - [System::Runtime::InteropServices::Out] double% gradn, - [System::Runtime::InteropServices::Out] double% grade); - /** * Convert a height above the geoid to a height above the ellipsoid and * vice versa. @@ -357,22 +330,22 @@ namespace NETGeographicLib /** * @return the default path for geoid data files. * - * This is the value of the environment variable GEOID_PATH, if set; - * otherwise, it is $GEOGRAPHICLIB_DATA/geoids if the environment variable + * This is the value of the environment variable + * GEOGRAPHICLIB_GEOID_PATH, if set; otherwise, it is + * $GEOGRAPHICLIB_DATA/geoids if the environment variable * GEOGRAPHICLIB_DATA is set; otherwise, it is a compile-time default * (/usr/local/share/GeographicLib/geoids on non-Windows systems and - * C:/Documents and Settings/All Users/Application - * Data/GeographicLib/geoids on Windows systems). + * C:/ProgramData/GeographicLib/geoids on Windows systems). **********************************************************************/ static System::String^ DefaultGeoidPath(); /** * @return the default name for the geoid. * - * This is the value of the environment variable GEOID_NAME, if set, - * otherwise, it is "egm96-5". The Geoid class does not use this function; - * it is just provided as a convenience for a calling program when - * constructing a Geoid object. + * This is the value of the environment variable + * GEOGRAPHICLIB_GEOID_NAME, if set, otherwise, it is "egm96-5". The + * Geoid class does not use this function; it is just provided as a + * convenience for a calling program when constructing a Geoid object. **********************************************************************/ static System::String^ DefaultGeoidName(); }; diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Georef.cpp b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Georef.cpp new file mode 100644 index 000000000..f42e1aafe --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Georef.cpp @@ -0,0 +1,57 @@ +/** + * \file NETGeographicLib/Georef.cpp + * \brief Source for NETGeographicLib::Georef class + * + * NETGeographicLib is copyright (c) Scott Heiman (2013-2015) + * GeographicLib is Copyright (c) Charles Karney (2010-2012) + * and licensed under the MIT/X11 License. + * For more information, see + * https://geographiclib.sourceforge.io/ + **********************************************************************/ +#include "stdafx.h" +#include "GeographicLib/Georef.hpp" +#include "Georef.h" +#include "NETGeographicLib.h" + +using namespace NETGeographicLib; + +//***************************************************************************** +void Georef::Forward(double lat, double lon, int prec, System::String^% georef) +{ + try + { + std::string l; + GeographicLib::Georef::Forward( lat, lon, prec, l ); + georef = gcnew System::String( l.c_str() ); + } + catch ( const std::exception& xcpt ) + { + throw gcnew GeographicErr( xcpt.what() ); + } +} + +//***************************************************************************** +void Georef::Reverse( System::String^ georef, double% lat, double% lon, + int% prec, bool centerp) +{ + try + { + double llat, llon; + int lprec; + GeographicLib::Georef::Reverse( StringConvert::ManagedToUnmanaged( georef ), + llat, llon, lprec, centerp ); + lat = llat; + lon = llon; + prec = lprec; + } + catch ( const std::exception& err ) + { + throw gcnew GeographicErr( err.what() ); + } +} + +//***************************************************************************** +double Georef::Resolution(int prec) { return GeographicLib::Georef::Resolution(prec); } + +//***************************************************************************** +int Georef::Precision(double res) { return GeographicLib::Georef::Precision(res); } diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Georef.h b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Georef.h new file mode 100644 index 000000000..404fdbf93 --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Georef.h @@ -0,0 +1,119 @@ +/** + * \file NETGeographicLib/Georef.h + * \brief Header for NETGeographicLib::Georef class + * + * NETGeographicLib is copyright (c) Scott Heiman (2013-2015) + * GeographicLib is Copyright (c) Charles Karney (2010-2012) + * and licensed under the MIT/X11 License. + * For more information, see + * https://geographiclib.sourceforge.io/ + **********************************************************************/ +#pragma once + +namespace NETGeographicLib +{ + /** + * \brief .NET wrapper for GeographicLib::Georef. + * + * The World Geographic Reference System is described in + * - https://en.wikipedia.org/wiki/Georef + * - http://earth-info.nga.mil/GandG/coordsys/grids/georef.pdf + * . + * It provides a compact string representation of a geographic area + * (expressed as latitude and longitude). The classes GARS and Geohash + * implement similar compact representations. + * + * C# Example: + * \include example-Georef.cs + * Managed C++ Example: + * \include example-Georef.cpp + * Visual Basic Example: + * \include example-Georef.vb + **********************************************************************/ + public ref class Georef + { + private: + // hide the constructor since all members of this class are static. + Georef() {} + + public: + /** + * Convert from geographic coordinates to georef. + * + * @param[in] lat latitude of point (degrees). + * @param[in] lon longitude of point (degrees). + * @param[in] prec the precision of the resulting georef. + * @param[out] georef the georef string. + * @exception GeographicErr if \e lat is not in [−90°, + * 90°] or if memory for \e georef can't be allocated. + * + * \e prec specifies the precision of \e georef as follows: + * - \e prec = −1 (min), 15° + * - \e prec = 0, 1° + * - \e prec = 1, converted to \e prec = 2 + * - \e prec = 2, 1' + * - \e prec = 3, 0.1' + * - \e prec = 4, 0.01' + * - \e prec = 5, 0.001' + * - … + * - \e prec = 11 (max), 10−9' + * + * If \e lat or \e lon is NaN, then \e georef is set to "INVALID". + **********************************************************************/ + static void Forward(double lat, double lon, int prec, + [System::Runtime::InteropServices::Out] System::String^% georef); + + /** + * Convert from Georef to geographic coordinates. + * + * @param[in] georef the Georef. + * @param[out] lat latitude of point (degrees). + * @param[out] lon longitude of point (degrees). + * @param[out] prec the precision of \e georef. + * @param[in] centerp if true (the default) return the center + * \e georef, otherwise return the south-west corner. + * @exception GeographicErr if \e georef is illegal. + * + * The case of the letters in \e georef is ignored. \e prec is in the + * range [−1, 11] and gives the precision of \e georef as follows: + * - \e prec = −1 (min), 15° + * - \e prec = 0, 1° + * - \e prec = 1, not returned + * - \e prec = 2, 1' + * - \e prec = 3, 0.1' + * - \e prec = 4, 0.01' + * - \e prec = 5, 0.001' + * - … + * - \e prec = 11 (max), 10−9' + * + * If the first 3 characters of \e georef are "INV", then \e lat and \e lon + * are set to NaN and \e prec is unchanged. + **********************************************************************/ + static void Reverse( System::String^ georef, + [System::Runtime::InteropServices::Out] double% lat, + [System::Runtime::InteropServices::Out] double% lon, + [System::Runtime::InteropServices::Out] int% prec, + bool centerp ); + + /** + * The angular resolution of a Georef. + * + * @param[in] prec the precision of the Georef. + * @return the latitude-longitude resolution (degrees). + * + * Internally, \e prec is first put in the range [−1, 11]. + **********************************************************************/ + static double Resolution(int prec); + + /** + * The Georef precision required to meet a given geographic resolution. + * + * @param[in] res the minimum of resolution in latitude and longitude + * (degrees). + * @return Georef precision. + * + * The returned length is in the range [0, 11]. + **********************************************************************/ + static int Precision(double res); + }; +} diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Gnomonic.cpp b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Gnomonic.cpp index 5cfee2807..c574c7bdc 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Gnomonic.cpp +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Gnomonic.cpp @@ -6,7 +6,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #include "stdafx.h" #include "GeographicLib/Gnomonic.hpp" @@ -49,7 +49,7 @@ Gnomonic::Gnomonic() { try { - m_pGnomonic = new GeographicLib::Gnomonic( GeographicLib::Geodesic::WGS84 ); + m_pGnomonic = new GeographicLib::Gnomonic( GeographicLib::Geodesic::WGS84() ); } catch ( std::bad_alloc ) { diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Gnomonic.h b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Gnomonic.h index 67ef1a798..8c193a847 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Gnomonic.h +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Gnomonic.h @@ -7,7 +7,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ namespace NETGeographicLib @@ -21,12 +21,12 @@ namespace NETGeographicLib * %Gnomonic projection centered at an arbitrary position \e C on the * ellipsoid. This projection is derived in Section 8 of * - C. F. F. Karney, - * + * * Algorithms for geodesics, * J. Geodesy 87, 43--55 (2013); - * DOI: + * DOI: * 10.1007/s00190-012-0578-z; - * addenda: + * addenda: * geod-addenda.html. * . * The projection of \e P is defined as follows: compute the geodesic line @@ -140,15 +140,15 @@ namespace NETGeographicLib * @param[out] azi azimuth of geodesic at point (degrees). * @param[out] rk reciprocal of azimuthal scale at point. * - * \e lat0 and \e lat should be in the range [−90°, 90°] and - * \e lon0 and \e lon should be in the range [−540°, 540°). - * The scale of the projection is 1/rk2 in the "radial" - * direction, \e azi clockwise from true north, and is 1/\e rk in the - * direction perpendicular to this. If the point lies "over the horizon", - * i.e., if \e rk ≤ 0, then NaNs are returned for \e x and \e y (the - * correct values are returned for \e azi and \e rk). A call to Forward - * followed by a call to Reverse will return the original (\e lat, \e lon) - * (to within roundoff) provided the point in not over the horizon. + * \e lat0 and \e lat should be in the range [−90°, 90°]. + * The scale of the projection is 1/rk2 in the + * "radial" direction, \e azi clockwise from true north, and is 1/\e rk + * in the direction perpendicular to this. If the point lies "over the + * horizon", i.e., if \e rk ≤ 0, then NaNs are returned for \e x and + * \e y (the correct values are returned for \e azi and \e rk). A call + * to Forward followed by a call to Reverse will return the original + * (\e lat, \e lon) (to within roundoff) provided the point in not over + * the horizon. **********************************************************************/ void Forward(double lat0, double lon0, double lat, double lon, [System::Runtime::InteropServices::Out] double% x, @@ -168,17 +168,16 @@ namespace NETGeographicLib * @param[out] azi azimuth of geodesic at point (degrees). * @param[out] rk reciprocal of azimuthal scale at point. * - * \e lat0 should be in the range [−90°, 90°] and \e - * lon0 should be in the range [−540°, 540°). \e lat - * will be in the range [−90°, 90°] and \e lon will - * be in the range [−180°, 180°). The scale of the - * projection is 1/\e rk2 in the "radial" direction, \e azi - * clockwise from true north, and is 1/\e rk in the direction perpendicular - * to this. Even though all inputs should return a valid \e lat and \e - * lon, it's possible that the procedure fails to converge for very large - * \e x or \e y; in this case NaNs are returned for all the output - * arguments. A call to Reverse followed by a call to Forward will return - * the original (\e x, \e y) (to roundoff). + * \e lat0 should be in the range [−90°, 90°]. \e lat + * will be in the range [−90°, 90°] and \e lon will be in + * the range [−180°, 180°). The scale of the projection + * is 1/\e rk2 in the "radial" direction, \e azi clockwise + * from true north, and is 1/\e rk in the direction perpendicular to + * this. Even though all inputs should return a valid \e lat and \e + * lon, it's possible that the procedure fails to converge for very + * large \e x or \e y; in this case NaNs are returned for all the + * output arguments. A call to Reverse followed by a call to Forward + * will return the original (\e x, \e y) (to roundoff). **********************************************************************/ void Reverse(double lat0, double lon0, double x, double y, [System::Runtime::InteropServices::Out] double% lat, diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/GravityCircle.cpp b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/GravityCircle.cpp index 3b155cd21..6ff85296b 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/GravityCircle.cpp +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/GravityCircle.cpp @@ -6,7 +6,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #include "stdafx.h" #include "GeographicLib/GravityCircle.hpp" diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/GravityCircle.h b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/GravityCircle.h index 8a789f6d5..fa7ce686e 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/GravityCircle.h +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/GravityCircle.h @@ -7,7 +7,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ namespace NETGeographicLib @@ -23,7 +23,10 @@ namespace NETGeographicLib * different longitudes to be evaluated rapidly. * * Use GravityModel::Circle to create a GravityCircle object. (The - * constructor for this class is for internal use only.) + * constructor for this class is private.) + * + * See \ref gravityparallel for an example of using GravityCircle (together + * with OpenMP) to speed up the computation of geoid heights. * * C# Example: * \include example-GravityCircle.cs diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/GravityModel.cpp b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/GravityModel.cpp index 7504a9de9..dfa2eface 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/GravityModel.cpp +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/GravityModel.cpp @@ -6,7 +6,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #include "stdafx.h" #include "GeographicLib/GravityModel.hpp" diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/GravityModel.h b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/GravityModel.h index b56d5f0e6..456e9a95a 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/GravityModel.h +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/GravityModel.h @@ -7,7 +7,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ namespace NETGeographicLib @@ -491,19 +491,18 @@ namespace NETGeographicLib /** * @return the default path for gravity model data files. * - * This is the value of the environment variable GRAVITY_PATH, if set; + * This is the value of the environment variable GEOGRAPHICLIB_GRAVITY_PATH, if set; * otherwise, it is $GEOGRAPHICLIB_DATA/gravity if the environment variable * GEOGRAPHICLIB_DATA is set; otherwise, it is a compile-time default * (/usr/local/share/GeographicLib/gravity on non-Windows systems and - * C:/Documents and Settings/All Users/Application - * Data/GeographicLib/gravity on Windows systems). + * C:/ProgramData/GeographicLib/gravity on Windows systems). **********************************************************************/ static System::String^ DefaultGravityPath(); /** * @return the default name for the gravity model. * - * This is the value of the environment variable GRAVITY_NAME, if set, + * This is the value of the environment variable GEOGRAPHICLIB_GRAVITY_NAME, if set, * otherwise, it is "egm96". The GravityModel class does not use * this function; it is just provided as a convenience for a calling * program when constructing a GravityModel object. diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/LambertConformalConic.cpp b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/LambertConformalConic.cpp index 42fd4cb8a..7c0085033 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/LambertConformalConic.cpp +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/LambertConformalConic.cpp @@ -6,7 +6,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #include "stdafx.h" #include "GeographicLib/LambertConformalConic.hpp" @@ -93,7 +93,7 @@ LambertConformalConic::LambertConformalConic() try { m_pLambertConformalConic = new GeographicLib::LambertConformalConic( - GeographicLib::LambertConformalConic::Mercator ); + GeographicLib::LambertConformalConic::Mercator() ); } catch ( std::bad_alloc ) { diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/LambertConformalConic.h b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/LambertConformalConic.h index 63fa877f6..4babd64b0 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/LambertConformalConic.h +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/LambertConformalConic.h @@ -7,7 +7,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ namespace NETGeographicLib @@ -77,8 +77,7 @@ namespace NETGeographicLib * * @param[in] a equatorial radius of ellipsoid (meters). * @param[in] f flattening of ellipsoid. Setting \e f = 0 gives a sphere. - * Negative \e f gives a prolate ellipsoid. If \e f > 1, set flattening - * to 1/\e f. + * Negative \e f gives a prolate ellipsoid. * @param[in] stdlat standard parallel (degrees), the circle of tangency. * @param[in] k0 scale on the standard parallel. * @exception GeographicErr if \e a, (1 − \e f ) \e a, or \e k0 is @@ -93,8 +92,7 @@ namespace NETGeographicLib * * @param[in] a equatorial radius of ellipsoid (meters). * @param[in] f flattening of ellipsoid. Setting \e f = 0 gives a sphere. - * Negative \e f gives a prolate ellipsoid. If \e f > 1, set flattening - * to 1/\e f. + * Negative \e f gives a prolate ellipsoid. * @param[in] stdlat1 first standard parallel (degrees). * @param[in] stdlat2 second standard parallel (degrees). * @param[in] k1 scale on the standard parallels. @@ -111,8 +109,7 @@ namespace NETGeographicLib * * @param[in] a equatorial radius of ellipsoid (meters). * @param[in] f flattening of ellipsoid. Setting \e f = 0 gives a sphere. - * Negative \e f gives a prolate ellipsoid. If \e f > 1, set flattening - * to 1/\e f. + * Negative \e f gives a prolate ellipsoid. * @param[in] sinlat1 sine of first standard parallel. * @param[in] coslat1 cosine of first standard parallel. * @param[in] sinlat2 sine of second standard parallel. @@ -173,14 +170,14 @@ namespace NETGeographicLib * @param[out] gamma meridian convergence at point (degrees). * @param[out] k scale of projection at point. * - * The latitude origin is given by LambertConformalConic::LatitudeOrigin(). - * No false easting or northing is added and \e lat should be in the range - * [−90°, 90°]; \e lon and \e lon0 should be in the - * range [−540°, 540°). The error in the projection - * is less than about 10 nm (10 nanometers), true distance, and the errors - * in the meridian convergence and scale are consistent with this. The - * values of \e x and \e y returned for points which project to infinity - * (i.e., one or both of the poles) will be large but finite. + * The latitude origin is given by + * LambertConformalConic::LatitudeOrigin(). No false easting or + * northing is added and \e lat should be in the range [−90°, + * 90°]. The error in the projection is less than about 10 nm (10 + * nanometers), true distance, and the errors in the meridian + * convergence and scale are consistent with this. The values of \e x + * and \e y returned for points which project to infinity (i.e., one or + * both of the poles) will be large but finite. **********************************************************************/ void Forward(double lon0, double lat, double lon, [System::Runtime::InteropServices::Out] double% x, @@ -199,13 +196,12 @@ namespace NETGeographicLib * @param[out] gamma meridian convergence at point (degrees). * @param[out] k scale of projection at point. * - * The latitude origin is given by LambertConformalConic::LatitudeOrigin(). - * No false easting or northing is added. \e lon0 should be in the range - * [−540°, 540°). The value of \e lon returned is in - * the range [−180°, 180°). The error in the - * projection is less than about 10 nm (10 nanometers), true distance, and - * the errors in the meridian convergence and scale are consistent with - * this. + * The latitude origin is given by + * LambertConformalConic::LatitudeOrigin(). No false easting or + * northing is added. The value of \e lon returned is in the range + * [−180°, 180°). The error in the projection is less + * than about 10 nm (10 nanometers), true distance, and the errors in + * the meridian convergence and scale are consistent with this. **********************************************************************/ void Reverse(double lon0, double x, double y, [System::Runtime::InteropServices::Out] double% lat, diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/LocalCartesian.cpp b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/LocalCartesian.cpp index 0bcb37b72..a3883ec7f 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/LocalCartesian.cpp +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/LocalCartesian.cpp @@ -6,7 +6,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #include "stdafx.h" #include "GeographicLib/LocalCartesian.hpp" @@ -51,7 +51,7 @@ LocalCartesian::LocalCartesian(double lat0, double lon0, double h0 ) try { m_pLocalCartesian = new GeographicLib::LocalCartesian( lat0, lon0, h0, - GeographicLib::Geocentric::WGS84 ); + GeographicLib::Geocentric::WGS84() ); } catch ( std::bad_alloc ) { @@ -81,7 +81,7 @@ LocalCartesian::LocalCartesian() try { m_pLocalCartesian = new GeographicLib::LocalCartesian( - GeographicLib::Geocentric::WGS84 ); + GeographicLib::Geocentric::WGS84() ); } catch ( std::bad_alloc ) { diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/LocalCartesian.h b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/LocalCartesian.h index 6f7c31386..d3891c4e7 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/LocalCartesian.h +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/LocalCartesian.h @@ -7,7 +7,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ namespace NETGeographicLib @@ -64,8 +64,7 @@ namespace NETGeographicLib * @param[in] earth Geocentric object for the transformation; default * Geocentric::WGS84. * - * \e lat0 should be in the range [−90°, 90°]; \e - * lon0 should be in the range [−540°, 540°). + * \e lat0 should be in the range [−90°, 90°]. **********************************************************************/ LocalCartesian(double lat0, double lon0, double h0, Geocentric^ earth ); @@ -77,8 +76,7 @@ namespace NETGeographicLib * @param[in] lon0 longitude at origin (degrees). * @param[in] h0 height above ellipsoid at origin (meters); default 0. * - * \e lat0 should be in the range [−90°, 90°]; \e - * lon0 should be in the range [−540°, 540°). + * \e lat0 should be in the range [−90°, 90°]. **********************************************************************/ LocalCartesian(double lat0, double lon0, double h0 ); @@ -112,8 +110,7 @@ namespace NETGeographicLib * @param[in] lon0 longitude at origin (degrees). * @param[in] h0 height above ellipsoid at origin (meters); default 0. * - * \e lat0 should be in the range [−90°, 90°]; \e - * lon0 should be in the range [−540°, 540°). + * \e lat0 should be in the range [−90°, 90°]. **********************************************************************/ void Reset(double lat0, double lon0, double h0 ); @@ -127,8 +124,7 @@ namespace NETGeographicLib * @param[out] y local cartesian coordinate (meters). * @param[out] z local cartesian coordinate (meters). * - * \e lat should be in the range [−90°, 90°]; \e lon - * should be in the range [−540°, 540°). + * \e lat should be in the range [−90°, 90°]. **********************************************************************/ void Forward(double lat, double lon, double h, [System::Runtime::InteropServices::Out] double% x, @@ -147,8 +143,7 @@ namespace NETGeographicLib * @param[out] z local cartesian coordinate (meters). * @param[out] M a 3 × 3 rotation matrix. * - * \e lat should be in the range [−90°, 90°]; \e lon - * should be in the range [−540°, 540°). + * \e lat should be in the range [−90°, 90°]. * * Let \e v be a unit vector located at (\e lat, \e lon, \e h). We can * express \e v as \e column vectors in one of two ways diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/MGRS.cpp b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/MGRS.cpp index 753a7f199..8d0babaa9 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/MGRS.cpp +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/MGRS.cpp @@ -6,7 +6,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #include "stdafx.h" #include "GeographicLib/MGRS.hpp" diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/MGRS.h b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/MGRS.h index e3c0a61c6..319094c49 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/MGRS.h +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/MGRS.h @@ -7,7 +7,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ namespace NETGeographicLib @@ -79,6 +79,7 @@ namespace NETGeographicLib * allocated. * * \e prec specifies the precision of the MGRS string as follows: + * - prec = −1 (min), only the grid zone is returned * - prec = 0 (min), 100 km * - prec = 1, 10 km * - prec = 2, 1 km @@ -114,7 +115,7 @@ namespace NETGeographicLib * them \e within the allowed range. (This includes reducing a southern * hemisphere northing of 10000 km by 4 nm so that it is placed in latitude * band M.) The UTM or UPS coordinates are truncated to requested - * precision to determine the MGRS coordinate. Thus in UTM zone 38N, the + * precision to determine the MGRS coordinate. Thus in UTM zone 38n, the * square area with easting in [444 km, 445 km) and northing in [3688 km, * 3689 km) maps to MGRS coordinate 38SMB4488 (at \e prec = 2, 1 km), * Khulani Sq., Baghdad. @@ -131,6 +132,11 @@ namespace NETGeographicLib * of a band boundary. For prec in [6, 11], the conversion is accurate to * roundoff. * + * If \e prec = −1, then the "grid zone designation", e.g., 18T, is + * returned. This consists of the UTM zone number (absent for UPS) and the + * first letter of the MGRS string which labels the latitude band for UTM + * and the hemisphere for UPS. + * * If \e x or \e y is NaN or if \e zone is UTMUPS::INVALID, the returned * MGRS string is "INVALID". * @@ -157,6 +163,7 @@ namespace NETGeographicLib * allowed range. * @exception GeographicErr if \e lat is inconsistent with the given UTM * coordinates. + * @exception std::bad_alloc if the memory for \e mgrs can't be allocated. * * The latitude is ignored for \e zone = 0 (UPS); otherwise the latitude is * used to determine the latitude band and this is checked for consistency @@ -199,8 +206,15 @@ namespace NETGeographicLib * centerp = true the conversion from MGRS to geographic and back is * stable. This is not assured if \e centerp = false. * + * If a "grid zone designation" (for example, 18T or A) is given, then some + * suitable (but essentially arbitrary) point within that grid zone is + * returned. The main utility of the conversion is to allow \e zone and \e + * northp to be determined. In this case, the \e centerp parameter is + * ignored and \e prec is set to −1. + * * If the first 3 characters of \e mgrs are "INV", then \e x and \e y are - * set to NaN and \e zone is set to UTMUPS::INVALID. + * set to NaN, \e zone is set to UTMUPS::INVALID, and \e prec is set to + * −2. * * If an exception is thrown, then the arguments are unchanged. **********************************************************************/ diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/MagneticCircle.cpp b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/MagneticCircle.cpp index bef0ff095..4fdd5572b 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/MagneticCircle.cpp +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/MagneticCircle.cpp @@ -6,7 +6,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #include "stdafx.h" #include "GeographicLib/MagneticCircle.hpp" diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/MagneticCircle.h b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/MagneticCircle.h index a60298e26..cec853604 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/MagneticCircle.h +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/MagneticCircle.h @@ -7,7 +7,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ namespace NETGeographicLib diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/MagneticModel.cpp b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/MagneticModel.cpp index cfa1cb913..0b6be215c 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/MagneticModel.cpp +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/MagneticModel.cpp @@ -6,7 +6,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #include "stdafx.h" #include "GeographicLib/MagneticModel.hpp" @@ -72,7 +72,7 @@ MagneticModel::MagneticModel(System::String^ name, m_pMagneticModel = new GeographicLib::MagneticModel( StringConvert::ManagedToUnmanaged( name ), StringConvert::ManagedToUnmanaged( path ), - GeographicLib::Geocentric::WGS84 ); + GeographicLib::Geocentric::WGS84() ); } catch ( std::bad_alloc ) { diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/MagneticModel.h b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/MagneticModel.h index ff2d74e47..e0699689f 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/MagneticModel.h +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/MagneticModel.h @@ -7,7 +7,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ namespace NETGeographicLib @@ -34,6 +34,9 @@ namespace NETGeographicLib * - WMM2010: * - http://ngdc.noaa.gov/geomag/WMM/DoDWMM.shtml * - http://ngdc.noaa.gov/geomag/WMM/data/WMM2010/WMM2010COF.zip + * - WMM2015: + * - http://ngdc.noaa.gov/geomag/WMM/DoDWMM.shtml + * - http://ngdc.noaa.gov/geomag/WMM/data/WMM2015/WMM2015COF.zip * - IGRF11: * - http://ngdc.noaa.gov/IAGA/vmod/igrf.html * - http://ngdc.noaa.gov/IAGA/vmod/igrf11coeffs.txt @@ -343,22 +346,23 @@ namespace NETGeographicLib /** * @return the default path for magnetic model data files. * - * This is the value of the environment variable MAGNETIC_PATH, if set; - * otherwise, it is $GEOGRAPHICLIB_DATA/magnetic if the environment - * variable GEOGRAPHICLIB_DATA is set; otherwise, it is a compile-time - * default (/usr/local/share/GeographicLib/magnetic on non-Windows systems - * and C:/Documents and Settings/All Users/Application - * Data/GeographicLib/magnetic on Windows systems). + * This is the value of the environment variable + * GEOGRAPHICLIB_MAGNETIC_PATH, if set; otherwise, it is + * $GEOGRAPHICLIB_DATA/magnetic if the environment variable + * GEOGRAPHICLIB_DATA is set; otherwise, it is a compile-time default + * (/usr/local/share/GeographicLib/magnetic on non-Windows systems and + * C:/ProgramData/GeographicLib/magnetic on Windows systems). **********************************************************************/ static System::String^ DefaultMagneticPath(); /** * @return the default name for the magnetic model. * - * This is the value of the environment variable MAGNETIC_NAME, if set, - * otherwise, it is "wmm2010". The MagneticModel class does not use this - * function; it is just provided as a convenience for a calling program - * when constructing a MagneticModel object. + * This is the value of the environment variable + * GEOGRAPHICLIB_MAGNETIC_NAME, if set, otherwise, it is "wmm2015". + * The MagneticModel class does not use this function; it is just + * provided as a convenience for a calling program when constructing a + * MagneticModel object. **********************************************************************/ static System::String^ DefaultMagneticName(); }; diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/NETGeographicLib.cpp b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/NETGeographicLib.cpp index 001109a38..cbd31b3d6 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/NETGeographicLib.cpp +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/NETGeographicLib.cpp @@ -6,10 +6,11 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #include "stdafx.h" #include "GeographicLib/Config.h" +#include "GeographicLib/Utility.hpp" #include "NETGeographicLib.h" using namespace System::Runtime::InteropServices; @@ -47,3 +48,10 @@ int VersionInfo::Patch() { return GEOGRAPHICLIB_VERSION_PATCH; } + +//***************************************************************************** +double Utility::FractionalYear( System::String^ s ) +{ + return GeographicLib::Utility::fractionalyear( + StringConvert::ManagedToUnmanaged( s ) ); +} diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/NETGeographicLib.h b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/NETGeographicLib.h index 720af11e6..3594d512b 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/NETGeographicLib.h +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/NETGeographicLib.h @@ -7,7 +7,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #include @@ -23,7 +23,9 @@ namespace NETGeographicLib CAP_C3 = 1U<<3, CAP_C4 = 1U<<4, CAP_ALL = 0x1FU, + CAP_MASK = CAP_ALL, OUT_ALL = 0x7F80U, + OUT_MASK = 0xFF80U, }; /** @@ -86,6 +88,11 @@ namespace NETGeographicLib * @hideinitializer **********************************************************************/ AREA = 1U<<14 | unsigned(captype::CAP_C4), + /** + * Do not wrap the \e lon2 in the direct calculation. + * @hideinitializer + **********************************************************************/ + LONG_UNROLL = 1U<<15, /** * All capabilities, calculate everything. * @hideinitializer @@ -253,4 +260,31 @@ namespace NETGeographicLib static property double J2 { double get() { return m_J2; } } }; }; + + /** + * @brief Utility library. + * + * This class only exposes the GeographicLib::Utility::fractionalyear + * function. + **********************************************************************/ + public ref class Utility + { + private: + // hide the constructor since all members of this class are static + Utility() {} + public: + /** + * Convert a string representing a date to a fractional year. + * + * @param[in] s the string to be converted. + * @exception GeographicErr if \e s can't be interpreted as a date. + * @return the fractional year. + * + * The string is first read as an ordinary number (e.g., 2010 or 2012.5); + * if this is successful, the value is returned. Otherwise the string + * should be of the form yyyy-mm or yyyy-mm-dd and this is converted to a + * number with 2010-01-01 giving 2010.0 and 2012-07-03 giving 2012.5. + **********************************************************************/ + static double FractionalYear( System::String^ s ); + }; } // namespace NETGeographicLib diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/NormalGravity.cpp b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/NormalGravity.cpp index b693eea36..d9cd0e8bc 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/NormalGravity.cpp +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/NormalGravity.cpp @@ -6,7 +6,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #include "stdafx.h" #include "GeographicLib/NormalGravity.hpp" @@ -29,11 +29,11 @@ NormalGravity::!NormalGravity(void) } //***************************************************************************** -NormalGravity::NormalGravity(double a, double GM, double omega, double f, double J2) +NormalGravity::NormalGravity(double a, double GM, double omega, double f_J2, bool geometricp) { try { - m_pNormalGravity = new GeographicLib::NormalGravity( a, GM, omega, f, J2 ); + m_pNormalGravity = new GeographicLib::NormalGravity( a, GM, omega, f_J2, geometricp ); } catch ( std::bad_alloc ) { @@ -51,8 +51,8 @@ NormalGravity::NormalGravity(StandardModels model) try { m_pNormalGravity = model == StandardModels::WGS84 ? - new GeographicLib::NormalGravity( GeographicLib::NormalGravity::WGS84 ) : - new GeographicLib::NormalGravity( GeographicLib::NormalGravity::GRS80 ); + new GeographicLib::NormalGravity( GeographicLib::NormalGravity::WGS84() ) : + new GeographicLib::NormalGravity( GeographicLib::NormalGravity::GRS80() ); } catch ( std::bad_alloc ) { @@ -172,3 +172,29 @@ double NormalGravity::GravityFlattening::get() //***************************************************************************** double NormalGravity::SurfacePotential::get() { return m_pNormalGravity->SurfacePotential(); } + +//***************************************************************************** +NormalGravity^ NormalGravity::WGS84() +{ + return gcnew NormalGravity( StandardModels::WGS84 ); +} + +//***************************************************************************** +NormalGravity^ NormalGravity::GRS80() +{ + return gcnew NormalGravity( StandardModels::GRS80 ); +} + +//***************************************************************************** +double NormalGravity::J2ToFlattening(double a, double GM, double omega, + double J2) +{ + return GeographicLib::NormalGravity::J2ToFlattening( a, GM, omega, J2); +} + +//***************************************************************************** +double NormalGravity::FlatteningToJ2(double a, double GM, double omega, + double f) +{ + return GeographicLib::NormalGravity::FlatteningToJ2( a, GM, omega, f); +} diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/NormalGravity.h b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/NormalGravity.h index 2deeecbec..0eab35309 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/NormalGravity.h +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/NormalGravity.h @@ -7,7 +7,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ namespace NETGeographicLib @@ -51,7 +51,7 @@ namespace NETGeographicLib * - W. A. Heiskanen and H. Moritz, Physical Geodesy (Freeman, San * Francisco, 1967), Secs. 1-19, 2-7, 2-8 (2-9, 2-10), 6-2 (6-3). * - H. Moritz, Geodetic Reference System 1980, J. Geodesy 54(3), 395-405 - * (1980) http://dx.doi.org/10.1007/BF02521480 + * (1980) https://doi.org/10.1007/BF02521480 * * C# Example: * \include example-NormalGravity.cs @@ -96,23 +96,29 @@ namespace NETGeographicLib * the gravitational constant and \e M the mass of the earth (usually * including the mass of the earth's atmosphere). * @param[in] omega the angular velocity (rad s−1). - * @param[in] f the flattening of the ellipsoid. - * @param[in] J2 dynamical form factor. - * @exception if \e a is not positive or the other constants are - * inconsistent (see below). + * @param[in] f_J2 either the flattening of the ellipsoid \e f or the + * the dynamical form factor \e J2. + * @param[out] geometricp if true, then \e f_J2 denotes the + * flattening, else it denotes the dynamical form factor \e J2. + * @exception if \e a is not positive or if the other parameters do not + * obey the restrictions given below. * - * Exactly one of \e f and \e J2 should be positive and this will be used - * to define the ellipsoid. The shape of the ellipsoid can be given in one - * of two ways: - * - geometrically, the ellipsoid is defined by the flattening \e f = (\e a - * − \e b) / \e a, where \e a and \e b are the equatorial radius - * and the polar semi-axis. - * - physically, the ellipsoid is defined by the dynamical form factor - * J2 = (\e C − \e A) / Ma2, - * where \e A and \e C are the equatorial and polar moments of inertia - * and \e M is the mass of the earth. + * The shape of the ellipsoid can be given in one of two ways: + * - geometrically (\e geomtricp = true), the ellipsoid is defined by the + * flattening \e f = (\e a − \e b) / \e a, where \e a and \e b are + * the equatorial radius and the polar semi-axis. The parameters should + * obey \e a > 0, \e f < 1. There are no restrictions on \e GM or + * \e omega, in particular, \e GM need not be positive. + * - physically (\e geometricp = false), the ellipsoid is defined by the + * dynamical form factor J2 = (\e C − \e A) / + * Ma2, where \e A and \e C are the equatorial and + * polar moments of inertia and \e M is the mass of the earth. The + * parameters should obey \e a > 0, \e GM > 0 and \e J2 < 1/3 + * − (omega2a3/GM) + * 8/(45π). There is no restriction on \e omega. **********************************************************************/ - NormalGravity(double a, double GM, double omega, double f, double J2); + NormalGravity(double a, double GM, double omega, double f_J2, + bool geometricp); /** * A constructor for creating standard gravity models.. @@ -315,5 +321,45 @@ namespace NETGeographicLib **********************************************************************/ Geocentric^ Earth(); ///@} + + /** + * A global instantiation of NormalGravity for the WGS84 ellipsoid. + **********************************************************************/ + static NormalGravity^ WGS84(); + + /** + * A global instantiation of NormalGravity for the GRS80 ellipsoid. + **********************************************************************/ + static NormalGravity^ GRS80(); + + /** + * Compute the flattening from the dynamical form factor. + * + * @param[in] a equatorial radius (meters). + * @param[in] GM mass constant of the ellipsoid + * (meters3/seconds2); this is the product of \e G + * the gravitational constant and \e M the mass of the earth (usually + * including the mass of the earth's atmosphere). + * @param[in] omega the angular velocity (rad s−1). + * @param[in] J2 the dynamical form factor. + * @return \e f the flattening of the ellipsoid. + **********************************************************************/ + static double J2ToFlattening(double a, double GM, double omega, + double J2); + + /** + * Compute the dynamical form factor from the flattening. + * + * @param[in] a equatorial radius (meters). + * @param[in] GM mass constant of the ellipsoid + * (meters3/seconds2); this is the product of \e G + * the gravitational constant and \e M the mass of the earth (usually + * including the mass of the earth's atmosphere). + * @param[in] omega the angular velocity (rad s−1). + * @param[in] f the flattening of the ellipsoid. + * @return \e J2 the dynamical form factor. + **********************************************************************/ + static double FlatteningToJ2(double a, double GM, double omega, + double f); }; } //namespace NETGeographicLib diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/OSGB.cpp b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/OSGB.cpp index 766398b94..5fa656279 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/OSGB.cpp +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/OSGB.cpp @@ -6,7 +6,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #include "stdafx.h" #include "GeographicLib/OSGB.hpp" diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/OSGB.h b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/OSGB.h index 6dcc754cd..a252b1d5a 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/OSGB.h +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/OSGB.h @@ -6,7 +6,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #pragma once @@ -55,8 +55,7 @@ namespace NETGeographicLib * @param[out] gamma meridian convergence at point (degrees). * @param[out] k scale of projection at point. * - * \e lat should be in the range [−90°, 90°]; \e lon - * should be in the range [−540°, 540°). + * \e lat should be in the range [−90°, 90°]. **********************************************************************/ static void Forward(double lat, double lon, [System::Runtime::InteropServices::Out] double% x, @@ -124,6 +123,8 @@ namespace NETGeographicLib * northing must be in the range [−500 km, 2000 km). These bounds * are consistent with rules for the letter designations for the grid * system. + * + * If \e x or \e y is NaN, the returned grid reference is "INVALID". **********************************************************************/ static void GridReference(double x, double y, int prec, [System::Runtime::InteropServices::Out] System::String^% gridref); @@ -141,6 +142,9 @@ namespace NETGeographicLib * * The grid reference must be of the form: two letters (not including I) * followed by an even number of digits (up to 22). + * + * If the first 2 characters of \e gridref are "IN", then \e x and \e y are + * set to NaN and \e prec is set to −2. **********************************************************************/ static void GridReference(System::String^ gridref, [System::Runtime::InteropServices::Out] double% x, diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/PolarStereographic.cpp b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/PolarStereographic.cpp index f81b6ec74..d31a15040 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/PolarStereographic.cpp +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/PolarStereographic.cpp @@ -6,7 +6,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #include "stdafx.h" #include "GeographicLib/PolarStereographic.hpp" @@ -50,7 +50,7 @@ PolarStereographic::PolarStereographic() try { m_pPolarStereographic = new GeographicLib::PolarStereographic( - GeographicLib::PolarStereographic::UPS ); + GeographicLib::PolarStereographic::UPS() ); } catch (std::bad_alloc) { diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/PolarStereographic.h b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/PolarStereographic.h index 2dba46c3f..cc26dc714 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/PolarStereographic.h +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/PolarStereographic.h @@ -7,7 +7,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ namespace NETGeographicLib @@ -60,8 +60,7 @@ namespace NETGeographicLib * * @param[in] a equatorial radius (meters). * @param[in] f flattening of ellipsoid. Setting \e f = 0 gives a sphere. - * Negative \e f gives a prolate ellipsoid. If \e f > 1, set flattening - * to 1/\e f. + * Negative \e f gives a prolate ellipsoid. * @param[in] k0 central scale factor. * @exception GeographicErr if \e a, (1 − \e f ) \e a, or \e k0 is * not positive. @@ -105,8 +104,7 @@ namespace NETGeographicLib * * No false easting or northing is added. \e lat should be in the range * (−90°, 90°] for \e northp = true and in the range - * [−90°, 90°) for \e northp = false; \e lon should - * be in the range [−540°, 540°). + * [−90°, 90°) for \e northp = false. **********************************************************************/ void Forward(bool northp, double lat, double lon, [System::Runtime::InteropServices::Out] double% x, diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/PolygonArea.cpp b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/PolygonArea.cpp index 2a824c913..249c63b54 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/PolygonArea.cpp +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/PolygonArea.cpp @@ -6,12 +6,14 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #include "stdafx.h" #include "GeographicLib/PolygonArea.hpp" #include "PolygonArea.h" #include "Geodesic.h" +#include "GeodesicExact.h" +#include "Rhumb.h" #include "NETGeographicLib.h" using namespace NETGeographicLib; @@ -50,7 +52,7 @@ PolygonArea::PolygonArea(const bool polyline ) try { m_pPolygonArea = new GeographicLib::PolygonArea( - GeographicLib::Geodesic::WGS84, polyline ); + GeographicLib::Geodesic::WGS84(), polyline ); } catch (std::bad_alloc) { @@ -126,3 +128,227 @@ double PolygonArea::MajorRadius::get() //***************************************************************************** double PolygonArea::Flattening::get() { return m_pPolygonArea->Flattening(); } + +//***************************************************************************** +// PolygonAreaExact +//***************************************************************************** +PolygonAreaExact::!PolygonAreaExact(void) +{ + if ( m_pPolygonArea != NULL ) + { + delete m_pPolygonArea; + m_pPolygonArea = NULL; + } +} + +//***************************************************************************** +PolygonAreaExact::PolygonAreaExact(GeodesicExact^ earth, bool polyline ) +{ + try + { + const GeographicLib::GeodesicExact* pGeodesic = + reinterpret_cast( + earth->GetUnmanaged()->ToPointer() ); + m_pPolygonArea = new GeographicLib::PolygonAreaExact( *pGeodesic, polyline ); + } + catch (std::bad_alloc) + { + throw gcnew GeographicErr( BADALLOC ); + } +} + +//***************************************************************************** +PolygonAreaExact::PolygonAreaExact(const bool polyline ) +{ + try + { + m_pPolygonArea = new GeographicLib::PolygonAreaExact( + GeographicLib::GeodesicExact::WGS84(), polyline ); + } + catch (std::bad_alloc) + { + throw gcnew GeographicErr( BADALLOC ); + } +} + +//***************************************************************************** +void PolygonAreaExact::Clear() { m_pPolygonArea->Clear(); } + +//***************************************************************************** +void PolygonAreaExact::AddPoint(double lat, double lon) +{ + m_pPolygonArea->AddPoint( lat, lon ); +} + +//***************************************************************************** +void PolygonAreaExact::AddEdge(double azi, double s) +{ + m_pPolygonArea->AddEdge( azi, s ); +} + +//***************************************************************************** +unsigned PolygonAreaExact::Compute(bool reverse, bool sign, + [System::Runtime::InteropServices::Out] double% perimeter, + [System::Runtime::InteropServices::Out] double% area) +{ + double lperimeter, larea; + unsigned out = m_pPolygonArea->Compute( reverse, sign, lperimeter, larea ); + perimeter = lperimeter; + area = larea; + return out; +} + +//***************************************************************************** +unsigned PolygonAreaExact::TestPoint(double lat, double lon, bool reverse, bool sign, + [System::Runtime::InteropServices::Out] double% perimeter, + [System::Runtime::InteropServices::Out] double% area) +{ + double lperimeter, larea; + unsigned out = m_pPolygonArea->TestPoint( lat, lon, reverse, sign, lperimeter, larea ); + perimeter = lperimeter; + area = larea; + return out; +} + +//***************************************************************************** +unsigned PolygonAreaExact::TestEdge(double azi, double s, bool reverse, bool sign, + [System::Runtime::InteropServices::Out] double% perimeter, + [System::Runtime::InteropServices::Out] double% area) +{ + double lperimeter, larea; + unsigned out = m_pPolygonArea->TestEdge( azi, s, reverse, sign, lperimeter, larea ); + perimeter = lperimeter; + area = larea; + return out; +} + +//***************************************************************************** +void PolygonAreaExact::CurrentPoint( + [System::Runtime::InteropServices::Out] double% lat, + [System::Runtime::InteropServices::Out] double% lon) +{ + double llat, llon; + m_pPolygonArea->CurrentPoint( llat, llon ); + lat = llat; + lon = llon; +} + +//***************************************************************************** +double PolygonAreaExact::MajorRadius::get() +{ return m_pPolygonArea->MajorRadius(); } + +//***************************************************************************** +double PolygonAreaExact::Flattening::get() +{ return m_pPolygonArea->Flattening(); } + +//***************************************************************************** +// PolygonAreaRhumb +//***************************************************************************** +PolygonAreaRhumb::!PolygonAreaRhumb(void) +{ + if ( m_pPolygonArea != NULL ) + { + delete m_pPolygonArea; + m_pPolygonArea = NULL; + } +} + +//***************************************************************************** +PolygonAreaRhumb::PolygonAreaRhumb(Rhumb^ earth, bool polyline ) +{ + try + { + const GeographicLib::Rhumb* pGeodesic = + reinterpret_cast( + earth->GetUnmanaged()->ToPointer() ); + m_pPolygonArea = new GeographicLib::PolygonAreaRhumb( *pGeodesic, polyline ); + } + catch (std::bad_alloc) + { + throw gcnew GeographicErr( BADALLOC ); + } +} + +//***************************************************************************** +PolygonAreaRhumb::PolygonAreaRhumb(const bool polyline ) +{ + try + { + m_pPolygonArea = new GeographicLib::PolygonAreaRhumb( + GeographicLib::Rhumb::WGS84(), polyline ); + } + catch (std::bad_alloc) + { + throw gcnew GeographicErr( BADALLOC ); + } +} + +//***************************************************************************** +void PolygonAreaRhumb::Clear() { m_pPolygonArea->Clear(); } + +//***************************************************************************** +void PolygonAreaRhumb::AddPoint(double lat, double lon) +{ + m_pPolygonArea->AddPoint( lat, lon ); +} + +//***************************************************************************** +void PolygonAreaRhumb::AddEdge(double azi, double s) +{ + m_pPolygonArea->AddEdge( azi, s ); +} + +//***************************************************************************** +unsigned PolygonAreaRhumb::Compute(bool reverse, bool sign, + [System::Runtime::InteropServices::Out] double% perimeter, + [System::Runtime::InteropServices::Out] double% area) +{ + double lperimeter, larea; + unsigned out = m_pPolygonArea->Compute( reverse, sign, lperimeter, larea ); + perimeter = lperimeter; + area = larea; + return out; +} + +//***************************************************************************** +unsigned PolygonAreaRhumb::TestPoint(double lat, double lon, bool reverse, bool sign, + [System::Runtime::InteropServices::Out] double% perimeter, + [System::Runtime::InteropServices::Out] double% area) +{ + double lperimeter, larea; + unsigned out = m_pPolygonArea->TestPoint( lat, lon, reverse, sign, lperimeter, larea ); + perimeter = lperimeter; + area = larea; + return out; +} + +//***************************************************************************** +unsigned PolygonAreaRhumb::TestEdge(double azi, double s, bool reverse, bool sign, + [System::Runtime::InteropServices::Out] double% perimeter, + [System::Runtime::InteropServices::Out] double% area) +{ + double lperimeter, larea; + unsigned out = m_pPolygonArea->TestEdge( azi, s, reverse, sign, lperimeter, larea ); + perimeter = lperimeter; + area = larea; + return out; +} + +//***************************************************************************** +void PolygonAreaRhumb::CurrentPoint( + [System::Runtime::InteropServices::Out] double% lat, + [System::Runtime::InteropServices::Out] double% lon) +{ + double llat, llon; + m_pPolygonArea->CurrentPoint( llat, llon ); + lat = llat; + lon = llon; +} + +//***************************************************************************** +double PolygonAreaRhumb::MajorRadius::get() +{ return m_pPolygonArea->MajorRadius(); } + +//***************************************************************************** +double PolygonAreaRhumb::Flattening::get() +{ return m_pPolygonArea->Flattening(); } diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/PolygonArea.h b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/PolygonArea.h index febad8898..22292860e 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/PolygonArea.h +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/PolygonArea.h @@ -7,26 +7,26 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ namespace NETGeographicLib { ref class Geodesic; /** - * \brief .NET wrapper for GeographicLib::PolygonArea. + * \brief .NET wrapper for GeographicLib::PolygonArea and PolygonAreaExact. * * This class allows .NET applications to access GeographicLib::PolygonArea. * * This computes the area of a geodesic polygon using the method given * Section 6 of * - C. F. F. Karney, - * + * * Algorithms for geodesics, * J. Geodesy 87, 43--55 (2013); - * DOI: + * DOI: * 10.1007/s00190-012-0578-z; - * addenda: + * addenda: * geod-addenda.html. * * This class lets you add vertices one at a time to the polygon. The area @@ -90,8 +90,7 @@ namespace NETGeographicLib * @param[in] lat the latitude of the point (degrees). * @param[in] lon the longitude of the point (degrees). * - * \e lat should be in the range [−90°, 90°] and \e - * lon should be in the range [−540°, 540°). + * \e lat should be in the range [−90°, 90°]. **********************************************************************/ void AddPoint(double lat, double lon); @@ -101,9 +100,9 @@ namespace NETGeographicLib * @param[in] azi azimuth at current point (degrees). * @param[in] s distance from current point to next point (meters). * - * \e azi should be in the range [−540°, 540°). This does - * nothing if no points have been added yet. Use PolygonArea::CurrentPoint - * to determine the position of the new vertex. + * This does nothing if no points have been added yet. Use + * PolygonArea::CurrentPoint to determine the position of the new + * vertex. **********************************************************************/ void AddEdge(double azi, double s); @@ -148,8 +147,7 @@ namespace NETGeographicLib * constructor. * @return the number of points. * - * \e lat should be in the range [−90°, 90°] and \e - * lon should be in the range [−540°, 540°). + * \e lat should be in the range [−90°, 90°]. **********************************************************************/ unsigned TestPoint(double lat, double lon, bool reverse, bool sign, [System::Runtime::InteropServices::Out] double% perimeter, @@ -177,8 +175,342 @@ namespace NETGeographicLib * (meters2); only set if polyline is false in the * constructor. * @return the number of points. + **********************************************************************/ + unsigned TestEdge(double azi, double s, bool reverse, bool sign, + [System::Runtime::InteropServices::Out] double% perimeter, + [System::Runtime::InteropServices::Out] double% area); + + /** \name Inspector functions + **********************************************************************/ + ///@{ + /** + * @return \e a the equatorial radius of the ellipsoid (meters). This is + * the value inherited from the Geodesic object used in the constructor. + **********************************************************************/ + property double MajorRadius { double get(); } + + /** + * @return \e f the flattening of the ellipsoid. This is the value + * inherited from the Geodesic object used in the constructor. + **********************************************************************/ + property double Flattening { double get(); } + + /** + * Report the previous vertex added to the polygon or polyline. * - * \e azi should be in the range [−540°, 540°). + * @param[out] lat the latitude of the point (degrees). + * @param[out] lon the longitude of the point (degrees). + * + * If no points have been added, then NaNs are returned. Otherwise, \e lon + * will be in the range [−180°, 180°). + **********************************************************************/ + void CurrentPoint([System::Runtime::InteropServices::Out] double% lat, + [System::Runtime::InteropServices::Out] double% lon); + ///@} + }; + + //************************************************************************* + // PolygonAreaExact + //************************************************************************* + ref class GeodesicExact; + + public ref class PolygonAreaExact + { + private: + // a pointer to the unmanaged GeographicLib::PolygonArea + GeographicLib::PolygonAreaExact* m_pPolygonArea; + + // the finalize frees the unmanaged memory when the object is destroyed. + !PolygonAreaExact(void); + public: + + /** + * Constructor for PolygonArea. + * + * @param[in] earth the Geodesic object to use for geodesic calculations. + * @param[in] polyline if true that treat the points as defining a polyline + * instead of a polygon. + **********************************************************************/ + PolygonAreaExact(GeodesicExact^ earth, bool polyline ); + + /** + * Constructor for PolygonArea that assumes a WGS84 ellipsoid. + * + * @param[in] polyline if true that treat the points as defining a polyline + * instead of a polygon. + **********************************************************************/ + PolygonAreaExact(const bool polyline ); + + /** + * The destructor calls the finalizer. + **********************************************************************/ + ~PolygonAreaExact() + { this->!PolygonAreaExact(); } + + /** + * Clear PolygonArea, allowing a new polygon to be started. + **********************************************************************/ + void Clear(); + + /** + * Add a point to the polygon or polyline. + * + * @param[in] lat the latitude of the point (degrees). + * @param[in] lon the longitude of the point (degrees). + * + * \e lat should be in the range [−90°, 90°]. + **********************************************************************/ + void AddPoint(double lat, double lon); + + /** + * Add an edge to the polygon or polyline. + * + * @param[in] azi azimuth at current point (degrees). + * @param[in] s distance from current point to next point (meters). + * + * This does nothing if no points have been added yet. Use + * PolygonArea::CurrentPoint to determine the position of the new + * vertex. + **********************************************************************/ + void AddEdge(double azi, double s); + + /** + * Return the results so far. + * + * @param[in] reverse if true then clockwise (instead of counter-clockwise) + * traversal counts as a positive area. + * @param[in] sign if true then return a signed result for the area if + * the polygon is traversed in the "wrong" direction instead of returning + * the area for the rest of the earth. + * @param[out] perimeter the perimeter of the polygon or length of the + * polyline (meters). + * @param[out] area the area of the polygon (meters2); only set + * if \e polyline is false in the constructor. + * @return the number of points. + **********************************************************************/ + unsigned Compute(bool reverse, bool sign, + [System::Runtime::InteropServices::Out] double% perimeter, + [System::Runtime::InteropServices::Out] double% area); + + /** + * Return the results assuming a tentative final test point is added; + * however, the data for the test point is not saved. This lets you report + * a running result for the perimeter and area as the user moves the mouse + * cursor. Ordinary floating point arithmetic is used to accumulate the + * data for the test point; thus the area and perimeter returned are less + * accurate than if PolygonArea::AddPoint and PolygonArea::Compute are + * used. + * + * @param[in] lat the latitude of the test point (degrees). + * @param[in] lon the longitude of the test point (degrees). + * @param[in] reverse if true then clockwise (instead of counter-clockwise) + * traversal counts as a positive area. + * @param[in] sign if true then return a signed result for the area if + * the polygon is traversed in the "wrong" direction instead of returning + * the area for the rest of the earth. + * @param[out] perimeter the approximate perimeter of the polygon or length + * of the polyline (meters). + * @param[out] area the approximate area of the polygon + * (meters2); only set if polyline is false in the + * constructor. + * @return the number of points. + * + * \e lat should be in the range [−90°, 90°]. + **********************************************************************/ + unsigned TestPoint(double lat, double lon, bool reverse, bool sign, + [System::Runtime::InteropServices::Out] double% perimeter, + [System::Runtime::InteropServices::Out] double% area); + + /** + * Return the results assuming a tentative final test point is added via an + * azimuth and distance; however, the data for the test point is not saved. + * This lets you report a running result for the perimeter and area as the + * user moves the mouse cursor. Ordinary floating point arithmetic is used + * to accumulate the data for the test point; thus the area and perimeter + * returned are less accurate than if PolygonArea::AddEdge and + * PolygonArea::Compute are used. + * + * @param[in] azi azimuth at current point (degrees). + * @param[in] s distance from current point to final test point (meters). + * @param[in] reverse if true then clockwise (instead of counter-clockwise) + * traversal counts as a positive area. + * @param[in] sign if true then return a signed result for the area if + * the polygon is traversed in the "wrong" direction instead of returning + * the area for the rest of the earth. + * @param[out] perimeter the approximate perimeter of the polygon or length + * of the polyline (meters). + * @param[out] area the approximate area of the polygon + * (meters2); only set if polyline is false in the + * constructor. + * @return the number of points. + **********************************************************************/ + unsigned TestEdge(double azi, double s, bool reverse, bool sign, + [System::Runtime::InteropServices::Out] double% perimeter, + [System::Runtime::InteropServices::Out] double% area); + + /** \name Inspector functions + **********************************************************************/ + ///@{ + /** + * @return \e a the equatorial radius of the ellipsoid (meters). This is + * the value inherited from the Geodesic object used in the constructor. + **********************************************************************/ + property double MajorRadius { double get(); } + + /** + * @return \e f the flattening of the ellipsoid. This is the value + * inherited from the Geodesic object used in the constructor. + **********************************************************************/ + property double Flattening { double get(); } + + /** + * Report the previous vertex added to the polygon or polyline. + * + * @param[out] lat the latitude of the point (degrees). + * @param[out] lon the longitude of the point (degrees). + * + * If no points have been added, then NaNs are returned. Otherwise, \e lon + * will be in the range [−180°, 180°). + **********************************************************************/ + void CurrentPoint([System::Runtime::InteropServices::Out] double% lat, + [System::Runtime::InteropServices::Out] double% lon); + ///@} + }; + + //************************************************************************* + // PolygonAreaRhumb + //************************************************************************* + ref class Rhumb; + + public ref class PolygonAreaRhumb + { + private: + // a pointer to the unmanaged GeographicLib::PolygonArea + GeographicLib::PolygonAreaRhumb* m_pPolygonArea; + + // the finalize frees the unmanaged memory when the object is destroyed. + !PolygonAreaRhumb(void); + public: + + /** + * Constructor for PolygonArea. + * + * @param[in] earth the Geodesic object to use for geodesic calculations. + * @param[in] polyline if true that treat the points as defining a polyline + * instead of a polygon. + **********************************************************************/ + PolygonAreaRhumb(Rhumb^ earth, bool polyline ); + + /** + * Constructor for PolygonArea that assumes a WGS84 ellipsoid. + * + * @param[in] polyline if true that treat the points as defining a polyline + * instead of a polygon. + **********************************************************************/ + PolygonAreaRhumb(const bool polyline ); + + /** + * The destructor calls the finalizer. + **********************************************************************/ + ~PolygonAreaRhumb() + { this->!PolygonAreaRhumb(); } + + /** + * Clear PolygonArea, allowing a new polygon to be started. + **********************************************************************/ + void Clear(); + + /** + * Add a point to the polygon or polyline. + * + * @param[in] lat the latitude of the point (degrees). + * @param[in] lon the longitude of the point (degrees). + * + * \e lat should be in the range [−90°, 90°]. + **********************************************************************/ + void AddPoint(double lat, double lon); + + /** + * Add an edge to the polygon or polyline. + * + * @param[in] azi azimuth at current point (degrees). + * @param[in] s distance from current point to next point (meters). + * + * This does nothing if no points have been added yet. Use + * PolygonArea::CurrentPoint to determine the position of the new + * vertex. + **********************************************************************/ + void AddEdge(double azi, double s); + + /** + * Return the results so far. + * + * @param[in] reverse if true then clockwise (instead of counter-clockwise) + * traversal counts as a positive area. + * @param[in] sign if true then return a signed result for the area if + * the polygon is traversed in the "wrong" direction instead of returning + * the area for the rest of the earth. + * @param[out] perimeter the perimeter of the polygon or length of the + * polyline (meters). + * @param[out] area the area of the polygon (meters2); only set + * if \e polyline is false in the constructor. + * @return the number of points. + **********************************************************************/ + unsigned Compute(bool reverse, bool sign, + [System::Runtime::InteropServices::Out] double% perimeter, + [System::Runtime::InteropServices::Out] double% area); + + /** + * Return the results assuming a tentative final test point is added; + * however, the data for the test point is not saved. This lets you report + * a running result for the perimeter and area as the user moves the mouse + * cursor. Ordinary floating point arithmetic is used to accumulate the + * data for the test point; thus the area and perimeter returned are less + * accurate than if PolygonArea::AddPoint and PolygonArea::Compute are + * used. + * + * @param[in] lat the latitude of the test point (degrees). + * @param[in] lon the longitude of the test point (degrees). + * @param[in] reverse if true then clockwise (instead of counter-clockwise) + * traversal counts as a positive area. + * @param[in] sign if true then return a signed result for the area if + * the polygon is traversed in the "wrong" direction instead of returning + * the area for the rest of the earth. + * @param[out] perimeter the approximate perimeter of the polygon or length + * of the polyline (meters). + * @param[out] area the approximate area of the polygon + * (meters2); only set if polyline is false in the + * constructor. + * @return the number of points. + * + * \e lat should be in the range [−90°, 90°]. + **********************************************************************/ + unsigned TestPoint(double lat, double lon, bool reverse, bool sign, + [System::Runtime::InteropServices::Out] double% perimeter, + [System::Runtime::InteropServices::Out] double% area); + + /** + * Return the results assuming a tentative final test point is added via an + * azimuth and distance; however, the data for the test point is not saved. + * This lets you report a running result for the perimeter and area as the + * user moves the mouse cursor. Ordinary floating point arithmetic is used + * to accumulate the data for the test point; thus the area and perimeter + * returned are less accurate than if PolygonArea::AddEdge and + * PolygonArea::Compute are used. + * + * @param[in] azi azimuth at current point (degrees). + * @param[in] s distance from current point to final test point (meters). + * @param[in] reverse if true then clockwise (instead of counter-clockwise) + * traversal counts as a positive area. + * @param[in] sign if true then return a signed result for the area if + * the polygon is traversed in the "wrong" direction instead of returning + * the area for the rest of the earth. + * @param[out] perimeter the approximate perimeter of the polygon or length + * of the polyline (meters). + * @param[out] area the approximate area of the polygon + * (meters2); only set if polyline is false in the + * constructor. + * @return the number of points. **********************************************************************/ unsigned TestEdge(double azi, double s, bool reverse, bool sign, [System::Runtime::InteropServices::Out] double% perimeter, diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Rhumb.cpp b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Rhumb.cpp new file mode 100644 index 000000000..b235f6be9 --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Rhumb.cpp @@ -0,0 +1,237 @@ +/** + * \file NETGeographicLib/Rhumb.cpp + * \brief Implementation for NETGeographicLib::Rhumb and NETGeographicLib::RhumbLine class + * + * NETGeographicLib is copyright (c) Scott Heiman (2013) + * GeographicLib is Copyright (c) Charles Karney (2010-2012) + * and licensed under the MIT/X11 License. + * For more information, see + * https://geographiclib.sourceforge.io/ + **********************************************************************/ +#include "stdafx.h" +#include "GeographicLib/Rhumb.hpp" +#include "Rhumb.h" +#include "NETGeographicLib.h" + +using namespace NETGeographicLib; + +//***************************************************************************** +Rhumb::!Rhumb(void) +{ + if ( m_pRhumb != NULL ) + { + delete m_pRhumb; + m_pRhumb = NULL; + } +} + +//***************************************************************************** +Rhumb::Rhumb(double a, double f, bool exact) +{ + try + { + m_pRhumb = new GeographicLib::Rhumb( a, f, exact ); + } + catch ( GeographicLib::GeographicErr& err ) + { + throw gcnew GeographicErr( err.what() ); + } + catch ( std::bad_alloc ) + { + throw gcnew System::Exception("Failed to allocate memory for a Rhumb."); + } +} + +//***************************************************************************** +void Rhumb::Direct(double lat1, double lon1, double azi12, double s12, + [System::Runtime::InteropServices::Out] double% lat2, + [System::Runtime::InteropServices::Out] double% lon2, + [System::Runtime::InteropServices::Out] double% S12) +{ + double ilat2, ilon2, iS12; + m_pRhumb->Direct( lat1, lon1, azi12, s12, ilat2, ilon2, iS12 ); + lat2 = ilat2; + lon2 = ilon2; + S12 = iS12; +} + +//***************************************************************************** +void Rhumb::Direct(double lat1, double lon1, double azi12, double s12, + [System::Runtime::InteropServices::Out] double% lat2, + [System::Runtime::InteropServices::Out] double% lon2) +{ + double ilat2, ilon2; + m_pRhumb->Direct( lat1, lon1, azi12, s12, ilat2, ilon2 ); + lat2 = ilat2; + lon2 = ilon2; +} + +//***************************************************************************** +void Rhumb::GenDirect(double lat1, double lon1, double azi12, double s12, + Rhumb::mask outmask, + [System::Runtime::InteropServices::Out] double% lat2, + [System::Runtime::InteropServices::Out] double% lon2, + [System::Runtime::InteropServices::Out] double% S12) +{ + double ilat2, ilon2, iS12; + unsigned int iMask = (unsigned int)outmask; + m_pRhumb->GenDirect( lat1, lon1, azi12, s12, iMask, ilat2, ilon2, iS12 ); + lat2 = ilat2; + lon2 = ilon2; + S12 = iS12; +} + +//***************************************************************************** +void Rhumb::Inverse(double lat1, double lon1, double lat2, double lon2, + [System::Runtime::InteropServices::Out] double% s12, + [System::Runtime::InteropServices::Out] double% azi12, + [System::Runtime::InteropServices::Out] double% S12) +{ + double is12, iazi12, iS12; + m_pRhumb->Inverse( lat1, lon1, lat2, lon2, is12, iazi12, iS12 ); + s12 = is12; + azi12 = iazi12; + S12 = iS12; +} + +//***************************************************************************** +void Rhumb::Inverse(double lat1, double lon1, double lat2, double lon2, + [System::Runtime::InteropServices::Out] double% s12, + [System::Runtime::InteropServices::Out] double% azi12) +{ + double is12, iazi12; + m_pRhumb->Inverse( lat1, lon1, lat2, lon2, is12, iazi12 ); + s12 = is12; + azi12 = iazi12; +} + +//***************************************************************************** +void Rhumb::GenInverse(double lat1, double lon1, double lat2, double lon2, + Rhumb::mask outmask, + [System::Runtime::InteropServices::Out] double% s12, + [System::Runtime::InteropServices::Out] double% azi12, + [System::Runtime::InteropServices::Out] double% S12) +{ + double is12, iazi12, iS12; + unsigned int iMask = (unsigned int)outmask; + m_pRhumb->GenInverse( lat1, lon1, lat2, lon2, iMask, is12, iazi12, iS12 ); + s12 = is12; + azi12 = iazi12; + S12 = iS12; +} + +//***************************************************************************** +RhumbLine^ Rhumb::Line(double lat1, double lon1, double azi12) +{ + return gcnew RhumbLine( new GeographicLib::RhumbLine(m_pRhumb->Line( lat1, lon1, azi12 )) ); +} + +//***************************************************************************** +double Rhumb::MajorRadius::get() { return m_pRhumb->MajorRadius(); } + +//***************************************************************************** +double Rhumb::Flattening::get() { return m_pRhumb->Flattening(); } + +//***************************************************************************** +double Rhumb::EllipsoidArea::get() { return m_pRhumb->EllipsoidArea(); } + +//***************************************************************************** +Rhumb^ Rhumb::WGS84() +{ + return gcnew Rhumb( GeographicLib::Constants::WGS84_a(), + GeographicLib::Constants::WGS84_f(), false ); +} + +//***************************************************************************** +System::IntPtr^ Rhumb::GetUnmanaged() +{ + return gcnew System::IntPtr( const_cast(reinterpret_cast(m_pRhumb)) ); +} + +//***************************************************************************** +// RhumbLine functions +//***************************************************************************** +RhumbLine::!RhumbLine(void) +{ + if ( m_pRhumbLine != NULL ) + { + delete m_pRhumbLine; + m_pRhumbLine = NULL; + } +} + +//***************************************************************************** +RhumbLine::RhumbLine( GeographicLib::RhumbLine* pRhumbLine ) +{ + if ( pRhumbLine == NULL ) + throw gcnew System::Exception("Invalid pointer in RhumbLine constructor."); + m_pRhumbLine = pRhumbLine; +} + +//***************************************************************************** +void RhumbLine::Position(double s12, + [System::Runtime::InteropServices::Out] double% lat2, + [System::Runtime::InteropServices::Out] double% lon2, + [System::Runtime::InteropServices::Out] double% S12) +{ + double ilat2, ilon2, iS12; + m_pRhumbLine->Position( s12, ilat2, ilon2, iS12); + lat2 = ilat2; + lon2 = ilon2; + S12 = iS12; +} + +//***************************************************************************** +void RhumbLine::Position(double s12, + [System::Runtime::InteropServices::Out] double% lat2, + [System::Runtime::InteropServices::Out] double% lon2) +{ + double ilat2, ilon2; + m_pRhumbLine->Position( s12, ilat2, ilon2 ); + lat2 = ilat2; + lon2 = ilon2; +} + +//***************************************************************************** +void RhumbLine::GenPosition(double s12, RhumbLine::mask outmask, + [System::Runtime::InteropServices::Out] double% lat2, + [System::Runtime::InteropServices::Out] double% lon2, + [System::Runtime::InteropServices::Out] double% S12) +{ + double ilat2, ilon2, iS12; + unsigned int iMask = (unsigned int)outmask; + m_pRhumbLine->GenPosition( s12, iMask, ilat2, ilon2, iS12); + lat2 = ilat2; + lon2 = ilon2; + S12 = iS12; +} + +//***************************************************************************** +double RhumbLine::Latitude::get() +{ + return m_pRhumbLine->Latitude(); +} + +//***************************************************************************** +double RhumbLine::Longitude::get() +{ + return m_pRhumbLine->Longitude(); +} + +//***************************************************************************** +double RhumbLine::Azimuth::get() +{ + return m_pRhumbLine->Azimuth(); +} + +//***************************************************************************** +double RhumbLine::MajorRadius::get() +{ + return m_pRhumbLine->MajorRadius(); +} + +//***************************************************************************** +double RhumbLine::Flattening::get() +{ + return m_pRhumbLine->Flattening(); +} diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Rhumb.h b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Rhumb.h new file mode 100644 index 000000000..887e34367 --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/Rhumb.h @@ -0,0 +1,543 @@ +#pragma once +/** + * \file NETGeographicLib/Rhumb.h + * \brief Header for NETGeographicLib::Rhumb and NETGeographicLib::RhumbLine classes + * + * NETGeographicLib is copyright (c) Scott Heiman (2013) + * GeographicLib is Copyright (c) Charles Karney (2010-2012) + * and licensed under the MIT/X11 License. + * For more information, see + * https://geographiclib.sourceforge.io/ + **********************************************************************/ + +namespace NETGeographicLib { + + ref class RhumbLine; + + /** + * \brief .NET wrapper for GeographicLib::Rhumb. + * + * This class allows .NET applications to access GeographicLib::Rhumb. + * + * Solve of the direct and inverse rhumb problems. + * + * The path of constant azimuth between two points on a ellipsoid at (\e + * lat1, \e lon1) and (\e lat2, \e lon2) is called the rhumb line (also + * called the loxodrome). Its length is \e s12 and its azimuth is \e azi12. + * (The azimuth is the heading measured clockwise from north.) + * + * Given \e lat1, \e lon1, \e azi12, and \e s12, we can determine \e lat2, + * and \e lon2. This is the \e direct rhumb problem and its solution is + * given by the function Rhumb::Direct. + * + * Given \e lat1, \e lon1, \e lat2, and \e lon2, we can determine \e azi12 + * and \e s12. This is the \e inverse rhumb problem, whose solution is given + * by Rhumb::Inverse. This finds the shortest such rhumb line, i.e., the one + * that wraps no more than half way around the earth. If the end points are + * on opposite meridians, there are two shortest rhumb lines and the + * east-going one is chosen. + * + * These routines also optionally calculate the area under the rhumb line, \e + * S12. This is the area, measured counter-clockwise, of the rhumb line + * quadrilateral with corners (lat1,lon1), (0,lon1), + * (0,lon2), and (lat2,lon2). + * + * Note that rhumb lines may be appreciably longer (up to 50%) than the + * corresponding Geodesic. For example the distance between London Heathrow + * and Tokyo Narita via the rhumb line is 11400 km which is 18% longer than + * the geodesic distance 9600 km. + * + * For more information on rhumb lines see \ref rhumb. + * + * For more information on rhumb lines see \ref rhumb. + * + * C# Example: + * \include example-Rhumb.cs + * Managed C++ Example: + * \include example-Rhumb.cpp + * Visual Basic Example: + * \include example-Rhumb.vb + * + * INTERFACE DIFFERENCES:
+ * The MajorRadius and Flattening functions are implemented as properties. + **********************************************************************/ + + public ref class Rhumb { + private: + // pointer to the unmanaged Rhumb object + GeographicLib::Rhumb* m_pRhumb; + + // The finalizer destroys m_pRhumb when this object is destroyed. + !Rhumb(void); + public: + /** + * Bit masks for what calculations to do. They specify which results to + * return in the general routines Rhumb::GenDirect and Rhumb::GenInverse + * routines. RhumbLine::mask is a duplication of this enum. + **********************************************************************/ + enum class mask { + /** + * No output. + * @hideinitializer + **********************************************************************/ + NONE = 0U, + /** + * Calculate latitude \e lat2. + * @hideinitializer + **********************************************************************/ + LATITUDE = 1U<<7, + /** + * Calculate longitude \e lon2. + * @hideinitializer + **********************************************************************/ + LONGITUDE = 1U<<8, + /** + * Calculate azimuth \e azi12. + * @hideinitializer + **********************************************************************/ + AZIMUTH = 1U<<9, + /** + * Calculate distance \e s12. + * @hideinitializer + **********************************************************************/ + DISTANCE = 1U<<10, + /** + * Calculate area \e S12. + * @hideinitializer + **********************************************************************/ + AREA = 1U<<14, + /** + * Unroll \e lon2 in the direct calculation. + * @hideinitializer + **********************************************************************/ + LONG_UNROLL = 1U<<15, + /** + * Calculate everything. (LONG_UNROLL is not included in this mask.) + * @hideinitializer + **********************************************************************/ + ALL = 0x7F80U, + }; + + /** + * Constructor for a ellipsoid with + * + * @param[in] a equatorial radius (meters). + * @param[in] f flattening of ellipsoid. Setting \e f = 0 gives a sphere. + * Negative \e f gives a prolate ellipsoid. + * @param[in] exact if true (the default) use an addition theorem for + * elliptic integrals to compute divided differences; otherwise use + * series expansion (accurate for |f| < 0.01). + * @exception GeographicErr if \e a or (1 − \e f) \e a is not + * positive. + * + * See \ref rhumb, for a detailed description of the \e exact parameter. + **********************************************************************/ + Rhumb(double a, double f, bool exact); + + /** + * \brief The destructor calls the finalizer. + **********************************************************************/ + ~Rhumb() { this->!Rhumb(); } + + /** + * Solve the direct rhumb problem returning also the area. + * + * @param[in] lat1 latitude of point 1 (degrees). + * @param[in] lon1 longitude of point 1 (degrees). + * @param[in] azi12 azimuth of the rhumb line (degrees). + * @param[in] s12 distance between point 1 and point 2 (meters); it can be + * negative. + * @param[out] lat2 latitude of point 2 (degrees). + * @param[out] lon2 longitude of point 2 (degrees). + * @param[out] S12 area under the rhumb line (meters2). + * + * \e lat1 should be in the range [−90°, 90°]. The value of + * \e lon2 returned is in the range [−180°, 180°). + * + * If point 1 is a pole, the cosine of its latitude is taken to be + * 1/ε2 (where ε is 2-52). This + * position, which is extremely close to the actual pole, allows the + * calculation to be carried out in finite terms. If \e s12 is large + * enough that the rhumb line crosses a pole, the longitude of point 2 + * is indeterminate (a NaN is returned for \e lon2 and \e S12). + **********************************************************************/ + void Direct(double lat1, double lon1, double azi12, double s12, + [System::Runtime::InteropServices::Out] double% lat2, + [System::Runtime::InteropServices::Out] double% lon2, + [System::Runtime::InteropServices::Out] double% S12); + + /** + * Solve the direct rhumb problem without the area. + * + * @param[in] lat1 latitude of point 1 (degrees). + * @param[in] lon1 longitude of point 1 (degrees). + * @param[in] azi12 azimuth of the rhumb line (degrees). + * @param[in] s12 distance between point 1 and point 2 (meters); it can be + * negative. + * @param[out] lat2 latitude of point 2 (degrees). + * @param[out] lon2 longitude of point 2 (degrees). + * + * \e lat1 should be in the range [−90°, 90°]. The values of + * \e lon2 and \e azi2 returned are in the range [−180°, + * 180°). + * + * If point 1 is a pole, the cosine of its latitude is taken to be + * 1/ε2 (where ε is 2-52). This + * position, which is extremely close to the actual pole, allows the + * calculation to be carried out in finite terms. If \e s12 is large + * enough that the rhumb line crosses a pole, the longitude of point 2 + * is indeterminate (a NaN is returned for \e lon2). + **********************************************************************/ + void Direct(double lat1, double lon1, double azi12, double s12, + [System::Runtime::InteropServices::Out] double% lat2, + [System::Runtime::InteropServices::Out] double% lon2); + + /** + * The general direct rhumb problem. Rhumb::Direct is defined in terms + * of this function. + * + * @param[in] lat1 latitude of point 1 (degrees). + * @param[in] lon1 longitude of point 1 (degrees). + * @param[in] azi12 azimuth of the rhumb line (degrees). + * @param[in] s12 distance between point 1 and point 2 (meters); it can be + * negative. + * @param[in] outmask a bitor'ed combination of Rhumb::mask values + * specifying which of the following parameters should be set. + * @param[out] lat2 latitude of point 2 (degrees). + * @param[out] lon2 longitude of point 2 (degrees). + * @param[out] S12 area under the rhumb line (meters2). + * + * The Rhumb::mask values possible for \e outmask are + * - \e outmask |= Rhumb.LATITUDE for the latitude \e lat2; + * - \e outmask |= Rhumb.LONGITUDE for the latitude \e lon2; + * - \e outmask |= Rhumb.AREA for the area \e S12; + * - \e outmask |= Rhumb:.ALL for all of the above; + * - \e outmask |= Rhumb.LONG_UNROLL to unroll \e lon2 instead of + * wrapping it into the range [−180°, 180°). + * . + * With the LONG_UNROLL bit set, the quantity \e lon2 − \e lon1 + * indicates how many times the rhumb line wrapped around the ellipsoid. + **********************************************************************/ + void GenDirect(double lat1, double lon1, double azi12, double s12, + Rhumb::mask outmask, + [System::Runtime::InteropServices::Out] double% lat2, + [System::Runtime::InteropServices::Out] double% lon2, + [System::Runtime::InteropServices::Out] double% S12); + + /** + * Solve the inverse rhumb problem returning also the area. + * + * @param[in] lat1 latitude of point 1 (degrees). + * @param[in] lon1 longitude of point 1 (degrees). + * @param[in] lat2 latitude of point 2 (degrees). + * @param[in] lon2 longitude of point 2 (degrees). + * @param[out] s12 rhumb distance between point 1 and point 2 (meters). + * @param[out] azi12 azimuth of the rhumb line (degrees). + * @param[out] S12 area under the rhumb line (meters2). + * + * The shortest rhumb line is found. If the end points are on opposite + * meridians, there are two shortest rhumb lines and the east-going one is + * chosen. \e lat1 and \e lat2 should be in the range [−90°, + * 90°]. The value of \e azi12 returned is in the range + * [−180°, 180°). + * + * If either point is a pole, the cosine of its latitude is taken to be + * 1/ε2 (where ε is 2-52). This + * position, which is extremely close to the actual pole, allows the + * calculation to be carried out in finite terms. + **********************************************************************/ + void Inverse(double lat1, double lon1, double lat2, double lon2, + [System::Runtime::InteropServices::Out] double% s12, + [System::Runtime::InteropServices::Out] double% azi12, + [System::Runtime::InteropServices::Out] double% S12); + + /** + * Solve the inverse rhumb problem without the area. + * + * @param[in] lat1 latitude of point 1 (degrees). + * @param[in] lon1 longitude of point 1 (degrees). + * @param[in] lat2 latitude of point 2 (degrees). + * @param[in] lon2 longitude of point 2 (degrees). + * @param[out] s12 rhumb distance between point 1 and point 2 (meters). + * @param[out] azi12 azimuth of the rhumb line (degrees). + * + * The shortest rhumb line is found. \e lat1 and \e lat2 should be in the + * range [−90°, 90°]. The value of \e azi12 returned is in + * the range [−180°, 180°). + * + * If either point is a pole, the cosine of its latitude is taken to be + * 1/ε2 (where ε is 2-52). This + * position, which is extremely close to the actual pole, allows the + * calculation to be carried out in finite terms. + **********************************************************************/ + void Inverse(double lat1, double lon1, double lat2, double lon2, + [System::Runtime::InteropServices::Out] double% s12, + [System::Runtime::InteropServices::Out] double% azi12); + + /** + * The general inverse rhumb problem. Rhumb::Inverse is defined in terms + * of this function. + * + * @param[in] lat1 latitude of point 1 (degrees). + * @param[in] lon1 longitude of point 1 (degrees). + * @param[in] lat2 latitude of point 2 (degrees). + * @param[in] lon2 longitude of point 2 (degrees). + * @param[in] outmask a bitor'ed combination of Rhumb::mask values + * specifying which of the following parameters should be set. + * @param[out] s12 rhumb distance between point 1 and point 2 (meters). + * @param[out] azi12 azimuth of the rhumb line (degrees). + * @param[out] S12 area under the rhumb line (meters2). + * + * The Rhumb::mask values possible for \e outmask are + * - \e outmask |= Rhumb::DISTANCE for the latitude \e s12; + * - \e outmask |= Rhumb::AZIMUTH for the latitude \e azi12; + * - \e outmask |= Rhumb::AREA for the area \e S12; + * - \e outmask |= Rhumb::ALL for all of the above; + **********************************************************************/ + void GenInverse(double lat1, double lon1, double lat2, double lon2, + Rhumb::mask outmask, + [System::Runtime::InteropServices::Out] double% s12, + [System::Runtime::InteropServices::Out] double% azi12, + [System::Runtime::InteropServices::Out] double% S12); + + /** + * Set up to compute several points on a single rhumb line. + * + * @param[in] lat1 latitude of point 1 (degrees). + * @param[in] lon1 longitude of point 1 (degrees). + * @param[in] azi12 azimuth of the rhumb line (degrees). + * @return a RhumbLine object. + * + * \e lat1 should be in the range [−90°, 90°]. + * + * If point 1 is a pole, the cosine of its latitude is taken to be + * 1/ε2 (where ε is 2-52). This + * position, which is extremely close to the actual pole, allows the + * calculation to be carried out in finite terms. + **********************************************************************/ + RhumbLine^ Line(double lat1, double lon1, double azi12); + + /** \name Inspector functions. + **********************************************************************/ + ///@{ + + /** + * @return the equatorial radius of the ellipsoid (meters). This is + * the value used in the constructor. + **********************************************************************/ + property double MajorRadius { double get(); } + + /** + * @return f the flattening of the ellipsoid. This is the + * value used in the constructor. + **********************************************************************/ + property double Flattening { double get(); } + + /** + * @return the area of the ellipsoid. + **********************************************************************/ + property double EllipsoidArea { double get(); } + + /** + * %return The unmanaged pointer to the GeographicLib::Geodesic. + * + * This function is for internal use only. + **********************************************************************/ + System::IntPtr^ GetUnmanaged(); + + /** + * A global instantiation of Rhumb with the parameters for the WGS84 + * ellipsoid. + **********************************************************************/ + static Rhumb^ WGS84(); + }; + + /** + * \brief .NET wrapper for GeographicLib::RhumbLine. + * + * This class allows .NET applications to access GeographicLib::RhumbLine. + * + * Find a sequence of points on a single rhumb line. + * + * RhumbLine facilitates the determination of a series of points on a single + * rhumb line. The starting point (\e lat1, \e lon1) and the azimuth \e + * azi12 are specified in the call to Rhumb::Line which returns a RhumbLine + * object. RhumbLine.Position returns the location of point 2 a distance \e + * s12 along the rhumb line. + + * There is no public constructor for this class. (Use Rhumb::Line to create + * an instance.) The Rhumb object used to create a RhumbLine must stay in + * scope as long as the RhumbLine. + * + **********************************************************************/ + + public ref class RhumbLine { + private: + // pointer to the unmanaged RhumbLine object. + GeographicLib::RhumbLine* m_pRhumbLine; + + // The finalizer destroys m_pRhumbLine when this object is destroyed. + !RhumbLine(void); + public: + enum class mask { + /** + * No output. + * @hideinitializer + **********************************************************************/ + NONE = 0, //NETGeographicLib::Rhumb::NONE, + /** + * Calculate latitude \e lat2. + * @hideinitializer + **********************************************************************/ + LATITUDE = 1U<<7, //Rhumb::LATITUDE, + /** + * Calculate longitude \e lon2. + * @hideinitializer + **********************************************************************/ + LONGITUDE = 1U<<8, //Rhumb::LONGITUDE, + /** + * Calculate azimuth \e azi12. + * @hideinitializer + **********************************************************************/ + AZIMUTH = 1U<<9, //Rhumb::AZIMUTH, + /** + * Calculate distance \e s12. + * @hideinitializer + **********************************************************************/ + DISTANCE = 1U<<10, //Rhumb::DISTANCE, + /** + * Calculate area \e S12. + * @hideinitializer + **********************************************************************/ + AREA = 1U<<14, //Rhumb::AREA, + /** + * Unroll \e lon2 in the direct calculation. + * @hideinitializer + **********************************************************************/ + LONG_UNROLL = 1U<<15, //Rhumb::LONG_UNROLL, + /** + * Calculate everything. (LONG_UNROLL is not included in this mask.) + * @hideinitializer + **********************************************************************/ + ALL = 0x7F80U, //Rhumb::ALL, + }; + /** + * \brief Constructor. + * + * For internal use only. Developers should not call this constructor + * directly. Use the Rhumb::Line function to create RhumbLine objects. + **********************************************************************/ + RhumbLine( GeographicLib::RhumbLine* pRhumbLine ); + + /** + * \brief The destructor calls the finalizer. + **********************************************************************/ + ~RhumbLine() { this->!RhumbLine(); } + + /** + * Compute the position of point 2 which is a distance \e s12 (meters) from + * point 1. The area is also computed. + * + * @param[in] s12 distance between point 1 and point 2 (meters); it can be + * negative. + * @param[out] lat2 latitude of point 2 (degrees). + * @param[out] lon2 longitude of point 2 (degrees). + * @param[out] S12 area under the rhumb line (meters2). + * + * The value of \e lon2 returned is in the range [−180°, + * 180°). + * + * If \e s12 is large enough that the rhumb line crosses a pole, the + * longitude of point 2 is indeterminate (a NaN is returned for \e lon2 and + * \e S12). + **********************************************************************/ + void Position(double s12, + [System::Runtime::InteropServices::Out] double% lat2, + [System::Runtime::InteropServices::Out] double% lon2, + [System::Runtime::InteropServices::Out] double% S12); + + /** + * Compute the position of point 2 which is a distance \e s12 (meters) from + * point 1. + * + * @param[in] s12 distance between point 1 and point 2 (meters); it can be + * negative. + * @param[out] lat2 latitude of point 2 (degrees). + * @param[out] lon2 longitude of point 2 (degrees). + * + * The values of \e lon2 and \e azi2 returned are in the range + * [−180°, 180°). + * + * If \e s12 is large enough that the rhumb line crosses a pole, the + * longitude of point 2 is indeterminate (a NaN is returned for \e lon2). + **********************************************************************/ + void Position(double s12, + [System::Runtime::InteropServices::Out] double% lat2, + [System::Runtime::InteropServices::Out] double% lon2); + + /** + * The general position routine. RhumbLine::Position is defined in term so + * this function. + * + * @param[in] s12 distance between point 1 and point 2 (meters); it can be + * negative. + * @param[in] outmask a bitor'ed combination of RhumbLine::mask values + * specifying which of the following parameters should be set. + * @param[out] lat2 latitude of point 2 (degrees). + * @param[out] lon2 longitude of point 2 (degrees). + * @param[out] S12 area under the rhumb line (meters2). + * + * The RhumbLine::mask values possible for \e outmask are + * - \e outmask |= RhumbLine::LATITUDE for the latitude \e lat2; + * - \e outmask |= RhumbLine::LONGITUDE for the latitude \e lon2; + * - \e outmask |= RhumbLine::AREA for the area \e S12; + * - \e outmask |= RhumbLine::ALL for all of the above; + * - \e outmask |= RhumbLine::LONG_UNROLL to unroll \e lon2 instead of + * wrapping it into the range [−180°, 180°). + * . + * With the LONG_UNROLL bit set, the quantity \e lon2 − \e lon1 + * indicates how many times and in what sense the rhumb line encircles the + * ellipsoid. + * + * If \e s12 is large enough that the rhumb line crosses a pole, the + * longitude of point 2 is indeterminate (a NaN is returned for \e lon2 and + * \e S12). + **********************************************************************/ + void GenPosition(double s12, RhumbLine::mask outmask, + [System::Runtime::InteropServices::Out] double% lat2, + [System::Runtime::InteropServices::Out] double% lon2, + [System::Runtime::InteropServices::Out] double% S12); + + /** \name Inspector functions + **********************************************************************/ + ///@{ + + /** + * @return the latitude of point 1 (degrees). + **********************************************************************/ + property double Latitude { double get(); } + + /** + * @return the longitude of point 1 (degrees). + **********************************************************************/ + property double Longitude { double get(); } + + /** + * @return the azimuth of the rhumb line (degrees). + **********************************************************************/ + property double Azimuth { double get(); } + + /** + * @return the equatorial radius of the ellipsoid (meters). This is + * the value inherited from the Rhumb object used in the constructor. + **********************************************************************/ + property double MajorRadius { double get(); } + + /** + * @return the flattening of the ellipsoid. This is the value + * inherited from the Rhumb object used in the constructor. + **********************************************************************/ + property double Flattening { double get(); } + }; + +} // namespace NETGeographicLib diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/SphericalCoefficients.cpp b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/SphericalCoefficients.cpp index ec834ffa1..9c97bfdf8 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/SphericalCoefficients.cpp +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/SphericalCoefficients.cpp @@ -6,7 +6,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #include "stdafx.h" #include "GeographicLib/SphericalEngine.hpp" diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/SphericalCoefficients.h b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/SphericalCoefficients.h index c2727c6e1..8f1d38e40 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/SphericalCoefficients.h +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/SphericalCoefficients.h @@ -7,7 +7,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ namespace NETGeographicLib diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/SphericalHarmonic.cpp b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/SphericalHarmonic.cpp index 964609a8c..08a0e7239 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/SphericalHarmonic.cpp +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/SphericalHarmonic.cpp @@ -6,7 +6,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #include "stdafx.h" #include "GeographicLib/SphericalHarmonic.hpp" diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/SphericalHarmonic.h b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/SphericalHarmonic.h index 6bacb3a8b..2b1b214a1 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/SphericalHarmonic.h +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/SphericalHarmonic.h @@ -7,7 +7,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ namespace NETGeographicLib diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/SphericalHarmonic1.cpp b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/SphericalHarmonic1.cpp index 4308591f7..9ccb7f393 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/SphericalHarmonic1.cpp +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/SphericalHarmonic1.cpp @@ -6,7 +6,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #include "stdafx.h" #include "GeographicLib/SphericalHarmonic1.hpp" diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/SphericalHarmonic1.h b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/SphericalHarmonic1.h index c05a1b8ab..68c613690 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/SphericalHarmonic1.h +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/SphericalHarmonic1.h @@ -7,7 +7,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ namespace NETGeographicLib diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/SphericalHarmonic2.cpp b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/SphericalHarmonic2.cpp index b529359a3..b2e7ce189 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/SphericalHarmonic2.cpp +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/SphericalHarmonic2.cpp @@ -6,7 +6,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #include "stdafx.h" #include "GeographicLib/SphericalHarmonic2.hpp" diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/SphericalHarmonic2.h b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/SphericalHarmonic2.h index faffcae19..1e8d86ccf 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/SphericalHarmonic2.h +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/SphericalHarmonic2.h @@ -7,7 +7,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ namespace NETGeographicLib diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/TransverseMercator.cpp b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/TransverseMercator.cpp index ea559bc66..e79874909 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/TransverseMercator.cpp +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/TransverseMercator.cpp @@ -6,7 +6,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #include "stdafx.h" #include "GeographicLib/TransverseMercator.hpp" @@ -50,7 +50,7 @@ TransverseMercator::TransverseMercator() try { m_pTransverseMercator = new GeographicLib::TransverseMercator( - GeographicLib::TransverseMercator::UTM ); + GeographicLib::TransverseMercator::UTM() ); } catch (std::bad_alloc ) { diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/TransverseMercator.h b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/TransverseMercator.h index a18147c1e..07144fb85 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/TransverseMercator.h +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/TransverseMercator.h @@ -7,7 +7,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ namespace NETGeographicLib @@ -20,23 +20,23 @@ namespace NETGeographicLib * This uses Krüger's method which evaluates the projection and its * inverse in terms of a series. See * - L. Krüger, - * Konforme + * Konforme * Abbildung des Erdellipsoids in der Ebene (Conformal mapping of the * ellipsoidal earth to the plane), Royal Prussian Geodetic Institute, New * Series 52, 172 pp. (1912). * - C. F. F. Karney, - * + * * Transverse Mercator with an accuracy of a few nanometers, * J. Geodesy 85(8), 475--485 (Aug. 2011); * preprint - * arXiv:1002.1417. + * arXiv:1002.1417. * * Krüger's method has been extended from 4th to 6th order. The maximum * error is 5 nm (5 nanometers), ground distance, for all positions within 35 * degrees of the central meridian. The error in the convergence is 2 * × 10−15" and the relative error in the scale * is 6 − 10−12%%. See Sec. 4 of - * arXiv:1002.1417 for details. + * arXiv:1002.1417 for details. * The speed penalty in going to 6th order is only about 1%. * TransverseMercatorExact is an alternative implementation of the projection * using exact formulas which yield accurate (to 8 nm) results over the @@ -87,8 +87,7 @@ namespace NETGeographicLib * * @param[in] a equatorial radius (meters). * @param[in] f flattening of ellipsoid. Setting \e f = 0 gives a sphere. - * Negative \e f gives a prolate ellipsoid. If \e f > 1, set flattening - * to 1/\e f. + * Negative \e f gives a prolate ellipsoid. * @param[in] k0 central scale factor. * @exception GeographicErr if \e a, (1 − \e f ) \e a, or \e k0 is * not positive. @@ -119,8 +118,7 @@ namespace NETGeographicLib * @param[out] k scale of projection at point. * * No false easting or northing is added. \e lat should be in the range - * [−90°, 90°]; \e lon and \e lon0 should be in the - * range [−540°, 540°). + * [−90°, 90°]. **********************************************************************/ void Forward(double lon0, double lat, double lon, [System::Runtime::InteropServices::Out] double% x, @@ -139,9 +137,8 @@ namespace NETGeographicLib * @param[out] gamma meridian convergence at point (degrees). * @param[out] k scale of projection at point. * - * No false easting or northing is added. \e lon0 should be in the range - * [−540°, 540°). The value of \e lon returned is in - * the range [−180°, 180°). + * No false easting or northing is added. The value of \e lon returned + * is in the range [−180°, 180°). **********************************************************************/ void Reverse(double lon0, double x, double y, [System::Runtime::InteropServices::Out] double% lat, diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/TransverseMercatorExact.cpp b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/TransverseMercatorExact.cpp index 733c6d120..bbdc952fd 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/TransverseMercatorExact.cpp +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/TransverseMercatorExact.cpp @@ -6,7 +6,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #include "stdafx.h" #include "GeographicLib/TransverseMercatorExact.hpp" @@ -53,7 +53,7 @@ TransverseMercatorExact::TransverseMercatorExact() { m_pTransverseMercatorExact = new GeographicLib::TransverseMercatorExact( - GeographicLib::TransverseMercatorExact::UTM ); + GeographicLib::TransverseMercatorExact::UTM() ); } catch (std::bad_alloc) { diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/TransverseMercatorExact.h b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/TransverseMercatorExact.h index 26ebe58e8..3a5879d11 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/TransverseMercatorExact.h +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/TransverseMercatorExact.h @@ -7,7 +7,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ namespace NETGeographicLib @@ -19,7 +19,7 @@ namespace NETGeographicLib * * Implementation of the Transverse Mercator Projection given in * - L. P. Lee, - * Conformal + * Conformal * Projections Based On Jacobian Elliptic Functions, Part V of * Conformal Projections Based on Elliptic Functions, * (B. V. Gutsell, Toronto, 1976), 128pp., @@ -27,11 +27,11 @@ namespace NETGeographicLib * (also appeared as: * Monograph 16, Suppl. No. 1 to Canadian Cartographer, Vol 13). * - C. F. F. Karney, - * + * * Transverse Mercator with an accuracy of a few nanometers, * J. Geodesy 85(8), 475--485 (Aug. 2011); * preprint - * arXiv:1002.1417. + * arXiv:1002.1417. * * Lee gives the correct results for forward and reverse transformations * subject to the branch cut rules (see the description of the \e extendp @@ -40,7 +40,7 @@ namespace NETGeographicLib * The error in the convergence is 2 × 10−15", * the relative error in the scale is 7 × 10−12%%. * See Sec. 3 of - * arXiv:1002.1417 for details. + * arXiv:1002.1417 for details. * The method is "exact" in the sense that the errors are close to the * round-off limit and that no changes are needed in the algorithms for them * to be used with reals of a higher precision. Thus the errors using long @@ -58,7 +58,7 @@ namespace NETGeographicLib * taken to be the equator. See the documentation on TransverseMercator for * how to include a false easting, false northing, or a latitude of origin. * - * See tm-grid.kmz, for an * illustration of the transverse Mercator grid in Google Earth. * @@ -93,8 +93,7 @@ namespace NETGeographicLib * Constructor for a ellipsoid with * * @param[in] a equatorial radius (meters). - * @param[in] f flattening of ellipsoid. If \e f > 1, set flattening - * to 1/\e f. + * @param[in] f flattening of ellipsoid. * @param[in] k0 central scale factor. * @param[in] extendp use extended domain. * @exception GeographicErr if \e a, \e f, or \e k0 is not positive. @@ -129,7 +128,7 @@ namespace NETGeographicLib * a) in (−∞, 0] * . * See Sec. 5 of - * arXiv:1002.1417 for a full + * arXiv:1002.1417 for a full * discussion of the treatment of the branch cut. * * The method will work for all ellipsoids used in terrestrial geodesy. @@ -165,8 +164,7 @@ namespace NETGeographicLib * @param[out] k scale of projection at point. * * No false easting or northing is added. \e lat should be in the range - * [−90°, 90°]; \e lon and \e lon0 should be in the - * range [−540°, 540°). + * [−90°, 90°]. **********************************************************************/ void Forward(double lon0, double lat, double lon, [System::Runtime::InteropServices::Out] double% x, @@ -185,9 +183,8 @@ namespace NETGeographicLib * @param[out] gamma meridian convergence at point (degrees). * @param[out] k scale of projection at point. * - * No false easting or northing is added. \e lon0 should be in the range - * [−540°, 540°). The value of \e lon returned is in - * the range [−180°, 180°). + * No false easting or northing is added. The value of \e lon returned + * is in the range [−180°, 180°). **********************************************************************/ void Reverse(double lon0, double x, double y, [System::Runtime::InteropServices::Out] double% lat, diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/UTMUPS.cpp b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/UTMUPS.cpp index 307610cb8..890dfb145 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/UTMUPS.cpp +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/UTMUPS.cpp @@ -6,7 +6,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #include "stdafx.h" #include "GeographicLib/UTMUPS.hpp" @@ -175,11 +175,11 @@ void UTMUPS::DecodeZone(System::String^ zonestr, } //***************************************************************************** -System::String^ UTMUPS::EncodeZone(int zone, bool northp) +System::String^ UTMUPS::EncodeZone(int zone, bool northp, bool abbrev) { try { - return StringConvert::UnmanagedToManaged( GeographicLib::UTMUPS::EncodeZone( zone, northp ) ); + return StringConvert::UnmanagedToManaged( GeographicLib::UTMUPS::EncodeZone( zone, northp, abbrev ) ); } catch ( const std::exception& err ) { diff --git a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/UTMUPS.h b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/UTMUPS.h index 4b9c7d257..b7aa36640 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/UTMUPS.h +++ b/gtsam/3rdparty/GeographicLib/dotnet/NETGeographicLib/UTMUPS.h @@ -7,7 +7,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ namespace NETGeographicLib @@ -166,8 +166,6 @@ namespace NETGeographicLib * coordinates (default = false). * @exception GeographicErr if \e lat is not in [−90°, * 90°]. - * @exception GeographicErr if \e lon is not in [−540°, - * 540°). * @exception GeographicErr if the resulting \e x or \e y is out of allowed * range (see Reverse); in this case, these arguments are unchanged. * @@ -311,12 +309,13 @@ namespace NETGeographicLib * * For UTM, \e zonestr has the form of a zone number in the range * [UTMUPS::MINUTMZONE, UTMUPS::MAXUTMZONE] = [1, 60] followed by a - * hemisphere letter, N or S. For UPS, it consists just of the hemisphere - * letter. The returned value of \e zone is UTMUPS::UPS = 0 for UPS. Note - * well that "38S" indicates the southern hemisphere of zone 38 and not - * latitude band S, [32, 40]. N, 01S, 2N, 38S are legal. 0N, 001S, 61N, - * 38P are illegal. INV is a special value for which the returned value of - * \e is UTMUPS::INVALID. + * hemisphere letter, n or s (or "north" or "south" spelled out). For UPS, + * it consists just of the hemisphere letter (or the spelled out + * hemisphere). The returned value of \e zone is UTMUPS::UPS = 0 for UPS. + * Note well that "38s" indicates the southern hemisphere of zone 38 and + * not latitude band S, 32° ≤ \e lat < 40°. n, 01s, 2n, 38s, + * south, 3north are legal. 0n, 001s, +3n, 61n, 38P are illegal. INV is a + * special value for which the returned value of \e is UTMUPS::INVALID. **********************************************************************/ static void DecodeZone(System::String^ zonestr, [System::Runtime::InteropServices::Out] int% zone, @@ -327,6 +326,8 @@ namespace NETGeographicLib * * @param[in] zone the UTM zone (zero means UPS). * @param[in] northp hemisphere (true means north, false means south). + * @param[in] abbrev if true (the default) use abbreviated (n/s) notation + * for hemisphere; otherwise spell out the hemisphere (north/south) * @exception GeographicErr if \e zone is out of range (see below). * @exception std::bad_alloc if memoy for the string can't be allocated. * @return string representation of zone and hemisphere. @@ -334,10 +335,10 @@ namespace NETGeographicLib * \e zone must be in the range [UTMUPS::MINZONE, UTMUPS::MAXZONE] = [0, * 60] with \e zone = UTMUPS::UPS, 0, indicating UPS (but the resulting * string does not contain "0"). \e zone may also be UTMUPS::INVALID, in - * which case the returned string is "INV". This reverses + * which case the returned string is "inv". This reverses * UTMUPS::DecodeZone. **********************************************************************/ - static System::String^ EncodeZone(int zone, bool northp); + static System::String^ EncodeZone(int zone, bool northp, bool abbrev); /** * Decode EPSG. diff --git a/gtsam/3rdparty/GeographicLib/dotnet/Projections/AccumPanel.cs b/gtsam/3rdparty/GeographicLib/dotnet/Projections/AccumPanel.cs index 045981222..c49ec5ad4 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/Projections/AccumPanel.cs +++ b/gtsam/3rdparty/GeographicLib/dotnet/Projections/AccumPanel.cs @@ -6,7 +6,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ using System; using System.Collections.Generic; diff --git a/gtsam/3rdparty/GeographicLib/dotnet/Projections/AlbersPanel.cs b/gtsam/3rdparty/GeographicLib/dotnet/Projections/AlbersPanel.cs index db2384fc7..80276081b 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/Projections/AlbersPanel.cs +++ b/gtsam/3rdparty/GeographicLib/dotnet/Projections/AlbersPanel.cs @@ -11,7 +11,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ using System; using System.Collections.Generic; diff --git a/gtsam/3rdparty/GeographicLib/dotnet/Projections/EllipsoidPanel.cs b/gtsam/3rdparty/GeographicLib/dotnet/Projections/EllipsoidPanel.cs index 85372a863..276f5a2a5 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/Projections/EllipsoidPanel.cs +++ b/gtsam/3rdparty/GeographicLib/dotnet/Projections/EllipsoidPanel.cs @@ -6,7 +6,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ using System; using System.Collections.Generic; diff --git a/gtsam/3rdparty/GeographicLib/dotnet/Projections/EllipticPanel.cs b/gtsam/3rdparty/GeographicLib/dotnet/Projections/EllipticPanel.cs index 715441a2d..9dcd2102f 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/Projections/EllipticPanel.cs +++ b/gtsam/3rdparty/GeographicLib/dotnet/Projections/EllipticPanel.cs @@ -6,7 +6,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ using System; using System.Collections.Generic; diff --git a/gtsam/3rdparty/GeographicLib/dotnet/Projections/Form1.Designer.cs b/gtsam/3rdparty/GeographicLib/dotnet/Projections/Form1.Designer.cs index 8f5198054..f658b2ad1 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/Projections/Form1.Designer.cs +++ b/gtsam/3rdparty/GeographicLib/dotnet/Projections/Form1.Designer.cs @@ -45,6 +45,7 @@ namespace Projections this.m_magneticPage = new System.Windows.Forms.TabPage(); this.m_polyPage = new System.Windows.Forms.TabPage(); this.m_accumPage = new System.Windows.Forms.TabPage(); + this.m_rhumbTabPage = new System.Windows.Forms.TabPage(); this.m_tabControl.SuspendLayout(); this.SuspendLayout(); // @@ -66,6 +67,7 @@ namespace Projections this.m_tabControl.Controls.Add(this.m_magneticPage); this.m_tabControl.Controls.Add(this.m_polyPage); this.m_tabControl.Controls.Add(this.m_accumPage); + this.m_tabControl.Controls.Add(this.m_rhumbTabPage); this.m_tabControl.Dock = System.Windows.Forms.DockStyle.Fill; this.m_tabControl.Location = new System.Drawing.Point(0, 0); this.m_tabControl.Name = "m_tabControl"; @@ -228,6 +230,16 @@ namespace Projections this.m_accumPage.Text = "Accumulator"; this.m_accumPage.UseVisualStyleBackColor = true; // + // m_rhumbTabPage + // + this.m_rhumbTabPage.Location = new System.Drawing.Point(4, 22); + this.m_rhumbTabPage.Name = "m_rhumbTabPage"; + this.m_rhumbTabPage.Padding = new System.Windows.Forms.Padding(3); + this.m_rhumbTabPage.Size = new System.Drawing.Size(936, 236); + this.m_rhumbTabPage.TabIndex = 16; + this.m_rhumbTabPage.Text = "Rhumb"; + this.m_rhumbTabPage.UseVisualStyleBackColor = true; + // // Form1 // this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F); @@ -260,7 +272,7 @@ namespace Projections private System.Windows.Forms.TabPage m_magneticPage; private System.Windows.Forms.TabPage m_polyPage; private System.Windows.Forms.TabPage m_accumPage; + private System.Windows.Forms.TabPage m_rhumbTabPage; } } - diff --git a/gtsam/3rdparty/GeographicLib/dotnet/Projections/Form1.cs b/gtsam/3rdparty/GeographicLib/dotnet/Projections/Form1.cs index d93f46edf..24a64167b 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/Projections/Form1.cs +++ b/gtsam/3rdparty/GeographicLib/dotnet/Projections/Form1.cs @@ -6,7 +6,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ using System; using System.Collections.Generic; @@ -44,6 +44,7 @@ namespace Projections m_magneticPage.Controls.Add(new MagneticPanel()); m_polyPage.Controls.Add(new PolyPanel()); m_accumPage.Controls.Add(new AccumPanel()); + m_rhumbTabPage.Controls.Add(new RhumbPanel()); } } } diff --git a/gtsam/3rdparty/GeographicLib/dotnet/Projections/GeocentricPanel.cs b/gtsam/3rdparty/GeographicLib/dotnet/Projections/GeocentricPanel.cs index a3231b34f..4bdb039a4 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/Projections/GeocentricPanel.cs +++ b/gtsam/3rdparty/GeographicLib/dotnet/Projections/GeocentricPanel.cs @@ -6,7 +6,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ using System; using System.Collections.Generic; diff --git a/gtsam/3rdparty/GeographicLib/dotnet/Projections/GeodesicPanel.cs b/gtsam/3rdparty/GeographicLib/dotnet/Projections/GeodesicPanel.cs index 24e78eeb7..bbba69dbd 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/Projections/GeodesicPanel.cs +++ b/gtsam/3rdparty/GeographicLib/dotnet/Projections/GeodesicPanel.cs @@ -11,7 +11,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ using System; using System.Collections.Generic; @@ -369,7 +369,7 @@ namespace Projections faz != finalAzimuth || frd != reducedLength || fm12 != M12 || fm21 != M21) throw new Exception("Geodesic.Direct #5 failed"); double outd = 0.0; - fad = g.GenDirect(32.0, -86.0, 45.0, false, 20000.0, Mask.ALL, out flat, out flon, out faz, out outd, out frd, out fm12, out fm21, out fs12); + fad = g.GenDirect(32.0, -86.0, 45.0, false, 20000.0, Geodesic.mask.ALL, out flat, out flon, out faz, out outd, out frd, out fm12, out fm21, out fs12); if (fad != arcDistance || flat != finalLatitude || flon != finalLongitude || faz != finalAzimuth || frd != reducedLength || fm12 != M12 || fm21 != M21 || outd != 20000.0 || fs12 != S12) @@ -394,7 +394,7 @@ namespace Projections if (flat != finalLatitude || flon != finalLongitude || faz != finalAzimuth || fad != arcDistance || fm12 != M12 || fm21 != M21) throw new Exception("Geodesic.ArcDirect #5 failed"); - fad = g.GenDirect(32.0, -86.0, 45.0, true, 1.0, Mask.ALL, out flat, out flon, + fad = g.GenDirect(32.0, -86.0, 45.0, true, 1.0, Geodesic.mask.ALL, out flat, out flon, out faz, out outd, out frd, out fm12, out fm21, out fs12); if (outd != arcDistance || flat != finalLatitude || flon != finalLongitude || faz != finalAzimuth || frd != reducedLength || fm12 != M12 || fm21 != M21 || @@ -426,6 +426,9 @@ namespace Projections outd != distance || fm12 != M12 || fm21 != M21 || frd != reducedLength) throw new Exception("Geodesic.Inverse #6 failed"); GeodesicLine gl = g.Line(32.0, -86.0, 45.0, Mask.ALL); + gl = g.InverseLine(32.0, -86.0, 33.0, -87.0, Mask.ALL); + gl = g.DirectLine(32.0, -86.0, 45.0, 10000.0, Mask.ALL); + gl = g.ArcDirectLine(32.0, -86.0, 45.0, 10000.0, Mask.ALL); gl = new GeodesicLine(32.0, -86.0, 45.0, Mask.ALL); gl = new GeodesicLine(g, 32.0, -86.0, 45.0, Mask.ALL); arcDistance = gl.Position(10000.0, out finalLatitude, out finalLongitude, out finalAzimuth, @@ -449,7 +452,7 @@ namespace Projections if (fad != arcDistance || flat != finalLatitude || flon != finalLongitude || faz != finalAzimuth || fm12 != M12 || fm21 != M21 || frd != reducedLength ) throw new Exception("GeodesicLine.Position #5 failed"); - fad = gl.GenPosition(false, 10000.0, Mask.ALL, out flat, out flon, out faz, out outd, out frd, out fm12, out fm21, out fs12); + fad = gl.GenPosition(false, 10000.0, GeodesicLine.mask.ALL, out flat, out flon, out faz, out outd, out frd, out fm12, out fm21, out fs12); if (fad != arcDistance || flat != finalLatitude || flon != finalLongitude || faz != finalAzimuth || outd != 10000.0 || fm12 != M12 || fm21 != M21 || frd != reducedLength || fs12 != S12 ) @@ -478,7 +481,7 @@ namespace Projections if (flat != finalLatitude || flon != finalLongitude || faz != finalAzimuth || outd != distance || fm12 != M12 || fm21 != M21 || frd != reducedLength) throw new Exception("GeodesicLine.ArcPosition #6 failed"); - fad = gl.GenPosition(true, 1.0, Mask.ALL, out flat, out flon, out faz, out outd, out frd, out fm12, out fm21, out fs12); + fad = gl.GenPosition(true, 1.0, GeodesicLine.mask.ALL, out flat, out flon, out faz, out outd, out frd, out fm12, out fm21, out fs12); if (fad != 1.0 || flat != finalLatitude || flon != finalLongitude || faz != finalAzimuth || outd != distance || fm12 != M12 || fm21 != M21 || frd != reducedLength || fs12 != S12) @@ -508,7 +511,7 @@ namespace Projections if (fad != arcDistance || flat != finalLatitude || flon != finalLongitude || faz != finalAzimuth || frd != reducedLength || fm12 != M12 || fm21 != M21) throw new Exception("GeodesicExact.Direct #5 failed"); - fad = ge.GenDirect(32.0, -86.0, 45.0, false, 20000.0, Mask.ALL, out flat, out flon, out faz, out outd, out frd, out fm12, out fm21, out fs12); + fad = ge.GenDirect(32.0, -86.0, 45.0, false, 20000.0, GeodesicExact.mask.ALL, out flat, out flon, out faz, out outd, out frd, out fm12, out fm21, out fs12); if (fad != arcDistance || flat != finalLatitude || flon != finalLongitude || faz != finalAzimuth || frd != reducedLength || fm12 != M12 || fm21 != M21 || outd != 20000.0 || fs12 != S12) @@ -533,7 +536,7 @@ namespace Projections if (flat != finalLatitude || flon != finalLongitude || faz != finalAzimuth || fad != arcDistance || fm12 != M12 || fm21 != M21) throw new Exception("GeodesicExact.ArcDirect #5 failed"); - fad = ge.GenDirect(32.0, -86.0, 45.0, true, 1.0, Mask.ALL, out flat, out flon, out faz, out outd, out frd, out fm12, out fm21, out fs12); + fad = ge.GenDirect(32.0, -86.0, 45.0, true, 1.0, GeodesicExact.mask.ALL, out flat, out flon, out faz, out outd, out frd, out fm12, out fm21, out fs12); if (outd != arcDistance || flat != finalLatitude || flon != finalLongitude || faz != finalAzimuth || frd != reducedLength || fm12 != M12 || fm21 != M21 || fad != 1.0 || fs12 != S12) @@ -563,6 +566,9 @@ namespace Projections outd != distance || fm12 != M12 || fm21 != M21 || frd != reducedLength) throw new Exception("GeodesicExact.Inverse #6 failed"); GeodesicLineExact gle = ge.Line(32.0, -86.0, 45.0, Mask.ALL); + gle = ge.InverseLine(32.0, -86.0, 33.0, -87.0, Mask.ALL); + gle = ge.DirectLine(32.0, -86.0, 45.0, 10000.0, Mask.ALL); + gle = ge.ArcDirectLine(32.0, -86.0, 45.0, 10000.0, Mask.ALL); gle = new GeodesicLineExact(32.0, -86.0, 45.0, Mask.ALL); gle = new GeodesicLineExact(ge, 32.0, -86.0, 45.0, Mask.ALL); arcDistance = gle.Position(10000.0, out finalLatitude, out finalLongitude, out finalAzimuth, @@ -586,7 +592,7 @@ namespace Projections if (fad != arcDistance || flat != finalLatitude || flon != finalLongitude || faz != finalAzimuth || fm12 != M12 || fm21 != M21 || frd != reducedLength) throw new Exception("GeodesicLineExact.Position #5 failed"); - fad = gle.GenPosition(false, 10000.0, Mask.ALL, out flat, out flon, out faz, out outd, out frd, out fm12, out fm21, out fs12); + fad = gle.GenPosition(false, 10000.0, GeodesicLineExact.mask.ALL, out flat, out flon, out faz, out outd, out frd, out fm12, out fm21, out fs12); if (fad != arcDistance || flat != finalLatitude || flon != finalLongitude || faz != finalAzimuth || outd != 10000.0 || fm12 != M12 || fm21 != M21 || frd != reducedLength || fs12 != S12) @@ -615,7 +621,7 @@ namespace Projections if (flat != finalLatitude || flon != finalLongitude || faz != finalAzimuth || outd != distance || fm12 != M12 || fm21 != M21 || frd != reducedLength) throw new Exception("GeodesicLineExact.ArcPosition #6 failed"); - fad = gle.GenPosition(true, 1.0, Mask.ALL, out flat, out flon, out faz, out outd, out frd, out fm12, out fm21, out fs12); + fad = gle.GenPosition(true, 1.0, GeodesicLineExact.mask.ALL, out flat, out flon, out faz, out outd, out frd, out fm12, out fm21, out fs12); if (fad != 1.0 || flat != finalLatitude || flon != finalLongitude || faz != finalAzimuth || outd != distance || fm12 != M12 || fm21 != M21 || frd != reducedLength || fs12 != S12) diff --git a/gtsam/3rdparty/GeographicLib/dotnet/Projections/GeoidPanel.cs b/gtsam/3rdparty/GeographicLib/dotnet/Projections/GeoidPanel.cs index 7a1a7d550..cf795d907 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/Projections/GeoidPanel.cs +++ b/gtsam/3rdparty/GeographicLib/dotnet/Projections/GeoidPanel.cs @@ -6,7 +6,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ using System; using System.Collections.Generic; @@ -153,11 +153,7 @@ namespace Projections Geoid g = new Geoid(m_fileName, m_path, false, false); g.CacheArea(20.0, -30.0, 30.0, -20.0); g.CacheAll(); - double gradx, grady; - double h1 = g.Height(32.0, -60.0, out gradx, out grady); double h2 = g.Height(32.0, -60.0); - if (h1 != h2) - throw new Exception("Error in Geoid.Height"); g.ConvertHeight(32.0, -60.0, 100.0, Geoid.ConvertFlag.ELLIPSOIDTOGEOID); MessageBox.Show("No errors detected", "OK", MessageBoxButtons.OK, MessageBoxIcon.Information); } diff --git a/gtsam/3rdparty/GeographicLib/dotnet/Projections/GravityPanel.cs b/gtsam/3rdparty/GeographicLib/dotnet/Projections/GravityPanel.cs index 8e4d5ba3d..62e247b38 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/Projections/GravityPanel.cs +++ b/gtsam/3rdparty/GeographicLib/dotnet/Projections/GravityPanel.cs @@ -10,7 +10,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ using System; using System.Collections.Generic; diff --git a/gtsam/3rdparty/GeographicLib/dotnet/Projections/LocalCartesianPanel.cs b/gtsam/3rdparty/GeographicLib/dotnet/Projections/LocalCartesianPanel.cs index 2f9a9e90d..575d278f2 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/Projections/LocalCartesianPanel.cs +++ b/gtsam/3rdparty/GeographicLib/dotnet/Projections/LocalCartesianPanel.cs @@ -6,7 +6,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ using System; using System.Collections.Generic; diff --git a/gtsam/3rdparty/GeographicLib/dotnet/Projections/MagneticPanel.cs b/gtsam/3rdparty/GeographicLib/dotnet/Projections/MagneticPanel.cs index 653126570..f13218bbf 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/Projections/MagneticPanel.cs +++ b/gtsam/3rdparty/GeographicLib/dotnet/Projections/MagneticPanel.cs @@ -9,7 +9,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ using System; using System.Collections.Generic; @@ -134,6 +134,9 @@ namespace Projections if (bx != x || by != y || bz != z ) throw new Exception("Error in MagneticCircle.Field (2)"); + double dtest = Utility.FractionalYear("2015.34"); + dtest = Utility.FractionalYear("2015-07-31"); + MessageBox.Show("No errors detected", "OK", MessageBoxButtons.OK, MessageBoxIcon.Information); } catch (Exception xcpt) diff --git a/gtsam/3rdparty/GeographicLib/dotnet/Projections/MiscPanel.Designer.cs b/gtsam/3rdparty/GeographicLib/dotnet/Projections/MiscPanel.Designer.cs index fda76668b..4ee9fa5fc 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/Projections/MiscPanel.Designer.cs +++ b/gtsam/3rdparty/GeographicLib/dotnet/Projections/MiscPanel.Designer.cs @@ -39,11 +39,11 @@ namespace Projections this.m_LongitudeTextBox = new System.Windows.Forms.TextBox(); this.m_latitudeTextBox = new System.Windows.Forms.TextBox(); this.m_geohashTextBox = new System.Windows.Forms.TextBox(); - this.label5 = new System.Windows.Forms.Label(); this.button1 = new System.Windows.Forms.Button(); this.button2 = new System.Windows.Forms.Button(); this.button3 = new System.Windows.Forms.Button(); this.button4 = new System.Windows.Forms.Button(); + this.m_comboBox = new System.Windows.Forms.ComboBox(); this.SuspendLayout(); // // label1 @@ -117,15 +117,6 @@ namespace Projections this.m_geohashTextBox.Size = new System.Drawing.Size(155, 20); this.m_geohashTextBox.TabIndex = 8; // - // label5 - // - this.label5.AutoSize = true; - this.label5.Location = new System.Drawing.Point(409, 4); - this.label5.Name = "label5"; - this.label5.Size = new System.Drawing.Size(50, 13); - this.label5.TabIndex = 9; - this.label5.Text = "Geohash"; - // // button1 // this.button1.Location = new System.Drawing.Point(96, 83); @@ -166,15 +157,29 @@ namespace Projections this.button4.UseVisualStyleBackColor = true; this.button4.Click += new System.EventHandler(this.OnValidate); // + // m_comboBox + // + this.m_comboBox.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; + this.m_comboBox.FormattingEnabled = true; + this.m_comboBox.Items.AddRange(new object[] { + "Geohash", + "GARS", + "Georef"}); + this.m_comboBox.Location = new System.Drawing.Point(376, 4); + this.m_comboBox.Name = "m_comboBox"; + this.m_comboBox.Size = new System.Drawing.Size(121, 21); + this.m_comboBox.TabIndex = 14; + this.m_toolTip.SetToolTip(this.m_comboBox, "Select the reference system"); + // // MiscPanel // this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F); this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font; + this.Controls.Add(this.m_comboBox); this.Controls.Add(this.button4); this.Controls.Add(this.button3); this.Controls.Add(this.button2); this.Controls.Add(this.button1); - this.Controls.Add(this.label5); this.Controls.Add(this.m_geohashTextBox); this.Controls.Add(this.m_latitudeTextBox); this.Controls.Add(this.m_LongitudeTextBox); @@ -203,10 +208,10 @@ namespace Projections private System.Windows.Forms.TextBox m_LongitudeTextBox; private System.Windows.Forms.TextBox m_latitudeTextBox; private System.Windows.Forms.TextBox m_geohashTextBox; - private System.Windows.Forms.Label label5; private System.Windows.Forms.Button button1; private System.Windows.Forms.Button button2; private System.Windows.Forms.Button button3; private System.Windows.Forms.Button button4; + private System.Windows.Forms.ComboBox m_comboBox; } } diff --git a/gtsam/3rdparty/GeographicLib/dotnet/Projections/MiscPanel.cs b/gtsam/3rdparty/GeographicLib/dotnet/Projections/MiscPanel.cs index 0fcb9908b..d1a9bf5cd 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/Projections/MiscPanel.cs +++ b/gtsam/3rdparty/GeographicLib/dotnet/Projections/MiscPanel.cs @@ -6,7 +6,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ using System; using System.Collections.Generic; @@ -25,6 +25,7 @@ namespace Projections public MiscPanel() { InitializeComponent(); + m_comboBox.SelectedIndex = 0; } private void OnConvertDMS(object sender, EventArgs e) @@ -55,7 +56,18 @@ namespace Projections m_longitudeDMSTextBox.Text = DMS.Encode(lon, 5, DMS.Flag.LONGITUDE, 0); m_latitudeDMSTextBox.Text = DMS.Encode(lat, 5, DMS.Flag.LATITUDE, 0); string tmp = ""; - Geohash.Forward(lat, lon, 12, out tmp); + switch (m_comboBox.SelectedIndex) + { + case 0: // Geohash + Geohash.Forward(lat, lon, 12, out tmp); + break; + case 1: // GARS + GARS.Forward(lat, lon, 2, out tmp); + break; + case 2: // Georef + Georef.Forward(lat, lon, 2, out tmp); + break; + } m_geohashTextBox.Text = tmp; } catch (Exception xcpt) @@ -68,9 +80,20 @@ namespace Projections { try { - double lat, lon; + double lat = 0.0, lon = 0.0; int len; - Geohash.Reverse(m_geohashTextBox.Text, out lat, out lon, out len, true); + switch (m_comboBox.SelectedIndex) + { + case 0: // Geohash + Geohash.Reverse(m_geohashTextBox.Text, out lat, out lon, out len, true); + break; + case 1: // GARS + GARS.Reverse(m_geohashTextBox.Text, out lat, out lon, out len, true); + break; + case 2: // Georef + Georef.Reverse(m_geohashTextBox.Text, out lat, out lon, out len, true); + break; + } m_LongitudeTextBox.Text = lon.ToString(); m_latitudeTextBox.Text = lat.ToString(); m_longitudeDMSTextBox.Text = DMS.Encode(lon, 5, DMS.Flag.LONGITUDE, 0); @@ -90,7 +113,6 @@ namespace Projections DMS.Flag ind; int len; string tmp; - DMS.Decode("34.245"); DMS.Decode("34d22\'34.567\"", out ind); DMS.Decode(-86.0, 32.0, 34.214); DMS.DecodeAngle("-67.4532"); @@ -107,6 +129,10 @@ namespace Projections Geohash.LatitudeResolution(12); Geohash.LongitudeResolution(12); Geohash.Reverse("djds54mrfc0g", out lat, out lon, out len, true); + GARS.Forward(32.0, -86.0, 2, out tmp); + GARS.Reverse("189LE37", out lat, out lon, out len, true); + Georef.Forward(32.0, -86.0, 2, out tmp); + Georef.Reverse("GJEC0000", out lat, out lon, out len, true); MessageBox.Show("No errors detected", "OK", MessageBoxButtons.OK, MessageBoxIcon.Information); } catch (Exception xcpt) diff --git a/gtsam/3rdparty/GeographicLib/dotnet/Projections/PolarStereoPanel.cs b/gtsam/3rdparty/GeographicLib/dotnet/Projections/PolarStereoPanel.cs index 655a04f51..da2c94d7c 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/Projections/PolarStereoPanel.cs +++ b/gtsam/3rdparty/GeographicLib/dotnet/Projections/PolarStereoPanel.cs @@ -6,7 +6,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ using System; using System.Collections.Generic; diff --git a/gtsam/3rdparty/GeographicLib/dotnet/Projections/PolyPanel.cs b/gtsam/3rdparty/GeographicLib/dotnet/Projections/PolyPanel.cs index e50673c0f..a5ed4cebe 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/Projections/PolyPanel.cs +++ b/gtsam/3rdparty/GeographicLib/dotnet/Projections/PolyPanel.cs @@ -6,7 +6,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ using System; using System.Collections.Generic; @@ -118,6 +118,25 @@ namespace Projections pa.Compute(false, false, out perim, out area); pa.TestEdge(-70.0, 5000.0, false, false, out perim, out area); pa.TestPoint(31.0, -86.5, false, false, out perim, out area); + + PolygonAreaExact p2 = new PolygonAreaExact(new GeodesicExact(), false); + p2.AddPoint(32.0, -86.0); + p2.AddEdge(20.0, 10000.0); + p2.AddEdge(-45.0, 10000.0); + p2.CurrentPoint(out lat, out lon); + p2.Compute(false, false, out perim, out area); + p2.TestEdge(-70.0, 5000.0, false, false, out perim, out area); + p2.TestPoint(31.0, -86.5, false, false, out perim, out area); + + PolygonAreaRhumb p3 = new PolygonAreaRhumb(Rhumb.WGS84(), false); + p3.AddPoint(32.0, -86.0); + p3.AddEdge(20.0, 10000.0); + p3.AddEdge(-45.0, 10000.0); + p3.CurrentPoint(out lat, out lon); + p3.Compute(false, false, out perim, out area); + p3.TestEdge(-70.0, 5000.0, false, false, out perim, out area); + p3.TestPoint(31.0, -86.5, false, false, out perim, out area); + MessageBox.Show("No errors detected", "OK", MessageBoxButtons.OK, MessageBoxIcon.Information); } catch (Exception xcpt) diff --git a/gtsam/3rdparty/GeographicLib/dotnet/Projections/Program.cs b/gtsam/3rdparty/GeographicLib/dotnet/Projections/Program.cs index 87882dcf5..d1543af36 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/Projections/Program.cs +++ b/gtsam/3rdparty/GeographicLib/dotnet/Projections/Program.cs @@ -6,7 +6,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ using System; using System.Collections.Generic; diff --git a/gtsam/3rdparty/GeographicLib/dotnet/Projections/Projections-vs13.csproj b/gtsam/3rdparty/GeographicLib/dotnet/Projections/Projections-vs13.csproj new file mode 100644 index 000000000..5c2fa7f39 --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/dotnet/Projections/Projections-vs13.csproj @@ -0,0 +1,273 @@ + + + + Debug + x86 + 8.0.30703 + 2.0 + {74B48389-E1D1-491F-B198-ADD4878C3F2B} + WinExe + Properties + Projections + Projections + v4.5 + + + 512 + + + x86 + true + full + false + $(SolutionDir)$(Configuration)\ + DEBUG;TRACE + prompt + 4 + false + + + x64 + true + full + false + $(SolutionDir)$(Configuration)64\ + DEBUG;TRACE + prompt + 4 + false + + + x86 + pdbonly + true + $(SolutionDir)$(Configuration)\ + TRACE + prompt + 4 + false + + + x64 + pdbonly + true + $(SolutionDir)$(Configuration)64\ + TRACE + prompt + 4 + false + + + + + + + + + + + + + + + + UserControl + + + AccumPanel.cs + + + UserControl + + + AlbersPanel.cs + + + + UserControl + + + EllipsoidPanel.cs + + + UserControl + + + EllipticPanel.cs + + + Form + + + Form1.cs + + + UserControl + + + GeocentricPanel.cs + + + UserControl + + + GeodesicPanel.cs + + + UserControl + + + GeoidPanel.cs + + + UserControl + + + GravityPanel.cs + + + UserControl + + + LocalCartesianPanel.cs + + + UserControl + + + MagneticPanel.cs + + + UserControl + + + MiscPanel.cs + + + UserControl + + + PolarStereoPanel.cs + + + UserControl + + + PolyPanel.cs + + + + UserControl + + + ProjectionsPanel.cs + + + True + True + Resources.resx + + + True + True + Settings.settings + + + UserControl + + + RhumbPanel.cs + + + UserControl + + + SphericalHarmonicsPanel.cs + + + UserControl + + + TypeIIIProjPanel.cs + + + AccumPanel.cs + + + AlbersPanel.cs + + + EllipsoidPanel.cs + + + EllipticPanel.cs + + + Form1.cs + + + GeocentricPanel.cs + + + GeodesicPanel.cs + + + GeoidPanel.cs + + + GravityPanel.cs + + + LocalCartesianPanel.cs + + + MagneticPanel.cs + + + MiscPanel.cs + + + PolarStereoPanel.cs + + + PolyPanel.cs + + + ProjectionsPanel.cs + + + ResXFileCodeGenerator + Resources.Designer.cs + + + RhumbPanel.cs + + + SphericalHarmonicsPanel.cs + + + TypeIIIProjPanel.cs + + + + + {BC1ADBEC-537D-487E-AF21-8B7025AAF46D} + NETGeographic + + + + + SettingsSingleFileGenerator + Settings.Designer.cs + + + + + diff --git a/gtsam/3rdparty/GeographicLib/dotnet/Projections/Projections.csproj b/gtsam/3rdparty/GeographicLib/dotnet/Projections/Projections.csproj index 9dfe2a101..0bb5f9560 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/Projections/Projections.csproj +++ b/gtsam/3rdparty/GeographicLib/dotnet/Projections/Projections.csproj @@ -77,6 +77,7 @@ AlbersPanel.cs + UserControl @@ -156,7 +157,22 @@ ProjectionsPanel.cs - + + True + True + Resources.resx + + + True + True + Settings.settings + + + UserControl + + + RhumbPanel.cs + UserControl @@ -214,30 +230,19 @@ ProjectionsPanel.cs - + ResXFileCodeGenerator Resources.Designer.cs - Designer - - True - Resources.resx - + + RhumbPanel.cs + SphericalHarmonicsPanel.cs TypeIIIProjPanel.cs - - SettingsSingleFileGenerator - Settings.Designer.cs - - - True - Settings.settings - True - @@ -245,9 +250,16 @@ NETGeographic + + + SettingsSingleFileGenerator + Settings.Designer.cs + + - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + text/microsoft-resx + + + 2.0 + + + System.Resources.ResXResourceReader, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Resources.ResXResourceWriter, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + diff --git a/gtsam/3rdparty/GeographicLib/dotnet/Projections/SphericalHarmonicsPanel.cs b/gtsam/3rdparty/GeographicLib/dotnet/Projections/SphericalHarmonicsPanel.cs index 7b04fb3e4..aedf2fe32 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/Projections/SphericalHarmonicsPanel.cs +++ b/gtsam/3rdparty/GeographicLib/dotnet/Projections/SphericalHarmonicsPanel.cs @@ -11,7 +11,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ using System; using System.Collections.Generic; diff --git a/gtsam/3rdparty/GeographicLib/dotnet/Projections/TypeIIIProjPanel.cs b/gtsam/3rdparty/GeographicLib/dotnet/Projections/TypeIIIProjPanel.cs index 675d766fb..fcbeafb0c 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/Projections/TypeIIIProjPanel.cs +++ b/gtsam/3rdparty/GeographicLib/dotnet/Projections/TypeIIIProjPanel.cs @@ -10,7 +10,7 @@ * GeographicLib is Copyright (c) Charles Karney (2010-2012) * and licensed under the MIT/X11 License. * For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ using System; using System.Collections.Generic; @@ -138,7 +138,7 @@ namespace Projections if (lat != x1 || lon != y1) throw new Exception("Error in UTMUPS.Reverse"); UTMUPS.Transfer(zone, northp, x, y, zone + 1, true, out x1, out y1, out zout); - str = UTMUPS.EncodeZone(zone, northp); + str = UTMUPS.EncodeZone(zone, northp, true); prec = UTMUPS.EncodeEPSG(zone, northp); UTMUPS.DecodeZone(str, out zone, out northp); UTMUPS.DecodeEPSG(prec, out zone, out northp); diff --git a/gtsam/3rdparty/GeographicLib/dotnet/examples/CS/example-AlbersEqualArea.cs b/gtsam/3rdparty/GeographicLib/dotnet/examples/CS/example-AlbersEqualArea.cs index bf063d372..4d31bcb2a 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/examples/CS/example-AlbersEqualArea.cs +++ b/gtsam/3rdparty/GeographicLib/dotnet/examples/CS/example-AlbersEqualArea.cs @@ -11,7 +11,7 @@ namespace example_AlbersEqualArea const double lat1 = 40 + 58/60.0, lat2 = 39 + 56/60.0, // standard parallels k1 = 1, // scale - lon0 = -77 - 45/60.0; // Central meridan + lon0 = -77 - 45/60.0; // Central meridian // Set up basic projection AlbersEqualArea albers = new AlbersEqualArea( Constants.WGS84.MajorRadius, Constants.WGS84.Flattening, diff --git a/gtsam/3rdparty/GeographicLib/dotnet/examples/CS/example-GARS.cs b/gtsam/3rdparty/GeographicLib/dotnet/examples/CS/example-GARS.cs new file mode 100644 index 000000000..ac1783d6f --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/dotnet/examples/CS/example-GARS.cs @@ -0,0 +1,36 @@ +using System; +using NETGeographicLib; + +namespace example_GARS +{ + class Program + { + static void Main(string[] args) + { + try { + { + // Sample forward calculation + double lat = 57.64911, lon = 10.40744; // Jutland + string gars; + for (int prec = 0; prec <= 2; ++prec) { + GARS.Forward(lat, lon, prec, out gars); + Console.WriteLine(String.Format("Precision: {0} GARS: {1}", prec, gars)); + } + } + { + // Sample reverse calculation + string gars = "381NH45"; + double lat, lon; + for (int len = 5; len <= gars.Length; ++len) { + int prec; + GARS.Reverse(gars.Substring(0, len), out lat, out lon, out prec, true); + Console.WriteLine(String.Format("Precision: {0} Latitude: {1} Longitude {2}", prec, lat, lon)); + } + } + } + catch (GeographicErr e) { + Console.WriteLine(String.Format("Caught Exception {0}", e.Message)); + } + } + } +} diff --git a/gtsam/3rdparty/GeographicLib/dotnet/examples/CS/example-Georef.cs b/gtsam/3rdparty/GeographicLib/dotnet/examples/CS/example-Georef.cs new file mode 100644 index 000000000..e73047387 --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/dotnet/examples/CS/example-Georef.cs @@ -0,0 +1,38 @@ +using System; +using NETGeographicLib; + +namespace example_Georef +{ + class Program + { + static void Main(string[] args) + { + try { + { + // Sample forward calculation + double lat = 57.64911, lon = 10.40744; // Jutland + string georef; + for (int prec = -1; prec <= 11; ++prec) { + Georef.Forward(lat, lon, prec, out georef); + Console.WriteLine(String.Format("Precision: {0} Georef: {1}", prec, georef)); + } + } + { + // Sample reverse calculation + string georef = "NKLN2444638946"; + double lat, lon; + int prec; + Georef.Reverse(georef.Substring(0, 2), out lat, out lon, out prec, true); + Console.WriteLine(String.Format("Precision: {0} Latitude: {1} Longitude: {2}", prec, lat, lon)); + Georef.Reverse(georef.Substring(0, 4), out lat, out lon, out prec, true); + Console.WriteLine(String.Format("Precision: {0} Latitude: {1} Longitude: {2}", prec, lat, lon)); + Georef.Reverse(georef, out lat, out lon, out prec, true); + Console.WriteLine(String.Format("Precision: {0} Latitude: {1} Longitude: {2}", prec, lat, lon)); + } + } + catch (GeographicErr e) { + Console.WriteLine(String.Format("Caught Exception {0}", e.Message)); + } + } + } +} diff --git a/gtsam/3rdparty/GeographicLib/dotnet/examples/CS/example-Rhumb.cs b/gtsam/3rdparty/GeographicLib/dotnet/examples/CS/example-Rhumb.cs new file mode 100644 index 000000000..1f512923a --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/dotnet/examples/CS/example-Rhumb.cs @@ -0,0 +1,38 @@ +using System; +using System.Collections.Generic; +using System.Linq; +using System.Text; +using NETGeographicLib; + +namespace example_Rhumb +{ + class Program + { + static void Main(string[] args) + { + try { + Rhumb rhumb = new Rhumb(Constants.WGS84.MajorRadius, Constants.WGS84.Flattening, true); + // Alternatively: const Rhumb& rhumb = Rhumb::WGS84(); + { + // Sample direct calculation, travelling about NE from JFK + double lat1 = 40.6, lon1 = -73.8, s12 = 5.5e6, azi12 = 51; + double lat2, lon2; + rhumb.Direct(lat1, lon1, azi12, s12, out lat2, out lon2); + Console.WriteLine( "{0} {1}", lat2, lon2 ); + } + { + // Sample inverse calculation, JFK to LHR + double + lat1 = 40.6, lon1 = -73.8, // JFK Airport + lat2 = 51.6, lon2 = -0.5; // LHR Airport + double s12, azi12; + rhumb.Inverse(lat1, lon1, lat2, lon2, out s12, out azi12); + Console.WriteLine( "{0} {1}", s12, azi12 ); + } + } + catch (GeographicErr e) { + Console.WriteLine(String.Format("Caught exception: {0}", e.Message)); + } + } + } +} diff --git a/gtsam/3rdparty/GeographicLib/dotnet/examples/CS/example-RhumbLine.cs b/gtsam/3rdparty/GeographicLib/dotnet/examples/CS/example-RhumbLine.cs new file mode 100644 index 000000000..531d18b28 --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/dotnet/examples/CS/example-RhumbLine.cs @@ -0,0 +1,42 @@ +using System; +using System.Collections.Generic; +using System.Linq; +using System.Text; +using NETGeographicLib; + +namespace example_RhumbLine +{ + class Program + { + static void Main(string[] args) + { + try { + // Print waypoints between JFK and SIN + Rhumb rhumb = new Rhumb(Constants.WGS84.MajorRadius, Constants.WGS84.Flattening, true); + // Alternatively: const Rhumb& rhumb = Rhumb::WGS84(); + double + lat1 = 40.640, lon1 = -73.779, // JFK + lat2 = 1.359, lon2 = 103.989; // SIN + double s12, azi12; + rhumb.Inverse(lat1, lon1, lat2, lon2, out s12, out azi12); + RhumbLine line = rhumb.Line(lat1, lon1, azi12); + // Alternatively + // const GeographicLib::RhumbLine line = rhumb.Line(lat1, lon1, azi1); + double ds = 500e3; // Nominal distance between points = 500 km + int num = (int)Math.Ceiling(s12 / ds); // The number of intervals + { + // Use intervals of equal length + ds = s12 / num; + for (int i = 0; i <= num; ++i) { + double lat, lon; + line.Position(i * ds, out lat, out lon); + Console.WriteLine( "{0} {1} {2}", i, lat, lon ); + } + } + } + catch (GeographicErr e) { + Console.WriteLine(String.Format("Caught exception: {0}", e.Message)); + } + } + } +} diff --git a/gtsam/3rdparty/GeographicLib/dotnet/examples/CS/example-UTMUPS.cs b/gtsam/3rdparty/GeographicLib/dotnet/examples/CS/example-UTMUPS.cs index 2e8594d0e..28173c2be 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/examples/CS/example-UTMUPS.cs +++ b/gtsam/3rdparty/GeographicLib/dotnet/examples/CS/example-UTMUPS.cs @@ -16,7 +16,7 @@ namespace example_UTMUPS bool northp; double x, y; UTMUPS.Forward(lat, lon, out zone, out northp, out x, out y, -1, true); - string zonestr = UTMUPS.EncodeZone(zone, northp); + string zonestr = UTMUPS.EncodeZone(zone, northp, true); Console.WriteLine(String.Format("{0} {1} {2}", zonestr, x, y)); } { diff --git a/gtsam/3rdparty/GeographicLib/dotnet/examples/ManagedCPP/CMakeLists.txt b/gtsam/3rdparty/GeographicLib/dotnet/examples/ManagedCPP/CMakeLists.txt index ceee57c16..defb19380 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/examples/ManagedCPP/CMakeLists.txt +++ b/gtsam/3rdparty/GeographicLib/dotnet/examples/ManagedCPP/CMakeLists.txt @@ -15,14 +15,21 @@ foreach (EXAMPLE_SOURCE ${EXAMPLE_SOURCES}) set_target_properties (${EXAMPLE} PROPERTIES COMPILE_FLAGS "/clr") # This is set up for Release builds only. Change # Release/NETGeographic.dll to Debug/NETGeographic_d.dll for Debug - # builds. + # builds. TODO: get this to work for Debug + Release. Unfortunately + # generator expressions don't work in this context. set_target_properties (${EXAMPLE} PROPERTIES VS_DOTNET_REFERENCES - "${CMAKE_CURRENT_BINARY_DIR}/../../NETGeographicLib/Release/NETGeographic.dll") + "${PROJECT_BINARY_DIR}/bin/Release/NETGeographic.dll") endforeach () string (REPLACE "/RTC1" "" CMAKE_CXX_FLAGS_DEBUG "${CMAKE_CXX_FLAGS_DEBUG}") string (REPLACE "/EHsc" "" CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS}") +if (MSVC AND NOT MSVC_VERSION GREATER 1600) + # Disable "already imported" and "unsupported default parameter" + # warnings with VS 10 + set (CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} /wd4945 /wd4564") +endif () + add_custom_target (netexamples DEPENDS ${EXAMPLES}) get_target_property (_LIBTYPE ${PROJECT_LIBRARIES} TYPE) diff --git a/gtsam/3rdparty/GeographicLib/dotnet/examples/ManagedCPP/example-AlbersEqualArea.cpp b/gtsam/3rdparty/GeographicLib/dotnet/examples/ManagedCPP/example-AlbersEqualArea.cpp index 0f3fa7af8..59eb06c48 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/examples/ManagedCPP/example-AlbersEqualArea.cpp +++ b/gtsam/3rdparty/GeographicLib/dotnet/examples/ManagedCPP/example-AlbersEqualArea.cpp @@ -7,7 +7,7 @@ int main(array ^/*args*/) const double lat1 = 40 + 58/60.0, lat2 = 39 + 56/60.0, // standard parallels k1 = 1, // scale - lon0 = -77 - 45/60.0; // Central meridan + lon0 = -77 - 45/60.0; // Central meridian // Set up basic projection AlbersEqualArea^ albers = gcnew AlbersEqualArea( Constants::WGS84::MajorRadius, Constants::WGS84::Flattening, diff --git a/gtsam/3rdparty/GeographicLib/dotnet/examples/ManagedCPP/example-GARS.cpp b/gtsam/3rdparty/GeographicLib/dotnet/examples/ManagedCPP/example-GARS.cpp new file mode 100644 index 000000000..5c08e57c1 --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/dotnet/examples/ManagedCPP/example-GARS.cpp @@ -0,0 +1,32 @@ +using namespace System; +using namespace NETGeographicLib; + +int main(array ^/*args*/) +{ + try { + { + // Sample forward calculation + double lat = 57.64911, lon = 10.40744; // Jutland + String^ gars; + for (int prec = 0; prec <= 2; ++prec) { + GARS::Forward(lat, lon, prec, gars); + Console::WriteLine(String::Format("Precision: {0} GARS: {1}", prec, gars)); + } + } + { + // Sample reverse calculation + String^ gars = gcnew String("381NH45"); + double lat, lon; + for (int len = 5; len <= gars->Length; ++len) { + int prec; + GARS::Reverse(gars->Substring(0, len), lat, lon, prec, true); + Console::WriteLine(String::Format("Precision: {0} Latitude: {1} Longitude {2}", prec, lat, lon)); + } + } + } + catch (GeographicErr^ e) { + Console::WriteLine(String::Format("Caught Exception {0}", e->Message)); + return 1; + } + return 0; +} diff --git a/gtsam/3rdparty/GeographicLib/dotnet/examples/ManagedCPP/example-GeodesicLine.cpp b/gtsam/3rdparty/GeographicLib/dotnet/examples/ManagedCPP/example-GeodesicLine.cpp index a57b903b8..799ce9af8 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/examples/ManagedCPP/example-GeodesicLine.cpp +++ b/gtsam/3rdparty/GeographicLib/dotnet/examples/ManagedCPP/example-GeodesicLine.cpp @@ -14,8 +14,8 @@ int main(array ^/*args*/) GeodesicLine^ line = gcnew GeodesicLine(geod, lat1, lon1, azi1, Mask::ALL); // Alternatively // const GeographicLib::GeodesicLine line = geod.Line(lat1, lon1, azi1); - double ds = 500e3; // Nominal distance between points = 500 km - int num = int(Math::Ceiling(s12 / ds)); // The number of intervals + double ds0 = 500e3; // Nominal distance between points = 500 km + int num = int(Math::Ceiling(s12 / ds0)); // The number of intervals { // Use intervals of equal length double ds = s12 / num; diff --git a/gtsam/3rdparty/GeographicLib/dotnet/examples/ManagedCPP/example-GeodesicLineExact.cpp b/gtsam/3rdparty/GeographicLib/dotnet/examples/ManagedCPP/example-GeodesicLineExact.cpp index 54a8fc767..5621108b9 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/examples/ManagedCPP/example-GeodesicLineExact.cpp +++ b/gtsam/3rdparty/GeographicLib/dotnet/examples/ManagedCPP/example-GeodesicLineExact.cpp @@ -14,8 +14,8 @@ int main(array ^/*args*/) GeodesicLineExact^ line = gcnew GeodesicLineExact(geod, lat1, lon1, azi1, Mask::ALL); // Alternatively // const GeographicLib::GeodesicLine line = geod.Line(lat1, lon1, azi1); - double ds = 500e3; // Nominal distance between points = 500 km - int num = int(Math::Ceiling(s12 / ds)); // The number of intervals + double ds0 = 500e3; // Nominal distance between points = 500 km + int num = int(Math::Ceiling(s12 / ds0)); // The number of intervals { // Use intervals of equal length double ds = s12 / num; diff --git a/gtsam/3rdparty/GeographicLib/dotnet/examples/ManagedCPP/example-Georef.cpp b/gtsam/3rdparty/GeographicLib/dotnet/examples/ManagedCPP/example-Georef.cpp new file mode 100644 index 000000000..ede327232 --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/dotnet/examples/ManagedCPP/example-Georef.cpp @@ -0,0 +1,34 @@ +using namespace System; +using namespace NETGeographicLib; + +int main(array ^/*args*/) +{ + try { + { + // Sample forward calculation + double lat = 57.64911, lon = 10.40744; // Jutland + String^ georef; + for (int prec = -1; prec <= 11; ++prec) { + Georef::Forward(lat, lon, prec, georef); + Console::WriteLine(String::Format("Precision: {0} Georef: {1}", prec, georef)); + } + } + { + // Sample reverse calculation + String^ georef = gcnew String("NKLN2444638946"); + double lat, lon; + int prec; + Georef::Reverse(georef->Substring(0, 2), lat, lon, prec, true); + Console::WriteLine(String::Format("Precision: {0} Latitude: {1} Longitude: {2}", prec, lat, lon)); + Georef::Reverse(georef->Substring(0, 4), lat, lon, prec, true); + Console::WriteLine(String::Format("Precision: {0} Latitude: {1} Longitude: {2}", prec, lat, lon)); + Georef::Reverse(georef, lat, lon, prec, true); + Console::WriteLine(String::Format("Precision: {0} Latitude: {1} Longitude: {2}", prec, lat, lon)); + } + } + catch (GeographicErr^ e) { + Console::WriteLine(String::Format("Caught Exception {0}", e->Message)); + return 1; + } + return 0; +} diff --git a/gtsam/3rdparty/GeographicLib/dotnet/examples/ManagedCPP/example-Rhumb.cpp b/gtsam/3rdparty/GeographicLib/dotnet/examples/ManagedCPP/example-Rhumb.cpp new file mode 100644 index 000000000..c8d08c925 --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/dotnet/examples/ManagedCPP/example-Rhumb.cpp @@ -0,0 +1,32 @@ +using namespace System; +using namespace NETGeographicLib; + +int main(array ^/*args*/ +) +{ + try { + Rhumb^ rhumb = gcnew Rhumb(Constants::WGS84::MajorRadius, Constants::WGS84::Flattening, true); + // Alternatively: const Rhumb& rhumb = Rhumb::WGS84(); + { + // Sample direct calculation, travelling about NE from JFK + double lat1 = 40.6, lon1 = -73.8, s12 = 5.5e6, azi12 = 51; + double lat2, lon2; + rhumb->Direct(lat1, lon1, azi12, s12, lat2, lon2); + Console::WriteLine( "{0} {1}", lat2, lon2 ); + } + { + // Sample inverse calculation, JFK to LHR + double + lat1 = 40.6, lon1 = -73.8, // JFK Airport + lat2 = 51.6, lon2 = -0.5; // LHR Airport + double s12, azi12; + rhumb->Inverse(lat1, lon1, lat2, lon2, s12, azi12); + Console::WriteLine( "{0} {1}", s12, azi12 ); + } + } + catch (GeographicErr^ e) { + Console::WriteLine(String::Format("Caught exception: {0}", e->Message)); + return -1; + } + return 0; +} diff --git a/gtsam/3rdparty/GeographicLib/dotnet/examples/ManagedCPP/example-RhumbLine.cpp b/gtsam/3rdparty/GeographicLib/dotnet/examples/ManagedCPP/example-RhumbLine.cpp new file mode 100644 index 000000000..889d01472 --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/dotnet/examples/ManagedCPP/example-RhumbLine.cpp @@ -0,0 +1,35 @@ +using namespace System; +using namespace NETGeographicLib; + +int main(array ^/*args*/) +{ + try { + // Print waypoints between JFK and SIN + Rhumb^ rhumb = gcnew Rhumb(Constants::WGS84::MajorRadius, Constants::WGS84::Flattening, true); + // Alternatively: const Rhumb& rhumb = Rhumb::WGS84(); + double + lat1 = 40.640, lon1 = -73.779, // JFK + lat2 = 1.359, lon2 = 103.989; // SIN + double s12, azi12; + rhumb->Inverse(lat1, lon1, lat2, lon2, s12, azi12); + RhumbLine^ line = rhumb->Line(lat1, lon1, azi12); + // Alternatively + // const GeographicLib::RhumbLine line = rhumb.Line(lat1, lon1, azi1); + double ds0 = 500e3; // Nominal distance between points = 500 km + int num = int(Math::Ceiling(s12 / ds0)); // The number of intervals + { + // Use intervals of equal length + double ds = s12 / num; + for (int i = 0; i <= num; ++i) { + double lat, lon; + line->Position(i * ds, lat, lon); + Console::WriteLine( "{0} {1} {2}", i, lat, lon ); + } + } + } + catch (GeographicErr^ e) { + Console::WriteLine(String::Format("Caught exception: {0}", e->Message)); + return -1; + } + return 0; +} diff --git a/gtsam/3rdparty/GeographicLib/dotnet/examples/ManagedCPP/example-UTMUPS.cpp b/gtsam/3rdparty/GeographicLib/dotnet/examples/ManagedCPP/example-UTMUPS.cpp index c90ebe0ba..c0b62ace5 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/examples/ManagedCPP/example-UTMUPS.cpp +++ b/gtsam/3rdparty/GeographicLib/dotnet/examples/ManagedCPP/example-UTMUPS.cpp @@ -12,7 +12,7 @@ int main(array ^/*args*/) bool northp; double x, y; UTMUPS::Forward(lat, lon, zone, northp, x, y, -1, true); - String^ zonestr = UTMUPS::EncodeZone(zone, northp); + String^ zonestr = UTMUPS::EncodeZone(zone, northp, true); Console::WriteLine(String::Format("{0} {1} {2}", zonestr, x, y)); } { diff --git a/gtsam/3rdparty/GeographicLib/dotnet/examples/VB/example-AlbersEqualArea.vb b/gtsam/3rdparty/GeographicLib/dotnet/examples/VB/example-AlbersEqualArea.vb index 221eebb16..267845064 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/examples/VB/example-AlbersEqualArea.vb +++ b/gtsam/3rdparty/GeographicLib/dotnet/examples/VB/example-AlbersEqualArea.vb @@ -5,7 +5,7 @@ Module example_AlbersEqualArea Try Dim lat1 As Double = 40 + 58 / 60.0 : Dim lat2 As Double = 39 + 56 / 60.0 ' standard parallels Dim k1 As Double = 1 ' scale - Dim lon0 As Double = -77 - 45 / 60.0 ' Central meridan + Dim lon0 As Double = -77 - 45 / 60.0 ' Central meridian ' Set up basic projection Dim albers As AlbersEqualArea = New AlbersEqualArea(Constants.WGS84.MajorRadius, Constants.WGS84.Flattening, diff --git a/gtsam/3rdparty/GeographicLib/dotnet/examples/VB/example-GARS.vb b/gtsam/3rdparty/GeographicLib/dotnet/examples/VB/example-GARS.vb new file mode 100644 index 000000000..88da5529d --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/dotnet/examples/VB/example-GARS.vb @@ -0,0 +1,23 @@ +Imports NETGeographicLib +Module example_GARS + Sub Main() + Try + ' Sample forward calculation + Dim lat As Double = 57.64911, lon = 10.40744 + Dim garstring As String + For prec As Integer = 0 To 2 + GARS.Forward(lat, lon, prec, garstring) + Console.WriteLine(String.Format("Precision: {0} GARS: {1}", prec, garstring)) + Next + ' Sample reverse calculation + garstring = "381NH45" + For len As Integer = 5 To garstring.Length + Dim prec As Integer + GARS.Reverse(garstring.Substring(0, len), lat, lon, prec, True) + Console.WriteLine(String.Format("Precision: {0} Latitude: {1} Longitude {2}", prec, lat, lon)) + Next + Catch ex As GeographicErr + Console.WriteLine(String.Format("Caught Exception {0}", ex.Message)) + End Try + End Sub +End Module diff --git a/gtsam/3rdparty/GeographicLib/dotnet/examples/VB/example-Georef.vb b/gtsam/3rdparty/GeographicLib/dotnet/examples/VB/example-Georef.vb new file mode 100644 index 000000000..d6f745465 --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/dotnet/examples/VB/example-Georef.vb @@ -0,0 +1,25 @@ +Imports NETGeographicLib +Module example_Georef + Sub Main() + Try + ' Sample forward calculation + Dim lat As Double = 57.64911, lon = 10.40744 ' Jutland + Dim georefstring As String + For prec1 As Integer = -1 To 11 + Georef.Forward(lat, lon, prec1, georefstring) + Console.WriteLine(String.Format("Precision: {0} Georef: {1}", prec1, georefstring)) + Next + ' Sample reverse calculation + georefstring = "NKLN2444638946" + Dim prec As Integer + Georef.Reverse(georefstring.Substring(0, 2), lat, lon, prec, True) + Console.WriteLine(String.Format("Precision: {0} Latitude: {1} Longitude: {2}", prec, lat, lon)) + Georef.Reverse(georefstring.Substring(0, 4), lat, lon, prec, True) + Console.WriteLine(String.Format("Precision: {0} Latitude: {1} Longitude: {2}", prec, lat, lon)) + Georef.Reverse(georefstring, lat, lon, prec, True) + Console.WriteLine(String.Format("Precision: {0} Latitude: {1} Longitude: {2}", prec, lat, lon)) + Catch ex As GeographicErr + Console.WriteLine(String.Format("Caught Exception {0}", ex.Message)) + End Try + End Sub +End Module diff --git a/gtsam/3rdparty/GeographicLib/dotnet/examples/VB/example-Rhumb.vb b/gtsam/3rdparty/GeographicLib/dotnet/examples/VB/example-Rhumb.vb new file mode 100644 index 000000000..a27a9b4c5 --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/dotnet/examples/VB/example-Rhumb.vb @@ -0,0 +1,24 @@ +Imports NETGeographicLib + +Module example_Rhumb + Sub Main() + Try + Dim rhumb As Rhumb = New Rhumb(Constants.WGS84.MajorRadius, Constants.WGS84.Flattening, True) + ' Alternatively: const Rhumb& rhumb = Rhumb::WGS84(); + + ' Sample direct calculation, travelling about NE from JFK + Dim lat1 As Double = 40.6, lon1 = -73.8, s12 = 5500000.0, azi12 = 51 + Dim lat2 As Double, lon2 + rhumb.Direct(lat1, lon1, azi12, s12, lat2, lon2) + Console.WriteLine("{0} {1}", lat2, lon2) + + ' Sample inverse calculation, JFK to LHR + lat1 = 40.6 : lon1 = -73.8 ' JFK Airport + lat2 = 51.6 : lon2 = -0.5 ' LHR Airport + rhumb.Inverse(lat1, lon1, lat2, lon2, s12, azi12) + Console.WriteLine("{0} {1}", s12, azi12) + Catch ex As GeographicErr + Console.WriteLine(String.Format("Caught exception: {0}", ex.Message)) + End Try + End Sub +End Module diff --git a/gtsam/3rdparty/GeographicLib/dotnet/examples/VB/example-RhumbLine.vb b/gtsam/3rdparty/GeographicLib/dotnet/examples/VB/example-RhumbLine.vb new file mode 100644 index 000000000..264109796 --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/dotnet/examples/VB/example-RhumbLine.vb @@ -0,0 +1,27 @@ +Imports NETGeographicLib +Module example_RhumbLine + Sub Main() + Try + ' Print waypoints between JFK and SIN + Dim rhumb As Rhumb = New Rhumb(Constants.WGS84.MajorRadius, Constants.WGS84.Flattening, True) + ' Alternatively: const Rhumb& rhumb = Rhumb::WGS84(); + Dim lat1 As Double = 40.64, lon1 = -73.779 ' JFK + Dim lat2 As Double = 1.359, lon2 = 103.989 ' SIN + Dim s12 As Double, azi12 + rhumb.Inverse(lat1, lon1, lat2, lon2, s12, azi12); + Dim line As RhumbLine = rhumb.Line(lat1, lon1, azi12) + + Dim ds As Double = 500000.0 ' Nominal distance between points = 500 km + Dim num As Integer = (Integer)Math.Ceiling(s12 / ds) ' The number of intervals + ' Use intervals of equal length + ds = s12 / num + For i As Integer = 0 To num - 1 + Dim lat As Double, lon + line.Position(i * ds, lat, lon) + Console.WriteLine("{0} {1} {2}", i, lat, lon) + Next + Catch ex As GeographicErr + Console.WriteLine(String.Format("Caught exception: {0}", ex.Message)) + End Try + End Sub +End Module diff --git a/gtsam/3rdparty/GeographicLib/dotnet/examples/VB/example-UTMUPS.vb b/gtsam/3rdparty/GeographicLib/dotnet/examples/VB/example-UTMUPS.vb index 9e45a0fa8..bf3fc9cae 100644 --- a/gtsam/3rdparty/GeographicLib/dotnet/examples/VB/example-UTMUPS.vb +++ b/gtsam/3rdparty/GeographicLib/dotnet/examples/VB/example-UTMUPS.vb @@ -10,7 +10,7 @@ Module example_UTMUPS Dim northp As Boolean Dim x, y As Double UTMUPS.Forward(lat, lon, zone, northp, x, y, -1, True) - Dim zonestr As String = UTMUPS.EncodeZone(zone, northp) + Dim zonestr As String = UTMUPS.EncodeZone(zone, northp, True) Console.WriteLine(String.Format("{0} {1} {2}", zonestr, x, y)) ' Sample reverse calculation zonestr = "38N" diff --git a/gtsam/3rdparty/GeographicLib/examples/CMakeLists.txt b/gtsam/3rdparty/GeographicLib/examples/CMakeLists.txt index fe0034b04..c2d9f0323 100644 --- a/gtsam/3rdparty/GeographicLib/examples/CMakeLists.txt +++ b/gtsam/3rdparty/GeographicLib/examples/CMakeLists.txt @@ -2,52 +2,49 @@ # "exampleprograms" target. These are mainly for including as examples # within the doxygen documentation; however, compiling them catches some # obvious blunders. -file (GLOB EXAMPLE_SOURCES example-*.cpp) +if (GEOGRAPHICLIB_PRECISION EQUAL 2) + # These examples all assume real = double + file (GLOB EXAMPLE_SOURCES example-*.cpp) + if (USE_BOOST_FOR_EXAMPLES AND Boost_FOUND) + add_definitions (-DGEOGRAPHICLIB_HAVE_BOOST_SERIALIZATION=1) + include_directories ("${Boost_INCLUDE_DIRS}") + endif () +else () + set (EXAMPLE_SOURCES) +endif () +set (EXAMPLE_SOURCES ${EXAMPLE_SOURCES} + GeoidToGTX.cpp make-egmcof.cpp JacobiConformal.cpp) + set (EXAMPLES) add_definitions (${PROJECT_DEFINITIONS}) foreach (EXAMPLE_SOURCE ${EXAMPLE_SOURCES}) get_filename_component (EXAMPLE ${EXAMPLE_SOURCE} NAME_WE) set (EXAMPLES ${EXAMPLES} ${EXAMPLE}) + if (EXISTS ${EXAMPLE}.hpp) + set (EXAMPLE_SOURCE ${EXAMPLE_SOURCE} ${EXAMPLE}.hpp) + endif () add_executable (${EXAMPLE} EXCLUDE_FROM_ALL ${EXAMPLE_SOURCE}) - target_link_libraries (${EXAMPLE} ${PROJECT_LIBRARIES}) + target_link_libraries (${EXAMPLE} ${PROJECT_LIBRARIES} + ${QUAD_LIBRARIES} ${MPFR_LIBRARIES}) endforeach () -set (OTHER_EXAMPLES GeoidToGTX.cpp) - -foreach (EXAMPLE_SOURCE ${OTHER_EXAMPLES}) - get_filename_component (EXAMPLE ${EXAMPLE_SOURCE} NAME_WE) - set (EXAMPLES ${EXAMPLES} ${EXAMPLE}) - add_executable (${EXAMPLE} EXCLUDE_FROM_ALL ${EXAMPLE_SOURCE}) - target_link_libraries (${EXAMPLE} ${PROJECT_LIBRARIES}) -endforeach () +if (Boost_FOUND AND GEOGRAPHICLIB_PRECISION EQUAL 2) + target_link_libraries (example-NearestNeighbor ${Boost_LIBRARIES}) +endif () find_package (OpenMP QUIET) if (OPENMP_FOUND) set_target_properties (GeoidToGTX PROPERTIES - COMPILE_FLAGS ${OpenMP_CXX_FLAGS} COMPILE_DEFINITIONS HAVE_OPENMP=1) + COMPILE_FLAGS ${OpenMP_CXX_FLAGS}) if (NOT WIN32) - set_target_properties (GeoidToGTX PROPERTIES LINK_FLAGS ${OpenMP_CXX_FLAGS}) + set_target_properties (GeoidToGTX PROPERTIES + LINK_FLAGS ${OpenMP_CXX_FLAGS}) endif () - message (STATUS "Example program GeoidToGTX will use OpenMP") -else () - message (STATUS "Example program GeoidToGTX will not use OpenMP") endif () add_custom_target (exampleprograms DEPENDS ${EXAMPLES}) -if (MSVC) - get_target_property (_LIBTYPE ${PROJECT_LIBRARIES} TYPE) - if (_LIBTYPE STREQUAL "SHARED_LIBRARY") - # Copy the shared library on Windows systems to this directory - # (examples) so that the tests can be run. - add_custom_command (TARGET exampleprograms POST_BUILD - COMMAND ${CMAKE_COMMAND} -E - copy $ ${CMAKE_CFG_INTDIR} - COMMENT "Copying shared library to examples directory") - endif () -endif () - # Put all the examples into a folder in the IDE set_property (TARGET exampleprograms ${EXAMPLES} PROPERTY FOLDER examples) diff --git a/gtsam/3rdparty/GeographicLib/examples/GeoidToGTX.cpp b/gtsam/3rdparty/GeographicLib/examples/GeoidToGTX.cpp index b4b29deed..936dd11d9 100644 --- a/gtsam/3rdparty/GeographicLib/examples/GeoidToGTX.cpp +++ b/gtsam/3rdparty/GeographicLib/examples/GeoidToGTX.cpp @@ -1,6 +1,6 @@ -// Write out a gtx file of geoid heights. For egm2008 at 1' resolution this -// takes about 40 mins on a 8-processor Intel 2.66 GHz machine using OpenMP -// (-DHAVE_OPENMP=1). +// Write out a gtx file of geoid heights above the ellipsoid. For egm2008 at +// 1' resolution this takes about 40 mins on a 8-processor Intel 2.66 GHz +// machine using OpenMP. // // For the format of gtx files, see // http://vdatum.noaa.gov/dev/gtx_info.html#dev_gtx_binary @@ -20,6 +20,12 @@ #include #include +#if defined(_OPENMP) +#define HAVE_OPENMP 1 +#else +#define HAVE_OPENMP 0 +#endif + #if HAVE_OPENMP # include #endif @@ -31,7 +37,7 @@ using namespace std; using namespace GeographicLib; -int main(int argc, char* argv[]) { +int main(int argc, const char* const argv[]) { // Hardwired for 3 args: // 1 = the gravity model (e.g., egm2008) // 2 = intervals per degree @@ -42,16 +48,18 @@ int main(int argc, char* argv[]) { return 1; } try { + // Will need to set the precision for each thread, so save return value + int ndigits = Utility::set_digits(); string model(argv[1]); // Number of intervals per degree - int ndeg = Utility::num(string(argv[2])); + int ndeg = Utility::val(string(argv[2])); string filename(argv[3]); GravityModel g(model); int nlat = 180 * ndeg + 1, nlon = 360 * ndeg; - double - delta = 1 / double(ndeg), // Grid spacing + Math::real + delta = 1 / Math::real(ndeg), // Grid spacing latorg = -90, lonorg = -180; // Write results as floats in binary mode @@ -59,9 +67,9 @@ int main(int argc, char* argv[]) { // Write header { - double transform[] = {latorg, lonorg, delta, delta}; + Math::real transform[] = {latorg, lonorg, delta, delta}; unsigned sizes[] = {unsigned(nlat), unsigned(nlon)}; - Utility::writearray(file, transform, 4); + Utility::writearray(file, transform, 4); Utility::writearray(file, sizes, 2); } @@ -76,12 +84,13 @@ int main(int argc, char* argv[]) { # pragma omp parallel for #endif for (int ilat = ilat0; ilat < nlat0; ++ilat) { // Loop over latitudes - double + Utility::set_digits(ndigits); // Set the precision + Math::real lat = latorg + (ilat / ndeg) + delta * (ilat - ndeg * (ilat / ndeg)), h = 0; GravityCircle c(g.Circle(lat, h, GravityModel::GEOID_HEIGHT)); for (int ilon = 0; ilon < nlon; ++ilon) { // Loop over longitudes - double lon = lonorg + Math::real lon = lonorg + (ilon / ndeg) + delta * (ilon - ndeg * (ilon / ndeg)); N[ilat - ilat0][ilon] = float(c.GeoidHeight(lon)); } // longitude loop @@ -99,5 +108,4 @@ int main(int argc, char* argv[]) { cerr << "Caught unknown exception\n"; return 1; } - return 0; } diff --git a/gtsam/3rdparty/GeographicLib/examples/JacobiConformal.cpp b/gtsam/3rdparty/GeographicLib/examples/JacobiConformal.cpp new file mode 100644 index 000000000..3340b0a10 --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/examples/JacobiConformal.cpp @@ -0,0 +1,43 @@ +// Example of using the GeographicLib::JacobiConformal class. + +#include +#include +#include +#include +#include "JacobiConformal.hpp" + +using namespace std; +using namespace GeographicLib; + +int main() { + try { + Utility::set_digits(); + // These parameters were derived from the EGM2008 geoid; see 2011-07-04 + // E-mail to PROJ.4 list, "Analyzing the bumps in the EGM2008 geoid". The + // longitude of the major axis is -15. These are close to the values given + // by Milan Bursa, Vladimira Fialova, "Parameters of the Earth's tri-axial + // level ellipsoid", Studia Geophysica et Geodaetica 37(1), 1-13 (1993): + // + // longitude of major axis = -14.93 +/- 0.05 + // a = 6378171.36 +/- 0.30 + // a/(a-c) = 297.7738 +/- 0.0003 + // a/(a-b) = 91449 +/- 60 + // which gives: a = 6378171.36, b = 6378101.61, c = 6356751.84 + Math::real a = 6378137+35, b = 6378137-35, c = 6356752; + JacobiConformal jc(a, b, c, a-b, b-c); + cout << fixed << setprecision(1) + << "Ellipsoid parameters: a = " + << a << ", b = " << b << ", c = " << c << "\n" + << setprecision(10) + << "Quadrants: x = " << jc.x() << ", y = " << jc.y() << "\n"; + cout << "Coordinates (angle x y) in degrees:\n"; + for (int i = 0; i <= 90; i += 5) { + Math::real omg = i, bet = i; + cout << i << " " << jc.x(omg) << " " << jc.y(bet) << "\n"; + } + } + catch (const exception& e) { + cerr << "Caught exception: " << e.what() << "\n"; + return 1; + } +} diff --git a/gtsam/3rdparty/GeographicLib/examples/JacobiConformal.hpp b/gtsam/3rdparty/GeographicLib/examples/JacobiConformal.hpp new file mode 100644 index 000000000..6b356162e --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/examples/JacobiConformal.hpp @@ -0,0 +1,167 @@ +/** + * \file JacobiConformal.hpp + * \brief Header for GeographicLib::JacobiConformal class + * + * NOTE: This is just sample code. It is not part of GeographicLib + * itself. + * + * Copyright (c) Charles Karney (2014-2015) and licensed + * under the MIT/X11 License. For more information, see + * https://geographiclib.sourceforge.io/ + **********************************************************************/ + +#include + +namespace GeographicLib { + /** + * \brief Jacobi's conformal projection of a triaxial ellipsoid + * + * NOTE: This is just sample code. It is not part of GeographicLib + * itself. + * + * This is a conformal projection of the ellipsoid to a plane in which + * the grid lines are straight; see Jacobi, + * + * Vorlesungen über Dynamik, §28. The constructor takes the + * semi-axes of the ellipsoid (which must be in order). Member functions map + * the ellipsoidal coordinates ω and β separately to \e x and \e + * y. Jacobi's coordinates have been multiplied by + * (a2c2)1/2 / + * (2b) so that the customary results are returned in the cases of + * a sphere or an ellipsoid of revolution. + * + * The ellipsoid is oriented so that the large principal ellipse, \f$Z=0\f$, + * is the equator, \f$\beta=0\f$, while the small principal ellipse, + * \f$Y=0\f$, is the prime meridian, \f$\omega=0\f$. The four umbilic + * points, \f$\left|\omega\right| = \left|\beta\right| = \frac12\pi\f$, lie + * on middle principal ellipse in the plane \f$X=0\f$. + * + * For more information on this projection, see \ref jacobi. + **********************************************************************/ + class JacobiConformal { + typedef Math::real real; + real _a, _b, _c, _ab2, _bc2, _ac2; + EllipticFunction _ex, _ey; + static void norm(real& x, real& y) + { real z = Math::hypot(x, y); x /= z; y /= z; } + public: + /** + * Constructor for a trixial ellipsoid with semi-axes. + * + * @param[in] a the largest semi-axis. + * @param[in] b the middle semi-axis. + * @param[in] c the smallest semi-axis. + * + * The semi-axes must satisfy \e a ≥ \e b ≥ \e c > 0 and \e a > + * \e c. This form of the constructor cannot be used to specify a + * sphere (use the next constructor). + **********************************************************************/ + JacobiConformal(real a, real b, real c) + : _a(a), _b(b), _c(c) + , _ab2((_a - _b) * (_a + _b)) + , _bc2((_b - _c) * (_b + _c)) + , _ac2((_a - _c) * (_a + _c)) + , _ex(_ab2 / _ac2 * Math::sq(_c / _b), -_ab2 / Math::sq(_b), + _bc2 / _ac2 * Math::sq(_a / _b), Math::sq(_a / _b)) + , _ey(_bc2 / _ac2 * Math::sq(_a / _b), +_bc2 / Math::sq(_b), + _ab2 / _ac2 * Math::sq(_c / _b), Math::sq(_c / _b)) + { + if (!(Math::isfinite(_a) && _a >= _b && _b >= _c && _c > 0)) + throw GeographicErr("JacobiConformal: axes are not in order"); + if (!(_a > _c)) + throw GeographicErr + ("JacobiConformal: use alternate constructor for sphere"); + } + /** + * Alternate constructor for a triaxial ellipsoid. + * + * @param[in] a the largest semi-axis. + * @param[in] b the middle semi-axis. + * @param[in] c the smallest semi-axis. + * @param[in] ab the relative magnitude of \e a − \e b. + * @param[in] bc the relative magnitude of \e b − \e c. + * + * This form can be used to specify a sphere. The semi-axes must + * satisfy \e a ≥ \e b ≥ c > 0. The ratio \e ab : \e bc must equal + * (ab) : (bc) with \e ab + * ≥ 0, \e bc ≥ 0, and \e ab + \e bc > 0. + **********************************************************************/ + JacobiConformal(real a, real b, real c, real ab, real bc) + : _a(a), _b(b), _c(c) + , _ab2(ab * (_a + _b)) + , _bc2(bc * (_b + _c)) + , _ac2(_ab2 + _bc2) + , _ex(_ab2 / _ac2 * Math::sq(_c / _b), + -(_a - _b) * (_a + _b) / Math::sq(_b), + _bc2 / _ac2 * Math::sq(_a / _b), Math::sq(_a / _b)) + , _ey(_bc2 / _ac2 * Math::sq(_a / _b), + +(_b - _c) * (_b + _c) / Math::sq(_b), + _ab2 / _ac2 * Math::sq(_c / _b), Math::sq(_c / _b)) + { + if (!(Math::isfinite(_a) && _a >= _b && _b >= _c && _c > 0 && + ab >= 0 && bc >= 0)) + throw GeographicErr("JacobiConformal: axes are not in order"); + if (!(ab + bc > 0 && Math::isfinite(_ac2))) + throw GeographicErr("JacobiConformal: ab + bc must be positive"); + } + /** + * @return the quadrant length in the \e x direction. + **********************************************************************/ + Math::real x() const { return Math::sq(_a / _b) * _ex.Pi(); } + /** + * The \e x projection. + * + * @param[in] somg sin(ω). + * @param[in] comg cos(ω). + * @return \e x. + **********************************************************************/ + Math::real x(real somg, real comg) const { + real somg1 = _b * somg, comg1 = _a * comg; norm(somg1, comg1); + return Math::sq(_a / _b) + * _ex.Pi(somg1, comg1, _ex.Delta(somg1, comg1)); + } + /** + * The \e x projection. + * + * @param[in] omg ω (in degrees). + * @return \e x (in degrees). + * + * ω must be in (−180°, 180°]. + **********************************************************************/ + Math::real x(real omg) const { + real somg, comg; + Math::sincosd(omg, somg, comg); + return x(somg, comg) / Math::degree(); + } + /** + * @return the quadrant length in the \e y direction. + **********************************************************************/ + Math::real y() const { return Math::sq(_c / _b) * _ey.Pi(); } + /** + * The \e y projection. + * + * @param[in] sbet sin(β). + * @param[in] cbet cos(β). + * @return \e y. + **********************************************************************/ + Math::real y(real sbet, real cbet) const { + real sbet1 = _b * sbet, cbet1 = _c * cbet; norm(sbet1, cbet1); + return Math::sq(_c / _b) + * _ey.Pi(sbet1, cbet1, _ey.Delta(sbet1, cbet1)); + } + /** + * The \e y projection. + * + * @param[in] bet β (in degrees). + * @return \e y (in degrees). + * + * β must be in (−180°, 180°]. + **********************************************************************/ + Math::real y(real bet) const { + real sbet, cbet; + Math::sincosd(bet, sbet, cbet); + return y(sbet, cbet) / Math::degree(); + } + }; + +} // namespace GeographicLib diff --git a/gtsam/3rdparty/GeographicLib/examples/Makefile.am b/gtsam/3rdparty/GeographicLib/examples/Makefile.am index 8e3205745..e74aa69f5 100644 --- a/gtsam/3rdparty/GeographicLib/examples/Makefile.am +++ b/gtsam/3rdparty/GeographicLib/examples/Makefile.am @@ -13,6 +13,7 @@ EXAMPLE_FILES = \ example-DMS.cpp \ example-Ellipsoid.cpp \ example-EllipticFunction.cpp \ + example-GARS.cpp \ example-GeoCoords.cpp \ example-Geocentric.cpp \ example-Geodesic.cpp \ @@ -23,6 +24,7 @@ EXAMPLE_FILES = \ example-GeographicErr.cpp \ example-Geohash.cpp \ example-Geoid.cpp \ + example-Georef.cpp \ example-Gnomonic.cpp \ example-GravityCircle.cpp \ example-GravityModel.cpp \ @@ -32,10 +34,13 @@ EXAMPLE_FILES = \ example-MagneticCircle.cpp \ example-MagneticModel.cpp \ example-Math.cpp \ + example-NearestNeighbor.cpp \ example-NormalGravity.cpp \ example-OSGB.cpp \ example-PolarStereographic.cpp \ example-PolygonArea.cpp \ + example-Rhumb.cpp \ + example-RhumbLine.cpp \ example-SphericalEngine.cpp \ example-SphericalHarmonic.cpp \ example-SphericalHarmonic1.cpp \ @@ -44,6 +49,8 @@ EXAMPLE_FILES = \ example-TransverseMercatorExact.cpp \ example-UTMUPS.cpp \ example-Utility.cpp \ - GeoidToGTX.cpp + GeoidToGTX.cpp \ + JacobiConformal.cpp JacobiConformal.hpp \ + make-egmcof.cpp EXTRA_DIST = CMakeLists.txt $(EXAMPLE_FILES) diff --git a/gtsam/3rdparty/GeographicLib/examples/Makefile.in b/gtsam/3rdparty/GeographicLib/examples/Makefile.in index 8e86fd70e..0135a0789 100644 --- a/gtsam/3rdparty/GeographicLib/examples/Makefile.in +++ b/gtsam/3rdparty/GeographicLib/examples/Makefile.in @@ -1,7 +1,7 @@ -# Makefile.in generated by automake 1.12.2 from Makefile.am. +# Makefile.in generated by automake 1.15 from Makefile.am. # @configure_input@ -# Copyright (C) 1994-2012 Free Software Foundation, Inc. +# Copyright (C) 1994-2014 Free Software Foundation, Inc. # This Makefile.in is free software; the Free Software Foundation # gives unlimited permission to copy and/or distribute it, @@ -19,23 +19,61 @@ # # Copyright (C) 2011, Charles Karney VPATH = @srcdir@ -am__make_dryrun = \ - { \ - am__dry=no; \ +am__is_gnu_make = { \ + if test -z '$(MAKELEVEL)'; then \ + false; \ + elif test -n '$(MAKE_HOST)'; then \ + true; \ + elif test -n '$(MAKE_VERSION)' && test -n '$(CURDIR)'; then \ + true; \ + else \ + false; \ + fi; \ +} +am__make_running_with_option = \ + case $${target_option-} in \ + ?) ;; \ + *) echo "am__make_running_with_option: internal error: invalid" \ + "target option '$${target_option-}' specified" >&2; \ + exit 1;; \ + esac; \ + has_opt=no; \ + sane_makeflags=$$MAKEFLAGS; \ + if $(am__is_gnu_make); then \ + sane_makeflags=$$MFLAGS; \ + else \ case $$MAKEFLAGS in \ *\\[\ \ ]*) \ - echo 'am--echo: ; @echo "AM" OK' | $(MAKE) -f - 2>/dev/null \ - | grep '^AM OK$$' >/dev/null || am__dry=yes;; \ - *) \ - for am__flg in $$MAKEFLAGS; do \ - case $$am__flg in \ - *=*|--*) ;; \ - *n*) am__dry=yes; break;; \ - esac; \ - done;; \ + bs=\\; \ + sane_makeflags=`printf '%s\n' "$$MAKEFLAGS" \ + | sed "s/$$bs$$bs[$$bs $$bs ]*//g"`;; \ esac; \ - test $$am__dry = yes; \ - } + fi; \ + skip_next=no; \ + strip_trailopt () \ + { \ + flg=`printf '%s\n' "$$flg" | sed "s/$$1.*$$//"`; \ + }; \ + for flg in $$sane_makeflags; do \ + test $$skip_next = yes && { skip_next=no; continue; }; \ + case $$flg in \ + *=*|--*) continue;; \ + -*I) strip_trailopt 'I'; skip_next=yes;; \ + -*I?*) strip_trailopt 'I';; \ + -*O) strip_trailopt 'O'; skip_next=yes;; \ + -*O?*) strip_trailopt 'O';; \ + -*l) strip_trailopt 'l'; skip_next=yes;; \ + -*l?*) strip_trailopt 'l';; \ + -[dEDm]) skip_next=yes;; \ + -[JT]) skip_next=yes;; \ + esac; \ + case $$flg in \ + *$$target_option*) has_opt=yes; break;; \ + esac; \ + done; \ + test $$has_opt = yes +am__make_dryrun = (target_option=n; $(am__make_running_with_option)) +am__make_keepgoing = (target_option=k; $(am__make_running_with_option)) pkgdatadir = $(datadir)/@PACKAGE@ pkgincludedir = $(includedir)/@PACKAGE@ pkglibdir = $(libdir)/@PACKAGE@ @@ -56,18 +94,30 @@ build_triplet = @build@ host_triplet = @host@ target_triplet = @target@ subdir = examples -DIST_COMMON = $(srcdir)/Makefile.am $(srcdir)/Makefile.in ACLOCAL_M4 = $(top_srcdir)/aclocal.m4 am__aclocal_m4_deps = $(top_srcdir)/m4/libtool.m4 \ $(top_srcdir)/m4/ltoptions.m4 $(top_srcdir)/m4/ltsugar.m4 \ $(top_srcdir)/m4/ltversion.m4 $(top_srcdir)/m4/lt~obsolete.m4 \ - $(top_srcdir)/configure.ac + $(top_srcdir)/m4/pkg.m4 $(top_srcdir)/configure.ac am__configure_deps = $(am__aclocal_m4_deps) $(CONFIGURE_DEPENDENCIES) \ $(ACLOCAL_M4) +DIST_COMMON = $(srcdir)/Makefile.am $(am__DIST_COMMON) mkinstalldirs = $(install_sh) -d CONFIG_HEADER = $(top_builddir)/include/GeographicLib/Config-ac.h CONFIG_CLEAN_FILES = CONFIG_CLEAN_VPATH_FILES = +AM_V_P = $(am__v_P_@AM_V@) +am__v_P_ = $(am__v_P_@AM_DEFAULT_V@) +am__v_P_0 = false +am__v_P_1 = : +AM_V_GEN = $(am__v_GEN_@AM_V@) +am__v_GEN_ = $(am__v_GEN_@AM_DEFAULT_V@) +am__v_GEN_0 = @echo " GEN " $@; +am__v_GEN_1 = +AM_V_at = $(am__v_at_@AM_V@) +am__v_at_ = $(am__v_at_@AM_DEFAULT_V@) +am__v_at_0 = @ +am__v_at_1 = SOURCES = DIST_SOURCES = am__can_run_installinfo = \ @@ -75,9 +125,12 @@ am__can_run_installinfo = \ n|no|NO) false;; \ *) (install-info --version) >/dev/null 2>&1;; \ esac +am__tagged_files = $(HEADERS) $(SOURCES) $(TAGS_FILES) $(LISP) +am__DIST_COMMON = $(srcdir)/Makefile.in DISTFILES = $(DIST_COMMON) $(DIST_SOURCES) $(TEXINFOS) $(EXTRA_DIST) ACLOCAL = @ACLOCAL@ AMTAR = @AMTAR@ +AM_DEFAULT_VERBOSITY = @AM_DEFAULT_VERBOSITY@ AR = @AR@ AUTOCONF = @AUTOCONF@ AUTOHEADER = @AUTOHEADER@ @@ -126,6 +179,7 @@ LTLIBOBJS = @LTLIBOBJS@ LT_AGE = @LT_AGE@ LT_CURRENT = @LT_CURRENT@ LT_REVISION = @LT_REVISION@ +LT_SYS_LIBRARY_PATH = @LT_SYS_LIBRARY_PATH@ MAINT = @MAINT@ MAKEINFO = @MAKEINFO@ MANIFEST_TOOL = @MANIFEST_TOOL@ @@ -144,9 +198,11 @@ PACKAGE_TARNAME = @PACKAGE_TARNAME@ PACKAGE_URL = @PACKAGE_URL@ PACKAGE_VERSION = @PACKAGE_VERSION@ PATH_SEPARATOR = @PATH_SEPARATOR@ +PKG_CONFIG = @PKG_CONFIG@ +PKG_CONFIG_LIBDIR = @PKG_CONFIG_LIBDIR@ +PKG_CONFIG_PATH = @PKG_CONFIG_PATH@ POD2HTML = @POD2HTML@ POD2MAN = @POD2MAN@ -POW_LIB = @POW_LIB@ RANLIB = @RANLIB@ SED = @SED@ SET_MAKE = @SET_MAKE@ @@ -195,6 +251,7 @@ mandir = @mandir@ mkdir_p = @mkdir_p@ oldincludedir = @oldincludedir@ pdfdir = @pdfdir@ +pkgconfigdir = @pkgconfigdir@ prefix = @prefix@ program_transform_name = @program_transform_name@ psdir = @psdir@ @@ -220,6 +277,7 @@ EXAMPLE_FILES = \ example-DMS.cpp \ example-Ellipsoid.cpp \ example-EllipticFunction.cpp \ + example-GARS.cpp \ example-GeoCoords.cpp \ example-Geocentric.cpp \ example-Geodesic.cpp \ @@ -230,6 +288,7 @@ EXAMPLE_FILES = \ example-GeographicErr.cpp \ example-Geohash.cpp \ example-Geoid.cpp \ + example-Georef.cpp \ example-Gnomonic.cpp \ example-GravityCircle.cpp \ example-GravityModel.cpp \ @@ -239,10 +298,13 @@ EXAMPLE_FILES = \ example-MagneticCircle.cpp \ example-MagneticModel.cpp \ example-Math.cpp \ + example-NearestNeighbor.cpp \ example-NormalGravity.cpp \ example-OSGB.cpp \ example-PolarStereographic.cpp \ example-PolygonArea.cpp \ + example-Rhumb.cpp \ + example-RhumbLine.cpp \ example-SphericalEngine.cpp \ example-SphericalHarmonic.cpp \ example-SphericalHarmonic1.cpp \ @@ -251,7 +313,9 @@ EXAMPLE_FILES = \ example-TransverseMercatorExact.cpp \ example-UTMUPS.cpp \ example-Utility.cpp \ - GeoidToGTX.cpp + GeoidToGTX.cpp \ + JacobiConformal.cpp JacobiConformal.hpp \ + make-egmcof.cpp EXTRA_DIST = CMakeLists.txt $(EXAMPLE_FILES) all: all-am @@ -269,7 +333,6 @@ $(srcdir)/Makefile.in: @MAINTAINER_MODE_TRUE@ $(srcdir)/Makefile.am $(am__confi echo ' cd $(top_srcdir) && $(AUTOMAKE) --gnu examples/Makefile'; \ $(am__cd) $(top_srcdir) && \ $(AUTOMAKE) --gnu examples/Makefile -.PRECIOUS: Makefile Makefile: $(srcdir)/Makefile.in $(top_builddir)/config.status @case '$?' in \ *config.status*) \ @@ -293,11 +356,9 @@ mostlyclean-libtool: clean-libtool: -rm -rf .libs _libs -tags: TAGS -TAGS: +tags TAGS: -ctags: CTAGS -CTAGS: +ctags CTAGS: cscope cscopelist: @@ -435,15 +496,18 @@ uninstall-am: .MAKE: install-am install-strip .PHONY: all all-am check check-am clean clean-generic clean-libtool \ - distclean distclean-generic distclean-libtool distdir dvi \ - dvi-am html html-am info info-am install install-am \ - install-data install-data-am install-dvi install-dvi-am \ - install-exec install-exec-am install-html install-html-am \ - install-info install-info-am install-man install-pdf \ - install-pdf-am install-ps install-ps-am install-strip \ - installcheck installcheck-am installdirs maintainer-clean \ - maintainer-clean-generic mostlyclean mostlyclean-generic \ - mostlyclean-libtool pdf pdf-am ps ps-am uninstall uninstall-am + cscopelist-am ctags-am distclean distclean-generic \ + distclean-libtool distdir dvi dvi-am html html-am info info-am \ + install install-am install-data install-data-am install-dvi \ + install-dvi-am install-exec install-exec-am install-html \ + install-html-am install-info install-info-am install-man \ + install-pdf install-pdf-am install-ps install-ps-am \ + install-strip installcheck installcheck-am installdirs \ + maintainer-clean maintainer-clean-generic mostlyclean \ + mostlyclean-generic mostlyclean-libtool pdf pdf-am ps ps-am \ + tags-am uninstall uninstall-am + +.PRECIOUS: Makefile # Tell versions [3.59,3.63) of GNU make to not export all variables. diff --git a/gtsam/3rdparty/GeographicLib/examples/example-Accumulator.cpp b/gtsam/3rdparty/GeographicLib/examples/example-Accumulator.cpp index d301e1900..fde8dff96 100644 --- a/gtsam/3rdparty/GeographicLib/examples/example-Accumulator.cpp +++ b/gtsam/3rdparty/GeographicLib/examples/example-Accumulator.cpp @@ -12,7 +12,7 @@ int main() { // Compare using Accumulator and ordinary summation for a sum of large and // small terms. double sum = 0; - Accumulator acc = 0; + Accumulator<> acc = 0; sum += 1e20; sum += 1; sum += 2; sum += 100; sum += 5000; sum += -1e20; acc += 1e20; acc += 1; acc += 2; acc += 100; acc += 5000; acc += -1e20; cout << sum << " " << acc() << "\n"; @@ -21,5 +21,4 @@ int main() { cerr << "Caught exception: " << e.what() << "\n"; return 1; } - return 0; } diff --git a/gtsam/3rdparty/GeographicLib/examples/example-AlbersEqualArea.cpp b/gtsam/3rdparty/GeographicLib/examples/example-AlbersEqualArea.cpp index f56dc73c0..cb7dfdf38 100644 --- a/gtsam/3rdparty/GeographicLib/examples/example-AlbersEqualArea.cpp +++ b/gtsam/3rdparty/GeographicLib/examples/example-AlbersEqualArea.cpp @@ -10,11 +10,11 @@ using namespace GeographicLib; int main() { try { const double - a = Constants::WGS84_a(), - f = Constants::WGS84_f(), + a = Constants::WGS84_a(), + f = Constants::WGS84_f(), lat1 = 40 + 58/60.0, lat2 = 39 + 56/60.0, // standard parallels k1 = 1, // scale - lon0 = -77 - 45/60.0; // Central meridan + lon0 = -77 - 45/60.0; // Central meridian // Set up basic projection const AlbersEqualArea albers(a, f, lat1, lat2, k1); { @@ -22,19 +22,18 @@ int main() { double lat = 39.95, lon = -75.17; // Philadelphia double x, y; albers.Forward(lon0, lat, lon, x, y); - std::cout << x << " " << y << "\n"; + cout << x << " " << y << "\n"; } { // Sample conversion from Albers Equal Area grid to geodetic double x = 220e3, y = -53e3; double lat, lon; albers.Reverse(lon0, x, y, lat, lon); - std::cout << lat << " " << lon << "\n"; + cout << lat << " " << lon << "\n"; } } catch (const exception& e) { cerr << "Caught exception: " << e.what() << "\n"; return 1; } - return 0; } diff --git a/gtsam/3rdparty/GeographicLib/examples/example-AzimuthalEquidistant.cpp b/gtsam/3rdparty/GeographicLib/examples/example-AzimuthalEquidistant.cpp index 8af2d009b..d5299809d 100644 --- a/gtsam/3rdparty/GeographicLib/examples/example-AzimuthalEquidistant.cpp +++ b/gtsam/3rdparty/GeographicLib/examples/example-AzimuthalEquidistant.cpp @@ -11,7 +11,7 @@ using namespace GeographicLib; int main() { try { Geodesic geod(Constants::WGS84_a(), Constants::WGS84_f()); - // Alternatively: const Geodesic& geod = Geodesic::WGS84; + // Alternatively: const Geodesic& geod = Geodesic::WGS84(); const double lat0 = 48 + 50/60.0, lon0 = 2 + 20/60.0; // Paris AzimuthalEquidistant proj(geod); { @@ -33,5 +33,4 @@ int main() { cerr << "Caught exception: " << e.what() << "\n"; return 1; } - return 0; } diff --git a/gtsam/3rdparty/GeographicLib/examples/example-CassiniSoldner.cpp b/gtsam/3rdparty/GeographicLib/examples/example-CassiniSoldner.cpp index 173a717f0..4922ca8a6 100644 --- a/gtsam/3rdparty/GeographicLib/examples/example-CassiniSoldner.cpp +++ b/gtsam/3rdparty/GeographicLib/examples/example-CassiniSoldner.cpp @@ -11,7 +11,7 @@ using namespace GeographicLib; int main() { try { Geodesic geod(Constants::WGS84_a(), Constants::WGS84_f()); - // Alternatively: const Geodesic& geod = Geodesic::WGS84; + // Alternatively: const Geodesic& geod = Geodesic::WGS84(); const double lat0 = 48 + 50/60.0, lon0 = 2 + 20/60.0; // Paris CassiniSoldner proj(lat0, lon0, geod); { @@ -33,5 +33,4 @@ int main() { cerr << "Caught exception: " << e.what() << "\n"; return 1; } - return 0; } diff --git a/gtsam/3rdparty/GeographicLib/examples/example-CircularEngine.cpp b/gtsam/3rdparty/GeographicLib/examples/example-CircularEngine.cpp index 10ac74c6b..2bb8f07ac 100644 --- a/gtsam/3rdparty/GeographicLib/examples/example-CircularEngine.cpp +++ b/gtsam/3rdparty/GeographicLib/examples/example-CircularEngine.cpp @@ -31,5 +31,4 @@ int main() { cerr << "Caught exception: " << e.what() << "\n"; return 1; } - return 0; } diff --git a/gtsam/3rdparty/GeographicLib/examples/example-Constants.cpp b/gtsam/3rdparty/GeographicLib/examples/example-Constants.cpp index 8123d8d89..706f4ad25 100644 --- a/gtsam/3rdparty/GeographicLib/examples/example-Constants.cpp +++ b/gtsam/3rdparty/GeographicLib/examples/example-Constants.cpp @@ -17,5 +17,4 @@ int main() { cerr << "Caught exception: " << e.what() << "\n"; return 1; } - return 0; } diff --git a/gtsam/3rdparty/GeographicLib/examples/example-DMS.cpp b/gtsam/3rdparty/GeographicLib/examples/example-DMS.cpp index dc4006c99..583a174d4 100644 --- a/gtsam/3rdparty/GeographicLib/examples/example-DMS.cpp +++ b/gtsam/3rdparty/GeographicLib/examples/example-DMS.cpp @@ -1,6 +1,7 @@ // Example of using the GeographicLib::DMS class #include +#include #include #include @@ -25,5 +26,4 @@ int main() { cerr << "Caught exception: " << e.what() << "\n"; return 1; } - return 0; } diff --git a/gtsam/3rdparty/GeographicLib/examples/example-Ellipsoid.cpp b/gtsam/3rdparty/GeographicLib/examples/example-Ellipsoid.cpp index 3e00a7562..fcda24543 100644 --- a/gtsam/3rdparty/GeographicLib/examples/example-Ellipsoid.cpp +++ b/gtsam/3rdparty/GeographicLib/examples/example-Ellipsoid.cpp @@ -10,7 +10,7 @@ using namespace GeographicLib; int main() { try { Ellipsoid wgs84(Constants::WGS84_a(), Constants::WGS84_f()); - // Alternatively: const Ellipsoid& wgs84 = Ellipsoid::WGS84; + // Alternatively: const Ellipsoid& wgs84 = Ellipsoid::WGS84(); cout << "The latitude half way between the equator and the pole is " << wgs84.InverseRectifyingLatitude(45) << "\n"; cout << "Half the area of the ellipsoid lies between latitudes +/- " @@ -22,5 +22,4 @@ int main() { cerr << "Caught exception: " << e.what() << "\n"; return 1; } - return 0; } diff --git a/gtsam/3rdparty/GeographicLib/examples/example-EllipticFunction.cpp b/gtsam/3rdparty/GeographicLib/examples/example-EllipticFunction.cpp index c2ae4a338..51b6b14eb 100644 --- a/gtsam/3rdparty/GeographicLib/examples/example-EllipticFunction.cpp +++ b/gtsam/3rdparty/GeographicLib/examples/example-EllipticFunction.cpp @@ -2,6 +2,7 @@ #include #include +#include #include #include #include @@ -14,11 +15,12 @@ int main() { EllipticFunction ell(0.1); // parameter m = 0.1 // See Abramowitz and Stegun, table 17.1 cout << ell.K() << " " << ell.E() << "\n"; - double phi = 20 * Math::degree(); + double phi = 20, sn, cn; + Math::sincosd(phi, sn ,cn); // See Abramowitz and Stegun, table 17.6 with // alpha = asin(sqrt(m)) = 18.43 deg and phi = 20 deg - cout << ell.E(phi) << " " - << ell.E(sin(phi), cos(phi), sqrt(1 - ell.k2() * Math::sq(sin(phi)))) + cout << ell.E(phi * Math::degree()) << " " + << ell.E(sn, cn, ell.Delta(sn, cn)) << "\n"; // See Carlson 1995, Sec 3. cout << fixed << setprecision(16) @@ -35,8 +37,7 @@ int main() { << "RG(2,3,4) = " << EllipticFunction::RG(2,3,4) << "\n" << "RG(0,0.0796,4) = " << EllipticFunction::RG(0.0796,4) << "\n"; } - catch (const GeographicErr& e) { + catch (const exception& e) { cout << "Caught exception: " << e.what() << "\n"; } - return 0; } diff --git a/gtsam/3rdparty/GeographicLib/examples/example-GARS.cpp b/gtsam/3rdparty/GeographicLib/examples/example-GARS.cpp new file mode 100644 index 000000000..f75083160 --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/examples/example-GARS.cpp @@ -0,0 +1,39 @@ +// Example of using the GeographicLib::GARS class + +#include +#include +#include +#include +#include + +using namespace std; +using namespace GeographicLib; + +int main() { + try { + { + // Sample forward calculation + double lat = 57.64911, lon = 10.40744; // Jutland + string gars; + for (int prec = 0; prec <= 2; ++prec) { + GARS::Forward(lat, lon, prec, gars); + cout << prec << " " << gars << "\n"; + } + } + { + // Sample reverse calculation + string gars = "381NH45"; + double lat, lon; + cout << fixed; + for (int len = 5; len <= int(gars.size()); ++len) { + int prec; + GARS::Reverse(gars.substr(0, len), lat, lon, prec); + cout << prec << " " << lat << " " << lon << "\n"; + } + } + } + catch (const exception& e) { + cerr << "Caught exception: " << e.what() << "\n"; + return 1; + } +} diff --git a/gtsam/3rdparty/GeographicLib/examples/example-GeoCoords.cpp b/gtsam/3rdparty/GeographicLib/examples/example-GeoCoords.cpp index 1756f4fd1..bca624a6e 100644 --- a/gtsam/3rdparty/GeographicLib/examples/example-GeoCoords.cpp +++ b/gtsam/3rdparty/GeographicLib/examples/example-GeoCoords.cpp @@ -2,7 +2,6 @@ #include #include -#include #include using namespace std; @@ -24,5 +23,4 @@ int main() { cerr << "Caught exception: " << e.what() << "\n"; return 1; } - return 0; } diff --git a/gtsam/3rdparty/GeographicLib/examples/example-Geocentric.cpp b/gtsam/3rdparty/GeographicLib/examples/example-Geocentric.cpp index 4f069f28b..7b7b41d6e 100644 --- a/gtsam/3rdparty/GeographicLib/examples/example-Geocentric.cpp +++ b/gtsam/3rdparty/GeographicLib/examples/example-Geocentric.cpp @@ -11,7 +11,7 @@ using namespace GeographicLib; int main() { try { Geocentric earth(Constants::WGS84_a(), Constants::WGS84_f()); - // Alternatively: const Geocentric& earth = Geocentric::WGS84; + // Alternatively: const Geocentric& earth = Geocentric::WGS84(); { // Sample forward calculation double lat = 27.99, lon = 86.93, h = 8820; // Mt Everest @@ -33,5 +33,4 @@ int main() { cerr << "Caught exception: " << e.what() << "\n"; return 1; } - return 0; } diff --git a/gtsam/3rdparty/GeographicLib/examples/example-Geodesic-small.cpp b/gtsam/3rdparty/GeographicLib/examples/example-Geodesic-small.cpp index 07cf13598..a9cd39812 100644 --- a/gtsam/3rdparty/GeographicLib/examples/example-Geodesic-small.cpp +++ b/gtsam/3rdparty/GeographicLib/examples/example-Geodesic-small.cpp @@ -7,7 +7,7 @@ using namespace std; using namespace GeographicLib; int main() { - const Geodesic& geod = Geodesic::WGS84; + const Geodesic& geod = Geodesic::WGS84(); // Distance from JFK to LHR double lat1 = 40.6, lon1 = -73.8, // JFK Airport @@ -15,5 +15,4 @@ int main() { double s12; geod.Inverse(lat1, lon1, lat2, lon2, s12); cout << s12 / 1000 << " km\n"; - return 0; } diff --git a/gtsam/3rdparty/GeographicLib/examples/example-Geodesic.cpp b/gtsam/3rdparty/GeographicLib/examples/example-Geodesic.cpp index d6258d9f9..6246a09c3 100644 --- a/gtsam/3rdparty/GeographicLib/examples/example-Geodesic.cpp +++ b/gtsam/3rdparty/GeographicLib/examples/example-Geodesic.cpp @@ -11,7 +11,7 @@ using namespace GeographicLib; int main() { try { Geodesic geod(Constants::WGS84_a(), Constants::WGS84_f()); - // Alternatively: const Geodesic& geod = Geodesic::WGS84; + // Alternatively: const Geodesic& geod = Geodesic::WGS84(); { // Sample direct calculation, travelling about NE from JFK double lat1 = 40.6, lon1 = -73.8, s12 = 5.5e6, azi1 = 51; @@ -33,5 +33,4 @@ int main() { cerr << "Caught exception: " << e.what() << "\n"; return 1; } - return 0; } diff --git a/gtsam/3rdparty/GeographicLib/examples/example-GeodesicExact.cpp b/gtsam/3rdparty/GeographicLib/examples/example-GeodesicExact.cpp index 0745b222e..27d7cb16b 100644 --- a/gtsam/3rdparty/GeographicLib/examples/example-GeodesicExact.cpp +++ b/gtsam/3rdparty/GeographicLib/examples/example-GeodesicExact.cpp @@ -11,7 +11,7 @@ using namespace GeographicLib; int main() { try { GeodesicExact geod(Constants::WGS84_a(), Constants::WGS84_f()); - // Alternatively: const GeodesicExact& geod = GeodesicExact::WGS84; + // Alternatively: const GeodesicExact& geod = GeodesicExact::WGS84(); { // Sample direct calculation, travelling about NE from JFK double lat1 = 40.6, lon1 = -73.8, s12 = 5.5e6, azi1 = 51; @@ -33,5 +33,4 @@ int main() { cerr << "Caught exception: " << e.what() << "\n"; return 1; } - return 0; } diff --git a/gtsam/3rdparty/GeographicLib/examples/example-GeodesicLine.cpp b/gtsam/3rdparty/GeographicLib/examples/example-GeodesicLine.cpp index ffe4c3735..131062053 100644 --- a/gtsam/3rdparty/GeographicLib/examples/example-GeodesicLine.cpp +++ b/gtsam/3rdparty/GeographicLib/examples/example-GeodesicLine.cpp @@ -1,9 +1,9 @@ // Example of using the GeographicLib::GeodesicLine class #include +#include #include #include -#include #include #include #include @@ -15,21 +15,18 @@ int main() { try { // Print waypoints between JFK and SIN Geodesic geod(Constants::WGS84_a(), Constants::WGS84_f()); - // Alternatively: const Geodesic& geod = Geodesic::WGS84; + // Alternatively: const Geodesic& geod = Geodesic::WGS84(); double lat1 = 40.640, lon1 = -73.779, // JFK lat2 = 1.359, lon2 = 103.989; // SIN - double s12, azi1, azi2, - a12 = geod.Inverse(lat1, lon1, lat2, lon2, s12, azi1, azi2); - const GeographicLib::GeodesicLine line(geod, lat1, lon1, azi1); - // Alternatively - // const GeographicLib::GeodesicLine line = geod.Line(lat1, lon1, azi1); - double ds = 500e3; // Nominal distance between points = 500 km - int num = int(ceil(s12 / ds)); // The number of intervals + const GeographicLib::GeodesicLine line = + geod.InverseLine(lat1, lon1, lat2, lon2); + double ds0 = 500e3; // Nominal distance between points = 500 km + int num = int(ceil(line.Distance() / ds0)); // The number of intervals cout << fixed << setprecision(3); { // Use intervals of equal length - double ds = s12 / num; + double ds = line.Distance() / num; for (int i = 0; i <= num; ++i) { double lat, lon; line.Position(i * ds, lat, lon); @@ -38,7 +35,7 @@ int main() { } { // Slightly faster, use intervals of equal arc length - double da = a12 / num; + double da = line.Arc() / num; for (int i = 0; i <= num; ++i) { double lat, lon; line.ArcPosition(i * da, lat, lon); @@ -50,5 +47,4 @@ int main() { cerr << "Caught exception: " << e.what() << "\n"; return 1; } - return 0; } diff --git a/gtsam/3rdparty/GeographicLib/examples/example-GeodesicLineExact.cpp b/gtsam/3rdparty/GeographicLib/examples/example-GeodesicLineExact.cpp index 20473667d..c1842af30 100644 --- a/gtsam/3rdparty/GeographicLib/examples/example-GeodesicLineExact.cpp +++ b/gtsam/3rdparty/GeographicLib/examples/example-GeodesicLineExact.cpp @@ -1,9 +1,9 @@ // Example of using the GeographicLib::GeodesicLineExact class #include +#include #include #include -#include #include #include #include @@ -15,21 +15,18 @@ int main() { try { // Print waypoints between JFK and SIN GeodesicExact geod(Constants::WGS84_a(), Constants::WGS84_f()); - // Alternatively: const GeodesicExact& geod = GeodesicExact::WGS84; + // Alternatively: const GeodesicExact& geod = GeodesicExact::WGS84(); double lat1 = 40.640, lon1 = -73.779, // JFK lat2 = 1.359, lon2 = 103.989; // SIN - double s12, azi1, azi2, - a12 = geod.Inverse(lat1, lon1, lat2, lon2, s12, azi1, azi2); - const GeographicLib::GeodesicLineExact line(geod, lat1, lon1, azi1); - // Alternatively - // const GeographicLib::GeodesicLineExact line = geod.Line(lat1, lon1, azi1); - double ds = 500e3; // Nominal distance between points = 500 km - int num = int(ceil(s12 / ds)); // The number of intervals + const GeographicLib::GeodesicLineExact line = + geod.InverseLine(lat1, lon1, lat2, lon2); + double ds0 = 500e3; // Nominal distance between points = 500 km + int num = int(ceil(line.Distance() / ds0)); // The number of intervals cout << fixed << setprecision(3); { // Use intervals of equal length - double ds = s12 / num; + double ds = line.Distance() / num; for (int i = 0; i <= num; ++i) { double lat, lon; line.Position(i * ds, lat, lon); @@ -38,7 +35,7 @@ int main() { } { // Slightly faster, use intervals of equal arc length - double da = a12 / num; + double da = line.Arc() / num; for (int i = 0; i <= num; ++i) { double lat, lon; line.ArcPosition(i * da, lat, lon); @@ -50,5 +47,4 @@ int main() { cerr << "Caught exception: " << e.what() << "\n"; return 1; } - return 0; } diff --git a/gtsam/3rdparty/GeographicLib/examples/example-GeographicErr.cpp b/gtsam/3rdparty/GeographicLib/examples/example-GeographicErr.cpp index 7bf4acfb5..c64423cc1 100644 --- a/gtsam/3rdparty/GeographicLib/examples/example-GeographicErr.cpp +++ b/gtsam/3rdparty/GeographicLib/examples/example-GeographicErr.cpp @@ -13,5 +13,4 @@ int main() { catch (const GeographicErr& e) { cout << "Caught exception: " << e.what() << "\n"; } - return 0; } diff --git a/gtsam/3rdparty/GeographicLib/examples/example-Geohash.cpp b/gtsam/3rdparty/GeographicLib/examples/example-Geohash.cpp index 3f3fad019..7e40b05e9 100644 --- a/gtsam/3rdparty/GeographicLib/examples/example-Geohash.cpp +++ b/gtsam/3rdparty/GeographicLib/examples/example-Geohash.cpp @@ -38,5 +38,4 @@ int main() { cerr << "Caught exception: " << e.what() << "\n"; return 1; } - return 0; } diff --git a/gtsam/3rdparty/GeographicLib/examples/example-Geoid.cpp b/gtsam/3rdparty/GeographicLib/examples/example-Geoid.cpp index df6e134b8..936e69ecb 100644 --- a/gtsam/3rdparty/GeographicLib/examples/example-Geoid.cpp +++ b/gtsam/3rdparty/GeographicLib/examples/example-Geoid.cpp @@ -22,5 +22,4 @@ int main() { cerr << "Caught exception: " << e.what() << "\n"; return 1; } - return 0; } diff --git a/gtsam/3rdparty/GeographicLib/examples/example-Georef.cpp b/gtsam/3rdparty/GeographicLib/examples/example-Georef.cpp new file mode 100644 index 000000000..c63529ec6 --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/examples/example-Georef.cpp @@ -0,0 +1,41 @@ +// Example of using the GeographicLib::GARS class + +#include +#include +#include +#include +#include + +using namespace std; +using namespace GeographicLib; + +int main() { + try { + { + // Sample forward calculation + double lat = 57.64911, lon = 10.40744; // Jutland + string georef; + for (int prec = -1; prec <= 11; ++prec) { + Georef::Forward(lat, lon, prec, georef); + cout << prec << " " << georef << "\n"; + } + } + { + // Sample reverse calculation + string georef = "NKLN2444638946"; + double lat, lon; + int prec; + cout << fixed; + Georef::Reverse(georef.substr(0, 2), lat, lon, prec); + cout << prec << " " << lat << " " << lon << "\n"; + Georef::Reverse(georef.substr(0, 4), lat, lon, prec); + cout << prec << " " << lat << " " << lon << "\n"; + Georef::Reverse(georef, lat, lon, prec); + cout << prec << " " << lat << " " << lon << "\n"; + } + } + catch (const exception& e) { + cerr << "Caught exception: " << e.what() << "\n"; + return 1; + } +} diff --git a/gtsam/3rdparty/GeographicLib/examples/example-Gnomonic.cpp b/gtsam/3rdparty/GeographicLib/examples/example-Gnomonic.cpp index a78a8605c..1ce909713 100644 --- a/gtsam/3rdparty/GeographicLib/examples/example-Gnomonic.cpp +++ b/gtsam/3rdparty/GeographicLib/examples/example-Gnomonic.cpp @@ -11,7 +11,7 @@ using namespace GeographicLib; int main() { try { Geodesic geod(Constants::WGS84_a(), Constants::WGS84_f()); - // Alternatively: const Geodesic& geod = Geodesic::WGS84; + // Alternatively: const Geodesic& geod = Geodesic::WGS84(); const double lat0 = 48 + 50/60.0, lon0 = 2 + 20/60.0; // Paris Gnomonic proj(geod); { @@ -33,5 +33,4 @@ int main() { cerr << "Caught exception: " << e.what() << "\n"; return 1; } - return 0; } diff --git a/gtsam/3rdparty/GeographicLib/examples/example-GravityCircle.cpp b/gtsam/3rdparty/GeographicLib/examples/example-GravityCircle.cpp index 55dd5ee87..6b8df3d01 100644 --- a/gtsam/3rdparty/GeographicLib/examples/example-GravityCircle.cpp +++ b/gtsam/3rdparty/GeographicLib/examples/example-GravityCircle.cpp @@ -38,5 +38,4 @@ int main() { cerr << "Caught exception: " << e.what() << "\n"; return 1; } - return 0; } diff --git a/gtsam/3rdparty/GeographicLib/examples/example-GravityModel.cpp b/gtsam/3rdparty/GeographicLib/examples/example-GravityModel.cpp index f0e634cd6..d90148673 100644 --- a/gtsam/3rdparty/GeographicLib/examples/example-GravityModel.cpp +++ b/gtsam/3rdparty/GeographicLib/examples/example-GravityModel.cpp @@ -19,5 +19,4 @@ int main() { cerr << "Caught exception: " << e.what() << "\n"; return 1; } - return 0; } diff --git a/gtsam/3rdparty/GeographicLib/examples/example-LambertConformalConic.cpp b/gtsam/3rdparty/GeographicLib/examples/example-LambertConformalConic.cpp index b57308eeb..651b543d7 100644 --- a/gtsam/3rdparty/GeographicLib/examples/example-LambertConformalConic.cpp +++ b/gtsam/3rdparty/GeographicLib/examples/example-LambertConformalConic.cpp @@ -12,7 +12,7 @@ int main() { // Define the Pennsylvania South state coordinate system EPSG:3364 // http://www.spatialreference.org/ref/epsg/3364/ const double - a = Constants::WGS84_a(), + a = Constants::WGS84_a(), f = 1/298.257222101, // GRS80 lat1 = 40 + 58/60.0, lat2 = 39 + 56/60.0, // standard parallels k1 = 1, // scale @@ -30,7 +30,7 @@ int main() { double x, y; PASouth.Forward(lon0, lat, lon, x, y); x -= x0; y -= y0; - std::cout << x << " " << y << "\n"; + cout << x << " " << y << "\n"; } { // Sample conversion from PASouth grid to geodetic @@ -38,12 +38,11 @@ int main() { double lat, lon; x += x0; y += y0; PASouth.Reverse(lon0, x, y, lat, lon); - std::cout << lat << " " << lon << "\n"; + cout << lat << " " << lon << "\n"; } } catch (const exception& e) { cerr << "Caught exception: " << e.what() << "\n"; return 1; } - return 0; } diff --git a/gtsam/3rdparty/GeographicLib/examples/example-LocalCartesian.cpp b/gtsam/3rdparty/GeographicLib/examples/example-LocalCartesian.cpp index ce090729b..205c6fa3c 100644 --- a/gtsam/3rdparty/GeographicLib/examples/example-LocalCartesian.cpp +++ b/gtsam/3rdparty/GeographicLib/examples/example-LocalCartesian.cpp @@ -12,7 +12,7 @@ using namespace GeographicLib; int main() { try { Geocentric earth(Constants::WGS84_a(), Constants::WGS84_f()); - // Alternatively: const Geocentric& earth = Geocentric::WGS84; + // Alternatively: const Geocentric& earth = Geocentric::WGS84(); const double lat0 = 48 + 50/60.0, lon0 = 2 + 20/60.0; // Paris LocalCartesian proj(lat0, lon0, 0, earth); { @@ -34,5 +34,4 @@ int main() { cerr << "Caught exception: " << e.what() << "\n"; return 1; } - return 0; } diff --git a/gtsam/3rdparty/GeographicLib/examples/example-MGRS.cpp b/gtsam/3rdparty/GeographicLib/examples/example-MGRS.cpp index 1fe2f6524..54bc8a110 100644 --- a/gtsam/3rdparty/GeographicLib/examples/example-MGRS.cpp +++ b/gtsam/3rdparty/GeographicLib/examples/example-MGRS.cpp @@ -39,5 +39,4 @@ int main() { cerr << "Caught exception: " << e.what() << "\n"; return 1; } - return 0; } diff --git a/gtsam/3rdparty/GeographicLib/examples/example-MagneticCircle.cpp b/gtsam/3rdparty/GeographicLib/examples/example-MagneticCircle.cpp index 8dfcbbcfd..149458f5a 100644 --- a/gtsam/3rdparty/GeographicLib/examples/example-MagneticCircle.cpp +++ b/gtsam/3rdparty/GeographicLib/examples/example-MagneticCircle.cpp @@ -38,5 +38,4 @@ int main() { cerr << "Caught exception: " << e.what() << "\n"; return 1; } - return 0; } diff --git a/gtsam/3rdparty/GeographicLib/examples/example-MagneticModel.cpp b/gtsam/3rdparty/GeographicLib/examples/example-MagneticModel.cpp index 8453ad529..8a3e28ea0 100644 --- a/gtsam/3rdparty/GeographicLib/examples/example-MagneticModel.cpp +++ b/gtsam/3rdparty/GeographicLib/examples/example-MagneticModel.cpp @@ -21,5 +21,4 @@ int main() { cerr << "Caught exception: " << e.what() << "\n"; return 1; } - return 0; } diff --git a/gtsam/3rdparty/GeographicLib/examples/example-Math.cpp b/gtsam/3rdparty/GeographicLib/examples/example-Math.cpp index 31b1dbf99..c94e40e64 100644 --- a/gtsam/3rdparty/GeographicLib/examples/example-Math.cpp +++ b/gtsam/3rdparty/GeographicLib/examples/example-Math.cpp @@ -15,5 +15,4 @@ int main() { cerr << "Caught exception: " << e.what() << "\n"; return 1; } - return 0; } diff --git a/gtsam/3rdparty/GeographicLib/examples/example-NearestNeighbor.cpp b/gtsam/3rdparty/GeographicLib/examples/example-NearestNeighbor.cpp new file mode 100644 index 000000000..750afda6e --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/examples/example-NearestNeighbor.cpp @@ -0,0 +1,140 @@ +// Example of using the GeographicLib::NearestNeighbor class. WARNING: this +// creates a file, pointset.xml or pointset.txt, in the current directory. +// Read lat/lon locations from locations.txt and lat/lon queries from +// queries.txt. For each query print to standard output: the index for the +// closest location and the distance to it. Print statistics to standard error +// at the end. + +#include +#include +#include +#include +#include + +#if !defined(GEOGRAPHICLIB_HAVE_BOOST_SERIALIZATION) +#define GEOGRAPHICLIB_HAVE_BOOST_SERIALIZATION 0 +#endif + +#if GEOGRAPHICLIB_HAVE_BOOST_SERIALIZATION +// If Boost serialization is available, use it. +#include +#include +#endif + +#include +#include +#include + +using namespace std; +using namespace GeographicLib; + +// A structure to hold a geographic coordinate. +struct pos { + double _lat, _lon; + pos(double lat = 0, double lon = 0) : _lat(lat), _lon(lon) {} +}; + +// A class to compute the distance between 2 positions. +class DistanceCalculator { +private: + Geodesic _geod; +public: + explicit DistanceCalculator(const Geodesic& geod) : _geod(geod) {} + double operator() (const pos& a, const pos& b) const { + double d; + _geod.Inverse(a._lat, a._lon, b._lat, b._lon, d); + if ( !(d >= 0) ) + // Catch illegal positions which result in d = NaN + throw GeographicErr("distance doesn't satisfy d >= 0"); + return d; + } +}; + +int main() { + try { + // Read in locations + vector locs; + double lat, lon; + string sa, sb; + { + ifstream is("locations.txt"); + if (!is.good()) + throw GeographicErr("locations.txt not readable"); + while (is >> sa >> sb) { + DMS::DecodeLatLon(sa, sb, lat, lon); + locs.push_back(pos(lat, lon)); + } + if (locs.size() == 0) + throw GeographicErr("need at least one location"); + } + + // Define a distance function object + DistanceCalculator distance(Geodesic::WGS84()); + + // Create NearestNeighbor object + NearestNeighbor pointset; + + { + // Used saved object if it is available +#if GEOGRAPHICLIB_HAVE_BOOST_SERIALIZATION + ifstream is("pointset.xml"); + if (is.good()) { + boost::archive::xml_iarchive ia(is); + ia >> BOOST_SERIALIZATION_NVP(pointset); + } +#else + ifstream is("pointset.txt"); + if (is.good()) + is >> pointset; +#endif + } + // Is the saved pointset up-to-date? + if (pointset.NumPoints() != int(locs.size())) { + // else initialize it + pointset.Initialize(locs, distance); + // and save it +#if GEOGRAPHICLIB_HAVE_BOOST_SERIALIZATION + ofstream os("pointset.xml"); + if (!os.good()) + throw GeographicErr("cannot write to pointset.xml"); + boost::archive::xml_oarchive oa(os); + oa << BOOST_SERIALIZATION_NVP(pointset); +#else + ofstream os("pointset.txt"); + if (!os.good()) + throw GeographicErr("cannot write to pointset.txt"); + os << pointset << "\n"; +#endif + } + + ifstream is("queries.txt"); + double d; + int count = 0; + vector k; + while (is >> sa >> sb) { + ++count; + DMS::DecodeLatLon(sa, sb, lat, lon); + d = pointset.Search(locs, distance, pos(lat, lon), k); + if (k.size() != 1) + throw GeographicErr("unexpected number of results"); + cout << k[0] << " " << d << "\n"; + } + int setupcost, numsearches, searchcost, mincost, maxcost; + double mean, sd; + pointset.Statistics(setupcost, numsearches, searchcost, + mincost, maxcost, mean, sd); + int + totcost = setupcost + searchcost, + exhaustivecost = count * pointset.NumPoints(); + cerr + << "Number of distance calculations = " << totcost << "\n" + << "With an exhaustive search = " << exhaustivecost << "\n" + << "Ratio = " << double(totcost) / exhaustivecost << "\n" + << "Efficiency improvement = " + << 100 * (1 - double(totcost) / exhaustivecost) << "%\n"; + } + catch (const exception& e) { + cerr << "Caught exception: " << e.what() << "\n"; + return 1; + } +} diff --git a/gtsam/3rdparty/GeographicLib/examples/example-NormalGravity.cpp b/gtsam/3rdparty/GeographicLib/examples/example-NormalGravity.cpp index 461c1652c..aa6510b57 100644 --- a/gtsam/3rdparty/GeographicLib/examples/example-NormalGravity.cpp +++ b/gtsam/3rdparty/GeographicLib/examples/example-NormalGravity.cpp @@ -10,10 +10,9 @@ using namespace GeographicLib; int main() { try { - NormalGravity grav(Constants::WGS84_a(), Constants::WGS84_GM(), - Constants::WGS84_omega(), - Constants::WGS84_f(), 0); - // Alternatively: const NormalGravity& grav = NormalGravity::WGS84; + NormalGravity grav(Constants::WGS84_a(), Constants::WGS84_GM(), + Constants::WGS84_omega(), Constants::WGS84_f()); + // Alternatively: const NormalGravity& grav = NormalGravity::WGS84(); double lat = 27.99, h = 8820; // Mt Everest double gammay, gammaz; grav.Gravity(lat, h, gammay, gammaz); @@ -23,5 +22,4 @@ int main() { cerr << "Caught exception: " << e.what() << "\n"; return 1; } - return 0; } diff --git a/gtsam/3rdparty/GeographicLib/examples/example-OSGB.cpp b/gtsam/3rdparty/GeographicLib/examples/example-OSGB.cpp index 801dcea61..1e27111b7 100644 --- a/gtsam/3rdparty/GeographicLib/examples/example-OSGB.cpp +++ b/gtsam/3rdparty/GeographicLib/examples/example-OSGB.cpp @@ -41,5 +41,4 @@ int main() { cerr << "Caught exception: " << e.what() << "\n"; return 1; } - return 0; } diff --git a/gtsam/3rdparty/GeographicLib/examples/example-PolarStereographic.cpp b/gtsam/3rdparty/GeographicLib/examples/example-PolarStereographic.cpp index 0bf5c633a..cae3fe39e 100644 --- a/gtsam/3rdparty/GeographicLib/examples/example-PolarStereographic.cpp +++ b/gtsam/3rdparty/GeographicLib/examples/example-PolarStereographic.cpp @@ -1,9 +1,8 @@ // Example of using the GeographicLib::PolarStereographic class #include -#include -#include #include +#include #include using namespace std; @@ -14,7 +13,7 @@ int main() { PolarStereographic proj(Constants::WGS84_a(), Constants::WGS84_f(), Constants::UPS_k0()); // Alternatively: - // const PolarStereographic& proj = PolarStereographic::UPS; + // const PolarStereographic& proj = PolarStereographic::UPS(); bool northp = true; { // Sample forward calculation @@ -35,5 +34,4 @@ int main() { cerr << "Caught exception: " << e.what() << "\n"; return 1; } - return 0; } diff --git a/gtsam/3rdparty/GeographicLib/examples/example-PolygonArea.cpp b/gtsam/3rdparty/GeographicLib/examples/example-PolygonArea.cpp index f2610ce55..ece25e4d2 100644 --- a/gtsam/3rdparty/GeographicLib/examples/example-PolygonArea.cpp +++ b/gtsam/3rdparty/GeographicLib/examples/example-PolygonArea.cpp @@ -12,7 +12,7 @@ using namespace GeographicLib; int main() { try { Geodesic geod(Constants::WGS84_a(), Constants::WGS84_f()); - // Alternatively: const Geodesic& geod = Geodesic::WGS84; + // Alternatively: const Geodesic& geod = Geodesic::WGS84(); PolygonArea poly(geod); poly.AddPoint( 52, 0); // London poly.AddPoint( 41,-74); // New York @@ -26,5 +26,4 @@ int main() { cerr << "Caught exception: " << e.what() << "\n"; return 1; } - return 0; } diff --git a/gtsam/3rdparty/GeographicLib/examples/example-Rhumb.cpp b/gtsam/3rdparty/GeographicLib/examples/example-Rhumb.cpp new file mode 100644 index 000000000..869ae7e1c --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/examples/example-Rhumb.cpp @@ -0,0 +1,36 @@ +// Example of using the GeographicLib::Rhumb class + +#include +#include +#include +#include + +using namespace std; +using namespace GeographicLib; + +int main() { + try { + Rhumb rhumb(Constants::WGS84_a(), Constants::WGS84_f()); + // Alternatively: const Rhumb& rhumb = Rhumb::WGS84(); + { + // Sample direct calculation, travelling about NE from JFK + double lat1 = 40.6, lon1 = -73.8, s12 = 5.5e6, azi12 = 51; + double lat2, lon2; + rhumb.Direct(lat1, lon1, azi12, s12, lat2, lon2); + cout << lat2 << " " << lon2 << "\n"; + } + { + // Sample inverse calculation, JFK to LHR + double + lat1 = 40.6, lon1 = -73.8, // JFK Airport + lat2 = 51.6, lon2 = -0.5; // LHR Airport + double s12, azi12; + rhumb.Inverse(lat1, lon1, lat2, lon2, s12, azi12); + cout << s12 << " " << azi12 << "\n"; + } + } + catch (const exception& e) { + cerr << "Caught exception: " << e.what() << "\n"; + return 1; + } +} diff --git a/gtsam/3rdparty/GeographicLib/examples/example-RhumbLine.cpp b/gtsam/3rdparty/GeographicLib/examples/example-RhumbLine.cpp new file mode 100644 index 000000000..04c5615dc --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/examples/example-RhumbLine.cpp @@ -0,0 +1,43 @@ +// Example of using the GeographicLib::RhumbLine class + +#include +#include +#include +#include +#include +#include + +using namespace std; +using namespace GeographicLib; + +int main() { + try { + // Print waypoints between JFK and SIN + Rhumb rhumb(Constants::WGS84_a(), Constants::WGS84_f()); + // Alternatively: const Rhumb& rhumb = Rhumb::WGS84(); + double + lat1 = 40.640, lon1 = -73.779, // JFK + lat2 = 1.359, lon2 = 103.989; // SIN + double s12, azi12; + rhumb.Inverse(lat1, lon1, lat2, lon2, s12, azi12); + const GeographicLib::RhumbLine line = rhumb.Line(lat1, lon1, azi12); + // Alternatively + // const GeographicLib::RhumbLine line = rhumb.Line(lat1, lon1, azi1); + double ds0 = 500e3; // Nominal distance between points = 500 km + int num = int(ceil(s12 / ds0)); // The number of intervals + cout << fixed << setprecision(3); + { + // Use intervals of equal length + double ds = s12 / num; + for (int i = 0; i <= num; ++i) { + double lat, lon; + line.Position(i * ds, lat, lon); + cout << i << " " << lat << " " << lon << "\n"; + } + } + } + catch (const exception& e) { + cerr << "Caught exception: " << e.what() << "\n"; + return 1; + } +} diff --git a/gtsam/3rdparty/GeographicLib/examples/example-SphericalEngine.cpp b/gtsam/3rdparty/GeographicLib/examples/example-SphericalEngine.cpp index 29fd7a3cd..52b328807 100644 --- a/gtsam/3rdparty/GeographicLib/examples/example-SphericalEngine.cpp +++ b/gtsam/3rdparty/GeographicLib/examples/example-SphericalEngine.cpp @@ -29,5 +29,4 @@ int main() { cerr << "Caught exception: " << e.what() << "\n"; return 1; } - return 0; } diff --git a/gtsam/3rdparty/GeographicLib/examples/example-SphericalHarmonic.cpp b/gtsam/3rdparty/GeographicLib/examples/example-SphericalHarmonic.cpp index 213b2a772..989b550c4 100644 --- a/gtsam/3rdparty/GeographicLib/examples/example-SphericalHarmonic.cpp +++ b/gtsam/3rdparty/GeographicLib/examples/example-SphericalHarmonic.cpp @@ -26,5 +26,4 @@ int main() { cerr << "Caught exception: " << e.what() << "\n"; return 1; } - return 0; } diff --git a/gtsam/3rdparty/GeographicLib/examples/example-SphericalHarmonic1.cpp b/gtsam/3rdparty/GeographicLib/examples/example-SphericalHarmonic1.cpp index fa3d9b809..111f5ce63 100644 --- a/gtsam/3rdparty/GeographicLib/examples/example-SphericalHarmonic1.cpp +++ b/gtsam/3rdparty/GeographicLib/examples/example-SphericalHarmonic1.cpp @@ -30,5 +30,4 @@ int main() { cerr << "Caught exception: " << e.what() << "\n"; return 1; } - return 0; } diff --git a/gtsam/3rdparty/GeographicLib/examples/example-SphericalHarmonic2.cpp b/gtsam/3rdparty/GeographicLib/examples/example-SphericalHarmonic2.cpp index cce1f49ee..d5c9fde0a 100644 --- a/gtsam/3rdparty/GeographicLib/examples/example-SphericalHarmonic2.cpp +++ b/gtsam/3rdparty/GeographicLib/examples/example-SphericalHarmonic2.cpp @@ -34,5 +34,4 @@ int main() { cerr << "Caught exception: " << e.what() << "\n"; return 1; } - return 0; } diff --git a/gtsam/3rdparty/GeographicLib/examples/example-TransverseMercator.cpp b/gtsam/3rdparty/GeographicLib/examples/example-TransverseMercator.cpp index 678eeab2e..e0a1b4e6b 100644 --- a/gtsam/3rdparty/GeographicLib/examples/example-TransverseMercator.cpp +++ b/gtsam/3rdparty/GeographicLib/examples/example-TransverseMercator.cpp @@ -1,38 +1,63 @@ // Example of using the GeographicLib::TransverseMercator class #include -#include -#include #include +#include #include using namespace std; using namespace GeographicLib; +// Define a UTM projection for an arbitrary ellipsoid +class UTMalt { +private: + TransverseMercator _tm; // The projection + double _lon0; // Central longitude + double _falseeasting, _falsenorthing; +public: + UTMalt(double a, // equatorial radius + double f, // flattening + int zone, // the UTM zone + hemisphere + bool northp) + : _tm(a, f, Constants::UTM_k0()) + , _lon0(6 * zone - 183) + , _falseeasting(5e5) + , _falsenorthing(northp ? 0 : 100e5) { + if (!(zone >= 1 && zone <= 60)) + throw GeographicErr("zone not in [1,60]"); + } + void Forward(double lat, double lon, double& x, double& y) { + _tm.Forward(_lon0, lat, lon, x, y); + x += _falseeasting; + y += _falsenorthing; + } + void Reverse(double x, double y, double& lat, double& lon) { + x -= _falseeasting; + y -= _falsenorthing; + _tm.Reverse(_lon0, x, y, lat, lon); + } +}; + int main() { try { - TransverseMercator proj(Constants::WGS84_a(), Constants::WGS84_f(), - Constants::UTM_k0()); - // Alternatively: const TransverseMercator& proj = TransverseMercator::UTM; - double lon0 = -75; // Central meridian for UTM zone 18 + UTMalt tm(6378388, 1/297.0, 30, true); // International ellipsoid, zone 30n { // Sample forward calculation - double lat = 40.3, lon = -74.7; // Princeton, NJ + double lat = 40.4, lon = -3.7; // Madrid double x, y; - proj.Forward(lon0, lat, lon, x, y); - cout << x << " " << y << "\n"; + tm.Forward(lat, lon, x, y); + cout << fixed << setprecision(0) << x << " " << y << "\n"; } { // Sample reverse calculation - double x = 25e3, y = 4461e3; + double x = 441e3, y = 4472e3; double lat, lon; - proj.Reverse(lon0, x, y, lat, lon); - cout << lat << " " << lon << "\n"; + tm.Reverse(x, y, lat, lon); + cout << fixed << setprecision(5) << lat << " " << lon << "\n"; } } catch (const exception& e) { cerr << "Caught exception: " << e.what() << "\n"; return 1; } - return 0; } diff --git a/gtsam/3rdparty/GeographicLib/examples/example-TransverseMercatorExact.cpp b/gtsam/3rdparty/GeographicLib/examples/example-TransverseMercatorExact.cpp index 0c951bc4a..6247c35da 100644 --- a/gtsam/3rdparty/GeographicLib/examples/example-TransverseMercatorExact.cpp +++ b/gtsam/3rdparty/GeographicLib/examples/example-TransverseMercatorExact.cpp @@ -1,9 +1,8 @@ // Example of using the GeographicLib::TransverseMercatorExact class #include -#include -#include #include +#include #include using namespace std; @@ -14,7 +13,7 @@ int main() { TransverseMercatorExact proj(Constants::WGS84_a(), Constants::WGS84_f(), Constants::UTM_k0()); // Alternatively: - // const TransverseMercatorExact& proj = TransverseMercatorExact::UTM; + // const TransverseMercatorExact& proj = TransverseMercatorExact::UTM(); double lon0 = -75; // Central meridian for UTM zone 18 { // Sample forward calculation @@ -35,5 +34,4 @@ int main() { cerr << "Caught exception: " << e.what() << "\n"; return 1; } - return 0; } diff --git a/gtsam/3rdparty/GeographicLib/examples/example-UTMUPS.cpp b/gtsam/3rdparty/GeographicLib/examples/example-UTMUPS.cpp index a2671d018..03d2b1502 100644 --- a/gtsam/3rdparty/GeographicLib/examples/example-UTMUPS.cpp +++ b/gtsam/3rdparty/GeographicLib/examples/example-UTMUPS.cpp @@ -1,9 +1,9 @@ // Example of using the GeographicLib::UTMUPS class #include +#include #include #include -#include #include using namespace std; @@ -25,7 +25,7 @@ int main() { } { // Sample reverse calculation - string zonestr = "38N"; + string zonestr = "38n"; int zone; bool northp; UTMUPS::DecodeZone(zonestr, zone, northp); @@ -39,5 +39,4 @@ int main() { cerr << "Caught exception: " << e.what() << "\n"; return 1; } - return 0; } diff --git a/gtsam/3rdparty/GeographicLib/examples/example-Utility.cpp b/gtsam/3rdparty/GeographicLib/examples/example-Utility.cpp index 463f85e99..6bc968499 100644 --- a/gtsam/3rdparty/GeographicLib/examples/example-Utility.cpp +++ b/gtsam/3rdparty/GeographicLib/examples/example-Utility.cpp @@ -18,5 +18,4 @@ int main() { cerr << "Caught exception: " << e.what() << "\n"; return 1; } - return 0; } diff --git a/gtsam/3rdparty/GeographicLib/examples/make-egmcof.cpp b/gtsam/3rdparty/GeographicLib/examples/make-egmcof.cpp new file mode 100644 index 000000000..d1ba4410f --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/examples/make-egmcof.cpp @@ -0,0 +1,45 @@ +// Write the coefficient files needed for approximating the normal gravity +// field with a GravityModel. WARNING: this creates files, wgs84.egm.cof and +// grs80.egm.cof, in the current directory. + +#include +#include +#include +#include +#include + +using namespace std; +using namespace GeographicLib; + +int main() { + try { + Utility::set_digits(); + const char* filenames[] = {"wgs84.egm.cof", "grs80.egm.cof"}; + const char* ids[] = {"WGS1984A", "GRS1980A"}; + for (int grs80 = 0; grs80 < 2; ++grs80) { + ofstream file(filenames[grs80], ios::binary); + Utility::writearray(file, ids[grs80], 8); + const int N = 20, M = 0, + cnum = (M + 1) * (2 * N - M + 2) / 2; // cnum = N + 1 + vector num(2); + num[0] = N; num[1] = M; + Utility::writearray(file, num); + vector c(cnum, 0); + const NormalGravity& earth(grs80 ? NormalGravity::GRS80() : + NormalGravity::WGS84()); + for (int n = 2; n <= N; n += 2) + c[n] = - earth.DynamicalFormFactor(n) / sqrt(Math::real(2*n + 1)); + Utility::writearray(file, c); + num[0] = num[1] = -1; + Utility::writearray(file, num); + } + } + catch (const exception& e) { + cerr << "Caught exception: " << e.what() << "\n"; + return 1; + } + catch (...) { + cerr << "Caught unknown exception\n"; + return 1; + } +} diff --git a/gtsam/3rdparty/GeographicLib/include/GeographicLib/Accumulator.hpp b/gtsam/3rdparty/GeographicLib/include/GeographicLib/Accumulator.hpp index 798b5b07e..25457ebd0 100644 --- a/gtsam/3rdparty/GeographicLib/include/GeographicLib/Accumulator.hpp +++ b/gtsam/3rdparty/GeographicLib/include/GeographicLib/Accumulator.hpp @@ -2,9 +2,9 @@ * \file Accumulator.hpp * \brief Header for GeographicLib::Accumulator class * - * Copyright (c) Charles Karney (2010-2011) and licensed + * Copyright (c) Charles Karney (2010-2015) and licensed * under the MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #if !defined(GEOGRAPHICLIB_ACCUMULATOR_HPP) @@ -17,12 +17,12 @@ namespace GeographicLib { /** * \brief An accumulator for sums * - * This allow many numbers of floating point type \e T to be added together + * This allows many numbers of floating point type \e T to be added together * with twice the normal precision. Thus if \e T is double, the effective * precision of the sum is 106 bits or about 32 decimal places. * * The implementation follows J. R. Shewchuk, - * Adaptive Precision + * Adaptive Precision * Floating-Point Arithmetic and Fast Robust Geometric Predicates, * Discrete & Computational Geometry 18(3) 305--363 (1997). * @@ -43,16 +43,17 @@ namespace GeographicLib { T _s, _t; // Same as Math::sum, but requires abs(u) >= abs(v). This isn't currently // used. - static inline T fastsum(T u, T v, T& t) throw() { - volatile T s = u + v; - volatile T vp = s - u; + static T fastsum(T u, T v, T& t) { + GEOGRAPHICLIB_VOLATILE T s = u + v; + GEOGRAPHICLIB_VOLATILE T vp = s - u; t = v - vp; return s; } - void Add(T y) throw() { + void Add(T y) { // Here's Shewchuk's solution... T u; // hold exact sum as [s, t, u] - y = Math::sum(y, _t, u); // Accumulate starting at least significant end + // Accumulate starting at least significant end + y = Math::sum(y, _t, u); _s = Math::sum(y, _s, _t); // Start is _s, _t decreasing and non-adjacent. Sum is now (s + t + u) // exactly with s, t, u non-adjacent and in decreasing order (except for @@ -86,7 +87,7 @@ namespace GeographicLib { else _t += u; // otherwise just accumulate u to t. } - T Sum(T y) const throw() { + T Sum(T y) const { Accumulator a(*this); a.Add(y); return a._s; @@ -98,41 +99,42 @@ namespace GeographicLib { * * @param[in] y set \e sum = \e y. **********************************************************************/ - Accumulator(T y = T(0)) throw() : _s(y), _t(0) { - STATIC_ASSERT(!std::numeric_limits::is_integer, - "Accumulator type is not floating point"); + Accumulator(T y = T(0)) : _s(y), _t(0) { + GEOGRAPHICLIB_STATIC_ASSERT(!std::numeric_limits::is_integer, + "Accumulator type is not floating point"); } /** * Set the accumulator to a number. * * @param[in] y set \e sum = \e y. **********************************************************************/ - Accumulator& operator=(T y) throw() { _s = y; _t = 0; return *this; } + Accumulator& operator=(T y) { _s = y; _t = 0; return *this; } /** * Return the value held in the accumulator. * * @return \e sum. **********************************************************************/ - T operator()() const throw() { return _s; } + T operator()() const { return _s; } /** - * Return the result of adding a number to \e sum (but don't change \e sum). + * Return the result of adding a number to \e sum (but don't change \e + * sum). * * @param[in] y the number to be added to the sum. * @return \e sum + \e y. **********************************************************************/ - T operator()(T y) const throw() { return Sum(y); } + T operator()(T y) const { return Sum(y); } /** * Add a number to the accumulator. * * @param[in] y set \e sum += \e y. **********************************************************************/ - Accumulator& operator+=(T y) throw() { Add(y); return *this; } + Accumulator& operator+=(T y) { Add(y); return *this; } /** * Subtract a number from the accumulator. * * @param[in] y set \e sum -= \e y. **********************************************************************/ - Accumulator& operator-=(T y) throw() { Add(-y); return *this; } + Accumulator& operator-=(T y) { Add(-y); return *this; } /** * Multiply accumulator by an integer. To avoid loss of accuracy, use only * integers such that \e n × \e T is exactly representable as a \e T @@ -140,31 +142,43 @@ namespace GeographicLib { * * @param[in] n set \e sum *= \e n. **********************************************************************/ - Accumulator& operator*=(int n) throw() { _s *= n; _t *= n; return *this; } + Accumulator& operator*=(int n) { _s *= n; _t *= n; return *this; } + /** + * Multiply accumulator by a number. The fma (fused multiply and add) + * instruction is used (if available) in order to maintain accuracy. + * + * @param[in] y set \e sum *= \e y. + **********************************************************************/ + Accumulator& operator*=(T y) { + T d = _s; _s *= y; + d = Math::fma(y, d, -_s); // the error in the first multiplication + _t = Math::fma(y, _t, d); // add error to the second term + return *this; + } /** * Test equality of an Accumulator with a number. **********************************************************************/ - bool operator==(T y) const throw() { return _s == y; } + bool operator==(T y) const { return _s == y; } /** * Test inequality of an Accumulator with a number. **********************************************************************/ - bool operator!=(T y) const throw() { return _s != y; } + bool operator!=(T y) const { return _s != y; } /** * Less operator on an Accumulator and a number. **********************************************************************/ - bool operator<(T y) const throw() { return _s < y; } + bool operator<(T y) const { return _s < y; } /** * Less or equal operator on an Accumulator and a number. **********************************************************************/ - bool operator<=(T y) const throw() { return _s <= y; } + bool operator<=(T y) const { return _s <= y; } /** * Greater operator on an Accumulator and a number. **********************************************************************/ - bool operator>(T y) const throw() { return _s > y; } + bool operator>(T y) const { return _s > y; } /** * Greater or equal operator on an Accumulator and a number. **********************************************************************/ - bool operator>=(T y) const throw() { return _s >= y; } + bool operator>=(T y) const { return _s >= y; } }; } // namespace GeographicLib diff --git a/gtsam/3rdparty/GeographicLib/include/GeographicLib/AlbersEqualArea.hpp b/gtsam/3rdparty/GeographicLib/include/GeographicLib/AlbersEqualArea.hpp index 27cc4725f..290b0c5f2 100644 --- a/gtsam/3rdparty/GeographicLib/include/GeographicLib/AlbersEqualArea.hpp +++ b/gtsam/3rdparty/GeographicLib/include/GeographicLib/AlbersEqualArea.hpp @@ -2,9 +2,9 @@ * \file AlbersEqualArea.hpp * \brief Header for GeographicLib::AlbersEqualArea class * - * Copyright (c) Charles Karney (2010-2012) and licensed + * Copyright (c) Charles Karney (2010-2017) and licensed * under the MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #if !defined(GEOGRAPHICLIB_ALBERSEQUALAREA_HPP) @@ -60,31 +60,27 @@ namespace GeographicLib { class GEOGRAPHICLIB_EXPORT AlbersEqualArea { private: typedef Math::real real; + real eps_, epsx_, epsx2_, tol_, tol0_; real _a, _f, _fm, _e2, _e, _e2m, _qZ, _qx; real _sign, _lat0, _k0; real _n0, _m02, _nrho0, _k2, _txi0, _scxi0, _sxi0; - static const real eps_; - static const real epsx_; - static const real epsx2_; - static const real tol_; - static const real tol0_; - static const real ahypover_; static const int numit_ = 5; // Newton iterations in Reverse static const int numit0_ = 20; // Newton iterations in Init - static inline real hyp(real x) throw() { return Math::hypot(real(1), x); } + static real hyp(real x) { return Math::hypot(real(1), x); } // atanh( e * x)/ e if f > 0 // atan (sqrt(-e2) * x)/sqrt(-e2) if f < 0 // x if f = 0 - inline real atanhee(real x) const throw() { + real atanhee(real x) const { + using std::atan2; using std::abs; return _f > 0 ? Math::atanh(_e * x)/_e : // We only invoke atanhee in txif for positive latitude. Then x is // only negative for very prolate ellipsoids (_b/_a >= sqrt(2)) and we // still need to return a positive result in this case; hence the need // for the call to atan2. - (_f < 0 ? (std::atan2(_e * std::abs(x), x < 0 ? -1 : 1)/_e) : x); + (_f < 0 ? (atan2(_e * abs(x), real(x < 0 ? -1 : 1))/_e) : x); } // return atanh(sqrt(x))/sqrt(x) - 1, accurate for small x - static real atanhxm1(real x) throw(); + static real atanhxm1(real x); // Divided differences // Definition: Df(x,y) = (f(x)-f(y))/(x-y) @@ -92,7 +88,7 @@ namespace GeographicLib { // W. M. Kahan and R. J. Fateman, // Symbolic computation of divided differences, // SIGSAM Bull. 33(3), 7-28 (1999) - // http://dx.doi.org/10.1145/334714.334716 + // https://doi.org/10.1145/334714.334716 // http://www.cs.berkeley.edu/~fateman/papers/divdiff.pdf // // General rules @@ -103,22 +99,22 @@ namespace GeographicLib { // = Df(x,y)*(g(x)+g(y))/2 + Dg(x,y)*(f(x)+f(y))/2 // // sn(x) = x/sqrt(1+x^2): Dsn(x,y) = (x+y)/((sn(x)+sn(y))*(1+x^2)*(1+y^2)) - static inline real Dsn(real x, real y, real sx, real sy) throw() { + static real Dsn(real x, real y, real sx, real sy) { // sx = x/hyp(x) real t = x * y; return t > 0 ? (x + y) * Math::sq( (sx * sy)/t ) / (sx + sy) : (x - y != 0 ? (sx - sy) / (x - y) : 1); } // Datanhee(x,y) = atanhee((x-y)/(1-e^2*x*y))/(x-y) - inline real Datanhee(real x, real y) const throw() { + real Datanhee(real x, real y) const { real t = x - y, d = 1 - _e2 * x * y; return t != 0 ? atanhee(t / d) / t : 1 / d; } // DDatanhee(x,y) = (Datanhee(1,y) - Datanhee(1,x))/(y-x) - real DDatanhee(real x, real y) const throw(); - void Init(real sphi1, real cphi1, real sphi2, real cphi2, real k1) throw(); - real txif(real tphi) const throw(); - real tphif(real txi) const throw(); + real DDatanhee(real x, real y) const; + void Init(real sphi1, real cphi1, real sphi2, real cphi2, real k1); + real txif(real tphi) const; + real tphif(real txi) const; friend class Ellipsoid; // For access to txif, tphif, etc. public: @@ -128,11 +124,10 @@ namespace GeographicLib { * * @param[in] a equatorial radius of ellipsoid (meters). * @param[in] f flattening of ellipsoid. Setting \e f = 0 gives a sphere. - * Negative \e f gives a prolate ellipsoid. If \e f > 1, set flattening - * to 1/\e f. + * Negative \e f gives a prolate ellipsoid. * @param[in] stdlat standard parallel (degrees), the circle of tangency. * @param[in] k0 azimuthal scale on the standard parallel. - * @exception GeographicErr if \e a, (1 − \e f ) \e a, or \e k0 is + * @exception GeographicErr if \e a, (1 − \e f) \e a, or \e k0 is * not positive. * @exception GeographicErr if \e stdlat is not in [−90°, * 90°]. @@ -144,12 +139,11 @@ namespace GeographicLib { * * @param[in] a equatorial radius of ellipsoid (meters). * @param[in] f flattening of ellipsoid. Setting \e f = 0 gives a sphere. - * Negative \e f gives a prolate ellipsoid. If \e f > 1, set flattening - * to 1/\e f. + * Negative \e f gives a prolate ellipsoid. * @param[in] stdlat1 first standard parallel (degrees). * @param[in] stdlat2 second standard parallel (degrees). * @param[in] k1 azimuthal scale on the standard parallels. - * @exception GeographicErr if \e a, (1 − \e f ) \e a, or \e k1 is + * @exception GeographicErr if \e a, (1 − \e f) \e a, or \e k1 is * not positive. * @exception GeographicErr if \e stdlat1 or \e stdlat2 is not in * [−90°, 90°], or if \e stdlat1 and \e stdlat2 are @@ -162,14 +156,13 @@ namespace GeographicLib { * * @param[in] a equatorial radius of ellipsoid (meters). * @param[in] f flattening of ellipsoid. Setting \e f = 0 gives a sphere. - * Negative \e f gives a prolate ellipsoid. If \e f > 1, set flattening - * to 1/\e f. + * Negative \e f gives a prolate ellipsoid. * @param[in] sinlat1 sine of first standard parallel. * @param[in] coslat1 cosine of first standard parallel. * @param[in] sinlat2 sine of second standard parallel. * @param[in] coslat2 cosine of second standard parallel. * @param[in] k1 azimuthal scale on the standard parallels. - * @exception GeographicErr if \e a, (1 − \e f ) \e a, or \e k1 is + * @exception GeographicErr if \e a, (1 − \e f) \e a, or \e k1 is * not positive. * @exception GeographicErr if \e stdlat1 or \e stdlat2 is not in * [−90°, 90°], or if \e stdlat1 and \e stdlat2 are @@ -213,13 +206,12 @@ namespace GeographicLib { * * The latitude origin is given by AlbersEqualArea::LatitudeOrigin(). No * false easting or northing is added and \e lat should be in the range - * [−90°, 90°]; \e lon and \e lon0 should be in the - * range [−540°, 540°). The values of \e x and \e y - * returned for points which project to infinity (i.e., one or both of the - * poles) will be large but finite. + * [−90°, 90°]. The values of \e x and \e y returned for + * points which project to infinity (i.e., one or both of the poles) will + * be large but finite. **********************************************************************/ void Forward(real lon0, real lat, real lon, - real& x, real& y, real& gamma, real& k) const throw(); + real& x, real& y, real& gamma, real& k) const; /** * Reverse projection, from Lambert conformal conic to geographic. @@ -234,22 +226,20 @@ namespace GeographicLib { * scale is the 1/\e k. * * The latitude origin is given by AlbersEqualArea::LatitudeOrigin(). No - * false easting or northing is added. \e lon0 should be in the range - * [−540°, 540°). The value of \e lon returned is in - * the range [−180°, 180°). The value of \e lat - * returned is in the range [−90°, 90°]. If the - * input point is outside the legal projected space the nearest pole is - * returned. + * false easting or northing is added. The value of \e lon returned is in + * the range [−180°, 180°]. The value of \e lat returned is + * in the range [−90°, 90°]. If the input point is outside + * the legal projected space the nearest pole is returned. **********************************************************************/ void Reverse(real lon0, real x, real y, - real& lat, real& lon, real& gamma, real& k) const throw(); + real& lat, real& lon, real& gamma, real& k) const; /** * AlbersEqualArea::Forward without returning the convergence and * scale. **********************************************************************/ void Forward(real lon0, real lat, real lon, - real& x, real& y) const throw() { + real& x, real& y) const { real gamma, k; Forward(lon0, lat, lon, x, y, gamma, k); } @@ -259,7 +249,7 @@ namespace GeographicLib { * scale. **********************************************************************/ void Reverse(real lon0, real x, real y, - real& lat, real& lon) const throw() { + real& lat, real& lon) const { real gamma, k; Reverse(lon0, x, y, lat, lon, gamma, k); } @@ -271,21 +261,13 @@ namespace GeographicLib { * @return \e a the equatorial radius of the ellipsoid (meters). This is * the value used in the constructor. **********************************************************************/ - Math::real MajorRadius() const throw() { return _a; } + Math::real MajorRadius() const { return _a; } /** * @return \e f the flattening of the ellipsoid. This is the value used in * the constructor. **********************************************************************/ - Math::real Flattening() const throw() { return _f; } - - /// \cond SKIP - /** - * DEPRECATED - * @return \e r the inverse flattening of the ellipsoid. - **********************************************************************/ - Math::real InverseFlattening() const throw() { return 1/_f; } - /// \endcond + Math::real Flattening() const { return _f; } /** * @return latitude of the origin for the projection (degrees). @@ -294,13 +276,13 @@ namespace GeographicLib { * in the 1-parallel constructor and lies between \e stdlat1 and \e stdlat2 * in the 2-parallel constructors. **********************************************************************/ - Math::real OriginLatitude() const throw() { return _lat0; } + Math::real OriginLatitude() const { return _lat0; } /** * @return central scale for the projection. This is the azimuthal scale * on the latitude of origin. **********************************************************************/ - Math::real CentralScale() const throw() { return _k0; } + Math::real CentralScale() const { return _k0; } ///@} /** @@ -308,21 +290,21 @@ namespace GeographicLib { * stdlat = 0, and \e k0 = 1. This degenerates to the cylindrical equal * area projection. **********************************************************************/ - static const AlbersEqualArea CylindricalEqualArea; + static const AlbersEqualArea& CylindricalEqualArea(); /** * A global instantiation of AlbersEqualArea with the WGS84 ellipsoid, \e * stdlat = 90°, and \e k0 = 1. This degenerates to the * Lambert azimuthal equal area projection. **********************************************************************/ - static const AlbersEqualArea AzimuthalEqualAreaNorth; + static const AlbersEqualArea& AzimuthalEqualAreaNorth(); /** * A global instantiation of AlbersEqualArea with the WGS84 ellipsoid, \e * stdlat = −90°, and \e k0 = 1. This degenerates to the * Lambert azimuthal equal area projection. **********************************************************************/ - static const AlbersEqualArea AzimuthalEqualAreaSouth; + static const AlbersEqualArea& AzimuthalEqualAreaSouth(); }; } // namespace GeographicLib diff --git a/gtsam/3rdparty/GeographicLib/include/GeographicLib/AzimuthalEquidistant.hpp b/gtsam/3rdparty/GeographicLib/include/GeographicLib/AzimuthalEquidistant.hpp index 48d88423c..6eac6db37 100644 --- a/gtsam/3rdparty/GeographicLib/include/GeographicLib/AzimuthalEquidistant.hpp +++ b/gtsam/3rdparty/GeographicLib/include/GeographicLib/AzimuthalEquidistant.hpp @@ -2,9 +2,9 @@ * \file AzimuthalEquidistant.hpp * \brief Header for GeographicLib::AzimuthalEquidistant class * - * Copyright (c) Charles Karney (2009-2011) and licensed + * Copyright (c) Charles Karney (2009-2016) and licensed * under the MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #if !defined(GEOGRAPHICLIB_AZIMUTHALEQUIDISTANT_HPP) @@ -29,7 +29,7 @@ namespace GeographicLib { * projected coordinates. * * The conversions all take place using a Geodesic object (by default - * Geodesic::WGS84). For more information on geodesics see \ref geodesic. + * Geodesic::WGS84()). For more information on geodesics see \ref geodesic. * * Example of use: * \include example-AzimuthalEquidistant.cpp @@ -42,8 +42,8 @@ namespace GeographicLib { class GEOGRAPHICLIB_EXPORT AzimuthalEquidistant { private: typedef Math::real real; + real eps_; Geodesic _earth; - static const real eps_; public: /** @@ -52,8 +52,7 @@ namespace GeographicLib { * @param[in] earth the Geodesic object to use for geodesic calculations. * By default this uses the WGS84 ellipsoid. **********************************************************************/ - explicit AzimuthalEquidistant(const Geodesic& earth = Geodesic::WGS84) - throw() : _earth(earth) {} + explicit AzimuthalEquidistant(const Geodesic& earth = Geodesic::WGS84()); /** * Forward projection, from geographic to azimuthal equidistant. @@ -67,16 +66,14 @@ namespace GeographicLib { * @param[out] azi azimuth of geodesic at point (degrees). * @param[out] rk reciprocal of azimuthal scale at point. * - * \e lat0 and \e lat should be in the range [−90°, - * 90°] and \e lon0 and \e lon should be in the range - * [−540°, 540°). The scale of the projection is 1 - * in the "radial" direction, \e azi clockwise from true north, and is 1/\e - * rk in the direction perpendicular to this. A call to Forward followed - * by a call to Reverse will return the original (\e lat, \e lon) (to - * within roundoff). + * \e lat0 and \e lat should be in the range [−90°, 90°]. + * The scale of the projection is 1 in the "radial" direction, \e azi + * clockwise from true north, and is 1/\e rk in the direction perpendicular + * to this. A call to Forward followed by a call to Reverse will return + * the original (\e lat, \e lon) (to within roundoff). **********************************************************************/ void Forward(real lat0, real lon0, real lat, real lon, - real& x, real& y, real& azi, real& rk) const throw(); + real& x, real& y, real& azi, real& rk) const; /** * Reverse projection, from azimuthal equidistant to geographic. @@ -90,24 +87,22 @@ namespace GeographicLib { * @param[out] azi azimuth of geodesic at point (degrees). * @param[out] rk reciprocal of azimuthal scale at point. * - * \e lat0 should be in the range [−90°, 90°] and \e - * lon0 should be in the range [−540°, 540°). \e lat - * will be in the range [−90°, 90°] and \e lon will - * be in the range [−180°, 180°). The scale of the - * projection is 1 in the "radial" direction, \e azi clockwise from true - * north, and is 1/\e rk in the direction perpendicular to this. A call to - * Reverse followed by a call to Forward will return the original (\e x, \e - * y) (to roundoff) only if the geodesic to (\e x, \e y) is a shortest - * path. + * \e lat0 should be in the range [−90°, 90°]. \e lat will + * be in the range [−90°, 90°] and \e lon will be in the + * range [−180°, 180°]. The scale of the projection is 1 in + * the "radial" direction, \e azi clockwise from true north, and is 1/\e rk + * in the direction perpendicular to this. A call to Reverse followed by a + * call to Forward will return the original (\e x, \e y) (to roundoff) only + * if the geodesic to (\e x, \e y) is a shortest path. **********************************************************************/ void Reverse(real lat0, real lon0, real x, real y, - real& lat, real& lon, real& azi, real& rk) const throw(); + real& lat, real& lon, real& azi, real& rk) const; /** * AzimuthalEquidistant::Forward without returning the azimuth and scale. **********************************************************************/ void Forward(real lat0, real lon0, real lat, real lon, - real& x, real& y) const throw() { + real& x, real& y) const { real azi, rk; Forward(lat0, lon0, lat, lon, x, y, azi, rk); } @@ -116,7 +111,7 @@ namespace GeographicLib { * AzimuthalEquidistant::Reverse without returning the azimuth and scale. **********************************************************************/ void Reverse(real lat0, real lon0, real x, real y, - real& lat, real& lon) const throw() { + real& lat, real& lon) const { real azi, rk; Reverse(lat0, lon0, x, y, lat, lon, azi, rk); } @@ -128,23 +123,15 @@ namespace GeographicLib { * @return \e a the equatorial radius of the ellipsoid (meters). This is * the value inherited from the Geodesic object used in the constructor. **********************************************************************/ - Math::real MajorRadius() const throw() { return _earth.MajorRadius(); } + Math::real MajorRadius() const { return _earth.MajorRadius(); } /** * @return \e f the flattening of the ellipsoid. This is the value * inherited from the Geodesic object used in the constructor. **********************************************************************/ - Math::real Flattening() const throw() { return _earth.Flattening(); } + Math::real Flattening() const { return _earth.Flattening(); } ///@} - /// \cond SKIP - /** - * DEPRECATED - * @return \e r the inverse flattening of the ellipsoid. - **********************************************************************/ - Math::real InverseFlattening() const throw() - { return _earth.InverseFlattening(); } - /// \endcond }; } // namespace GeographicLib diff --git a/gtsam/3rdparty/GeographicLib/include/GeographicLib/CassiniSoldner.hpp b/gtsam/3rdparty/GeographicLib/include/GeographicLib/CassiniSoldner.hpp index 391505325..a9739131b 100644 --- a/gtsam/3rdparty/GeographicLib/include/GeographicLib/CassiniSoldner.hpp +++ b/gtsam/3rdparty/GeographicLib/include/GeographicLib/CassiniSoldner.hpp @@ -2,9 +2,9 @@ * \file CassiniSoldner.hpp * \brief Header for GeographicLib::CassiniSoldner class * - * Copyright (c) Charles Karney (2009-2011) and licensed + * Copyright (c) Charles Karney (2009-2015) and licensed * under the MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #if !defined(GEOGRAPHICLIB_CASSINISOLDNER_HPP) @@ -49,7 +49,7 @@ namespace GeographicLib { * reciprocal of the scale in the northing direction. * * The conversions all take place using a Geodesic object (by default - * Geodesic::WGS84). For more information on geodesics see \ref geodesic. + * Geodesic::WGS84()). For more information on geodesics see \ref geodesic. * The determination of (\e lat1, \e lon1) in the forward projection is by * solving the inverse geodesic problem for (\e lat, \e lon) and its twin * obtained by reflection in the meridional plane. The scale is found by @@ -72,28 +72,8 @@ namespace GeographicLib { Geodesic _earth; GeodesicLine _meridian; real _sbet0, _cbet0; - static const real eps1_; - static const real tiny_; static const unsigned maxit_ = 10; - // The following private helper functions are copied from Geodesic. - static inline real AngRound(real x) throw() { - // The makes the smallest gap in x = 1/16 - nextafter(1/16, 0) = 1/2^57 - // for reals = 0.7 pm on the earth if x is an angle in degrees. (This - // is about 1000 times more resolution than we get with angles around 90 - // degrees.) We use this to avoid having to deal with near singular - // cases when x is non-zero but tiny (e.g., 1.0e-200). - const real z = 1/real(16); - volatile real y = std::abs(x); - // The compiler mustn't "simplify" z - (z - y) to y - y = y < z ? z - (z - y) : y; - return x < 0 ? -y : y; - } - static inline void SinCosNorm(real& sinx, real& cosx) throw() { - real r = Math::hypot(sinx, cosx); - sinx /= r; - cosx /= r; - } public: /** @@ -105,8 +85,7 @@ namespace GeographicLib { * This constructor makes an "uninitialized" object. Call Reset to set the * central latitude and longitude, prior to calling Forward and Reverse. **********************************************************************/ - explicit CassiniSoldner(const Geodesic& earth = Geodesic::WGS84) throw() - : _earth(earth) {} + explicit CassiniSoldner(const Geodesic& earth = Geodesic::WGS84()); /** * Constructor for CassiniSoldner specifying a center point. @@ -116,14 +95,10 @@ namespace GeographicLib { * @param[in] earth the Geodesic object to use for geodesic calculations. * By default this uses the WGS84 ellipsoid. * - * \e lat0 should be in the range [−90°, 90°] and \e - * lon0 should be in the range [−540°, 540°). + * \e lat0 should be in the range [−90°, 90°]. **********************************************************************/ CassiniSoldner(real lat0, real lon0, - const Geodesic& earth = Geodesic::WGS84) throw() - : _earth(earth) { - Reset(lat0, lon0); - } + const Geodesic& earth = Geodesic::WGS84()); /** * Set the central point of the projection @@ -131,10 +106,9 @@ namespace GeographicLib { * @param[in] lat0 latitude of center point of projection (degrees). * @param[in] lon0 longitude of center point of projection (degrees). * - * \e lat0 should be in the range [−90°, 90°] and \e - * lon0 should be in the range [−540°, 540°). + * \e lat0 should be in the range [−90°, 90°]. **********************************************************************/ - void Reset(real lat0, real lon0) throw(); + void Reset(real lat0, real lon0); /** * Forward projection, from geographic to Cassini-Soldner. @@ -146,14 +120,13 @@ namespace GeographicLib { * @param[out] azi azimuth of easting direction at point (degrees). * @param[out] rk reciprocal of azimuthal northing scale at point. * - * \e lat should be in the range [−90°, 90°] and \e - * lon should be in the range [−540°, 540°). A call - * to Forward followed by a call to Reverse will return the original (\e - * lat, \e lon) (to within roundoff). The routine does nothing if the - * origin has not been set. + * \e lat should be in the range [−90°, 90°]. A call to + * Forward followed by a call to Reverse will return the original (\e lat, + * \e lon) (to within roundoff). The routine does nothing if the origin + * has not been set. **********************************************************************/ void Forward(real lat, real lon, - real& x, real& y, real& azi, real& rk) const throw(); + real& x, real& y, real& azi, real& rk) const; /** * Reverse projection, from Cassini-Soldner to geographic. @@ -171,13 +144,13 @@ namespace GeographicLib { * nothing if the origin has not been set. **********************************************************************/ void Reverse(real x, real y, - real& lat, real& lon, real& azi, real& rk) const throw(); + real& lat, real& lon, real& azi, real& rk) const; /** * CassiniSoldner::Forward without returning the azimuth and scale. **********************************************************************/ void Forward(real lat, real lon, - real& x, real& y) const throw() { + real& x, real& y) const { real azi, rk; Forward(lat, lon, x, y, azi, rk); } @@ -186,7 +159,7 @@ namespace GeographicLib { * CassiniSoldner::Reverse without returning the azimuth and scale. **********************************************************************/ void Reverse(real x, real y, - real& lat, real& lon) const throw() { + real& lat, real& lon) const { real azi, rk; Reverse(x, y, lat, lon, azi, rk); } @@ -197,41 +170,33 @@ namespace GeographicLib { /** * @return true if the object has been initialized. **********************************************************************/ - bool Init() const throw() { return _meridian.Init(); } + bool Init() const { return _meridian.Init(); } /** * @return \e lat0 the latitude of origin (degrees). **********************************************************************/ - Math::real LatitudeOrigin() const throw() + Math::real LatitudeOrigin() const { return _meridian.Latitude(); } /** * @return \e lon0 the longitude of origin (degrees). **********************************************************************/ - Math::real LongitudeOrigin() const throw() + Math::real LongitudeOrigin() const { return _meridian.Longitude(); } /** * @return \e a the equatorial radius of the ellipsoid (meters). This is * the value inherited from the Geodesic object used in the constructor. **********************************************************************/ - Math::real MajorRadius() const throw() { return _earth.MajorRadius(); } + Math::real MajorRadius() const { return _earth.MajorRadius(); } /** * @return \e f the flattening of the ellipsoid. This is the value * inherited from the Geodesic object used in the constructor. **********************************************************************/ - Math::real Flattening() const throw() { return _earth.Flattening(); } + Math::real Flattening() const { return _earth.Flattening(); } ///@} - /// \cond SKIP - /** - * DEPRECATED - * @return \e r the inverse flattening of the ellipsoid. - **********************************************************************/ - Math::real InverseFlattening() const throw() - { return _earth.InverseFlattening(); } - /// \endcond }; } // namespace GeographicLib diff --git a/gtsam/3rdparty/GeographicLib/include/GeographicLib/CircularEngine.hpp b/gtsam/3rdparty/GeographicLib/include/GeographicLib/CircularEngine.hpp index 3ce88b74c..ef43a215c 100644 --- a/gtsam/3rdparty/GeographicLib/include/GeographicLib/CircularEngine.hpp +++ b/gtsam/3rdparty/GeographicLib/include/GeographicLib/CircularEngine.hpp @@ -2,9 +2,9 @@ * \file CircularEngine.hpp * \brief Header for GeographicLib::CircularEngine class * - * Copyright (c) Charles Karney (2011) and licensed under - * the MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ + * Copyright (c) Charles Karney (2011-2015) and licensed + * under the MIT/X11 License. For more information, see + * https://geographiclib.sourceforge.io/ **********************************************************************/ #if !defined(GEOGRAPHICLIB_CIRCULARENGINE_HPP) @@ -63,19 +63,10 @@ namespace GeographicLib { std::vector _wc, _ws, _wrc, _wrs, _wtc, _wts; real _q, _uq, _uq2; - Math::real Value(bool gradp, real cl, real sl, - real& gradx, real& grady, real& gradz) const throw(); - - static inline void cossin(real x, real& cosx, real& sinx) { - x = x >= 180 ? x - 360 : (x < -180 ? x + 360 : x); - real xi = x * Math::degree(); - cosx = std::abs(x) == 90 ? 0 : cos(xi); - sinx = x == -180 ? 0 : sin(xi); - } + Math::real Value(bool gradp, real sl, real cl, + real& gradx, real& grady, real& gradz) const; friend class SphericalEngine; - friend class GravityCircle; // Access to cossin - friend class MagneticCircle; // Access to cossin CircularEngine(int M, bool gradp, unsigned norm, real a, real r, real u, real t) : _M(M) @@ -125,18 +116,18 @@ namespace GeographicLib { /** * Evaluate the sum for a particular longitude given in terms of its - * cosine and sine. + * sine and cosine. * - * @param[in] coslon the cosine of the longitude. * @param[in] sinlon the sine of the longitude. + * @param[in] coslon the cosine of the longitude. * @return \e V the value of the sum. * - * The arguments must satisfy coslon2 + - * sinlon2 = 1. + * The arguments must satisfy sinlon2 + + * coslon2 = 1. **********************************************************************/ - Math::real operator()(real coslon, real sinlon) const throw() { + Math::real operator()(real sinlon, real coslon) const { real dummy; - return Value(false, coslon, sinlon, dummy, dummy, dummy); + return Value(false, sinlon, coslon, dummy, dummy, dummy); } /** @@ -145,18 +136,18 @@ namespace GeographicLib { * @param[in] lon the longitude (degrees). * @return \e V the value of the sum. **********************************************************************/ - Math::real operator()(real lon) const throw() { - real coslon, sinlon; - cossin(lon, coslon, sinlon); - return (*this)(coslon, sinlon); + Math::real operator()(real lon) const { + real sinlon, coslon; + Math::sincosd(lon, sinlon, coslon); + return (*this)(sinlon, coslon); } /** * Evaluate the sum and its gradient for a particular longitude given in - * terms of its cosine and sine. + * terms of its sine and cosine. * - * @param[in] coslon the cosine of the longitude. * @param[in] sinlon the sine of the longitude. + * @param[in] coslon the cosine of the longitude. * @param[out] gradx \e x component of the gradient. * @param[out] grady \e y component of the gradient. * @param[out] gradz \e z component of the gradient. @@ -165,12 +156,12 @@ namespace GeographicLib { * The gradients will only be computed if the CircularEngine object was * created with this capability (e.g., via \e gradp = true in * SphericalHarmonic::Circle). If not, \e gradx, etc., will not be - * touched. The arguments must satisfy coslon2 + - * sinlon2 = 1. + * touched. The arguments must satisfy sinlon2 + + * coslon2 = 1. **********************************************************************/ - Math::real operator()(real coslon, real sinlon, - real& gradx, real& grady, real& gradz) const throw() { - return Value(true, coslon, sinlon, gradx, grady, gradz); + Math::real operator()(real sinlon, real coslon, + real& gradx, real& grady, real& gradz) const { + return Value(true, sinlon, coslon, gradx, grady, gradz); } /** @@ -188,10 +179,10 @@ namespace GeographicLib { * touched. **********************************************************************/ Math::real operator()(real lon, - real& gradx, real& grady, real& gradz) const throw() { - real coslon, sinlon; - cossin(lon, coslon, sinlon); - return (*this)(coslon, sinlon, gradx, grady, gradz); + real& gradx, real& grady, real& gradz) const { + real sinlon, coslon; + Math::sincosd(lon, sinlon, coslon); + return (*this)(sinlon, coslon, gradx, grady, gradz); } }; diff --git a/gtsam/3rdparty/GeographicLib/include/GeographicLib/Config-ac.h.in b/gtsam/3rdparty/GeographicLib/include/GeographicLib/Config-ac.h.in index a0064f4ce..e732376e2 100644 --- a/gtsam/3rdparty/GeographicLib/include/GeographicLib/Config-ac.h.in +++ b/gtsam/3rdparty/GeographicLib/include/GeographicLib/Config-ac.h.in @@ -15,9 +15,6 @@ /* Define to 1 if you have the header file. */ #undef HAVE_DLFCN_H -/* Define to 1 if you have the header file. */ -#undef HAVE_FLOAT_H - /* Define to 1 if you have the header file. */ #undef HAVE_INTTYPES_H @@ -27,9 +24,6 @@ /* Define to 1 if you have the header file. */ #undef HAVE_MEMORY_H -/* Define to 1 if stdbool.h conforms to C99. */ -#undef HAVE_STDBOOL_H - /* Define to 1 if you have the header file. */ #undef HAVE_STDINT_H @@ -42,9 +36,6 @@ /* Define to 1 if you have the header file. */ #undef HAVE_STRING_H -/* Define to 1 if you have the `strtol' function. */ -#undef HAVE_STRTOL - /* Define to 1 if you have the header file. */ #undef HAVE_SYS_STAT_H @@ -54,11 +45,7 @@ /* Define to 1 if you have the header file. */ #undef HAVE_UNISTD_H -/* Define to 1 if the system has the type `_Bool'. */ -#undef HAVE__BOOL - -/* Define to the sub-directory in which libtool stores uninstalled libraries. - */ +/* Define to the sub-directory where libtool stores uninstalled libraries. */ #undef LT_OBJDIR /* Name of package */ @@ -99,9 +86,3 @@ # undef WORDS_BIGENDIAN # endif #endif - -/* Define to `__inline__' or `__inline' if that's what the C compiler - calls it, or to nothing if 'inline' is not supported under any name. */ -#ifndef __cplusplus -#undef inline -#endif diff --git a/gtsam/3rdparty/GeographicLib/include/GeographicLib/Config.h b/gtsam/3rdparty/GeographicLib/include/GeographicLib/Config.h index 2249dd127..5611465bb 100644 --- a/gtsam/3rdparty/GeographicLib/include/GeographicLib/Config.h +++ b/gtsam/3rdparty/GeographicLib/include/GeographicLib/Config.h @@ -1,12 +1,12 @@ // This will be overwritten by ./configure -#define GEOGRAPHICLIB_VERSION_STRING "1.35" +#define GEOGRAPHICLIB_VERSION_STRING "1.49" #define GEOGRAPHICLIB_VERSION_MAJOR 1 -#define GEOGRAPHICLIB_VERSION_MINOR 35 +#define GEOGRAPHICLIB_VERSION_MINOR 49 #define GEOGRAPHICLIB_VERSION_PATCH 0 // Undefine HAVE_LONG_DOUBLE if this type is unknown to the compiler -#define HAVE_LONG_DOUBLE 1 +#define GEOGRAPHICLIB_HAVE_LONG_DOUBLE 1 // Define WORDS_BIGENDIAN to be 1 if your machine is big endian /* #undef WORDS_BIGENDIAN */ diff --git a/gtsam/3rdparty/GeographicLib/include/GeographicLib/Config.h.in b/gtsam/3rdparty/GeographicLib/include/GeographicLib/Config.h.in index 7aae77eef..9e8ec9b53 100644 --- a/gtsam/3rdparty/GeographicLib/include/GeographicLib/Config.h.in +++ b/gtsam/3rdparty/GeographicLib/include/GeographicLib/Config.h.in @@ -5,8 +5,8 @@ #define GEOGRAPHICLIB_DATA "@GEOGRAPHICLIB_DATA@" // These are macros which affect the building of the library -#cmakedefine01 HAVE_LONG_DOUBLE -#cmakedefine01 WORDS_BIGENDIAN +#cmakedefine01 GEOGRAPHICLIB_HAVE_LONG_DOUBLE +#cmakedefine01 GEOGRAPHICLIB_WORDS_BIGENDIAN #define GEOGRAPHICLIB_PRECISION @GEOGRAPHICLIB_PRECISION@ // Specify whether GeographicLib is a shared or static library. When compiling @@ -15,11 +15,11 @@ // cmake will correctly define as 0 or 1 when only one type of library is in // the package. If both shared and static libraries are available, // GEOGRAPHICLIB_SHARED_LIB is set to 2 which triggers a preprocessor error in -// Geographic.hpp. In this case, the appropriate value (0 or 1) for +// Constants.hpp. In this case, the appropriate value (0 or 1) for // GEOGRAPHICLIB_SHARED_LIB must be specified when compiling any program that // includes Geographic.hpp. This is done automatically if GeographicLib and -// the the user's code were built with cmake version 2.8.11 (which introduced -// the command target_compile_definitions) or later. +// the user's code were built with cmake version 2.8.11 (which introduced the +// command target_compile_definitions) or later. #if !defined(GEOGRAPHICLIB_SHARED_LIB) #define GEOGRAPHICLIB_SHARED_LIB @GEOGRAPHICLIB_LIB_TYPE_VAL@ #endif diff --git a/gtsam/3rdparty/GeographicLib/include/GeographicLib/Constants.hpp b/gtsam/3rdparty/GeographicLib/include/GeographicLib/Constants.hpp index 99baff31f..d87948057 100644 --- a/gtsam/3rdparty/GeographicLib/include/GeographicLib/Constants.hpp +++ b/gtsam/3rdparty/GeographicLib/include/GeographicLib/Constants.hpp @@ -2,9 +2,9 @@ * \file Constants.hpp * \brief Header for GeographicLib::Constants class * - * Copyright (c) Charles Karney (2008-2011) and licensed + * Copyright (c) Charles Karney (2008-2016) and licensed * under the MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #if !defined(GEOGRAPHICLIB_CONSTANTS_HPP) @@ -13,29 +13,68 @@ #include /** - * A compile-time assert. Use C++11 static_assert, if available. + * @relates GeographicLib::Constants + * Pack the version components into a single integer. Users should not rely on + * this particular packing of the components of the version number; see the + * documentation for GEOGRAPHICLIB_VERSION, below. **********************************************************************/ -#if !defined(STATIC_ASSERT) -# if __cplusplus >= 201103 -# define STATIC_ASSERT static_assert -# elif defined(__GXX_EXPERIMENTAL_CXX0X__) -# define STATIC_ASSERT static_assert +#define GEOGRAPHICLIB_VERSION_NUM(a,b,c) ((((a) * 10000 + (b)) * 100) + (c)) + +/** + * @relates GeographicLib::Constants + * The version of GeographicLib as a single integer, packed as MMmmmmpp where + * MM is the major version, mmmm is the minor version, and pp is the patch + * level. Users should not rely on this particular packing of the components + * of the version number. Instead they should use a test such as \code + #if GEOGRAPHICLIB_VERSION >= GEOGRAPHICLIB_VERSION_NUM(1,37,0) + ... + #endif + * \endcode + **********************************************************************/ +#define GEOGRAPHICLIB_VERSION \ + GEOGRAPHICLIB_VERSION_NUM(GEOGRAPHICLIB_VERSION_MAJOR, \ + GEOGRAPHICLIB_VERSION_MINOR, \ + GEOGRAPHICLIB_VERSION_PATCH) + +/** + * @relates GeographicLib::Constants + * Is the C++11 static_assert available? + **********************************************************************/ +#if !defined(GEOGRAPHICLIB_HAS_STATIC_ASSERT) +# if __cplusplus >= 201103 || defined(__GXX_EXPERIMENTAL_CXX0X__) +# define GEOGRAPHICLIB_HAS_STATIC_ASSERT 1 # elif defined(_MSC_VER) && _MSC_VER >= 1600 // For reference, here is a table of Visual Studio and _MSC_VER // correspondences: // // _MSC_VER Visual Studio +// 1100 vc5 +// 1200 vc6 // 1300 vc7 -// 1311 vc7.1 (2003) +// 1310 vc7.1 (2003) // 1400 vc8 (2005) // 1500 vc9 (2008) // 1600 vc10 (2010) // 1700 vc11 (2012) // 1800 vc12 (2013) -# define STATIC_ASSERT static_assert +// 1900 vc14 (2015) +// 1910+ vc15 (2017) +# define GEOGRAPHICLIB_HAS_STATIC_ASSERT 1 # else -# define STATIC_ASSERT(cond,reason) \ - { enum{ STATIC_ASSERT_ENUM = 1/int(cond) }; } +# define GEOGRAPHICLIB_HAS_STATIC_ASSERT 0 +# endif +#endif + +/** + * @relates GeographicLib::Constants + * A compile-time assert. Use C++11 static_assert, if available. + **********************************************************************/ +#if !defined(GEOGRAPHICLIB_STATIC_ASSERT) +# if GEOGRAPHICLIB_HAS_STATIC_ASSERT +# define GEOGRAPHICLIB_STATIC_ASSERT static_assert +# else +# define GEOGRAPHICLIB_STATIC_ASSERT(cond,reason) \ + { enum{ GEOGRAPHICLIB_STATIC_ASSERT_ENUM = 1/int(cond) }; } # endif #endif @@ -52,6 +91,21 @@ # define GEOGRAPHICLIB_EXPORT #endif +// Use GEOGRAPHICLIB_DEPRECATED to mark functions, types or variables as +// deprecated. Code inspired by Apache Subversion's svn_types.h file (via +// MPFR). +#if defined(__GNUC__) +# if __GNUC__ > 4 +# define GEOGRAPHICLIB_DEPRECATED(msg) __attribute__((deprecated(msg))) +# else +# define GEOGRAPHICLIB_DEPRECATED(msg) __attribute__((deprecated)) +# endif +#elif defined(_MSC_VER) && _MSC_VER >= 1300 +# define GEOGRAPHICLIB_DEPRECATED(msg) __declspec(deprecated(msg)) +#else +# define GEOGRAPHICLIB_DEPRECATED(msg) +#endif + #include #include #include @@ -83,17 +137,17 @@ namespace GeographicLib { /** * A synonym for Math::degree(). **********************************************************************/ - static inline Math::real degree() throw() { return Math::degree(); } + static Math::real degree() { return Math::degree(); } /** * @return the number of radians in an arcminute. **********************************************************************/ - static inline Math::real arcminute() throw() - { return Math::degree() / 60; } + static Math::real arcminute() + { return Math::degree() / 60; } /** * @return the number of radians in an arcsecond. **********************************************************************/ - static inline Math::real arcsecond() throw() - { return Math::degree() / 3600; } + static Math::real arcsecond() + { return Math::degree() / 3600; } /** \name Ellipsoid parameters **********************************************************************/ @@ -102,62 +156,69 @@ namespace GeographicLib { * @tparam T the type of the returned value. * @return the equatorial radius of WGS84 ellipsoid (6378137 m). **********************************************************************/ - template static inline T WGS84_a() throw() - { return T(6378137) * meter(); } + template static T WGS84_a() + { return 6378137 * meter(); } /** * A synonym for WGS84_a(). **********************************************************************/ - static inline Math::real WGS84_a() throw() { return WGS84_a(); } + static Math::real WGS84_a() { return WGS84_a(); } /** * @tparam T the type of the returned value. * @return the flattening of WGS84 ellipsoid (1/298.257223563). **********************************************************************/ - template static inline T WGS84_f() throw() - { return T(1) / ( T(298) + T(257223563) / T(1000000000) ); } + template static T WGS84_f() { + // Evaluating this as 1000000000 / T(298257223563LL) reduces the + // round-off error by about 10%. However, expressing the flattening as + // 1/298.257223563 is well ingrained. + return 1 / ( T(298257223563LL) / 1000000000 ); + } /** * A synonym for WGS84_f(). **********************************************************************/ - static inline Math::real WGS84_f() throw() { return WGS84_f(); } + static Math::real WGS84_f() { return WGS84_f(); } /** * @tparam T the type of the returned value. * @return the gravitational constant of the WGS84 ellipsoid, \e GM, in * m3 s−2. **********************************************************************/ - template static inline T WGS84_GM() throw() - { return T(3986004) * T(100000000) + T(41800000); } + template static T WGS84_GM() + { return T(3986004) * 100000000 + 41800000; } + /** + * A synonym for WGS84_GM(). + **********************************************************************/ + static Math::real WGS84_GM() { return WGS84_GM(); } /** * @tparam T the type of the returned value. * @return the angular velocity of the WGS84 ellipsoid, ω, in rad * s−1. **********************************************************************/ - template static inline T WGS84_omega() throw() - { return T(7292115) / (T(1000000) * T(100000)); } - /// \cond SKIP + template static T WGS84_omega() + { return 7292115 / (T(1000000) * 100000); } /** - * DEPRECATED - * @return the reciprocal flattening of WGS84 ellipsoid. + * A synonym for WGS84_omega(). **********************************************************************/ - template static inline T WGS84_r() throw() - { return 1/WGS84_f(); } - /** - * DEPRECATED - * A synonym for WGS84_r(). - **********************************************************************/ - static inline Math::real WGS84_r() throw() { return WGS84_r(); } - /// \endcond + static Math::real WGS84_omega() { return WGS84_omega(); } /** * @tparam T the type of the returned value. * @return the equatorial radius of GRS80 ellipsoid, \e a, in m. **********************************************************************/ - template static inline T GRS80_a() throw() - { return T(6378137); } + template static T GRS80_a() + { return 6378137 * meter(); } + /** + * A synonym for GRS80_a(). + **********************************************************************/ + static Math::real GRS80_a() { return GRS80_a(); } /** * @tparam T the type of the returned value. * @return the gravitational constant of the GRS80 ellipsoid, \e GM, in * m3 s−2. **********************************************************************/ - template static inline T GRS80_GM() throw() - { return T(3986005) * T(100000000); } + template static T GRS80_GM() + { return T(3986005) * 100000000; } + /** + * A synonym for GRS80_GM(). + **********************************************************************/ + static Math::real GRS80_GM() { return GRS80_GM(); } /** * @tparam T the type of the returned value. * @return the angular velocity of the GRS80 ellipsoid, ω, in rad @@ -170,35 +231,43 @@ namespace GeographicLib { * approximation (because the Gregorian year includes the precession of the * earth's axis). **********************************************************************/ - template static inline T GRS80_omega() throw() - { return T(7292115) / (T(1000000) * T(100000)); } + template static T GRS80_omega() + { return 7292115 / (T(1000000) * 100000); } + /** + * A synonym for GRS80_omega(). + **********************************************************************/ + static Math::real GRS80_omega() { return GRS80_omega(); } /** * @tparam T the type of the returned value. * @return the dynamical form factor of the GRS80 ellipsoid, * J2. **********************************************************************/ - template static inline T GRS80_J2() throw() - { return T(108263) / T(100000000); } + template static T GRS80_J2() + { return T(108263) / 100000000; } + /** + * A synonym for GRS80_J2(). + **********************************************************************/ + static Math::real GRS80_J2() { return GRS80_J2(); } /** * @tparam T the type of the returned value. * @return the central scale factor for UTM (0.9996). **********************************************************************/ - template static inline T UTM_k0() throw() - {return T(9996) / T(10000); } + template static T UTM_k0() + {return T(9996) / 10000; } /** * A synonym for UTM_k0(). **********************************************************************/ - static inline Math::real UTM_k0() throw() { return UTM_k0(); } + static Math::real UTM_k0() { return UTM_k0(); } /** * @tparam T the type of the returned value. * @return the central scale factor for UPS (0.994). **********************************************************************/ - template static inline T UPS_k0() throw() - { return T(994) / T(1000); } + template static T UPS_k0() + { return T(994) / 1000; } /** * A synonym for UPS_k0(). **********************************************************************/ - static inline Math::real UPS_k0() throw() { return UPS_k0(); } + static Math::real UPS_k0() { return UPS_k0(); } ///@} /** \name SI units @@ -211,21 +280,21 @@ namespace GeographicLib { * This is unity, but this lets the internal system of units be changed if * necessary. **********************************************************************/ - template static inline T meter() throw() { return T(1); } + template static T meter() { return T(1); } /** * A synonym for meter(). **********************************************************************/ - static inline Math::real meter() throw() { return meter(); } + static Math::real meter() { return meter(); } /** * @return the number of meters in a kilometer. **********************************************************************/ - static inline Math::real kilometer() throw() + static Math::real kilometer() { return 1000 * meter(); } /** * @return the number of meters in a nautical mile (approximately 1 arc * minute) **********************************************************************/ - static inline Math::real nauticalmile() throw() + static Math::real nauticalmile() { return 1852 * meter(); } /** @@ -235,27 +304,27 @@ namespace GeographicLib { * This is unity, but this lets the internal system of units be changed if * necessary. **********************************************************************/ - template static inline T square_meter() throw() + template static T square_meter() { return meter() * meter(); } /** * A synonym for square_meter(). **********************************************************************/ - static inline Math::real square_meter() throw() + static Math::real square_meter() { return square_meter(); } /** * @return the number of square meters in a hectare. **********************************************************************/ - static inline Math::real hectare() throw() + static Math::real hectare() { return 10000 * square_meter(); } /** * @return the number of square meters in a square kilometer. **********************************************************************/ - static inline Math::real square_kilometer() throw() + static Math::real square_kilometer() { return kilometer() * kilometer(); } /** * @return the number of square meters in a square nautical mile. **********************************************************************/ - static inline Math::real square_nauticalmile() throw() + static Math::real square_nauticalmile() { return nauticalmile() * nauticalmile(); } ///@} @@ -265,36 +334,36 @@ namespace GeographicLib { /** * @return the number of meters in an international foot. **********************************************************************/ - static inline Math::real foot() throw() - { return real(0.0254L) * 12 * meter(); } + static Math::real foot() + { return real(254 * 12) / 10000 * meter(); } /** * @return the number of meters in a yard. **********************************************************************/ - static inline Math::real yard() throw() { return 3 * foot(); } + static Math::real yard() { return 3 * foot(); } /** * @return the number of meters in a fathom. **********************************************************************/ - static inline Math::real fathom() throw() { return 2 * yard(); } + static Math::real fathom() { return 2 * yard(); } /** * @return the number of meters in a chain. **********************************************************************/ - static inline Math::real chain() throw() { return 22 * yard(); } + static Math::real chain() { return 22 * yard(); } /** * @return the number of meters in a furlong. **********************************************************************/ - static inline Math::real furlong() throw() { return 10 * chain(); } + static Math::real furlong() { return 10 * chain(); } /** * @return the number of meters in a statute mile. **********************************************************************/ - static inline Math::real mile() throw() { return 8 * furlong(); } + static Math::real mile() { return 8 * furlong(); } /** * @return the number of square meters in an acre. **********************************************************************/ - static inline Math::real acre() throw() { return chain() * furlong(); } + static Math::real acre() { return chain() * furlong(); } /** * @return the number of square meters in a square statute mile. **********************************************************************/ - static inline Math::real square_mile() throw() { return mile() * mile(); } + static Math::real square_mile() { return mile() * mile(); } ///@} /** \name Anachronistic US units @@ -303,8 +372,8 @@ namespace GeographicLib { /** * @return the number of meters in a US survey foot. **********************************************************************/ - static inline Math::real surveyfoot() throw() - { return real(1200) / real(3937) * meter(); } + static Math::real surveyfoot() + { return real(1200) / 3937 * meter(); } ///@} }; diff --git a/gtsam/3rdparty/GeographicLib/include/GeographicLib/DMS.hpp b/gtsam/3rdparty/GeographicLib/include/GeographicLib/DMS.hpp index ea9fe5ce0..169f2795c 100644 --- a/gtsam/3rdparty/GeographicLib/include/GeographicLib/DMS.hpp +++ b/gtsam/3rdparty/GeographicLib/include/GeographicLib/DMS.hpp @@ -2,9 +2,9 @@ * \file DMS.hpp * \brief Header for GeographicLib::DMS class * - * Copyright (c) Charles Karney (2008-2011) and licensed + * Copyright (c) Charles Karney (2008-2017) and licensed * under the MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #if !defined(GEOGRAPHICLIB_DMS_HPP) @@ -32,26 +32,6 @@ namespace GeographicLib { * \include example-DMS.cpp **********************************************************************/ class GEOGRAPHICLIB_EXPORT DMS { - private: - typedef Math::real real; - // Replace all occurrences of pat by c - static void replace(std::string& s, const std::string& pat, char c) { - std::string::size_type p = 0; - while (true) { - p = s.find(pat, p); - if (p == std::string::npos) - break; - s.replace(p, pat.length(), 1, c); - } - } - static const std::string hemispheres_; - static const std::string signs_; - static const std::string digits_; - static const std::string dmsindicators_; - static const std::string components_[3]; - static Math::real NumMatch(const std::string& s); - DMS(); // Disable constructor - public: /** @@ -108,6 +88,29 @@ namespace GeographicLib { SECOND = 2, }; + private: + typedef Math::real real; + // Replace all occurrences of pat by c + static void replace(std::string& s, const std::string& pat, char c) { + std::string::size_type p = 0; + while (true) { + p = s.find(pat, p); + if (p == std::string::npos) + break; + s.replace(p, pat.length(), 1, c); + } + } + static const char* const hemispheres_; + static const char* const signs_; + static const char* const digits_; + static const char* const dmsindicators_; + static const char* const components_[3]; + static Math::real NumMatch(const std::string& s); + static Math::real InternalDecode(const std::string& dmsa, flag& ind); + DMS(); // Disable constructor + + public: + /** * Convert a string in DMS to an angle. * @@ -120,42 +123,67 @@ namespace GeographicLib { * Degrees, minutes, and seconds are indicated by the characters d, ' * (single quote), " (double quote), and these components may only be * given in this order. Any (but not all) components may be omitted and - * other symbols (e.g., the ° symbol for degrees and the unicode - * prime and double prime symbols for minutes and seconds) may be - * substituted. The last component indicator may be omitted and is assumed - * to be the next smallest unit (thus 33d10 is interpreted as 33d10'). The - * final component may be a decimal fraction but the non-final components - * must be integers. Instead of using d, ', and " to indicate - * degrees, minutes, and seconds, : (colon) may be used to separate - * these components (numbers must appear before and after each colon); thus - * 50d30'10.3" may be written as 50:30:10.3, 5.5' may be written - * 0:5.5, and so on. The integer parts of the minutes and seconds - * components must be less than 60. A single leading sign is permitted. A - * hemisphere designator (N, E, W, S) may be added to the beginning or end - * of the string. The result is multiplied by the implied sign of the - * hemisphere designator (negative for S and W). In addition \e ind is set - * to DMS::LATITUDE if N or S is present, to DMS::LONGITUDE if E or W is - * present, and to DMS::NONE otherwise. Throws an error on a malformed - * string. No check is performed on the range of the result. Examples of - * legal and illegal strings are + * other symbols (e.g., the ° symbol for degrees and the unicode prime + * and double prime symbols for minutes and seconds) may be substituted; + * two single quotes can be used instead of ". The last component + * indicator may be omitted and is assumed to be the next smallest unit + * (thus 33d10 is interpreted as 33d10'). The final component may be a + * decimal fraction but the non-final components must be integers. Instead + * of using d, ', and " to indicate degrees, minutes, and seconds, : + * (colon) may be used to separate these components (numbers must + * appear before and after each colon); thus 50d30'10.3" may be + * written as 50:30:10.3, 5.5' may be written 0:5.5, and so on. The + * integer parts of the minutes and seconds components must be less + * than 60. A single leading sign is permitted. A hemisphere designator + * (N, E, W, S) may be added to the beginning or end of the string. The + * result is multiplied by the implied sign of the hemisphere designator + * (negative for S and W). In addition \e ind is set to DMS::LATITUDE if N + * or S is present, to DMS::LONGITUDE if E or W is present, and to + * DMS::NONE otherwise. Throws an error on a malformed string. No check + * is performed on the range of the result. Examples of legal and illegal + * strings are * - LEGAL (all the entries on each line are equivalent) * - -20.51125, 20d30'40.5"S, -20°30'40.5, -20d30.675, * N-20d30'40.5", -20:30:40.5 * - 4d0'9, 4d9", 4d9'', 4:0:9, 004:00:09, 4.0025, 4.0025d, 4d0.15, * 04:.15 + * - 4:59.99999999999999, 4:60.0, 4:59:59.9999999999999, 4:59:60.0, 5 * - ILLEGAL (the exception thrown explains the problem) * - 4d5"4', 4::5, 4:5:, :4:5, 4d4.5'4", -N20.5, 1.8e2d, 4:60, - * 4d-5' + * 4:59:60 * - * NOTE: At present, all the string handling in the C++ + * The decoding operation can also perform addition and subtraction + * operations. If the string includes internal signs (i.e., not at + * the beginning nor immediately after an initial hemisphere designator), + * then the string is split immediately before such signs and each piece is + * decoded according to the above rules and the results added; thus + * S3-2.5+4.1N is parsed as the sum of S3, + * -2.5, +4.1N. Any piece can include a + * hemisphere designator; however, if multiple designators are given, they + * must compatible; e.g., you cannot mix N and E. In addition, the + * designator can appear at the beginning or end of the first piece, but + * must be at the end of all subsequent pieces (a hemisphere designator is + * not allowed after the initial sign). Examples of legal and illegal + * combinations are + * - LEGAL (these are all equivalent) + * - 070:00:45, 70:01:15W+0:0.5, 70:01:15W-0:0:30W, W70:01:15+0:0:30E + * - ILLEGAL (the exception thrown explains the problem) + * - 70:01:15W+0:0:15N, W70:01:15+W0:0:15 + * + * \warning The "exponential" notation is not recognized. Thus + * 7.0E1 is illegal, while 7.0E+1 is parsed as + * (7.0E) + (+1), yielding the same result as + * 8.0E. + * + * \note At present, all the string handling in the C++ * implementation %GeographicLib is with 8-bit characters. The support for * unicode symbols for degrees, minutes, and seconds is therefore via the - * UTF-8 encoding. (The + * UTF-8 encoding. (The * JavaScript implementation of this class uses unicode natively, of * course.) * * Here is the list of Unicode symbols supported for degrees, minutes, - * seconds: + * seconds, and the sign: * - degrees: * - d, D lower and upper case letters * - U+00b0 degree symbol (°) @@ -172,6 +200,8 @@ namespace GeographicLib { * - U+2033 double prime (″) * - U+201d right double quote (”) * - ' ' any two consecutive symbols for minutes + * - leading sign: + * - U+2212 minus sign (−) * . * The codes with a leading zero byte, e.g., U+00b0, are accepted in their * UTF-8 coded form 0xc2 0xb0 and as a single byte 0xb0. @@ -186,47 +216,21 @@ namespace GeographicLib { * @param[in] s arc seconds. * @return angle (degrees) * - * This does not propagate the sign on \e d to the other components, so - * -3d20' would need to be represented as - DMS::Decode(3.0, 20.0) or + * This does not propagate the sign on \e d to the other components, + * so -3d20' would need to be represented as - DMS::Decode(3.0, 20.0) or * DMS::Decode(-3.0, -20.0). **********************************************************************/ - static Math::real Decode(real d, real m = 0, real s = 0) throw() - { return d + (m + s/real(60))/real(60); } - - /// \cond SKIP - /** - * DEPRECATED (use Utility::num, instead). - * Convert a string to a real number. - * - * @param[in] str string input. - * @exception GeographicErr if \e str is malformed. - * @return decoded number. - **********************************************************************/ - static Math::real Decode(const std::string& str) - { return Utility::num(str); } - - /** - * DEPRECATED (use Utility::fract, instead). - * Convert a string to a real number treating the case where the string is - * a simple fraction. - * - * @param[in] str string input. - * @exception GeographicErr if \e str is malformed. - * @return decoded number. - **********************************************************************/ - static Math::real DecodeFraction(const std::string& str) - { return Utility::fract(str); } - /// \endcond + static Math::real Decode(real d, real m = 0, real s = 0) + { return d + (m + s / 60) / 60; } /** * Convert a pair of strings to latitude and longitude. * * @param[in] dmsa first string. * @param[in] dmsb second string. - * @param[out] lat latitude. - * @param[out] lon longitude reduced to the range [−180°, - * 180°). - * @param[in] swaplatlong if true assume longitude is given before latitude + * @param[out] lat latitude (degrees). + * @param[out] lon longitude (degrees). + * @param[in] longfirst if true assume longitude is given before latitude * in the absence of hemisphere designators (default false). * @exception GeographicErr if \e dmsa or \e dmsb is malformed. * @exception GeographicErr if \e dmsa and \e dmsb are both interpreted as @@ -235,8 +239,6 @@ namespace GeographicLib { * longitudes. * @exception GeographicErr if decoded latitude is not in [−90°, * 90°]. - * @exception GeographicErr if decoded longitude is not in - * [−540°, 540°). * * By default, the \e lat (resp., \e lon) is assigned to the results of * decoding \e dmsa (resp., \e dmsb). However this is overridden if either @@ -245,7 +247,8 @@ namespace GeographicLib { * unchanged. **********************************************************************/ static void DecodeLatLon(const std::string& dmsa, const std::string& dmsb, - real& lat, real& lon, bool swaplatlong = false); + real& lat, real& lon, + bool longfirst = false); /** * Convert a string to an angle in degrees. @@ -266,10 +269,8 @@ namespace GeographicLib { * @param[in] azistr input string. * @exception GeographicErr if \e azistr is malformed. * @exception GeographicErr if \e azistr includes a N/S designator. - * @exception GeographicErr if decoded azimuth is not in - * [−540°, 540°). * @return azimuth (degrees) reduced to the range [−180°, - * 180°). + * 180°]. * * A hemisphere designator E/W can be used; the result is multiplied by * −1 if W is present. @@ -281,10 +282,11 @@ namespace GeographicLib { * * @param[in] angle input angle (degrees) * @param[in] trailing DMS::component value indicating the trailing units - * on the string and this is given as a decimal number if necessary. + * of the string (this component is given as a decimal number if + * necessary). * @param[in] prec the number of digits after the decimal point for the * trailing component. - * @param[in] ind DMS::flag value indicated additional formatting. + * @param[in] ind DMS::flag value indicating additional formatting. * @param[in] dmssep if non-null, use as the DMS separator character * (instead of d, ', " delimiters). * @exception std::bad_alloc if memory for the string can't be allocated. @@ -298,7 +300,7 @@ namespace GeographicLib { * - ind == DMS::LONGITUDE, trailing E or W hemisphere designator, no * sign, pad degrees to 3 digits, e.g., 008d03'W. * - ind == DMS::AZIMUTH, convert to the range [0, 360°), no - * sign, pad degrees to 3 digits, , e.g., 351d57'. + * sign, pad degrees to 3 digits, e.g., 351d57'. * . * The integer parts of the minutes and seconds components are always given * with 2 digits. @@ -326,7 +328,7 @@ namespace GeographicLib { **********************************************************************/ static std::string Encode(real angle, unsigned prec, flag ind = NONE, char dmssep = char(0)) { - return ind == NUMBER ? Utility::str(angle, int(prec)) : + return ind == NUMBER ? Utility::str(angle, int(prec)) : Encode(angle, prec < 2 ? DEGREE : (prec < 4 ? MINUTE : SECOND), prec < 2 ? prec : (prec < 4 ? prec - 2 : prec - 4), @@ -340,7 +342,7 @@ namespace GeographicLib { * @param[out] d degrees (an integer returned as a real) * @param[out] m arc minutes. **********************************************************************/ - static void Encode(real ang, real& d, real& m) throw() { + static void Encode(real ang, real& d, real& m) { d = int(ang); m = 60 * (ang - d); } @@ -352,7 +354,7 @@ namespace GeographicLib { * @param[out] m arc minutes (an integer returned as a real) * @param[out] s arc seconds. **********************************************************************/ - static void Encode(real ang, real& d, real& m, real& s) throw() { + static void Encode(real ang, real& d, real& m, real& s) { d = int(ang); ang = 60 * (ang - d); m = int(ang); s = 60 * (ang - m); } diff --git a/gtsam/3rdparty/GeographicLib/include/GeographicLib/Ellipsoid.hpp b/gtsam/3rdparty/GeographicLib/include/GeographicLib/Ellipsoid.hpp index 72e0c6d86..6bf683682 100644 --- a/gtsam/3rdparty/GeographicLib/include/GeographicLib/Ellipsoid.hpp +++ b/gtsam/3rdparty/GeographicLib/include/GeographicLib/Ellipsoid.hpp @@ -2,9 +2,9 @@ * \file Ellipsoid.hpp * \brief Header for GeographicLib::Ellipsoid class * - * Copyright (c) Charles Karney (2012) and licensed under - * the MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ + * Copyright (c) Charles Karney (2012-2017) and licensed + * under the MIT/X11 License. For more information, see + * https://geographiclib.sourceforge.io/ **********************************************************************/ #if !defined(GEOGRAPHICLIB_ELLIPSOID_HPP) @@ -40,21 +40,18 @@ namespace GeographicLib { private: typedef Math::real real; static const int numit_ = 10; - static const real stol_; - real _a, _f, _f1, _f12, _e2, _e12, _n, _b; + real stol_; + real _a, _f, _f1, _f12, _e2, _es, _e12, _n, _b; TransverseMercator _tm; EllipticFunction _ell; AlbersEqualArea _au; - static real tand(real x) throw() { - return - std::abs(x) == real(90) ? (x < 0 ? - - TransverseMercator::overflow_ - : TransverseMercator::overflow_) : - std::tan(x * Math::degree()); - } - static real atand(real x) throw() - { return std::atan(x) / Math::degree(); } + // These are the alpha and beta coefficients in the Krueger series from + // TransverseMercator. Thy are used by RhumbSolve to compute + // (psi2-psi1)/(mu2-mu1). + const Math::real* ConformalToRectifyingCoeffs() const { return _tm._alp; } + const Math::real* RectifyingToConformalCoeffs() const { return _tm._bet; } + friend class Rhumb; friend class RhumbLine; public: /** \name Constructor **********************************************************************/ @@ -65,9 +62,8 @@ namespace GeographicLib { * * @param[in] a equatorial radius (meters). * @param[in] f flattening of ellipsoid. Setting \e f = 0 gives a sphere. - * Negative \e f gives a prolate ellipsoid. If \e f > 1, set flattening - * to 1/\e f. - * @exception GeographicErr if \e a or (1 − \e f ) \e a is not + * Negative \e f gives a prolate ellipsoid. + * @exception GeographicErr if \e a or (1 − \e f) \e a is not * positive. **********************************************************************/ Ellipsoid(real a, real f); @@ -81,34 +77,34 @@ namespace GeographicLib { * @return \e a the equatorial radius of the ellipsoid (meters). This is * the value used in the constructor. **********************************************************************/ - Math::real MajorRadius() const throw() { return _a; } + Math::real MajorRadius() const { return _a; } /** * @return \e b the polar semi-axis (meters). **********************************************************************/ - Math::real MinorRadius() const throw() { return _b; } + Math::real MinorRadius() const { return _b; } /** * @return \e L the distance between the equator and a pole along a * meridian (meters). For a sphere \e L = (π/2) \e a. The radius * of a sphere with the same meridian length is \e L / (π/2). **********************************************************************/ - Math::real QuarterMeridian() const throw(); + Math::real QuarterMeridian() const; /** * @return \e A the total area of the ellipsoid (meters2). For * a sphere \e A = 4π a2. The radius of a sphere * with the same area is sqrt(\e A / (4π)). **********************************************************************/ - Math::real Area() const throw(); + Math::real Area() const; /** * @return \e V the total volume of the ellipsoid (meters3). * For a sphere \e V = (4π / 3) a3. The radius of * a sphere with the same volume is cbrt(\e V / (4π/3)). **********************************************************************/ - Math::real Volume() const throw() - { return (4 * Math::pi()) * Math::sq(_a) * _b / 3; } + Math::real Volume() const + { return (4 * Math::pi()) * Math::sq(_a) * _b / 3; } ///@} /** \name %Ellipsoid shape @@ -121,21 +117,21 @@ namespace GeographicLib { * positive, or negative for a sphere, oblate ellipsoid, or prolate * ellipsoid. **********************************************************************/ - Math::real Flattening() const throw() { return _f; } + Math::real Flattening() const { return _f; } /** * @return \e f ' = (\e a − \e b) / \e b, the second flattening of * the ellipsoid. This is zero, positive, or negative for a sphere, * oblate ellipsoid, or prolate ellipsoid. **********************************************************************/ - Math::real SecondFlattening() const throw() { return _f / (1 - _f); } + Math::real SecondFlattening() const { return _f / (1 - _f); } /** * @return \e n = (\e a − \e b) / (\e a + \e b), the third flattening * of the ellipsoid. This is zero, positive, or negative for a sphere, * oblate ellipsoid, or prolate ellipsoid. **********************************************************************/ - Math::real ThirdFlattening() const throw() { return _n; } + Math::real ThirdFlattening() const { return _n; } /** * @return e2 = (a2 − @@ -143,7 +139,7 @@ namespace GeographicLib { * of the ellipsoid. This is zero, positive, or negative for a sphere, * oblate ellipsoid, or prolate ellipsoid. **********************************************************************/ - Math::real EccentricitySq() const throw() { return _e2; } + Math::real EccentricitySq() const { return _e2; } /** * @return e' 2 = (a2 − @@ -151,7 +147,7 @@ namespace GeographicLib { * squared of the ellipsoid. This is zero, positive, or negative for a * sphere, oblate ellipsoid, or prolate ellipsoid. **********************************************************************/ - Math::real SecondEccentricitySq() const throw() { return _e12; } + Math::real SecondEccentricitySq() const { return _e12; } /** * @return e'' 2 = (a2 − @@ -160,7 +156,7 @@ namespace GeographicLib { * positive, or negative for a sphere, oblate ellipsoid, or prolate * ellipsoid. **********************************************************************/ - Math::real ThirdEccentricitySq() const throw() { return _e2 / (2 - _e2); } + Math::real ThirdEccentricitySq() const { return _e2 / (2 - _e2); } ///@} /** \name Latitude conversion. @@ -187,7 +183,7 @@ namespace GeographicLib { * result is undefined if this condition does not hold. The returned value * β lies in [−90°, 90°]. **********************************************************************/ - Math::real ParametricLatitude(real phi) const throw(); + Math::real ParametricLatitude(real phi) const; /** * @param[in] beta the parametric latitude (degrees). @@ -197,7 +193,7 @@ namespace GeographicLib { * result is undefined if this condition does not hold. The returned value * φ lies in [−90°, 90°]. **********************************************************************/ - Math::real InverseParametricLatitude(real beta) const throw(); + Math::real InverseParametricLatitude(real beta) const; /** * @param[in] phi the geographic latitude (degrees). @@ -211,7 +207,7 @@ namespace GeographicLib { * result is undefined if this condition does not hold. The returned value * θ lies in [−90°, 90°]. **********************************************************************/ - Math::real GeocentricLatitude(real phi) const throw(); + Math::real GeocentricLatitude(real phi) const; /** * @param[in] theta the geocentric latitude (degrees). @@ -221,7 +217,7 @@ namespace GeographicLib { * result is undefined if this condition does not hold. The returned value * φ lies in [−90°, 90°]. **********************************************************************/ - Math::real InverseGeocentricLatitude(real theta) const throw(); + Math::real InverseGeocentricLatitude(real theta) const; /** * @param[in] phi the geographic latitude (degrees). @@ -237,7 +233,7 @@ namespace GeographicLib { * result is undefined if this condition does not hold. The returned value * μ lies in [−90°, 90°]. **********************************************************************/ - Math::real RectifyingLatitude(real phi) const throw(); + Math::real RectifyingLatitude(real phi) const; /** * @param[in] mu the rectifying latitude (degrees). @@ -247,7 +243,7 @@ namespace GeographicLib { * result is undefined if this condition does not hold. The returned value * φ lies in [−90°, 90°]. **********************************************************************/ - Math::real InverseRectifyingLatitude(real mu) const throw(); + Math::real InverseRectifyingLatitude(real mu) const; /** * @param[in] phi the geographic latitude (degrees). @@ -263,7 +259,7 @@ namespace GeographicLib { * result is undefined if this condition does not hold. The returned value * ξ lies in [−90°, 90°]. **********************************************************************/ - Math::real AuthalicLatitude(real phi) const throw(); + Math::real AuthalicLatitude(real phi) const; /** * @param[in] xi the authalic latitude (degrees). @@ -273,7 +269,7 @@ namespace GeographicLib { * result is undefined if this condition does not hold. The returned value * φ lies in [−90°, 90°]. **********************************************************************/ - Math::real InverseAuthalicLatitude(real xi) const throw(); + Math::real InverseAuthalicLatitude(real xi) const; /** * @param[in] phi the geographic latitude (degrees). @@ -288,7 +284,7 @@ namespace GeographicLib { * result is undefined if this condition does not hold. The returned value * χ lies in [−90°, 90°]. **********************************************************************/ - Math::real ConformalLatitude(real phi) const throw(); + Math::real ConformalLatitude(real phi) const; /** * @param[in] chi the conformal latitude (degrees). @@ -298,7 +294,7 @@ namespace GeographicLib { * result is undefined if this condition does not hold. The returned value * φ lies in [−90°, 90°]. **********************************************************************/ - Math::real InverseConformalLatitude(real chi) const throw(); + Math::real InverseConformalLatitude(real chi) const; /** * @param[in] phi the geographic latitude (degrees). @@ -310,18 +306,21 @@ namespace GeographicLib { * defines the Mercator projection. For a sphere ψ = * sinh−1 tan φ. * - * φ must lie in the range [−90°, 90°]; the - * result is undefined if this condition does not hold. + * φ must lie in the range [−90°, 90°]; the result is + * undefined if this condition does not hold. The value returned for φ + * = ±90° is some (positive or negative) large but finite value, + * such that InverseIsometricLatitude returns the original value of φ. **********************************************************************/ - Math::real IsometricLatitude(real phi) const throw(); + Math::real IsometricLatitude(real phi) const; /** * @param[in] psi the isometric latitude (degrees). * @return φ the geographic latitude (degrees). * - * The returned value φ lies in [−90°, 90°]. + * The returned value φ lies in [−90°, 90°]. For a + * sphere φ = tan−1 sinh ψ. **********************************************************************/ - Math::real InverseIsometricLatitude(real psi) const throw(); + Math::real InverseIsometricLatitude(real psi) const; ///@} /** \name Other quantities. @@ -337,7 +336,7 @@ namespace GeographicLib { * φ must lie in the range [−90°, 90°]; the * result is undefined if this condition does not hold. **********************************************************************/ - Math::real CircleRadius(real phi) const throw(); + Math::real CircleRadius(real phi) const; /** * @param[in] phi the geographic latitude (degrees). @@ -348,7 +347,7 @@ namespace GeographicLib { * φ must lie in the range [−90°, 90°]; the * result is undefined if this condition does not hold. **********************************************************************/ - Math::real CircleHeight(real phi) const throw(); + Math::real CircleHeight(real phi) const; /** * @param[in] phi the geographic latitude (degrees). @@ -360,7 +359,7 @@ namespace GeographicLib { * φ must lie in the range [−90°, 90°]; the * result is undefined if this condition does not hold. **********************************************************************/ - Math::real MeridianDistance(real phi) const throw(); + Math::real MeridianDistance(real phi) const; /** * @param[in] phi the geographic latitude (degrees). @@ -373,7 +372,7 @@ namespace GeographicLib { * φ must lie in the range [−90°, 90°]; the * result is undefined if this condition does not hold. **********************************************************************/ - Math::real MeridionalCurvatureRadius(real phi) const throw(); + Math::real MeridionalCurvatureRadius(real phi) const; /** * @param[in] phi the geographic latitude (degrees). @@ -386,7 +385,7 @@ namespace GeographicLib { * φ must lie in the range [−90°, 90°]; the * result is undefined if this condition does not hold. **********************************************************************/ - Math::real TransverseCurvatureRadius(real phi) const throw(); + Math::real TransverseCurvatureRadius(real phi) const; /** * @param[in] phi the geographic latitude (degrees). @@ -396,11 +395,10 @@ namespace GeographicLib { * section at latitude φ inclined at an angle \e azi to the * meridian (meters). * - * φ must lie in the range [−90°, 90°] and \e - * azi must lie in the range [−540°, 540°); the - * result is undefined if either of conditions does not hold. + * φ must lie in the range [−90°, 90°]; the result is + * undefined this condition does not hold. **********************************************************************/ - Math::real NormalCurvatureRadius(real phi, real azi) const throw(); + Math::real NormalCurvatureRadius(real phi, real azi) const; ///@} /** \name Eccentricity conversions. @@ -415,7 +413,7 @@ namespace GeographicLib { * \e f ' should lie in (−1, ∞). * The returned value \e f lies in (−∞, 1). **********************************************************************/ - static Math::real SecondFlatteningToFlattening(real fp) throw() + static Math::real SecondFlatteningToFlattening(real fp) { return fp / (1 + fp); } /** @@ -425,7 +423,7 @@ namespace GeographicLib { * \e f should lie in (−∞, 1). * The returned value \e f ' lies in (−1, ∞). **********************************************************************/ - static Math::real FlatteningToSecondFlattening(real f) throw() + static Math::real FlatteningToSecondFlattening(real f) { return f / (1 - f); } /** @@ -436,7 +434,7 @@ namespace GeographicLib { * \e n should lie in (−1, 1). * The returned value \e f lies in (−∞, 1). **********************************************************************/ - static Math::real ThirdFlatteningToFlattening(real n) throw() + static Math::real ThirdFlatteningToFlattening(real n) { return 2 * n / (1 + n); } /** @@ -447,7 +445,7 @@ namespace GeographicLib { * \e f should lie in (−∞, 1). * The returned value \e n lies in (−1, 1). **********************************************************************/ - static Math::real FlatteningToThirdFlattening(real f) throw() + static Math::real FlatteningToThirdFlattening(real f) { return f / (2 - f); } /** @@ -459,8 +457,8 @@ namespace GeographicLib { * e2 should lie in (−∞, 1). * The returned value \e f lies in (−∞, 1). **********************************************************************/ - static Math::real EccentricitySqToFlattening(real e2) throw() - { return e2 / (std::sqrt(1 - e2) + 1); } + static Math::real EccentricitySqToFlattening(real e2) + { using std::sqrt; return e2 / (sqrt(1 - e2) + 1); } /** * @param[in] f = (\e a − \e b) / \e a, the flattening. @@ -471,7 +469,7 @@ namespace GeographicLib { * \e f should lie in (−∞, 1). * The returned value e2 lies in (−∞, 1). **********************************************************************/ - static Math::real FlatteningToEccentricitySq(real f) throw() + static Math::real FlatteningToEccentricitySq(real f) { return f * (2 - f); } /** @@ -483,8 +481,8 @@ namespace GeographicLib { * e' 2 should lie in (−1, ∞). * The returned value \e f lies in (−∞, 1). **********************************************************************/ - static Math::real SecondEccentricitySqToFlattening(real ep2) throw() - { return ep2 / (std::sqrt(1 + ep2) + 1 + ep2); } + static Math::real SecondEccentricitySqToFlattening(real ep2) + { using std::sqrt; return ep2 / (sqrt(1 + ep2) + 1 + ep2); } /** * @param[in] f = (\e a − \e b) / \e a, the flattening. @@ -495,7 +493,7 @@ namespace GeographicLib { * \e f should lie in (−∞, 1). * The returned value e' 2 lies in (−1, ∞). **********************************************************************/ - static Math::real FlatteningToSecondEccentricitySq(real f) throw() + static Math::real FlatteningToSecondEccentricitySq(real f) { return f * (2 - f) / Math::sq(1 - f); } /** @@ -507,8 +505,10 @@ namespace GeographicLib { * e'' 2 should lie in (−1, 1). * The returned value \e f lies in (−∞, 1). **********************************************************************/ - static Math::real ThirdEccentricitySqToFlattening(real epp2) throw() - { return 2 * epp2 / (sqrt((1 - epp2) * (1 + epp2)) + 1 + epp2); } + static Math::real ThirdEccentricitySqToFlattening(real epp2) { + using std::sqrt; + return 2 * epp2 / (sqrt((1 - epp2) * (1 + epp2)) + 1 + epp2); + } /** * @param[in] f = (\e a − \e b) / \e a, the flattening. @@ -519,7 +519,7 @@ namespace GeographicLib { * \e f should lie in (−∞, 1). * The returned value e'' 2 lies in (−1, 1). **********************************************************************/ - static Math::real FlatteningToThirdEccentricitySq(real f) throw() + static Math::real FlatteningToThirdEccentricitySq(real f) { return f * (2 - f) / (1 + Math::sq(1 - f)); } ///@} @@ -528,8 +528,7 @@ namespace GeographicLib { * A global instantiation of Ellipsoid with the parameters for the WGS84 * ellipsoid. **********************************************************************/ - static const Ellipsoid WGS84; - + static const Ellipsoid& WGS84(); }; } // namespace GeographicLib diff --git a/gtsam/3rdparty/GeographicLib/include/GeographicLib/EllipticFunction.hpp b/gtsam/3rdparty/GeographicLib/include/GeographicLib/EllipticFunction.hpp index 802b6e7cc..0ef37a684 100644 --- a/gtsam/3rdparty/GeographicLib/include/GeographicLib/EllipticFunction.hpp +++ b/gtsam/3rdparty/GeographicLib/include/GeographicLib/EllipticFunction.hpp @@ -2,9 +2,9 @@ * \file EllipticFunction.hpp * \brief Header for GeographicLib::EllipticFunction class * - * Copyright (c) Charles Karney (2008-2012) and licensed + * Copyright (c) Charles Karney (2008-2016) and licensed * under the MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #if !defined(GEOGRAPHICLIB_ELLIPTICFUNCTION_HPP) @@ -36,21 +36,21 @@ namespace GeographicLib { * In geodesic applications, it is convenient to separate the incomplete * integrals into secular and periodic components, e.g., * \f[ - * E(\phi, k) = (2 E(\phi) / \pi) [ \phi + \delta E(\phi, k) ] + * E(\phi, k) = (2 E(k) / \pi) [ \phi + \delta E(\phi, k) ] * \f] * where δ\e E(φ, \e k) is an odd periodic function with period * π. * * The computation of the elliptic integrals uses the algorithms given in * - B. C. Carlson, - * Computation of real or + * Computation of real or * complex elliptic integrals, Numerical Algorithms 10, 13--26 (1995) * . * with the additional optimizations given in http://dlmf.nist.gov/19.36.i. * The computation of the Jacobi elliptic functions uses the algorithm given * in * - R. Bulirsch, - * Numerical Calculation of + * Numerical Calculation of * Elliptic Integrals and Elliptic Functions, Numericshe Mathematik 7, * 78--90 (1965). * . @@ -62,16 +62,10 @@ namespace GeographicLib { class GEOGRAPHICLIB_EXPORT EllipticFunction { private: typedef Math::real real; - static const real tol_; - static const real tolRF_; - static const real tolRD_; - static const real tolRG0_; - static const real tolJAC_; - enum { num_ = 13 }; // Max depth required for sncndn. Probably 5 is enough. + + enum { num_ = 13 }; // Max depth required for sncndn; probably 5 is enough. real _k2, _kp2, _alpha2, _alphap2, _eps; - mutable bool _init; - mutable real _Kc, _Ec, _Dc, _Pic, _Gc, _Hc; - bool Init() const throw(); + real _Kc, _Ec, _Dc, _Pic, _Gc, _Hc; public: /** \name Constructor **********************************************************************/ @@ -80,10 +74,11 @@ namespace GeographicLib { * Constructor specifying the modulus and parameter. * * @param[in] k2 the square of the modulus k2. - * k2 must lie in (-∞, 1). (No checking is - * done.) + * k2 must lie in (−∞, 1]. * @param[in] alpha2 the parameter α2. - * α2 must lie in (-∞, 1). (No checking is done.) + * α2 must lie in (−∞, 1]. + * @exception GeographicErr if \e k2 or \e alpha2 is out of its legal + * range. * * If only elliptic integrals of the first and second kinds are needed, * then set α2 = 0 (the default value); in this case, we @@ -91,59 +86,65 @@ namespace GeographicLib { * E(φ, \e k), and \e H(φ, 0, \e k) = \e F(φ, \e k) - \e * D(φ, \e k). **********************************************************************/ - EllipticFunction(real k2 = 0, real alpha2 = 0) throw(); + EllipticFunction(real k2 = 0, real alpha2 = 0) + { Reset(k2, alpha2); } /** * Constructor specifying the modulus and parameter and their complements. * * @param[in] k2 the square of the modulus k2. - * k2 must lie in (-∞, 1). (No checking is - * done.) + * k2 must lie in (−∞, 1]. * @param[in] alpha2 the parameter α2. - * α2 must lie in (-∞, 1). (No checking is done.) + * α2 must lie in (−∞, 1]. * @param[in] kp2 the complementary modulus squared k'2 = - * 1 − k2. + * 1 − k2. This must lie in [0, ∞). * @param[in] alphap2 the complementary parameter α'2 = 1 - * − α2. + * − α2. This must lie in [0, ∞). + * @exception GeographicErr if \e k2, \e alpha2, \e kp2, or \e alphap2 is + * out of its legal range. * * The arguments must satisfy \e k2 + \e kp2 = 1 and \e alpha2 + \e alphap2 * = 1. (No checking is done that these conditions are met.) This * constructor is provided to enable accuracy to be maintained, e.g., when * \e k is very close to unity. **********************************************************************/ - EllipticFunction(real k2, real alpha2, real kp2, real alphap2) throw(); + EllipticFunction(real k2, real alpha2, real kp2, real alphap2) + { Reset(k2, alpha2, kp2, alphap2); } /** * Reset the modulus and parameter. * * @param[in] k2 the new value of square of the modulus - * k2 which must lie in (-∞, 1). (No checking is + * k2 which must lie in (−∞, ]. * done.) * @param[in] alpha2 the new value of parameter α2. - * α2 must lie in (-∞, 1). (No checking is done.) + * α2 must lie in (−∞, 1]. + * @exception GeographicErr if \e k2 or \e alpha2 is out of its legal + * range. **********************************************************************/ - void Reset(real k2 = 0, real alpha2 = 0) throw() + void Reset(real k2 = 0, real alpha2 = 0) { Reset(k2, alpha2, 1 - k2, 1 - alpha2); } /** * Reset the modulus and parameter supplying also their complements. * * @param[in] k2 the square of the modulus k2. - * k2 must lie in (-∞, 1). (No checking is - * done.) + * k2 must lie in (−∞, 1]. * @param[in] alpha2 the parameter α2. - * α2 must lie in (-∞, 1). (No checking is done.) + * α2 must lie in (−∞, 1]. * @param[in] kp2 the complementary modulus squared k'2 = - * 1 − k2. + * 1 − k2. This must lie in [0, ∞). * @param[in] alphap2 the complementary parameter α'2 = 1 - * − α2. + * − α2. This must lie in [0, ∞). + * @exception GeographicErr if \e k2, \e alpha2, \e kp2, or \e alphap2 is + * out of its legal range. * * The arguments must satisfy \e k2 + \e kp2 = 1 and \e alpha2 + \e alphap2 * = 1. (No checking is done that these conditions are met.) This * constructor is provided to enable accuracy to be maintained, e.g., when * is very small. **********************************************************************/ - void Reset(real k2, real alpha2, real kp2, real alphap2) throw(); + void Reset(real k2, real alpha2, real kp2, real alphap2); ///@} @@ -153,42 +154,26 @@ namespace GeographicLib { /** * @return the square of the modulus k2. **********************************************************************/ - Math::real k2() const throw() { return _k2; } + Math::real k2() const { return _k2; } /** * @return the square of the complementary modulus k'2 = * 1 − k2. **********************************************************************/ - Math::real kp2() const throw() { return _kp2; } + Math::real kp2() const { return _kp2; } /** * @return the parameter α2. **********************************************************************/ - Math::real alpha2() const throw() { return _alpha2; } + Math::real alpha2() const { return _alpha2; } /** * @return the complementary parameter α'2 = 1 − * α2. **********************************************************************/ - Math::real alphap2() const throw() { return _alphap2; } + Math::real alphap2() const { return _alphap2; } ///@} - /// \cond SKIP - /** - * @return the square of the modulus k2. - * - * DEPRECATED, use k2() instead. - **********************************************************************/ - Math::real m() const throw() { return _k2; } - /** - * @return the square of the complementary modulus k'2 = - * 1 − k2. - * - * DEPRECATED, use kp2() instead. - **********************************************************************/ - Math::real m1() const throw() { return _kp2; } - /// \endcond - /** \name Complete elliptic integrals. **********************************************************************/ ///@{ @@ -202,19 +187,19 @@ namespace GeographicLib { * K(k) = \int_0^{\pi/2} \frac1{\sqrt{1-k^2\sin^2\phi}}\,d\phi. * \f] **********************************************************************/ - Math::real K() const throw() { _init || Init(); return _Kc; } + Math::real K() const { return _Kc; } /** * The complete integral of the second kind. * - * @return \e E(\e k) + * @return \e E(\e k). * * \e E(\e k) is defined in http://dlmf.nist.gov/19.2.E5 * \f[ * E(k) = \int_0^{\pi/2} \sqrt{1-k^2\sin^2\phi}\,d\phi. * \f] **********************************************************************/ - Math::real E() const throw() { _init || Init(); return _Ec; } + Math::real E() const { return _Ec; } /** * Jahnke's complete integral. @@ -223,10 +208,11 @@ namespace GeographicLib { * * \e D(\e k) is defined in http://dlmf.nist.gov/19.2.E6 * \f[ - * D(k) = \int_0^{\pi/2} \frac{\sin^2\phi}{\sqrt{1-k^2\sin^2\phi}}\,d\phi. + * D(k) = + * \int_0^{\pi/2} \frac{\sin^2\phi}{\sqrt{1-k^2\sin^2\phi}}\,d\phi. * \f] **********************************************************************/ - Math::real D() const throw() { _init || Init(); return _Dc; } + Math::real D() const { return _Dc; } /** * The difference between the complete integrals of the first and second @@ -234,26 +220,26 @@ namespace GeographicLib { * * @return \e K(\e k) − \e E(\e k). **********************************************************************/ - Math::real KE() const throw() { _init || Init(); return _k2 * _Dc; } + Math::real KE() const { return _k2 * _Dc; } /** * The complete integral of the third kind. * - * @return Π(α2, \e k) + * @return Π(α2, \e k). * * Π(α2, \e k) is defined in * http://dlmf.nist.gov/19.2.E7 * \f[ * \Pi(\alpha^2, k) = \int_0^{\pi/2} - * \frac1{\sqrt{1-k^2\sin^2\phi}(1 - \alpha^2\sin^2\phi_)}\,d\phi. + * \frac1{\sqrt{1-k^2\sin^2\phi}(1 - \alpha^2\sin^2\phi)}\,d\phi. * \f] **********************************************************************/ - Math::real Pi() const throw() { _init || Init(); return _Pic; } + Math::real Pi() const { return _Pic; } /** * Legendre's complete geodesic longitude integral. * - * @return \e G(α2, \e k) + * @return \e G(α2, \e k). * * \e G(α2, \e k) is given by * \f[ @@ -261,12 +247,12 @@ namespace GeographicLib { * \frac{\sqrt{1-k^2\sin^2\phi}}{1 - \alpha^2\sin^2\phi}\,d\phi. * \f] **********************************************************************/ - Math::real G() const throw() { _init || Init(); return _Gc; } + Math::real G() const { return _Gc; } /** * Cayley's complete geodesic longitude difference integral. * - * @return \e H(α2, \e k) + * @return \e H(α2, \e k). * * \e H(α2, \e k) is given by * \f[ @@ -275,7 +261,7 @@ namespace GeographicLib { * \,d\phi. * \f] **********************************************************************/ - Math::real H() const throw() { _init || Init(); return _Hc; } + Math::real H() const { return _Hc; } ///@} /** \name Incomplete elliptic integrals. @@ -292,7 +278,7 @@ namespace GeographicLib { * F(\phi, k) = \int_0^\phi \frac1{\sqrt{1-k^2\sin^2\theta}}\,d\theta. * \f] **********************************************************************/ - Math::real F(real phi) const throw(); + Math::real F(real phi) const; /** * The incomplete integral of the second kind. @@ -305,7 +291,7 @@ namespace GeographicLib { * E(\phi, k) = \int_0^\phi \sqrt{1-k^2\sin^2\theta}\,d\theta. * \f] **********************************************************************/ - Math::real E(real phi) const throw(); + Math::real E(real phi) const; /** * The incomplete integral of the second kind with the argument given in @@ -314,7 +300,7 @@ namespace GeographicLib { * @param[in] ang in degrees. * @return \e E(π ang/180, \e k). **********************************************************************/ - Math::real Ed(real ang) const throw(); + Math::real Ed(real ang) const; /** * The inverse of the incomplete integral of the second kind. @@ -323,7 +309,7 @@ namespace GeographicLib { * @return φ = E−1(\e x, \e k); i.e., the * solution of such that \e E(φ, \e k) = \e x. **********************************************************************/ - Math::real Einv(real x) const throw(); + Math::real Einv(real x) const; /** * The incomplete integral of the third kind. @@ -335,10 +321,10 @@ namespace GeographicLib { * http://dlmf.nist.gov/19.2.E7 * \f[ * \Pi(\phi, \alpha^2, k) = \int_0^\phi - * \frac1{\sqrt{1-k^2\sin^2\theta}(1 - \alpha^2\sin^2\theta_)}\,d\theta. + * \frac1{\sqrt{1-k^2\sin^2\theta}(1 - \alpha^2\sin^2\theta)}\,d\theta. * \f] **********************************************************************/ - Math::real Pi(real phi) const throw(); + Math::real Pi(real phi) const; /** * Jahnke's incomplete elliptic integral. @@ -352,7 +338,7 @@ namespace GeographicLib { * \frac{\sin^2\theta}{\sqrt{1-k^2\sin^2\theta}}\,d\theta. * \f] **********************************************************************/ - Math::real D(real phi) const throw(); + Math::real D(real phi) const; /** * Legendre's geodesic longitude integral. @@ -362,24 +348,24 @@ namespace GeographicLib { * * \e G(φ, α2, \e k) is defined by * \f[ - * \begin{aligned} + * \begin{align} * G(\phi, \alpha^2, k) &= * \frac{k^2}{\alpha^2} F(\phi, k) + * \biggl(1 - \frac{k^2}{\alpha^2}\biggr) \Pi(\phi, \alpha^2, k) \\ * &= \int_0^\phi * \frac{\sqrt{1-k^2\sin^2\theta}}{1 - \alpha^2\sin^2\theta}\,d\theta. - * \end{aligned} + * \end{align} * \f] * * Legendre expresses the longitude of a point on the geodesic in terms of * this combination of elliptic integrals in Exercices de Calcul * Intégral, Vol. 1 (1811), p. 181, - * http://books.google.com/books?id=riIOAAAAQAAJ&pg=PA181. + * https://books.google.com/books?id=riIOAAAAQAAJ&pg=PA181. * * See \ref geodellip for the expression for the longitude in terms of this * function. **********************************************************************/ - Math::real G(real phi) const throw(); + Math::real G(real phi) const; /** * Cayley's geodesic longitude difference integral. @@ -389,24 +375,25 @@ namespace GeographicLib { * * \e H(φ, α2, \e k) is defined by * \f[ - * \begin{aligned} + * \begin{align} * H(\phi, \alpha^2, k) &= * \frac1{\alpha^2} F(\phi, k) + * \biggl(1 - \frac1{\alpha^2}\biggr) \Pi(\phi, \alpha^2, k) \\ * &= \int_0^\phi - * \frac{\cos^2\theta}{(1-\alpha^2\sin^2\theta)\sqrt{1-k^2\sin^2\theta}} + * \frac{\cos^2\theta} + * {(1-\alpha^2\sin^2\theta)\sqrt{1-k^2\sin^2\theta}} * \,d\theta. - * \end{aligned} + * \end{align} * \f] * * Cayley expresses the longitude difference of a point on the geodesic in * terms of this combination of elliptic integrals in Phil. Mag. 40 - * (1870), p. 333, http://books.google.com/books?id=Zk0wAAAAIAAJ&pg=PA333. + * (1870), p. 333, https://books.google.com/books?id=Zk0wAAAAIAAJ&pg=PA333. * * See \ref geodellip for the expression for the longitude in terms of this * function. **********************************************************************/ - Math::real H(real phi) const throw(); + Math::real H(real phi) const; ///@} /** \name Incomplete integrals in terms of Jacobi elliptic functions. @@ -415,76 +402,76 @@ namespace GeographicLib { * The incomplete integral of the first kind in terms of Jacobi elliptic * functions. * - * @param[in] sn = sinφ - * @param[in] cn = cosφ + * @param[in] sn = sinφ. + * @param[in] cn = cosφ. * @param[in] dn = sqrt(1 − k2 - * sin2φ) + * sin2φ). * @return \e F(φ, \e k) as though φ ∈ (−π, π]. **********************************************************************/ - Math::real F(real sn, real cn, real dn) const throw(); + Math::real F(real sn, real cn, real dn) const; /** * The incomplete integral of the second kind in terms of Jacobi elliptic * functions. * - * @param[in] sn = sinφ - * @param[in] cn = cosφ + * @param[in] sn = sinφ. + * @param[in] cn = cosφ. * @param[in] dn = sqrt(1 − k2 - * sin2φ) + * sin2φ). * @return \e E(φ, \e k) as though φ ∈ (−π, π]. **********************************************************************/ - Math::real E(real sn, real cn, real dn) const throw(); + Math::real E(real sn, real cn, real dn) const; /** * The incomplete integral of the third kind in terms of Jacobi elliptic * functions. * - * @param[in] sn = sinφ - * @param[in] cn = cosφ + * @param[in] sn = sinφ. + * @param[in] cn = cosφ. * @param[in] dn = sqrt(1 − k2 - * sin2φ) + * sin2φ). * @return Π(φ, α2, \e k) as though φ ∈ * (−π, π]. **********************************************************************/ - Math::real Pi(real sn, real cn, real dn) const throw(); + Math::real Pi(real sn, real cn, real dn) const; /** * Jahnke's incomplete elliptic integral in terms of Jacobi elliptic * functions. * - * @param[in] sn = sinφ - * @param[in] cn = cosφ + * @param[in] sn = sinφ. + * @param[in] cn = cosφ. * @param[in] dn = sqrt(1 − k2 - * sin2φ) + * sin2φ). * @return \e D(φ, \e k) as though φ ∈ (−π, π]. **********************************************************************/ - Math::real D(real sn, real cn, real dn) const throw(); + Math::real D(real sn, real cn, real dn) const; /** * Legendre's geodesic longitude integral in terms of Jacobi elliptic * functions. * - * @param[in] sn = sinφ - * @param[in] cn = cosφ + * @param[in] sn = sinφ. + * @param[in] cn = cosφ. * @param[in] dn = sqrt(1 − k2 - * sin2φ) + * sin2φ). * @return \e G(φ, α2, \e k) as though φ ∈ * (−π, π]. **********************************************************************/ - Math::real G(real sn, real cn, real dn) const throw(); + Math::real G(real sn, real cn, real dn) const; /** * Cayley's geodesic longitude difference integral in terms of Jacobi * elliptic functions. * - * @param[in] sn = sinφ - * @param[in] cn = cosφ + * @param[in] sn = sinφ. + * @param[in] cn = cosφ. * @param[in] dn = sqrt(1 − k2 - * sin2φ) + * sin2φ). * @return \e H(φ, α2, \e k) as though φ ∈ * (−π, π]. **********************************************************************/ - Math::real H(real sn, real cn, real dn) const throw(); + Math::real H(real sn, real cn, real dn) const; ///@} /** \name Periodic versions of incomplete elliptic integrals. @@ -493,84 +480,84 @@ namespace GeographicLib { /** * The periodic incomplete integral of the first kind. * - * @param[in] sn = sinφ - * @param[in] cn = cosφ + * @param[in] sn = sinφ. + * @param[in] cn = cosφ. * @param[in] dn = sqrt(1 − k2 - * sin2φ) + * sin2φ). * @return the periodic function π \e F(φ, \e k) / (2 \e K(\e k)) - - * φ + * φ. **********************************************************************/ - Math::real deltaF(real sn, real cn, real dn) const throw(); + Math::real deltaF(real sn, real cn, real dn) const; /** * The periodic incomplete integral of the second kind. * - * @param[in] sn = sinφ - * @param[in] cn = cosφ + * @param[in] sn = sinφ. + * @param[in] cn = cosφ. * @param[in] dn = sqrt(1 − k2 - * sin2φ) + * sin2φ). * @return the periodic function π \e E(φ, \e k) / (2 \e E(\e k)) - - * φ + * φ. **********************************************************************/ - Math::real deltaE(real sn, real cn, real dn) const throw(); + Math::real deltaE(real sn, real cn, real dn) const; /** * The periodic inverse of the incomplete integral of the second kind. * - * @param[in] stau = sinτ - * @param[in] ctau = sinτ + * @param[in] stau = sinτ. + * @param[in] ctau = sinτ. * @return the periodic function E−1(τ (2 \e - * E(\e k)/π), \e k) - τ + * E(\e k)/π), \e k) - τ. **********************************************************************/ - Math::real deltaEinv(real stau, real ctau) const throw(); + Math::real deltaEinv(real stau, real ctau) const; /** * The periodic incomplete integral of the third kind. * - * @param[in] sn = sinφ - * @param[in] cn = cosφ + * @param[in] sn = sinφ. + * @param[in] cn = cosφ. * @param[in] dn = sqrt(1 − k2 - * sin2φ) - * @return the periodic function π Π(φ, \e k) / (2 Π(\e k)) - - * φ + * sin2φ). + * @return the periodic function π Π(φ, α2, + * \e k) / (2 Π(α2, \e k)) - φ. **********************************************************************/ - Math::real deltaPi(real sn, real cn, real dn) const throw(); + Math::real deltaPi(real sn, real cn, real dn) const; /** * The periodic Jahnke's incomplete elliptic integral. * - * @param[in] sn = sinφ - * @param[in] cn = cosφ + * @param[in] sn = sinφ. + * @param[in] cn = cosφ. * @param[in] dn = sqrt(1 − k2 - * sin2φ) + * sin2φ). * @return the periodic function π \e D(φ, \e k) / (2 \e D(\e k)) - - * φ + * φ. **********************************************************************/ - Math::real deltaD(real sn, real cn, real dn) const throw(); + Math::real deltaD(real sn, real cn, real dn) const; /** * Legendre's periodic geodesic longitude integral. * - * @param[in] sn = sinφ - * @param[in] cn = cosφ + * @param[in] sn = sinφ. + * @param[in] cn = cosφ. * @param[in] dn = sqrt(1 − k2 - * sin2φ) + * sin2φ). * @return the periodic function π \e G(φ, \e k) / (2 \e G(\e k)) - - * φ + * φ. **********************************************************************/ - Math::real deltaG(real sn, real cn, real dn) const throw(); + Math::real deltaG(real sn, real cn, real dn) const; /** * Cayley's periodic geodesic longitude difference integral. * - * @param[in] sn = sinφ - * @param[in] cn = cosφ + * @param[in] sn = sinφ. + * @param[in] cn = cosφ. * @param[in] dn = sqrt(1 − k2 - * sin2φ) + * sin2φ). * @return the periodic function π \e H(φ, \e k) / (2 \e H(\e k)) - - * φ + * φ. **********************************************************************/ - Math::real deltaH(real sn, real cn, real dn) const throw(); + Math::real deltaH(real sn, real cn, real dn) const; ///@} /** \name Elliptic functions. @@ -584,72 +571,75 @@ namespace GeographicLib { * @param[out] cn cn(\e x, \e k). * @param[out] dn dn(\e x, \e k). **********************************************************************/ - void sncndn(real x, real& sn, real& cn, real& dn) const throw(); + void sncndn(real x, real& sn, real& cn, real& dn) const; /** * The Δ amplitude function. * - * @param[in] sn sinφ - * @param[in] cn cosφ + * @param[in] sn sinφ. + * @param[in] cn cosφ. * @return Δ = sqrt(1 − k2 - * sin2φ) + * sin2φ). **********************************************************************/ - Math::real Delta(real sn, real cn) const throw() - { return std::sqrt(_k2 < 0 ? 1 - _k2 * sn*sn : _kp2 + _k2 * cn*cn); } + Math::real Delta(real sn, real cn) const { + using std::sqrt; + return sqrt(_k2 < 0 ? 1 - _k2 * sn*sn : _kp2 + _k2 * cn*cn); + } ///@} /** \name Symmetric elliptic integrals. **********************************************************************/ ///@{ /** - * Symmetric integral of the first kind RF. + * Symmetric integral of the first kind RF. * * @param[in] x * @param[in] y * @param[in] z - * @return RF(\e x, \e y, \e z) + * @return RF(\e x, \e y, \e z). * - * RF is defined in http://dlmf.nist.gov/19.16.E1 + * RF is defined in http://dlmf.nist.gov/19.16.E1 * \f[ R_F(x, y, z) = \frac12 * \int_0^\infty\frac1{\sqrt{(t + x) (t + y) (t + z)}}\, dt \f] * If one of the arguments is zero, it is more efficient to call the * two-argument version of this function with the non-zero arguments. **********************************************************************/ - static real RF(real x, real y, real z) throw(); + static real RF(real x, real y, real z); /** - * Complete symmetric integral of the first kind, RF with - * one argument zero. + * Complete symmetric integral of the first kind, + * RF with one argument zero. * * @param[in] x * @param[in] y - * @return RF(\e x, \e y, 0) + * @return RF(\e x, \e y, 0). **********************************************************************/ - static real RF(real x, real y) throw(); + static real RF(real x, real y); /** - * Degenerate symmetric integral of the first kind RC. + * Degenerate symmetric integral of the first kind + * RC. * * @param[in] x * @param[in] y - * @return RC(\e x, \e y) = RF(\e x, \e - * y, \e y) + * @return RC(\e x, \e y) = + * RF(\e x, \e y, \e y). * - * RC is defined in http://dlmf.nist.gov/19.2.E17 + * RC is defined in http://dlmf.nist.gov/19.2.E17 * \f[ R_C(x, y) = \frac12 * \int_0^\infty\frac1{\sqrt{t + x}(t + y)}\,dt \f] **********************************************************************/ - static real RC(real x, real y) throw(); + static real RC(real x, real y); /** - * Symmetric integral of the second kind RG. + * Symmetric integral of the second kind RG. * * @param[in] x * @param[in] y * @param[in] z - * @return RG(\e x, \e y, \e z) + * @return RG(\e x, \e y, \e z). * - * RG is defined in Carlson, eq 1.5 + * RG is defined in Carlson, eq 1.5 * \f[ R_G(x, y, z) = \frac14 * \int_0^\infty[(t + x) (t + y) (t + z)]^{-1/2} * \biggl( @@ -659,47 +649,49 @@ namespace GeographicLib { * If one of the arguments is zero, it is more efficient to call the * two-argument version of this function with the non-zero arguments. **********************************************************************/ - static real RG(real x, real y, real z) throw(); + static real RG(real x, real y, real z); /** - * Complete symmetric integral of the second kind, RG - * with one argument zero. + * Complete symmetric integral of the second kind, + * RG with one argument zero. * * @param[in] x * @param[in] y - * @return RG(\e x, \e y, 0) + * @return RG(\e x, \e y, 0). **********************************************************************/ - static real RG(real x, real y) throw(); + static real RG(real x, real y); /** - * Symmetric integral of the third kind RJ. + * Symmetric integral of the third kind RJ. * * @param[in] x * @param[in] y * @param[in] z * @param[in] p - * @return RJ(\e x, \e y, \e z, \e p) + * @return RJ(\e x, \e y, \e z, \e p). * - * RJ is defined in http://dlmf.nist.gov/19.16.E2 + * RJ is defined in http://dlmf.nist.gov/19.16.E2 * \f[ R_J(x, y, z, p) = \frac32 - * \int_0^\infty[(t + x) (t + y) (t + z)]^{-1/2} (t + p)^{-1}\, dt \f] + * \int_0^\infty + * [(t + x) (t + y) (t + z)]^{-1/2} (t + p)^{-1}\, dt \f] **********************************************************************/ - static real RJ(real x, real y, real z, real p) throw(); + static real RJ(real x, real y, real z, real p); /** - * Degenerate symmetric integral of the third kind RD. + * Degenerate symmetric integral of the third kind + * RD. * * @param[in] x * @param[in] y * @param[in] z - * @return RD(\e x, \e y, \e z) = RJ(\e - * x, \e y, \e z, \e z) + * @return RD(\e x, \e y, \e z) = + * RJ(\e x, \e y, \e z, \e z). * - * RD is defined in http://dlmf.nist.gov/19.16.E5 + * RD is defined in http://dlmf.nist.gov/19.16.E5 * \f[ R_D(x, y, z) = \frac32 * \int_0^\infty[(t + x) (t + y)]^{-1/2} (t + z)^{-3/2}\, dt \f] **********************************************************************/ - static real RD(real x, real y, real z) throw(); + static real RD(real x, real y, real z); ///@} }; diff --git a/gtsam/3rdparty/GeographicLib/include/GeographicLib/GARS.hpp b/gtsam/3rdparty/GeographicLib/include/GeographicLib/GARS.hpp new file mode 100644 index 000000000..b66b3b22a --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/include/GeographicLib/GARS.hpp @@ -0,0 +1,143 @@ +/** + * \file GARS.hpp + * \brief Header for GeographicLib::GARS class + * + * Copyright (c) Charles Karney (2015-2017) and licensed + * under the MIT/X11 License. For more information, see + * https://geographiclib.sourceforge.io/ + **********************************************************************/ + +#if !defined(GEOGRAPHICLIB_GARS_HPP) +#define GEOGRAPHICLIB_GARS_HPP 1 + +#include + +#if defined(_MSC_VER) +// Squelch warnings about dll vs string +# pragma warning (push) +# pragma warning (disable: 4251) +#endif + +namespace GeographicLib { + + /** + * \brief Conversions for the Global Area Reference System (GARS) + * + * The Global Area Reference System is described in + * - https://en.wikipedia.org/wiki/Global_Area_Reference_System + * - http://earth-info.nga.mil/GandG/coordsys/grids/gars.html + * . + * It provides a compact string representation of a geographic area + * (expressed as latitude and longitude). The classes Georef and Geohash + * implement similar compact representations. + * + * Example of use: + * \include example-GARS.cpp + **********************************************************************/ + + class GEOGRAPHICLIB_EXPORT GARS { + private: + typedef Math::real real; + static const char* const digits_; + static const char* const letters_; + enum { + lonorig_ = -180, // Origin for longitude + latorig_ = -90, // Origin for latitude + baselon_ = 10, // Base for longitude tiles + baselat_ = 24, // Base for latitude tiles + lonlen_ = 3, + latlen_ = 2, + baselen_ = lonlen_ + latlen_, + mult1_ = 2, // base precision = 1/2 degree + mult2_ = 2, // 6th char gives 2x more precision + mult3_ = 3, // 7th char gives 3x more precision + m_ = mult1_ * mult2_ * mult3_, + maxprec_ = 2, + maxlen_ = baselen_ + maxprec_, + }; + GARS(); // Disable constructor + + public: + + /** + * Convert from geographic coordinates to GARS. + * + * @param[in] lat latitude of point (degrees). + * @param[in] lon longitude of point (degrees). + * @param[in] prec the precision of the resulting GARS. + * @param[out] gars the GARS string. + * @exception GeographicErr if \e lat is not in [−90°, + * 90°]. + * @exception std::bad_alloc if memory for \e gars can't be allocated. + * + * \e prec specifies the precision of \e gars as follows: + * - \e prec = 0 (min), 30' precision, e.g., 006AG; + * - \e prec = 1, 15' precision, e.g., 006AG3; + * - \e prec = 2 (max), 5' precision, e.g., 006AG39. + * + * If \e lat or \e lon is NaN, then \e gars is set to "INVALID". + **********************************************************************/ + static void Forward(real lat, real lon, int prec, std::string& gars); + + /** + * Convert from GARS to geographic coordinates. + * + * @param[in] gars the GARS. + * @param[out] lat latitude of point (degrees). + * @param[out] lon longitude of point (degrees). + * @param[out] prec the precision of \e gars. + * @param[in] centerp if true (the default) return the center of the + * \e gars, otherwise return the south-west corner. + * @exception GeographicErr if \e gars is illegal. + * + * The case of the letters in \e gars is ignored. \e prec is in the range + * [0, 2] and gives the precision of \e gars as follows: + * - \e prec = 0 (min), 30' precision, e.g., 006AG; + * - \e prec = 1, 15' precision, e.g., 006AG3; + * - \e prec = 2 (max), 5' precision, e.g., 006AG39. + * + * If the first 3 characters of \e gars are "INV", then \e lat and \e lon + * are set to NaN and \e prec is unchanged. + **********************************************************************/ + static void Reverse(const std::string& gars, real& lat, real& lon, + int& prec, bool centerp = true); + + /** + * The angular resolution of a GARS. + * + * @param[in] prec the precision of the GARS. + * @return the latitude-longitude resolution (degrees). + * + * Internally, \e prec is first put in the range [0, 2]. + **********************************************************************/ + static Math::real Resolution(int prec) { + return 1/real(prec <= 0 ? mult1_ : (prec == 1 ? mult1_ * mult2_ : + mult1_ * mult2_ * mult3_)); + } + + /** + * The GARS precision required to meet a given geographic resolution. + * + * @param[in] res the minimum of resolution in latitude and longitude + * (degrees). + * @return GARS precision. + * + * The returned length is in the range [0, 2]. + **********************************************************************/ + static int Precision(real res) { + using std::abs; res = abs(res); + for (int prec = 0; prec < maxprec_; ++prec) + if (Resolution(prec) <= res) + return prec; + return maxprec_; + } + + }; + +} // namespace GeographicLib + +#if defined(_MSC_VER) +# pragma warning (pop) +#endif + +#endif // GEOGRAPHICLIB_GARS_HPP diff --git a/gtsam/3rdparty/GeographicLib/include/GeographicLib/GeoCoords.hpp b/gtsam/3rdparty/GeographicLib/include/GeographicLib/GeoCoords.hpp index b97a692bb..ce0c8f723 100644 --- a/gtsam/3rdparty/GeographicLib/include/GeographicLib/GeoCoords.hpp +++ b/gtsam/3rdparty/GeographicLib/include/GeographicLib/GeoCoords.hpp @@ -2,9 +2,9 @@ * \file GeoCoords.hpp * \brief Header for GeographicLib::GeoCoords class * - * Copyright (c) Charles Karney (2008-2011) and licensed + * Copyright (c) Charles Karney (2008-2016) and licensed * under the MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #if !defined(GEOGRAPHICLIB_GEOCOORDS_HPP) @@ -55,15 +55,16 @@ namespace GeographicLib { mutable real _alt_easting, _alt_northing, _alt_gamma, _alt_k; mutable int _alt_zone; - void CopyToAlt() const throw() { + void CopyToAlt() const { _alt_easting = _easting; _alt_northing = _northing; _alt_gamma = _gamma; _alt_k = _k; _alt_zone = _zone; } - static void UTMUPSString(int zone, bool northp, real easting, real northing, - int prec, std::string& utm); + static void UTMUPSString(int zone, bool northp, + real easting, real northing, + int prec, bool abbrev, std::string& utm); void FixHemisphere(); public: @@ -71,17 +72,17 @@ namespace GeographicLib { **********************************************************************/ ///@{ /** - * The default constructor is equivalent to \e latitude = 90°, - * \e longitude = 0°. + * The default constructor sets the coordinate as undefined. **********************************************************************/ - GeoCoords() throw() - // This is the N pole - : _lat(90) - , _long(0) - , _easting(2000000) - , _northing(2000000) - , _northp(true) - , _zone(0) + GeoCoords() + : _lat(Math::NaN()) + , _long(Math::NaN()) + , _easting(Math::NaN()) + , _northing(Math::NaN()) + , _gamma(Math::NaN()) + , _k(Math::NaN()) + , _northp(false) + , _zone(UTMUPS::INVALID) { CopyToAlt(); } /** @@ -91,7 +92,7 @@ namespace GeographicLib { * the position. * @param[in] centerp governs the interpretation of MGRS coordinates (see * below). - * @param[in] swaplatlong governs the interpretation of geographic + * @param[in] longfirst governs the interpretation of geographic * coordinates (see below). * @exception GeographicErr if the \e s is malformed (see below). * @@ -109,19 +110,19 @@ namespace GeographicLib { * - 43d16'12"E 33d26'24"N * - 43:16:12E 33:26:24 * - MGRS - * - 38SLC301 + * - 38SLC30 * - 38SLC391014 * - 38SLC3918701405 * - 37SHT9708 * - UTM - * - 38N 339188 3701405 - * - 897039 3708229 37N + * - 38n 339188 3701405 + * - 897039 3708229 37n * * Latitude and Longitude parsing: Latitude precedes longitude, * unless a N, S, E, W hemisphere designator is used on one or both - * coordinates. If \e swaplatlong = true (default is false), then + * coordinates. If \e longfirst = true (default is false), then * longitude precedes latitude in the absence of a hemisphere designator. - * Thus (with \e swaplatlong = false) + * Thus (with \e longfirst = false) * - 40 -75 * - N40 W75 * - -75 N40 @@ -133,7 +134,8 @@ namespace GeographicLib { * seconds, etc. Use d, ', and " to mark off the degrees, * minutes and seconds. Various alternative symbols for degrees, minutes, * and seconds are allowed. Alternatively, use : to separate these - * components. (See DMS::Decode for details.) Thus + * components. A single addition or subtraction is allowed. (See + * DMS::Decode for details.) Thus * - 40d30'30" * - 40d30'30 * - 40°30'30 @@ -142,37 +144,41 @@ namespace GeographicLib { * - 40:30:30 * - 40:30.5 * - 40.508333333 + * - 40:30+0:0:30 + * - 40:31-0:0.5 * . - * all specify the same angle. The leading sign applies to all components - * so -1d30 is -(1+30/60) = -1.5. Latitudes must be in the range - * [−90°, 90°] and longitudes in the range - * [−540°, 540°). Internally longitudes are reduced - * to the range [−180°, 180°). + * all specify the same angle. The leading sign applies to the following + * components so -1d30 is -(1+30/60) = −1.5. However, note + * that -1:30-0:0:15 is parsed as (-1:30) + (-0:0:15) = −(1+30/60) + * − (15/3600). Latitudes must be in the range [−90°, + * 90°]. Internally longitudes are reduced to the range + * [−180°, 180°]. * * UTM/UPS parsing: For UTM zones (−80° ≤ Lat < * 84°), the zone designator is made up of a zone number (for 1 to 60) - * and a hemisphere letter (N or S), e.g., 38N. The latitude zone designer - * ([C--M] in the southern hemisphere and [N--X] in the northern) should - * NOT be used. (This is part of the MGRS coordinate.) The zone - * designator for the poles (where UPS is employed) is a hemisphere letter - * by itself, i.e., N or S. + * and a hemisphere letter (n or s), e.g., 38n (38north can also be used). + * The latitude band designer ([C--M] in the southern hemisphere and [N--X] + * in the northern) should NOT be used. (This is part of the MGRS + * coordinate.) The zone designator for the poles (where UPS is employed) + * is a hemisphere letter by itself, i.e., n or s (north or south can also + * be used). * * MGRS parsing interprets the grid references as square area at the * specified precision (1m, 10m, 100m, etc.). If \e centerp = true (the * default), the center of this square is then taken to be the precise * position; thus: - * - 38SMB = 38N 450000 3650000 - * - 38SMB4484 = 38N 444500 3684500 - * - 38SMB44148470 = 38N 444145 3684705 + * - 38SMB = 38n 450000 3650000 + * - 38SMB4484 = 38n 444500 3684500 + * - 38SMB44148470 = 38n 444145 3684705 * . * Otherwise, the "south-west" corner of the square is used, i.e., - * - 38SMB = 38N 400000 3600000 - * - 38SMB4484 = 38N 444000 3684000 - * - 38SMB44148470 = 38N 444140 3684700 + * - 38SMB = 38n 400000 3600000 + * - 38SMB4484 = 38n 444000 3684000 + * - 38SMB44148470 = 38n 444140 3684700 **********************************************************************/ explicit GeoCoords(const std::string& s, - bool centerp = true, bool swaplatlong = false) - { Reset(s, centerp, swaplatlong); } + bool centerp = true, bool longfirst = false) + { Reset(s, centerp, longfirst); } /** * Construct from geographic coordinates. @@ -183,8 +189,6 @@ namespace GeographicLib { * specified zone using the rules given in UTMUPS::zonespec. * @exception GeographicErr if \e latitude is not in [−90°, * 90°]. - * @exception GeographicErr if \e longitude is not in [−540°, - * 540°). * @exception GeographicErr if \e zone cannot be used for this location. **********************************************************************/ GeoCoords(real latitude, real longitude, int zone = UTMUPS::STANDARD) { @@ -207,17 +211,17 @@ namespace GeographicLib { /** * Reset the location from a string. See - * GeoCoords(const std::string& s, bool centerp, bool swaplatlong). + * GeoCoords(const std::string& s, bool centerp, bool longfirst). * * @param[in] s 1-element, 2-element, or 3-element string representation of * the position. * @param[in] centerp governs the interpretation of MGRS coordinates. - * @param[in] swaplatlong governs the interpretation of geographic + * @param[in] longfirst governs the interpretation of geographic * coordinates. * @exception GeographicErr if the \e s is malformed. **********************************************************************/ void Reset(const std::string& s, - bool centerp = true, bool swaplatlong = false); + bool centerp = true, bool longfirst = false); /** * Reset the location in terms of geographic coordinates. See @@ -229,8 +233,6 @@ namespace GeographicLib { * specified zone using the rules given in UTMUPS::zonespec. * @exception GeographicErr if \e latitude is not in [−90°, * 90°]. - * @exception GeographicErr if \e longitude is not in [−540°, - * 540°). * @exception GeographicErr if \e zone cannot be used for this location. **********************************************************************/ void Reset(real latitude, real longitude, int zone = UTMUPS::STANDARD) { @@ -273,47 +275,47 @@ namespace GeographicLib { /** * @return latitude (degrees) **********************************************************************/ - Math::real Latitude() const throw() { return _lat; } + Math::real Latitude() const { return _lat; } /** * @return longitude (degrees) **********************************************************************/ - Math::real Longitude() const throw() { return _long; } + Math::real Longitude() const { return _long; } /** * @return easting (meters) **********************************************************************/ - Math::real Easting() const throw() { return _easting; } + Math::real Easting() const { return _easting; } /** * @return northing (meters) **********************************************************************/ - Math::real Northing() const throw() { return _northing; } + Math::real Northing() const { return _northing; } /** * @return meridian convergence (degrees) for the UTM/UPS projection. **********************************************************************/ - Math::real Convergence() const throw() { return _gamma; } + Math::real Convergence() const { return _gamma; } /** * @return scale for the UTM/UPS projection. **********************************************************************/ - Math::real Scale() const throw() { return _k; } + Math::real Scale() const { return _k; } /** * @return hemisphere (false means south, true means north). **********************************************************************/ - bool Northp() const throw() { return _northp; } + bool Northp() const { return _northp; } /** - * @return hemisphere letter N or S. + * @return hemisphere letter n or s. **********************************************************************/ - char Hemisphere() const throw() { return _northp ? 'N' : 'S'; } + char Hemisphere() const { return _northp ? 'n' : 's'; } /** * @return the zone corresponding to the input (return 0 for UPS). **********************************************************************/ - int Zone() const throw() { return _zone; } + int Zone() const { return _zone; } ///@} @@ -350,27 +352,27 @@ namespace GeographicLib { /** * @return current alternate zone (return 0 for UPS). **********************************************************************/ - int AltZone() const throw() { return _alt_zone; } + int AltZone() const { return _alt_zone; } /** * @return easting (meters) for alternate zone. **********************************************************************/ - Math::real AltEasting() const throw() { return _alt_easting; } + Math::real AltEasting() const { return _alt_easting; } /** * @return northing (meters) for alternate zone. **********************************************************************/ - Math::real AltNorthing() const throw() { return _alt_northing; } + Math::real AltNorthing() const { return _alt_northing; } /** * @return meridian convergence (degrees) for alternate zone. **********************************************************************/ - Math::real AltConvergence() const throw() { return _alt_gamma; } + Math::real AltConvergence() const { return _alt_gamma; } /** * @return scale for alternate zone. **********************************************************************/ - Math::real AltScale() const throw() { return _alt_k; } + Math::real AltScale() const { return _alt_k; } ///@} /** \name String representations of the GeoCoords object @@ -381,7 +383,7 @@ namespace GeographicLib { * degrees. * * @param[in] prec precision (relative to about 1m). - * @param[in] swaplatlong if true give longitude first (default = false) + * @param[in] longfirst if true give longitude first (default = false) * @exception std::bad_alloc if memory for the string can't be allocated. * @return decimal latitude/longitude string representation. * @@ -391,14 +393,14 @@ namespace GeographicLib { * - prec = 3, 10−8° * - prec = 9 (max), 10−14° **********************************************************************/ - std::string GeoRepresentation(int prec = 0, bool swaplatlong = false) const; + std::string GeoRepresentation(int prec = 0, bool longfirst = false) const; /** * String representation with latitude and longitude as degrees, minutes, * seconds, and hemisphere. * * @param[in] prec precision (relative to about 1m) - * @param[in] swaplatlong if true give longitude first (default = false) + * @param[in] longfirst if true give longitude first (default = false) * @param[in] dmssep if non-null, use as the DMS separator character * (instead of d, ', " delimiters). * @exception std::bad_alloc if memory for the string can't be allocated. @@ -414,7 +416,7 @@ namespace GeographicLib { * - prec = 1, 0.01" * - prec = 10 (max), 10−11" **********************************************************************/ - std::string DMSRepresentation(int prec = 0, bool swaplatlong = false, + std::string DMSRepresentation(int prec = 0, bool longfirst = false, char dmssep = char(0)) const; @@ -426,11 +428,12 @@ namespace GeographicLib { * @return MGRS string. * * This gives the coordinates of the enclosing grid square with size given - * by the precision. Thus 38N 444180 3684790 converted to a MGRS + * by the precision. Thus 38n 444180 3684790 converted to a MGRS * coordinate at precision −2 (100m) is 38SMB441847 and not * 38SMB442848. \e prec specifies the precision of the MGRS string as * follows: - * - prec = −5 (min), 100km + * - prec = −6 (min), only the grid zone is returned, e.g., 38S + * - prec = −5, 100km, e.g., 38SMB * - prec = −4, 10km * - prec = −3, 1km * - prec = −2, 100m @@ -445,6 +448,8 @@ namespace GeographicLib { * UTM/UPS string. * * @param[in] prec precision (relative to about 1m) + * @param[in] abbrev if true (the default) use abbreviated (n/s) notation + * for hemisphere; otherwise spell out the hemisphere (north/south) * @exception std::bad_alloc if memory for the string can't be allocated. * @return UTM/UPS string representation: zone designator, easting, and * northing. @@ -457,20 +462,23 @@ namespace GeographicLib { * - prec = 6, 1μm * - prec = 9 (max), 1nm **********************************************************************/ - std::string UTMUPSRepresentation(int prec = 0) const; + std::string UTMUPSRepresentation(int prec = 0, bool abbrev = true) const; /** * UTM/UPS string with hemisphere override. * - * @param[in] prec precision (relative to about 1m) * @param[in] northp hemisphere override + * @param[in] prec precision (relative to about 1m) + * @param[in] abbrev if true (the default) use abbreviated (n/s) notation + * for hemisphere; otherwise spell out the hemisphere (north/south) * @exception GeographicErr if the hemisphere override attempts to change - * UPS N to UPS S or vice verse. + * UPS N to UPS S or vice versa. * @exception std::bad_alloc if memory for the string can't be allocated. * @return UTM/UPS string representation: zone designator, easting, and * northing. **********************************************************************/ - std::string UTMUPSRepresentation(bool northp, int prec = 0) const; + std::string UTMUPSRepresentation(bool northp, int prec = 0, + bool abbrev = true) const; /** * MGRS string for the alternate zone. See GeoCoords::MGRSRepresentation. @@ -486,24 +494,30 @@ namespace GeographicLib { * GeoCoords::UTMUPSRepresentation. * * @param[in] prec precision (relative to about 1m) + * @param[in] abbrev if true (the default) use abbreviated (n/s) notation + * for hemisphere; otherwise spell out the hemisphere (north/south) * @exception std::bad_alloc if memory for the string can't be allocated. * @return UTM/UPS string representation: zone designator, easting, and * northing. **********************************************************************/ - std::string AltUTMUPSRepresentation(int prec = 0) const; + std::string AltUTMUPSRepresentation(int prec = 0, bool abbrev = true) + const; /** * UTM/UPS string for the alternate zone, with hemisphere override. * - * @param[in] prec precision (relative to about 1m) * @param[in] northp hemisphere override + * @param[in] prec precision (relative to about 1m) + * @param[in] abbrev if true (the default) use abbreviated (n/s) notation + * for hemisphere; otherwise spell out the hemisphere (north/south) * @exception GeographicErr if the hemisphere override attempts to change - * UPS N to UPS S or vice verse. + * UPS n to UPS s or vice verse. * @exception std::bad_alloc if memory for the string can't be allocated. * @return UTM/UPS string representation: zone designator, easting, and * northing. **********************************************************************/ - std::string AltUTMUPSRepresentation(bool northp, int prec = 0) const; + std::string AltUTMUPSRepresentation(bool northp, int prec = 0, + bool abbrev = true) const; ///@} /** \name Inspector functions @@ -515,7 +529,7 @@ namespace GeographicLib { * (The WGS84 value is returned because the UTM and UPS projections are * based on this ellipsoid.) **********************************************************************/ - Math::real MajorRadius() const throw() { return UTMUPS::MajorRadius(); } + Math::real MajorRadius() const { return UTMUPS::MajorRadius(); } /** * @return \e f the flattening of the WGS84 ellipsoid. @@ -523,17 +537,9 @@ namespace GeographicLib { * (The WGS84 value is returned because the UTM and UPS projections are * based on this ellipsoid.) **********************************************************************/ - Math::real Flattening() const throw() { return UTMUPS::Flattening(); } + Math::real Flattening() const { return UTMUPS::Flattening(); } ///@} - /// \cond SKIP - /** - * DEPRECATED - * @return \e r the inverse flattening of the ellipsoid. - **********************************************************************/ - Math::real InverseFlattening() const throw() - { return UTMUPS::InverseFlattening(); } - /// \endcond }; } // namespace GeographicLib diff --git a/gtsam/3rdparty/GeographicLib/include/GeographicLib/Geocentric.hpp b/gtsam/3rdparty/GeographicLib/include/GeographicLib/Geocentric.hpp index 3afdb0b16..85122e4d6 100644 --- a/gtsam/3rdparty/GeographicLib/include/GeographicLib/Geocentric.hpp +++ b/gtsam/3rdparty/GeographicLib/include/GeographicLib/Geocentric.hpp @@ -2,9 +2,9 @@ * \file Geocentric.hpp * \brief Header for GeographicLib::Geocentric class * - * Copyright (c) Charles Karney (2008-2011) and licensed + * Copyright (c) Charles Karney (2008-2016) and licensed * under the MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #if !defined(GEOGRAPHICLIB_GEOCENTRIC_HPP) @@ -29,7 +29,7 @@ namespace GeographicLib { * The conversion from geographic to geocentric coordinates is * straightforward. For the reverse transformation we use * - H. Vermeille, - * Direct + * Direct * transformation from geocentric coordinates to geodetic coordinates, * J. Geodesy 76, 451--454 (2002). * . @@ -37,11 +37,17 @@ namespace GeographicLib { * results for all finite inputs (even if \e h is infinite). The changes are * described in Appendix B of * - C. F. F. Karney, - * Geodesics + * Geodesics * on an ellipsoid of revolution, * Feb. 2011; * preprint - * arxiv:1102.1215v1. + * arxiv:1102.1215v1. + * . + * Vermeille similarly updated his method in + * - H. Vermeille, + * + * An analytical method to transform geocentric into + * geodetic coordinates, J. Geodesy 85, 105--117 (2011). * . * See \ref geocentric for more information. * @@ -67,16 +73,13 @@ namespace GeographicLib { friend class GravityCircle; // GravityCircle uses Rotation friend class GravityModel; // GravityModel uses IntForward friend class NormalGravity; // NormalGravity uses IntForward - friend class SphericalHarmonic; - friend class SphericalHarmonic1; - friend class SphericalHarmonic2; static const size_t dim_ = 3; static const size_t dim2_ = dim_ * dim_; real _a, _f, _e2, _e2m, _e2a, _e4a, _maxrad; static void Rotation(real sphi, real cphi, real slam, real clam, - real M[dim2_]) throw(); + real M[dim2_]); static void Rotate(real M[dim2_], real x, real y, real z, - real& X, real& Y, real& Z) throw() { + real& X, real& Y, real& Z) { // Perform [X,Y,Z]^t = M.[x,y,z]^t // (typically local cartesian to geocentric) X = M[0] * x + M[1] * y + M[2] * z; @@ -84,7 +87,7 @@ namespace GeographicLib { Z = M[6] * x + M[7] * y + M[8] * z; } static void Unrotate(real M[dim2_], real X, real Y, real Z, - real& x, real& y, real& z) throw() { + real& x, real& y, real& z) { // Perform [x,y,z]^t = M^t.[X,Y,Z]^t // (typically geocentric to local cartesian) x = M[0] * X + M[3] * Y + M[6] * Z; @@ -92,9 +95,9 @@ namespace GeographicLib { z = M[2] * X + M[5] * Y + M[8] * Z; } void IntForward(real lat, real lon, real h, real& X, real& Y, real& Z, - real M[dim2_]) const throw(); + real M[dim2_]) const; void IntReverse(real X, real Y, real Z, real& lat, real& lon, real& h, - real M[dim2_]) const throw(); + real M[dim2_]) const; public: @@ -103,9 +106,8 @@ namespace GeographicLib { * * @param[in] a equatorial radius (meters). * @param[in] f flattening of ellipsoid. Setting \e f = 0 gives a sphere. - * Negative \e f gives a prolate ellipsoid. If \e f > 1, set flattening - * to 1/\e f. - * @exception GeographicErr if \e a or (1 − \e f ) \e a is not + * Negative \e f gives a prolate ellipsoid. + * @exception GeographicErr if \e a or (1 − \e f) \e a is not * positive. **********************************************************************/ Geocentric(real a, real f); @@ -125,11 +127,10 @@ namespace GeographicLib { * @param[out] Y geocentric coordinate (meters). * @param[out] Z geocentric coordinate (meters). * - * \e lat should be in the range [−90°, 90°]; \e lon - * should be in the range [−540°, 540°). + * \e lat should be in the range [−90°, 90°]. **********************************************************************/ void Forward(real lat, real lon, real h, real& X, real& Y, real& Z) - const throw() { + const { if (Init()) IntForward(lat, lon, h, X, Y, Z, NULL); } @@ -159,13 +160,13 @@ namespace GeographicLib { **********************************************************************/ void Forward(real lat, real lon, real h, real& X, real& Y, real& Z, std::vector& M) - const throw() { + const { if (!Init()) return; if (M.end() == M.begin() + dim2_) { real t[dim2_]; IntForward(lat, lon, h, X, Y, Z, t); - copy(t, t + dim2_, M.begin()); + std::copy(t, t + dim2_, M.begin()); } else IntForward(lat, lon, h, X, Y, Z, NULL); } @@ -188,10 +189,10 @@ namespace GeographicLib { * returned. The value of \e h returned satisfies \e h ≥ − \e a * (1 − e2) / sqrt(1 − e2 * sin2\e lat). The value of \e lon returned is in the range - * [−180°, 180°). + * [−180°, 180°]. **********************************************************************/ void Reverse(real X, real Y, real Z, real& lat, real& lon, real& h) - const throw() { + const { if (Init()) IntReverse(X, Y, Z, lat, lon, h, NULL); } @@ -216,18 +217,18 @@ namespace GeographicLib { * - in geocentric \e X, \e Y, \e Z coordinates; call this representation * \e v0. * . - * Then we have \e v1 = \e MT ⋅ \e v0, where \e - * MT is the transpose of \e M. + * Then we have \e v1 = MT ⋅ \e v0, where + * MT is the transpose of \e M. **********************************************************************/ void Reverse(real X, real Y, real Z, real& lat, real& lon, real& h, std::vector& M) - const throw() { + const { if (!Init()) return; if (M.end() == M.begin() + dim2_) { real t[dim2_]; IntReverse(X, Y, Z, lat, lon, h, t); - copy(t, t + dim2_, M.begin()); + std::copy(t, t + dim2_, M.begin()); } else IntReverse(X, Y, Z, lat, lon, h, NULL); } @@ -238,36 +239,27 @@ namespace GeographicLib { /** * @return true if the object has been initialized. **********************************************************************/ - bool Init() const throw() { return _a > 0; } + bool Init() const { return _a > 0; } /** * @return \e a the equatorial radius of the ellipsoid (meters). This is * the value used in the constructor. **********************************************************************/ - Math::real MajorRadius() const throw() - { return Init() ? _a : Math::NaN(); } + Math::real MajorRadius() const + { return Init() ? _a : Math::NaN(); } /** * @return \e f the flattening of the ellipsoid. This is the * value used in the constructor. **********************************************************************/ - Math::real Flattening() const throw() - { return Init() ? _f : Math::NaN(); } + Math::real Flattening() const + { return Init() ? _f : Math::NaN(); } ///@} - /// \cond SKIP - /** - * DEPRECATED - * @return \e r the inverse flattening of the ellipsoid. - **********************************************************************/ - Math::real InverseFlattening() const throw() - { return Init() ? 1/_f : Math::NaN(); } - /// \endcond - /** * A global instantiation of Geocentric with the parameters for the WGS84 * ellipsoid. **********************************************************************/ - static const Geocentric WGS84; + static const Geocentric& WGS84(); }; } // namespace GeographicLib diff --git a/gtsam/3rdparty/GeographicLib/include/GeographicLib/Geodesic.hpp b/gtsam/3rdparty/GeographicLib/include/GeographicLib/Geodesic.hpp index 6cec279a2..488440b7b 100644 --- a/gtsam/3rdparty/GeographicLib/include/GeographicLib/Geodesic.hpp +++ b/gtsam/3rdparty/GeographicLib/include/GeographicLib/Geodesic.hpp @@ -2,9 +2,9 @@ * \file Geodesic.hpp * \brief Header for GeographicLib::Geodesic class * - * Copyright (c) Charles Karney (2009-2013) and licensed + * Copyright (c) Charles Karney (2009-2016) and licensed * under the MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #if !defined(GEOGRAPHICLIB_GEODESIC_HPP) @@ -15,9 +15,12 @@ #if !defined(GEOGRAPHICLIB_GEODESIC_ORDER) /** * The order of the expansions used by Geodesic. + * GEOGRAPHICLIB_GEODESIC_ORDER can be set to any integer in [3, 8]. **********************************************************************/ # define GEOGRAPHICLIB_GEODESIC_ORDER \ - (GEOGRAPHICLIB_PRECISION == 2 ? 6 : (GEOGRAPHICLIB_PRECISION == 1 ? 3 : 7)) + (GEOGRAPHICLIB_PRECISION == 2 ? 6 : \ + (GEOGRAPHICLIB_PRECISION == 1 ? 3 : \ + (GEOGRAPHICLIB_PRECISION == 3 ? 7 : 8))) #endif namespace GeographicLib { @@ -36,7 +39,7 @@ namespace GeographicLib { * labeled φ, longitude λ (with λ12 = * λ2 − λ1), and azimuth α. * - * spheroidal triangle + * spheroidal triangle * * Given \e lat1, \e lon1, \e azi1, and \e s12, we can determine \e lat2, \e * lon2, and \e azi2. This is the \e direct geodesic problem and its @@ -79,7 +82,6 @@ namespace GeographicLib { * defined similarly (with the geodesics being parallel at point 2). On a * flat surface, we have \e M12 = \e M21 = 1. The quantity 1/\e M12 gives * the scale of the Cassini-Soldner projection. - * - area. The area between the geodesic from point 1 to point 2 and * the equation is represented by \e S12; it is the area, measured * counter-clockwise, of the geodesic quadrilateral with corners @@ -110,33 +112,33 @@ namespace GeographicLib { * catalog of those cases: * - \e lat1 = −\e lat2 (with neither point at a pole). If \e azi1 = * \e azi2, the geodesic is unique. Otherwise there are two geodesics and - * the second one is obtained by setting [\e azi1, \e azi2] = [\e azi2, \e - * azi1], [\e M12, \e M21] = [\e M21, \e M12], \e S12 = −\e S12. - * (This occurs when the longitude difference is near ±180° for - * oblate ellipsoids.) + * the second one is obtained by setting [\e azi1, \e azi2] → [\e + * azi2, \e azi1], [\e M12, \e M21] → [\e M21, \e M12], \e S12 → + * −\e S12. (This occurs when the longitude difference is near + * ±180° for oblate ellipsoids.) * - \e lon2 = \e lon1 ± 180° (with neither point at a pole). If * \e azi1 = 0° or ±180°, the geodesic is unique. Otherwise * there are two geodesics and the second one is obtained by setting [\e - * azi1, \e azi2] = [−\e azi1, −\e azi2], \e S12 = −\e - * S12. (This occurs when \e lat2 is near −\e lat1 for prolate - * ellipsoids.) + * azi1, \e azi2] → [−\e azi1, −\e azi2], \e S12 → + * −\e S12. (This occurs when \e lat2 is near −\e lat1 for + * prolate ellipsoids.) * - Points 1 and 2 at opposite poles. There are infinitely many geodesics - * which can be generated by setting [\e azi1, \e azi2] = [\e azi1, \e + * which can be generated by setting [\e azi1, \e azi2] → [\e azi1, \e * azi2] + [\e d, −\e d], for arbitrary \e d. (For spheres, this * prescription applies when points 1 and 2 are antipodal.) - * - s12 = 0 (coincident points). There are infinitely many geodesics which - * can be generated by setting [\e azi1, \e azi2] = [\e azi1, \e azi2] + - * [\e d, \e d], for arbitrary \e d. + * - \e s12 = 0 (coincident points). There are infinitely many geodesics + * which can be generated by setting [\e azi1, \e azi2] → + * [\e azi1, \e azi2] + [\e d, \e d], for arbitrary \e d. * * The calculations are accurate to better than 15 nm (15 nanometers) for the * WGS84 ellipsoid. See Sec. 9 of - * arXiv:1102.1215v1 for + * arXiv:1102.1215v1 for * details. The algorithms used by this class are based on series expansions * using the flattening \e f as a small parameter. These are only accurate * for |f| < 0.02; however reasonably accurate results will be * obtained for |f| < 0.2. Here is a table of the approximate * maximum error (expressed as a distance) for an ellipsoid with the same - * major radius as the WGS84 ellipsoid and different values of the + * equatorial radius as the WGS84 ellipsoid and different values of the * flattening.
    *     |f|      error
    *     0.01     25 nm
@@ -149,12 +151,13 @@ namespace GeographicLib {
    *
    * The algorithms are described in
    * - C. F. F. Karney,
-   *   
+   *   
    *   Algorithms for geodesics,
    *   J. Geodesy 87, 43--55 (2013);
-   *   DOI: 
+   *   DOI: 
    *   10.1007/s00190-012-0578-z;
-   *   addenda: 
+   *   addenda:
+   *   
    *   geod-addenda.html.
    * .
    * For more information on geodesics see \ref geodesic.
@@ -181,16 +184,12 @@ namespace GeographicLib {
     static const int nC3x_ = (nC3_ * (nC3_ - 1)) / 2;
     static const int nC4_ = GEOGRAPHICLIB_GEODESIC_ORDER;
     static const int nC4x_ = (nC4_ * (nC4_ + 1)) / 2;
+    // Size for temporary array
+    // nC = max(max(nC1_, nC1p_, nC2_) + 1, max(nC3_, nC4_))
+    static const int nC_ = GEOGRAPHICLIB_GEODESIC_ORDER + 1;
     static const unsigned maxit1_ = 20;
-    static const unsigned maxit2_ = maxit1_ +
-      std::numeric_limits::digits + 10;
-
-    static const real tiny_;
-    static const real tol0_;
-    static const real tol1_;
-    static const real tol2_;
-    static const real tolb_;
-    static const real xthresh_;
+    unsigned maxit2_;
+    real tiny_, tol0_, tol1_, tol2_, tolb_, xthresh_;
 
     enum captype {
       CAP_NONE = 0U,
@@ -200,30 +199,14 @@ namespace GeographicLib {
       CAP_C3   = 1U<<3,
       CAP_C4   = 1U<<4,
       CAP_ALL  = 0x1FU,
+      CAP_MASK = CAP_ALL,
       OUT_ALL  = 0x7F80U,
+      OUT_MASK = 0xFF80U,       // Includes LONG_UNROLL
     };
 
     static real SinCosSeries(bool sinp,
-                             real sinx, real cosx, const real c[], int n)
-      throw();
-    static inline real AngRound(real x) throw() {
-      // The makes the smallest gap in x = 1/16 - nextafter(1/16, 0) = 1/2^57
-      // for reals = 0.7 pm on the earth if x is an angle in degrees.  (This
-      // is about 1000 times more resolution than we get with angles around 90
-      // degrees.)  We use this to avoid having to deal with near singular
-      // cases when x is non-zero but tiny (e.g., 1.0e-200).
-      const real z = 1/real(16);
-      volatile real y = std::abs(x);
-      // The compiler mustn't "simplify" z - (z - y) to y
-      y = y < z ? z - (z - y) : y;
-      return x < 0 ? -y : y;
-    }
-    static inline void SinCosNorm(real& sinx, real& cosx) throw() {
-      real r = Math::hypot(sinx, cosx);
-      sinx /= r;
-      cosx /= r;
-    }
-    static real Astroid(real x, real y) throw();
+                             real sinx, real cosx, const real c[], int n);
+    static real Astroid(real x, real y);
 
     real _a, _f, _f1, _e2, _ep2, _n, _b, _c2, _etol2;
     real _A3x[nA3x_], _C3x[nC3x_], _C4x[nC4x_];
@@ -231,39 +214,41 @@ namespace GeographicLib {
     void Lengths(real eps, real sig12,
                  real ssig1, real csig1, real dn1,
                  real ssig2, real csig2, real dn2,
-                 real cbet1, real cbet2,
+                 real cbet1, real cbet2, unsigned outmask,
                  real& s12s, real& m12a, real& m0,
-                 bool scalep, real& M12, real& M21,
-                 real C1a[], real C2a[]) const throw();
+                 real& M12, real& M21, real Ca[]) const;
     real InverseStart(real sbet1, real cbet1, real dn1,
                       real sbet2, real cbet2, real dn2,
-                      real lam12,
+                      real lam12, real slam12, real clam12,
                       real& salp1, real& calp1,
                       real& salp2, real& calp2, real& dnm,
-                      real C1a[], real C2a[]) const throw();
+                      real Ca[]) const;
     real Lambda12(real sbet1, real cbet1, real dn1,
                   real sbet2, real cbet2, real dn2,
-                  real salp1, real calp1,
+                  real salp1, real calp1, real slam120, real clam120,
                   real& salp2, real& calp2, real& sig12,
                   real& ssig1, real& csig1, real& ssig2, real& csig2,
-                  real& eps, real& domg12, bool diffp, real& dlam12,
-                  real C1a[], real C2a[], real C3a[])
-      const throw();
+                  real& eps, real& domg12,
+                  bool diffp, real& dlam12, real Ca[]) const;
+    real GenInverse(real lat1, real lon1, real lat2, real lon2,
+                    unsigned outmask, real& s12,
+                    real& salp1, real& calp1, real& salp2, real& calp2,
+                    real& m12, real& M12, real& M21, real& S12) const;
 
     // These are Maxima generated functions to provide series approximations to
     // the integrals for the ellipsoidal geodesic.
-    static real A1m1f(real eps) throw();
-    static void C1f(real eps, real c[]) throw();
-    static void C1pf(real eps, real c[]) throw();
-    static real A2m1f(real eps) throw();
-    static void C2f(real eps, real c[]) throw();
+    static real A1m1f(real eps);
+    static void C1f(real eps, real c[]);
+    static void C1pf(real eps, real c[]);
+    static real A2m1f(real eps);
+    static void C2f(real eps, real c[]);
 
-    void A3coeff() throw();
-    real A3f(real eps) const throw();
-    void C3coeff() throw();
-    void C3f(real eps, real c[]) const throw();
-    void C4coeff() throw();
-    void C4f(real k2, real c[]) const throw();
+    void A3coeff();
+    real A3f(real eps) const;
+    void C3coeff();
+    void C3f(real eps, real c[]) const;
+    void C4coeff();
+    void C4f(real k2, real c[]) const;
 
   public:
 
@@ -326,7 +311,13 @@ namespace GeographicLib {
        **********************************************************************/
       AREA          = 1U<<14 | CAP_C4,
       /**
-       * All capabilities, calculate everything.
+       * Unroll \e lon2 in the direct calculation.
+       * @hideinitializer
+       **********************************************************************/
+      LONG_UNROLL   = 1U<<15,
+      /**
+       * All capabilities, calculate everything.  (LONG_UNROLL is not
+       * included in this mask.)
        * @hideinitializer
        **********************************************************************/
       ALL           = OUT_ALL| CAP_ALL,
@@ -340,9 +331,8 @@ namespace GeographicLib {
      *
      * @param[in] a equatorial radius (meters).
      * @param[in] f flattening of ellipsoid.  Setting \e f = 0 gives a sphere.
-     *   Negative \e f gives a prolate ellipsoid.  If \e f > 1, set flattening
-     *   to 1/\e f.
-     * @exception GeographicErr if \e a or (1 − \e f ) \e a is not
+     *   Negative \e f gives a prolate ellipsoid.
+     * @exception GeographicErr if \e a or (1 − \e f) \e a is not
      *   positive.
      **********************************************************************/
     Geodesic(real a, real f);
@@ -371,10 +361,9 @@ namespace GeographicLib {
      * @param[out] S12 area under the geodesic (meters2).
      * @return \e a12 arc length of between point 1 and point 2 (degrees).
      *
-     * \e lat1 should be in the range [−90°, 90°]; \e lon1 and \e
-     * azi1 should be in the range [−540°, 540°).  The values of
+     * \e lat1 should be in the range [−90°, 90°].  The values of
      * \e lon2 and \e azi2 returned are in the range [−180°,
-     * 180°).
+     * 180°].
      *
      * If either point is at a pole, the azimuth is defined by keeping the
      * longitude fixed, writing \e lat = ±(90° − ε),
@@ -390,7 +379,7 @@ namespace GeographicLib {
     Math::real Direct(real lat1, real lon1, real azi1, real s12,
                       real& lat2, real& lon2, real& azi2,
                       real& m12, real& M12, real& M21, real& S12)
-      const throw() {
+      const {
       real t;
       return GenDirect(lat1, lon1, azi1, false, s12,
                        LATITUDE | LONGITUDE | AZIMUTH |
@@ -403,7 +392,7 @@ namespace GeographicLib {
      **********************************************************************/
     Math::real Direct(real lat1, real lon1, real azi1, real s12,
                       real& lat2, real& lon2)
-      const throw() {
+      const {
       real t;
       return GenDirect(lat1, lon1, azi1, false, s12,
                        LATITUDE | LONGITUDE,
@@ -415,7 +404,7 @@ namespace GeographicLib {
      **********************************************************************/
     Math::real Direct(real lat1, real lon1, real azi1, real s12,
                       real& lat2, real& lon2, real& azi2)
-      const throw() {
+      const {
       real t;
       return GenDirect(lat1, lon1, azi1, false, s12,
                        LATITUDE | LONGITUDE | AZIMUTH,
@@ -427,7 +416,7 @@ namespace GeographicLib {
      **********************************************************************/
     Math::real Direct(real lat1, real lon1, real azi1, real s12,
                       real& lat2, real& lon2, real& azi2, real& m12)
-      const throw() {
+      const {
       real t;
       return GenDirect(lat1, lon1, azi1, false, s12,
                        LATITUDE | LONGITUDE | AZIMUTH | REDUCEDLENGTH,
@@ -440,7 +429,7 @@ namespace GeographicLib {
     Math::real Direct(real lat1, real lon1, real azi1, real s12,
                       real& lat2, real& lon2, real& azi2,
                       real& M12, real& M21)
-      const throw() {
+      const {
       real t;
       return GenDirect(lat1, lon1, azi1, false, s12,
                        LATITUDE | LONGITUDE | AZIMUTH | GEODESICSCALE,
@@ -453,7 +442,7 @@ namespace GeographicLib {
     Math::real Direct(real lat1, real lon1, real azi1, real s12,
                       real& lat2, real& lon2, real& azi2,
                       real& m12, real& M12, real& M21)
-      const throw() {
+      const {
       real t;
       return GenDirect(lat1, lon1, azi1, false, s12,
                        LATITUDE | LONGITUDE | AZIMUTH |
@@ -485,10 +474,9 @@ namespace GeographicLib {
      *   (dimensionless).
      * @param[out] S12 area under the geodesic (meters2).
      *
-     * \e lat1 should be in the range [−90°, 90°]; \e lon1 and \e
-     * azi1 should be in the range [−540°, 540°).  The values of
+     * \e lat1 should be in the range [−90°, 90°].  The values of
      * \e lon2 and \e azi2 returned are in the range [−180°,
-     * 180°).
+     * 180°].
      *
      * If either point is at a pole, the azimuth is defined by keeping the
      * longitude fixed, writing \e lat = ±(90° − ε),
@@ -503,7 +491,7 @@ namespace GeographicLib {
     void ArcDirect(real lat1, real lon1, real azi1, real a12,
                    real& lat2, real& lon2, real& azi2, real& s12,
                    real& m12, real& M12, real& M21, real& S12)
-      const throw() {
+      const {
       GenDirect(lat1, lon1, azi1, true, a12,
                 LATITUDE | LONGITUDE | AZIMUTH | DISTANCE |
                 REDUCEDLENGTH | GEODESICSCALE | AREA,
@@ -514,7 +502,7 @@ namespace GeographicLib {
      * See the documentation for Geodesic::ArcDirect.
      **********************************************************************/
     void ArcDirect(real lat1, real lon1, real azi1, real a12,
-                   real& lat2, real& lon2) const throw() {
+                   real& lat2, real& lon2) const {
       real t;
       GenDirect(lat1, lon1, azi1, true, a12,
                 LATITUDE | LONGITUDE,
@@ -525,7 +513,7 @@ namespace GeographicLib {
      * See the documentation for Geodesic::ArcDirect.
      **********************************************************************/
     void ArcDirect(real lat1, real lon1, real azi1, real a12,
-                   real& lat2, real& lon2, real& azi2) const throw() {
+                   real& lat2, real& lon2, real& azi2) const {
       real t;
       GenDirect(lat1, lon1, azi1, true, a12,
                 LATITUDE | LONGITUDE | AZIMUTH,
@@ -537,7 +525,7 @@ namespace GeographicLib {
      **********************************************************************/
     void ArcDirect(real lat1, real lon1, real azi1, real a12,
                    real& lat2, real& lon2, real& azi2, real& s12)
-      const throw() {
+      const {
       real t;
       GenDirect(lat1, lon1, azi1, true, a12,
                 LATITUDE | LONGITUDE | AZIMUTH | DISTANCE,
@@ -549,7 +537,7 @@ namespace GeographicLib {
      **********************************************************************/
     void ArcDirect(real lat1, real lon1, real azi1, real a12,
                    real& lat2, real& lon2, real& azi2,
-                   real& s12, real& m12) const throw() {
+                   real& s12, real& m12) const {
       real t;
       GenDirect(lat1, lon1, azi1, true, a12,
                 LATITUDE | LONGITUDE | AZIMUTH | DISTANCE |
@@ -562,7 +550,7 @@ namespace GeographicLib {
      **********************************************************************/
     void ArcDirect(real lat1, real lon1, real azi1, real a12,
                    real& lat2, real& lon2, real& azi2, real& s12,
-                   real& M12, real& M21) const throw() {
+                   real& M12, real& M21) const {
       real t;
       GenDirect(lat1, lon1, azi1, true, a12,
                 LATITUDE | LONGITUDE | AZIMUTH | DISTANCE |
@@ -575,7 +563,7 @@ namespace GeographicLib {
      **********************************************************************/
     void ArcDirect(real lat1, real lon1, real azi1, real a12,
                    real& lat2, real& lon2, real& azi2, real& s12,
-                   real& m12, real& M12, real& M21) const throw() {
+                   real& m12, real& M12, real& M21) const {
       real t;
       GenDirect(lat1, lon1, azi1, true, a12,
                 LATITUDE | LONGITUDE | AZIMUTH | DISTANCE |
@@ -624,19 +612,25 @@ namespace GeographicLib {
      * - \e outmask |= Geodesic::GEODESICSCALE for the geodesic scales \e
      *   M12 and \e M21;
      * - \e outmask |= Geodesic::AREA for the area \e S12;
-     * - \e outmask |= Geodesic::ALL for all of the above.
+     * - \e outmask |= Geodesic::ALL for all of the above;
+     * - \e outmask |= Geodesic::LONG_UNROLL to unroll \e lon2 instead of
+     *   wrapping it into the range [−180°, 180°].
      * .
      * The function value \e a12 is always computed and returned and this
      * equals \e s12_a12 is \e arcmode is true.  If \e outmask includes
      * Geodesic::DISTANCE and \e arcmode is false, then \e s12 = \e s12_a12.
      * It is not necessary to include Geodesic::DISTANCE_IN in \e outmask; this
      * is automatically included is \e arcmode is false.
+     *
+     * With the Geodesic::LONG_UNROLL bit set, the quantity \e lon2 − \e
+     * lon1 indicates how many times and in what sense the geodesic encircles
+     * the ellipsoid.
      **********************************************************************/
     Math::real GenDirect(real lat1, real lon1, real azi1,
                          bool arcmode, real s12_a12, unsigned outmask,
                          real& lat2, real& lon2, real& azi2,
                          real& s12, real& m12, real& M12, real& M21,
-                         real& S12) const throw();
+                         real& S12) const;
     ///@}
 
     /** \name Inverse geodesic problem.
@@ -660,10 +654,9 @@ namespace GeographicLib {
      * @param[out] S12 area under the geodesic (meters2).
      * @return \e a12 arc length of between point 1 and point 2 (degrees).
      *
-     * \e lat1 and \e lat2 should be in the range [−90°, 90°]; \e
-     * lon1 and \e lon2 should be in the range [−540°, 540°).
+     * \e lat1 and \e lat2 should be in the range [−90°, 90°].
      * The values of \e azi1 and \e azi2 returned are in the range
-     * [−180°, 180°).
+     * [−180°, 180°].
      *
      * If either point is at a pole, the azimuth is defined by keeping the
      * longitude fixed, writing \e lat = ±(90° − ε),
@@ -680,7 +673,7 @@ namespace GeographicLib {
      **********************************************************************/
     Math::real Inverse(real lat1, real lon1, real lat2, real lon2,
                        real& s12, real& azi1, real& azi2, real& m12,
-                       real& M12, real& M21, real& S12) const throw() {
+                       real& M12, real& M21, real& S12) const {
       return GenInverse(lat1, lon1, lat2, lon2,
                         DISTANCE | AZIMUTH |
                         REDUCEDLENGTH | GEODESICSCALE | AREA,
@@ -691,7 +684,7 @@ namespace GeographicLib {
      * See the documentation for Geodesic::Inverse.
      **********************************************************************/
     Math::real Inverse(real lat1, real lon1, real lat2, real lon2,
-                       real& s12) const throw() {
+                       real& s12) const {
       real t;
       return GenInverse(lat1, lon1, lat2, lon2,
                         DISTANCE,
@@ -702,7 +695,7 @@ namespace GeographicLib {
      * See the documentation for Geodesic::Inverse.
      **********************************************************************/
     Math::real Inverse(real lat1, real lon1, real lat2, real lon2,
-                       real& azi1, real& azi2) const throw() {
+                       real& azi1, real& azi2) const {
       real t;
       return GenInverse(lat1, lon1, lat2, lon2,
                         AZIMUTH,
@@ -714,7 +707,7 @@ namespace GeographicLib {
      **********************************************************************/
     Math::real Inverse(real lat1, real lon1, real lat2, real lon2,
                        real& s12, real& azi1, real& azi2)
-      const throw() {
+      const {
       real t;
       return GenInverse(lat1, lon1, lat2, lon2,
                         DISTANCE | AZIMUTH,
@@ -726,7 +719,7 @@ namespace GeographicLib {
      **********************************************************************/
     Math::real Inverse(real lat1, real lon1, real lat2, real lon2,
                        real& s12, real& azi1, real& azi2, real& m12)
-      const throw() {
+      const {
       real t;
       return GenInverse(lat1, lon1, lat2, lon2,
                         DISTANCE | AZIMUTH | REDUCEDLENGTH,
@@ -738,7 +731,7 @@ namespace GeographicLib {
      **********************************************************************/
     Math::real Inverse(real lat1, real lon1, real lat2, real lon2,
                        real& s12, real& azi1, real& azi2,
-                       real& M12, real& M21) const throw() {
+                       real& M12, real& M21) const {
       real t;
       return GenInverse(lat1, lon1, lat2, lon2,
                         DISTANCE | AZIMUTH | GEODESICSCALE,
@@ -750,7 +743,7 @@ namespace GeographicLib {
      **********************************************************************/
     Math::real Inverse(real lat1, real lon1, real lat2, real lon2,
                        real& s12, real& azi1, real& azi2, real& m12,
-                       real& M12, real& M21) const throw() {
+                       real& M12, real& M21) const {
       real t;
       return GenInverse(lat1, lon1, lat2, lon2,
                         DISTANCE | AZIMUTH |
@@ -798,8 +791,7 @@ namespace GeographicLib {
     Math::real GenInverse(real lat1, real lon1, real lat2, real lon2,
                           unsigned outmask,
                           real& s12, real& azi1, real& azi2,
-                          real& m12, real& M12, real& M21, real& S12)
-      const throw();
+                          real& m12, real& M12, real& M21, real& S12) const;
     ///@}
 
     /** \name Interface to GeodesicLine.
@@ -818,8 +810,7 @@ namespace GeographicLib {
      *   GeodesicLine::Position.
      * @return a GeodesicLine object.
      *
-     * \e lat1 should be in the range [−90°, 90°]; \e lon1 and \e
-     * azi1 should be in the range [−540°, 540°).
+     * \e lat1 should be in the range [−90°, 90°].
      *
      * The Geodesic::mask values are
      * - \e caps |= Geodesic::LATITUDE for the latitude \e lat2; this is
@@ -844,8 +835,101 @@ namespace GeographicLib {
      * limit ε → 0+.
      **********************************************************************/
     GeodesicLine Line(real lat1, real lon1, real azi1, unsigned caps = ALL)
-      const throw();
+      const;
 
+    /**
+     * Define a GeodesicLine in terms of the inverse geodesic problem.
+     *
+     * @param[in] lat1 latitude of point 1 (degrees).
+     * @param[in] lon1 longitude of point 1 (degrees).
+     * @param[in] lat2 latitude of point 2 (degrees).
+     * @param[in] lon2 longitude of point 2 (degrees).
+     * @param[in] caps bitor'ed combination of Geodesic::mask values
+     *   specifying the capabilities the GeodesicLine object should possess,
+     *   i.e., which quantities can be returned in calls to
+     *   GeodesicLine::Position.
+     * @return a GeodesicLine object.
+     *
+     * This function sets point 3 of the GeodesicLine to correspond to point 2
+     * of the inverse geodesic problem.
+     *
+     * \e lat1 and \e lat2 should be in the range [−90°, 90°].
+     **********************************************************************/
+    GeodesicLine InverseLine(real lat1, real lon1, real lat2, real lon2,
+                             unsigned caps = ALL) const;
+
+    /**
+     * Define a GeodesicLine in terms of the direct geodesic problem specified
+     * in terms of distance.
+     *
+     * @param[in] lat1 latitude of point 1 (degrees).
+     * @param[in] lon1 longitude of point 1 (degrees).
+     * @param[in] azi1 azimuth at point 1 (degrees).
+     * @param[in] s12 distance between point 1 and point 2 (meters); it can be
+     *   negative.
+     * @param[in] caps bitor'ed combination of Geodesic::mask values
+     *   specifying the capabilities the GeodesicLine object should possess,
+     *   i.e., which quantities can be returned in calls to
+     *   GeodesicLine::Position.
+     * @return a GeodesicLine object.
+     *
+     * This function sets point 3 of the GeodesicLine to correspond to point 2
+     * of the direct geodesic problem.
+     *
+     * \e lat1 should be in the range [−90°, 90°].
+     **********************************************************************/
+    GeodesicLine DirectLine(real lat1, real lon1, real azi1, real s12,
+                            unsigned caps = ALL) const;
+
+    /**
+     * Define a GeodesicLine in terms of the direct geodesic problem specified
+     * in terms of arc length.
+     *
+     * @param[in] lat1 latitude of point 1 (degrees).
+     * @param[in] lon1 longitude of point 1 (degrees).
+     * @param[in] azi1 azimuth at point 1 (degrees).
+     * @param[in] a12 arc length between point 1 and point 2 (degrees); it can
+     *   be negative.
+     * @param[in] caps bitor'ed combination of Geodesic::mask values
+     *   specifying the capabilities the GeodesicLine object should possess,
+     *   i.e., which quantities can be returned in calls to
+     *   GeodesicLine::Position.
+     * @return a GeodesicLine object.
+     *
+     * This function sets point 3 of the GeodesicLine to correspond to point 2
+     * of the direct geodesic problem.
+     *
+     * \e lat1 should be in the range [−90°, 90°].
+     **********************************************************************/
+    GeodesicLine ArcDirectLine(real lat1, real lon1, real azi1, real a12,
+                               unsigned caps = ALL) const;
+
+    /**
+     * Define a GeodesicLine in terms of the direct geodesic problem specified
+     * in terms of either distance or arc length.
+     *
+     * @param[in] lat1 latitude of point 1 (degrees).
+     * @param[in] lon1 longitude of point 1 (degrees).
+     * @param[in] azi1 azimuth at point 1 (degrees).
+     * @param[in] arcmode boolean flag determining the meaning of the \e
+     *   s12_a12.
+     * @param[in] s12_a12 if \e arcmode is false, this is the distance between
+     *   point 1 and point 2 (meters); otherwise it is the arc length between
+     *   point 1 and point 2 (degrees); it can be negative.
+     * @param[in] caps bitor'ed combination of Geodesic::mask values
+     *   specifying the capabilities the GeodesicLine object should possess,
+     *   i.e., which quantities can be returned in calls to
+     *   GeodesicLine::Position.
+     * @return a GeodesicLine object.
+     *
+     * This function sets point 3 of the GeodesicLine to correspond to point 2
+     * of the direct geodesic problem.
+     *
+     * \e lat1 should be in the range [−90°, 90°].
+     **********************************************************************/
+    GeodesicLine GenDirectLine(real lat1, real lon1, real azi1,
+                               bool arcmode, real s12_a12,
+                               unsigned caps = ALL) const;
     ///@}
 
     /** \name Inspector functions.
@@ -856,21 +940,13 @@ namespace GeographicLib {
      * @return \e a the equatorial radius of the ellipsoid (meters).  This is
      *   the value used in the constructor.
      **********************************************************************/
-    Math::real MajorRadius() const throw() { return _a; }
+    Math::real MajorRadius() const { return _a; }
 
     /**
      * @return \e f the  flattening of the ellipsoid.  This is the
      *   value used in the constructor.
      **********************************************************************/
-    Math::real Flattening() const throw() { return _f; }
-
-    /// \cond SKIP
-    /**
-     * DEPRECATED
-     * @return \e r the inverse flattening of the ellipsoid.
-     **********************************************************************/
-    Math::real InverseFlattening() const throw() { return 1/_f; }
-    /// \endcond
+    Math::real Flattening() const { return _f; }
 
     /**
      * @return total area of ellipsoid in meters2.  The area of a
@@ -878,15 +954,15 @@ namespace GeographicLib {
      *   Geodesic::EllipsoidArea()/2 to the sum of \e S12 for each side of the
      *   polygon.
      **********************************************************************/
-    Math::real EllipsoidArea() const throw()
-    { return 4 * Math::pi() * _c2; }
+    Math::real EllipsoidArea() const
+    { return 4 * Math::pi() * _c2; }
     ///@}
 
     /**
      * A global instantiation of Geodesic with the parameters for the WGS84
      * ellipsoid.
      **********************************************************************/
-    static const Geodesic WGS84;
+    static const Geodesic& WGS84();
 
   };
 
diff --git a/gtsam/3rdparty/GeographicLib/include/GeographicLib/GeodesicExact.hpp b/gtsam/3rdparty/GeographicLib/include/GeographicLib/GeodesicExact.hpp
index e76daee4c..0130ccb23 100644
--- a/gtsam/3rdparty/GeographicLib/include/GeographicLib/GeodesicExact.hpp
+++ b/gtsam/3rdparty/GeographicLib/include/GeographicLib/GeodesicExact.hpp
@@ -2,9 +2,9 @@
  * \file GeodesicExact.hpp
  * \brief Header for GeographicLib::GeodesicExact class
  *
- * Copyright (c) Charles Karney (2012-2013)  and licensed
+ * Copyright (c) Charles Karney (2012-2016)  and licensed
  * under the MIT/X11 License.  For more information, see
- * http://geographiclib.sourceforge.net/
+ * https://geographiclib.sourceforge.io/
  **********************************************************************/
 
 #if !defined(GEOGRAPHICLIB_GEODESICEXACT_HPP)
@@ -32,8 +32,8 @@ namespace GeographicLib {
    * in a series in the flattening \e f and this provides an accurate solution
    * for \e f ∈ [-0.01, 0.01].  The GeodesicExact class computes the
    * ellitpic integrals directly and so provides a solution which is valid for
-   * all \e f.  However, in practice, its use should be limited to about \e
-   * b/\e a ∈ [0.01, 100] or \e f ∈ [-99, 0.99].
+   * all \e f.  However, in practice, its use should be limited to about
+   * b/\e a ∈ [0.01, 100] or \e f ∈ [−99, 0.99].
    *
    * For the WGS84 ellipsoid, these classes are 2--3 times \e slower than the
    * series solution and 2--3 times \e less \e accurate (because it's less easy
@@ -41,8 +41,8 @@ namespace GeographicLib {
    * the error is about 40 nm (40 nanometers) instead of 15 nm.  However the
    * error in the series solution scales as f7 while the
    * error in the elliptic integral solution depends weakly on \e f.  If the
-   * quarter meridian distance is 10000 km and the ratio \e b/\e a = 1 −
-   * \e f is varied then the approximate maximum error (expressed as a
+   * quarter meridian distance is 10000 km and the ratio b/\e a = 1
+   * − \e f is varied then the approximate maximum error (expressed as a
    * distance) is 
    *       1 - f  error (nm)
    *       1/128     387
@@ -63,8 +63,8 @@ namespace GeographicLib {
    * 
* * The computation of the area in these classes is via a 30th order series. - * This gives accurate results for \e b/\e a ∈ [1/2, 2]; the accuracy is - * about 8 decimal digits for \e b/\e a ∈ [1/4, 4]. + * This gives accurate results for b/\e a ∈ [1/2, 2]; the + * accuracy is about 8 decimal digits for b/\e a ∈ [1/4, 4]. * * See \ref geodellip for the formulation. See the documentation on the * Geodesic class for additional information on the geodesic problems. @@ -84,15 +84,8 @@ namespace GeographicLib { static const int nC4_ = GEOGRAPHICLIB_GEODESICEXACT_ORDER; static const int nC4x_ = (nC4_ * (nC4_ + 1)) / 2; static const unsigned maxit1_ = 20; - static const unsigned maxit2_ = maxit1_ + - std::numeric_limits::digits + 10; - - static const real tiny_; - static const real tol0_; - static const real tol1_; - static const real tol2_; - static const real tolb_; - static const real xthresh_; + unsigned maxit2_; + real tiny_, tol0_, tol1_, tol2_, tolb_, xthresh_; enum captype { CAP_NONE = 0U, @@ -102,29 +95,13 @@ namespace GeographicLib { CAP_H = 1U<<3, CAP_C4 = 1U<<4, CAP_ALL = 0x1FU, + CAP_MASK = CAP_ALL, OUT_ALL = 0x7F80U, + OUT_MASK = 0xFF80U, // Includes LONG_UNROLL }; - static real CosSeries(real sinx, real cosx, const real c[], int n) - throw(); - static inline real AngRound(real x) throw() { - // The makes the smallest gap in x = 1/16 - nextafter(1/16, 0) = 1/2^57 - // for reals = 0.7 pm on the earth if x is an angle in degrees. (This - // is about 1000 times more resolution than we get with angles around 90 - // degrees.) We use this to avoid having to deal with near singular - // cases when x is non-zero but tiny (e.g., 1.0e-200). - const real z = 1/real(16); - volatile real y = std::abs(x); - // The compiler mustn't "simplify" z - (z - y) to y - y = y < z ? z - (z - y) : y; - return x < 0 ? -y : y; - } - static inline void SinCosNorm(real& sinx, real& cosx) throw() { - real r = Math::hypot(sinx, cosx); - sinx /= r; - cosx /= r; - } - static real Astroid(real x, real y) throw(); + static real CosSeries(real sinx, real cosx, const real c[], int n); + static real Astroid(real x, real y); real _a, _f, _f1, _e2, _ep2, _n, _b, _c2, _etol2; real _C4x[nC4x_]; @@ -133,28 +110,39 @@ namespace GeographicLib { real sig12, real ssig1, real csig1, real dn1, real ssig2, real csig2, real dn2, - real cbet1, real cbet2, + real cbet1, real cbet2, unsigned outmask, real& s12s, real& m12a, real& m0, - bool scalep, real& M12, real& M21) const throw(); + real& M12, real& M21) const; real InverseStart(EllipticFunction& E, real sbet1, real cbet1, real dn1, real sbet2, real cbet2, real dn2, - real lam12, + real lam12, real slam12, real clam12, real& salp1, real& calp1, - real& salp2, real& calp2, real& dnm) const throw(); + real& salp2, real& calp2, real& dnm) const; real Lambda12(real sbet1, real cbet1, real dn1, real sbet2, real cbet2, real dn2, - real salp1, real calp1, + real salp1, real calp1, real slam120, real clam120, real& salp2, real& calp2, real& sig12, real& ssig1, real& csig1, real& ssig2, real& csig2, EllipticFunction& E, - real& omg12, bool diffp, real& dlam12) - const throw(); + real& domg12, bool diffp, real& dlam12) const; + real GenInverse(real lat1, real lon1, real lat2, real lon2, + unsigned outmask, real& s12, + real& salp1, real& calp1, real& salp2, real& calp2, + real& m12, real& M12, real& M21, real& S12) const; // These are Maxima generated functions to provide series approximations to // the integrals for the area. - void C4coeff() throw(); - void C4f(real k2, real c[]) const throw(); + void C4coeff(); + void C4f(real k2, real c[]) const; + // Large coefficients are split so that lo contains the low 52 bits and hi + // the rest. This choice avoids double rounding with doubles and higher + // precision types. float coefficients will suffer double rounding; + // however the accuracy is already lousy for floats. + static Math::real reale(long long hi, long long lo) { + using std::ldexp; + return ldexp(real(hi), 52) + lo; + } public: @@ -218,7 +206,13 @@ namespace GeographicLib { **********************************************************************/ AREA = 1U<<14 | CAP_C4, /** - * All capabilities, calculate everything. + * Unroll \e lon2 in the direct calculation. + * @hideinitializer + **********************************************************************/ + LONG_UNROLL = 1U<<15, + /** + * All capabilities, calculate everything. (LONG_UNROLL is not + * included in this mask.) * @hideinitializer **********************************************************************/ ALL = OUT_ALL| CAP_ALL, @@ -232,9 +226,8 @@ namespace GeographicLib { * * @param[in] a equatorial radius (meters). * @param[in] f flattening of ellipsoid. Setting \e f = 0 gives a sphere. - * Negative \e f gives a prolate ellipsoid. If \e f > 1, set flattening - * to 1/\e f. - * @exception GeographicErr if \e a or (1 − \e f ) \e a is not + * Negative \e f gives a prolate ellipsoid. + * @exception GeographicErr if \e a or (1 − \e f) \e a is not * positive. **********************************************************************/ GeodesicExact(real a, real f); @@ -263,10 +256,9 @@ namespace GeographicLib { * @param[out] S12 area under the geodesic (meters2). * @return \e a12 arc length of between point 1 and point 2 (degrees). * - * \e lat1 should be in the range [−90°, 90°]; \e lon1 and \e - * azi1 should be in the range [−540°, 540°). The values of + * \e lat1 should be in the range [−90°, 90°]. The values of * \e lon2 and \e azi2 returned are in the range [−180°, - * 180°). + * 180°]. * * If either point is at a pole, the azimuth is defined by keeping the * longitude fixed, writing \e lat = ±(90° − ε), @@ -282,7 +274,7 @@ namespace GeographicLib { Math::real Direct(real lat1, real lon1, real azi1, real s12, real& lat2, real& lon2, real& azi2, real& m12, real& M12, real& M21, real& S12) - const throw() { + const { real t; return GenDirect(lat1, lon1, azi1, false, s12, LATITUDE | LONGITUDE | AZIMUTH | @@ -295,7 +287,7 @@ namespace GeographicLib { **********************************************************************/ Math::real Direct(real lat1, real lon1, real azi1, real s12, real& lat2, real& lon2) - const throw() { + const { real t; return GenDirect(lat1, lon1, azi1, false, s12, LATITUDE | LONGITUDE, @@ -307,7 +299,7 @@ namespace GeographicLib { **********************************************************************/ Math::real Direct(real lat1, real lon1, real azi1, real s12, real& lat2, real& lon2, real& azi2) - const throw() { + const { real t; return GenDirect(lat1, lon1, azi1, false, s12, LATITUDE | LONGITUDE | AZIMUTH, @@ -319,7 +311,7 @@ namespace GeographicLib { **********************************************************************/ Math::real Direct(real lat1, real lon1, real azi1, real s12, real& lat2, real& lon2, real& azi2, real& m12) - const throw() { + const { real t; return GenDirect(lat1, lon1, azi1, false, s12, LATITUDE | LONGITUDE | AZIMUTH | REDUCEDLENGTH, @@ -332,7 +324,7 @@ namespace GeographicLib { Math::real Direct(real lat1, real lon1, real azi1, real s12, real& lat2, real& lon2, real& azi2, real& M12, real& M21) - const throw() { + const { real t; return GenDirect(lat1, lon1, azi1, false, s12, LATITUDE | LONGITUDE | AZIMUTH | GEODESICSCALE, @@ -345,7 +337,7 @@ namespace GeographicLib { Math::real Direct(real lat1, real lon1, real azi1, real s12, real& lat2, real& lon2, real& azi2, real& m12, real& M12, real& M21) - const throw() { + const { real t; return GenDirect(lat1, lon1, azi1, false, s12, LATITUDE | LONGITUDE | AZIMUTH | @@ -377,10 +369,9 @@ namespace GeographicLib { * (dimensionless). * @param[out] S12 area under the geodesic (meters2). * - * \e lat1 should be in the range [−90°, 90°]; \e lon1 and \e - * azi1 should be in the range [−540°, 540°). The values of + * \e lat1 should be in the range [−90°, 90°]. The values of * \e lon2 and \e azi2 returned are in the range [−180°, - * 180°). + * 180°]. * * If either point is at a pole, the azimuth is defined by keeping the * longitude fixed, writing \e lat = ±(90° − ε), @@ -395,7 +386,7 @@ namespace GeographicLib { void ArcDirect(real lat1, real lon1, real azi1, real a12, real& lat2, real& lon2, real& azi2, real& s12, real& m12, real& M12, real& M21, real& S12) - const throw() { + const { GenDirect(lat1, lon1, azi1, true, a12, LATITUDE | LONGITUDE | AZIMUTH | DISTANCE | REDUCEDLENGTH | GEODESICSCALE | AREA, @@ -406,7 +397,7 @@ namespace GeographicLib { * See the documentation for GeodesicExact::ArcDirect. **********************************************************************/ void ArcDirect(real lat1, real lon1, real azi1, real a12, - real& lat2, real& lon2) const throw() { + real& lat2, real& lon2) const { real t; GenDirect(lat1, lon1, azi1, true, a12, LATITUDE | LONGITUDE, @@ -417,7 +408,7 @@ namespace GeographicLib { * See the documentation for GeodesicExact::ArcDirect. **********************************************************************/ void ArcDirect(real lat1, real lon1, real azi1, real a12, - real& lat2, real& lon2, real& azi2) const throw() { + real& lat2, real& lon2, real& azi2) const { real t; GenDirect(lat1, lon1, azi1, true, a12, LATITUDE | LONGITUDE | AZIMUTH, @@ -429,7 +420,7 @@ namespace GeographicLib { **********************************************************************/ void ArcDirect(real lat1, real lon1, real azi1, real a12, real& lat2, real& lon2, real& azi2, real& s12) - const throw() { + const { real t; GenDirect(lat1, lon1, azi1, true, a12, LATITUDE | LONGITUDE | AZIMUTH | DISTANCE, @@ -441,7 +432,7 @@ namespace GeographicLib { **********************************************************************/ void ArcDirect(real lat1, real lon1, real azi1, real a12, real& lat2, real& lon2, real& azi2, - real& s12, real& m12) const throw() { + real& s12, real& m12) const { real t; GenDirect(lat1, lon1, azi1, true, a12, LATITUDE | LONGITUDE | AZIMUTH | DISTANCE | @@ -454,7 +445,7 @@ namespace GeographicLib { **********************************************************************/ void ArcDirect(real lat1, real lon1, real azi1, real a12, real& lat2, real& lon2, real& azi2, real& s12, - real& M12, real& M21) const throw() { + real& M12, real& M21) const { real t; GenDirect(lat1, lon1, azi1, true, a12, LATITUDE | LONGITUDE | AZIMUTH | DISTANCE | @@ -467,7 +458,7 @@ namespace GeographicLib { **********************************************************************/ void ArcDirect(real lat1, real lon1, real azi1, real a12, real& lat2, real& lon2, real& azi2, real& s12, - real& m12, real& M12, real& M21) const throw() { + real& m12, real& M12, real& M21) const { real t; GenDirect(lat1, lon1, azi1, true, a12, LATITUDE | LONGITUDE | AZIMUTH | DISTANCE | @@ -516,19 +507,25 @@ namespace GeographicLib { * - \e outmask |= GeodesicExact::GEODESICSCALE for the geodesic scales \e * M12 and \e M21; * - \e outmask |= GeodesicExact::AREA for the area \e S12; - * - \e outmask |= GeodesicExact::ALL for all of the above. + * - \e outmask |= GeodesicExact::ALL for all of the above; + * - \e outmask |= GeodesicExact::LONG_UNROLL to unroll \e lon2 instead of + * wrapping it into the range [−180°, 180°]. * . * The function value \e a12 is always computed and returned and this * equals \e s12_a12 is \e arcmode is true. If \e outmask includes * GeodesicExact::DISTANCE and \e arcmode is false, then \e s12 = \e * s12_a12. It is not necessary to include GeodesicExact::DISTANCE_IN in * \e outmask; this is automatically included is \e arcmode is false. + * + * With the GeodesicExact::LONG_UNROLL bit set, the quantity \e lon2 + * − \e lon1 indicates how many times and in what sense the geodesic + * encircles the ellipsoid. **********************************************************************/ Math::real GenDirect(real lat1, real lon1, real azi1, bool arcmode, real s12_a12, unsigned outmask, real& lat2, real& lon2, real& azi2, real& s12, real& m12, real& M12, real& M21, - real& S12) const throw(); + real& S12) const; ///@} /** \name Inverse geodesic problem. @@ -552,22 +549,22 @@ namespace GeographicLib { * @param[out] S12 area under the geodesic (meters2). * @return \e a12 arc length of between point 1 and point 2 (degrees). * - * \e lat1 and \e lat2 should be in the range [−90°, 90°]; \e - * lon1 and \e lon2 should be in the range [−540°, 540°). + * \e lat1 and \e lat2 should be in the range [−90°, 90°]. * The values of \e azi1 and \e azi2 returned are in the range - * [−180°, 180°). + * [−180°, 180°]. * * If either point is at a pole, the azimuth is defined by keeping the * longitude fixed, writing \e lat = ±(90° − ε), * and taking the limit ε → 0+. * - * The following functions are overloaded versions of GeodesicExact::Inverse - * which omit some of the output parameters. Note, however, that the arc - * length is always computed and returned as the function value. + * The following functions are overloaded versions of + * GeodesicExact::Inverse which omit some of the output parameters. Note, + * however, that the arc length is always computed and returned as the + * function value. **********************************************************************/ Math::real Inverse(real lat1, real lon1, real lat2, real lon2, real& s12, real& azi1, real& azi2, real& m12, - real& M12, real& M21, real& S12) const throw() { + real& M12, real& M21, real& S12) const { return GenInverse(lat1, lon1, lat2, lon2, DISTANCE | AZIMUTH | REDUCEDLENGTH | GEODESICSCALE | AREA, @@ -578,7 +575,7 @@ namespace GeographicLib { * See the documentation for GeodesicExact::Inverse. **********************************************************************/ Math::real Inverse(real lat1, real lon1, real lat2, real lon2, - real& s12) const throw() { + real& s12) const { real t; return GenInverse(lat1, lon1, lat2, lon2, DISTANCE, @@ -589,7 +586,7 @@ namespace GeographicLib { * See the documentation for GeodesicExact::Inverse. **********************************************************************/ Math::real Inverse(real lat1, real lon1, real lat2, real lon2, - real& azi1, real& azi2) const throw() { + real& azi1, real& azi2) const { real t; return GenInverse(lat1, lon1, lat2, lon2, AZIMUTH, @@ -601,7 +598,7 @@ namespace GeographicLib { **********************************************************************/ Math::real Inverse(real lat1, real lon1, real lat2, real lon2, real& s12, real& azi1, real& azi2) - const throw() { + const { real t; return GenInverse(lat1, lon1, lat2, lon2, DISTANCE | AZIMUTH, @@ -613,7 +610,7 @@ namespace GeographicLib { **********************************************************************/ Math::real Inverse(real lat1, real lon1, real lat2, real lon2, real& s12, real& azi1, real& azi2, real& m12) - const throw() { + const { real t; return GenInverse(lat1, lon1, lat2, lon2, DISTANCE | AZIMUTH | REDUCEDLENGTH, @@ -625,7 +622,7 @@ namespace GeographicLib { **********************************************************************/ Math::real Inverse(real lat1, real lon1, real lat2, real lon2, real& s12, real& azi1, real& azi2, - real& M12, real& M21) const throw() { + real& M12, real& M21) const { real t; return GenInverse(lat1, lon1, lat2, lon2, DISTANCE | AZIMUTH | GEODESICSCALE, @@ -637,7 +634,7 @@ namespace GeographicLib { **********************************************************************/ Math::real Inverse(real lat1, real lon1, real lat2, real lon2, real& s12, real& azi1, real& azi2, real& m12, - real& M12, real& M21) const throw() { + real& M12, real& M21) const { real t; return GenInverse(lat1, lon1, lat2, lon2, DISTANCE | AZIMUTH | @@ -685,8 +682,7 @@ namespace GeographicLib { Math::real GenInverse(real lat1, real lon1, real lat2, real lon2, unsigned outmask, real& s12, real& azi1, real& azi2, - real& m12, real& M12, real& M21, real& S12) - const throw(); + real& m12, real& M12, real& M21, real& S12) const; ///@} /** \name Interface to GeodesicLineExact. @@ -705,8 +701,7 @@ namespace GeographicLib { * GeodesicLineExact::Position. * @return a GeodesicLineExact object. * - * \e lat1 should be in the range [−90°, 90°]; \e lon1 and \e - * azi1 should be in the range [−540°, 540°). + * \e lat1 should be in the range [−90°, 90°]. * * The GeodesicExact::mask values are * - \e caps |= GeodesicExact::LATITUDE for the latitude \e lat2; this is @@ -731,9 +726,102 @@ namespace GeographicLib { * fixed, writing \e lat1 = ±(90 − ε), and taking the * limit ε → 0+. **********************************************************************/ - GeodesicLineExact Line(real lat1, real lon1, real azi1, unsigned caps = ALL) - const throw(); + GeodesicLineExact Line(real lat1, real lon1, real azi1, + unsigned caps = ALL) const; + /** + * Define a GeodesicLineExact in terms of the inverse geodesic problem. + * + * @param[in] lat1 latitude of point 1 (degrees). + * @param[in] lon1 longitude of point 1 (degrees). + * @param[in] lat2 latitude of point 2 (degrees). + * @param[in] lon2 longitude of point 2 (degrees). + * @param[in] caps bitor'ed combination of GeodesicExact::mask values + * specifying the capabilities the GeodesicLineExact object should + * possess, i.e., which quantities can be returned in calls to + * GeodesicLineExact::Position. + * @return a GeodesicLineExact object. + * + * This function sets point 3 of the GeodesicLineExact to correspond to + * point 2 of the inverse geodesic problem. + * + * \e lat1 and \e lat2 should be in the range [−90°, 90°]. + **********************************************************************/ + GeodesicLineExact InverseLine(real lat1, real lon1, real lat2, real lon2, + unsigned caps = ALL) const; + + /** + * Define a GeodesicLineExact in terms of the direct geodesic problem + * specified in terms of distance. + * + * @param[in] lat1 latitude of point 1 (degrees). + * @param[in] lon1 longitude of point 1 (degrees). + * @param[in] azi1 azimuth at point 1 (degrees). + * @param[in] s12 distance between point 1 and point 2 (meters); it can be + * negative. + * @param[in] caps bitor'ed combination of GeodesicExact::mask values + * specifying the capabilities the GeodesicLineExact object should + * possess, i.e., which quantities can be returned in calls to + * GeodesicLineExact::Position. + * @return a GeodesicLineExact object. + * + * This function sets point 3 of the GeodesicLineExact to correspond to + * point 2 of the direct geodesic problem. + * + * \e lat1 should be in the range [−90°, 90°]. + **********************************************************************/ + GeodesicLineExact DirectLine(real lat1, real lon1, real azi1, real s12, + unsigned caps = ALL) const; + + /** + * Define a GeodesicLineExact in terms of the direct geodesic problem + * specified in terms of arc length. + * + * @param[in] lat1 latitude of point 1 (degrees). + * @param[in] lon1 longitude of point 1 (degrees). + * @param[in] azi1 azimuth at point 1 (degrees). + * @param[in] a12 arc length between point 1 and point 2 (degrees); it can + * be negative. + * @param[in] caps bitor'ed combination of GeodesicExact::mask values + * specifying the capabilities the GeodesicLineExact object should + * possess, i.e., which quantities can be returned in calls to + * GeodesicLineExact::Position. + * @return a GeodesicLineExact object. + * + * This function sets point 3 of the GeodesicLineExact to correspond to + * point 2 of the direct geodesic problem. + * + * \e lat1 should be in the range [−90°, 90°]. + **********************************************************************/ + GeodesicLineExact ArcDirectLine(real lat1, real lon1, real azi1, real a12, + unsigned caps = ALL) const; + + /** + * Define a GeodesicLineExact in terms of the direct geodesic problem + * specified in terms of either distance or arc length. + * + * @param[in] lat1 latitude of point 1 (degrees). + * @param[in] lon1 longitude of point 1 (degrees). + * @param[in] azi1 azimuth at point 1 (degrees). + * @param[in] arcmode boolean flag determining the meaning of the \e + * s12_a12. + * @param[in] s12_a12 if \e arcmode is false, this is the distance between + * point 1 and point 2 (meters); otherwise it is the arc length between + * point 1 and point 2 (degrees); it can be negative. + * @param[in] caps bitor'ed combination of GeodesicExact::mask values + * specifying the capabilities the GeodesicLineExact object should + * possess, i.e., which quantities can be returned in calls to + * GeodesicLineExact::Position. + * @return a GeodesicLineExact object. + * + * This function sets point 3 of the GeodesicLineExact to correspond to + * point 2 of the direct geodesic problem. + * + * \e lat1 should be in the range [−90°, 90°]. + **********************************************************************/ + GeodesicLineExact GenDirectLine(real lat1, real lon1, real azi1, + bool arcmode, real s12_a12, + unsigned caps = ALL) const; ///@} /** \name Inspector functions. @@ -744,21 +832,13 @@ namespace GeographicLib { * @return \e a the equatorial radius of the ellipsoid (meters). This is * the value used in the constructor. **********************************************************************/ - Math::real MajorRadius() const throw() { return _a; } + Math::real MajorRadius() const { return _a; } /** * @return \e f the flattening of the ellipsoid. This is the * value used in the constructor. **********************************************************************/ - Math::real Flattening() const throw() { return _f; } - - /// \cond SKIP - /** - * DEPRECATED - * @return \e r the inverse flattening of the ellipsoid. - **********************************************************************/ - Math::real InverseFlattening() const throw() { return 1/_f; } - /// \endcond + Math::real Flattening() const { return _f; } /** * @return total area of ellipsoid in meters2. The area of a @@ -766,15 +846,15 @@ namespace GeographicLib { * GeodesicExact::EllipsoidArea()/2 to the sum of \e S12 for each side of * the polygon. **********************************************************************/ - Math::real EllipsoidArea() const throw() - { return 4 * Math::pi() * _c2; } + Math::real EllipsoidArea() const + { return 4 * Math::pi() * _c2; } ///@} /** - * A global instantiation of GeodesicExact with the parameters for the WGS84 - * ellipsoid. + * A global instantiation of GeodesicExact with the parameters for the + * WGS84 ellipsoid. **********************************************************************/ - static const GeodesicExact WGS84; + static const GeodesicExact& WGS84(); }; diff --git a/gtsam/3rdparty/GeographicLib/include/GeographicLib/GeodesicLine.hpp b/gtsam/3rdparty/GeographicLib/include/GeographicLib/GeodesicLine.hpp index c901b3007..b1aad2219 100644 --- a/gtsam/3rdparty/GeographicLib/include/GeographicLib/GeodesicLine.hpp +++ b/gtsam/3rdparty/GeographicLib/include/GeographicLib/GeodesicLine.hpp @@ -2,9 +2,9 @@ * \file GeodesicLine.hpp * \brief Header for GeographicLib::GeodesicLine class * - * Copyright (c) Charles Karney (2009-2012) and licensed + * Copyright (c) Charles Karney (2009-2016) and licensed * under the MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #if !defined(GEOGRAPHICLIB_GEODESICLINE_HPP) @@ -20,17 +20,28 @@ namespace GeographicLib { * * GeodesicLine facilitates the determination of a series of points on a * single geodesic. The starting point (\e lat1, \e lon1) and the azimuth \e - * azi1 are specified in the constructor. GeodesicLine.Position returns the - * location of point 2 a distance \e s12 along the geodesic. Alternatively - * GeodesicLine.ArcPosition gives the position of point 2 an arc length \e - * a12 along the geodesic. + * azi1 are specified in the constructor; alternatively, the Geodesic::Line + * method can be used to create a GeodesicLine. GeodesicLine.Position + * returns the location of point 2 a distance \e s12 along the geodesic. In + * addition, GeodesicLine.ArcPosition gives the position of point 2 an arc + * length \e a12 along the geodesic. + * + * You can register the position of a reference point 3 a distance (arc + * length), \e s13 (\e a13) along the geodesic with the + * GeodesicLine.SetDistance (GeodesicLine.SetArc) functions. Points a + * fractional distance along the line can be found by providing, for example, + * 0.5 * Distance() as an argument to GeodesicLine.Position. The + * Geodesic::InverseLine or Geodesic::DirectLine methods return GeodesicLine + * objects with point 3 set to the point 2 of the corresponding geodesic + * problem. GeodesicLine objects created with the public constructor or with + * Geodesic::Line have \e s13 and \e a13 set to NaNs. * * The default copy constructor and assignment operators work with this * class. Similarly, a vector can be used to hold GeodesicLine objects. * * The calculations are accurate to better than 15 nm (15 nanometers). See * Sec. 9 of - * arXiv:1102.1215v1 for + * arXiv:1102.1215v1 for * details. The algorithms used by this class are based on series expansions * using the flattening \e f as a small parameter. These are only accurate * for |f| < 0.02; however reasonably accurate results will be @@ -39,12 +50,13 @@ namespace GeographicLib { * * The algorithms are described in * - C. F. F. Karney, - * + * * Algorithms for geodesics, * J. Geodesy 87, 43--55 (2013); - * DOI: + * DOI: * 10.1007/s00190-012-0578-z; - * addenda: + * addenda: + * * geod-addenda.html. * . * For more information on geodesics see \ref geodesic. @@ -66,15 +78,26 @@ namespace GeographicLib { static const int nC3_ = Geodesic::nC3_; static const int nC4_ = Geodesic::nC4_; + real tiny_; real _lat1, _lon1, _azi1; real _a, _f, _b, _c2, _f1, _salp0, _calp0, _k2, _salp1, _calp1, _ssig1, _csig1, _dn1, _stau1, _ctau1, _somg1, _comg1, _A1m1, _A2m1, _A3c, _B11, _B21, _B31, _A4, _B41; + real _a13, _s13; // index zero elements of _C1a, _C1pa, _C2a, _C3a are unused real _C1a[nC1_ + 1], _C1pa[nC1p_ + 1], _C2a[nC2_ + 1], _C3a[nC3_], _C4a[nC4_]; // all the elements of _C4a are used unsigned _caps; + void LineInit(const Geodesic& g, + real lat1, real lon1, + real azi1, real salp1, real calp1, + unsigned caps); + GeodesicLine(const Geodesic& g, + real lat1, real lon1, + real azi1, real salp1, real calp1, + unsigned caps, bool arcmode, real s13_a13); + enum captype { CAP_NONE = Geodesic::CAP_NONE, CAP_C1 = Geodesic::CAP_C1, @@ -83,7 +106,9 @@ namespace GeographicLib { CAP_C3 = Geodesic::CAP_C3, CAP_C4 = Geodesic::CAP_C4, CAP_ALL = Geodesic::CAP_ALL, + CAP_MASK = Geodesic::CAP_MASK, OUT_ALL = Geodesic::OUT_ALL, + OUT_MASK = Geodesic::OUT_MASK, }; public: @@ -144,7 +169,13 @@ namespace GeographicLib { **********************************************************************/ AREA = Geodesic::AREA, /** - * All capabilities, calculate everything. + * Unroll \e lon2 in the direct calculation. + * @hideinitializer + **********************************************************************/ + LONG_UNROLL = Geodesic::LONG_UNROLL, + /** + * All capabilities, calculate everything. (LONG_UNROLL is not + * included in this mask.) * @hideinitializer **********************************************************************/ ALL = Geodesic::ALL, @@ -168,8 +199,7 @@ namespace GeographicLib { * i.e., which quantities can be returned in calls to * GeodesicLine::Position. * - * \e lat1 should be in the range [−90°, 90°]; \e lon1 and \e - * azi1 should be in the range [−540°, 540°). + * \e lat1 should be in the range [−90°, 90°]. * * The GeodesicLine::mask values are * - \e caps |= GeodesicLine::LATITUDE for the latitude \e lat2; this is @@ -194,8 +224,7 @@ namespace GeographicLib { * the limit ε → 0+. **********************************************************************/ GeodesicLine(const Geodesic& g, real lat1, real lon1, real azi1, - unsigned caps = ALL) - throw(); + unsigned caps = ALL); /** * A default constructor. If GeodesicLine::Position is called on the @@ -203,7 +232,7 @@ namespace GeographicLib { * calculations). The object can be set with a call to Geodesic::Line. * Use Init() to test whether object is still in this uninitialized state. **********************************************************************/ - GeodesicLine() throw() : _caps(0U) {} + GeodesicLine() : _caps(0U) {} ///@} /** \name Position in terms of distance @@ -214,7 +243,7 @@ namespace GeographicLib { * Compute the position of point 2 which is a distance \e s12 (meters) from * point 1. * - * @param[in] s12 distance between point 1 and point 2 (meters); it can be + * @param[in] s12 distance from point 1 to point 2 (meters); it can be * negative. * @param[out] lat2 latitude of point 2 (degrees). * @param[out] lon2 longitude of point 2 (degrees); requires that the @@ -233,10 +262,10 @@ namespace GeographicLib { * @param[out] S12 area under the geodesic (meters2); requires * that the GeodesicLine object was constructed with \e caps |= * GeodesicLine::AREA. - * @return \e a12 arc length of between point 1 and point 2 (degrees). + * @return \e a12 arc length from point 1 to point 2 (degrees). * * The values of \e lon2 and \e azi2 returned are in the range - * [−180°, 180°). + * [−180°, 180°]. * * The GeodesicLine object \e must have been constructed with \e caps |= * GeodesicLine::DISTANCE_IN; otherwise Math::NaN() is returned and no @@ -252,7 +281,7 @@ namespace GeographicLib { Math::real Position(real s12, real& lat2, real& lon2, real& azi2, real& m12, real& M12, real& M21, - real& S12) const throw() { + real& S12) const { real t; return GenPosition(false, s12, LATITUDE | LONGITUDE | AZIMUTH | @@ -263,7 +292,7 @@ namespace GeographicLib { /** * See the documentation for GeodesicLine::Position. **********************************************************************/ - Math::real Position(real s12, real& lat2, real& lon2) const throw() { + Math::real Position(real s12, real& lat2, real& lon2) const { real t; return GenPosition(false, s12, LATITUDE | LONGITUDE, @@ -274,7 +303,7 @@ namespace GeographicLib { * See the documentation for GeodesicLine::Position. **********************************************************************/ Math::real Position(real s12, real& lat2, real& lon2, - real& azi2) const throw() { + real& azi2) const { real t; return GenPosition(false, s12, LATITUDE | LONGITUDE | AZIMUTH, @@ -285,7 +314,7 @@ namespace GeographicLib { * See the documentation for GeodesicLine::Position. **********************************************************************/ Math::real Position(real s12, real& lat2, real& lon2, - real& azi2, real& m12) const throw() { + real& azi2, real& m12) const { real t; return GenPosition(false, s12, LATITUDE | LONGITUDE | @@ -298,7 +327,7 @@ namespace GeographicLib { **********************************************************************/ Math::real Position(real s12, real& lat2, real& lon2, real& azi2, real& M12, real& M21) - const throw() { + const { real t; return GenPosition(false, s12, LATITUDE | LONGITUDE | @@ -312,14 +341,13 @@ namespace GeographicLib { Math::real Position(real s12, real& lat2, real& lon2, real& azi2, real& m12, real& M12, real& M21) - const throw() { + const { real t; return GenPosition(false, s12, LATITUDE | LONGITUDE | AZIMUTH | REDUCEDLENGTH | GEODESICSCALE, lat2, lon2, azi2, t, m12, M12, M21, t); } - ///@} /** \name Position in terms of arc length @@ -330,14 +358,14 @@ namespace GeographicLib { * Compute the position of point 2 which is an arc length \e a12 (degrees) * from point 1. * - * @param[in] a12 arc length between point 1 and point 2 (degrees); it can + * @param[in] a12 arc length from point 1 to point 2 (degrees); it can * be negative. * @param[out] lat2 latitude of point 2 (degrees). * @param[out] lon2 longitude of point 2 (degrees); requires that the * GeodesicLine object was constructed with \e caps |= * GeodesicLine::LONGITUDE. * @param[out] azi2 (forward) azimuth at point 2 (degrees). - * @param[out] s12 distance between point 1 and point 2 (meters); requires + * @param[out] s12 distance from point 1 to point 2 (meters); requires * that the GeodesicLine object was constructed with \e caps |= * GeodesicLine::DISTANCE. * @param[out] m12 reduced length of geodesic (meters); requires that the @@ -354,7 +382,7 @@ namespace GeographicLib { * GeodesicLine::AREA. * * The values of \e lon2 and \e azi2 returned are in the range - * [−180°, 180°). + * [−180°, 180°]. * * Requesting a value which the GeodesicLine object is not capable of * computing is not an error; the corresponding argument will not be @@ -365,7 +393,7 @@ namespace GeographicLib { **********************************************************************/ void ArcPosition(real a12, real& lat2, real& lon2, real& azi2, real& s12, real& m12, real& M12, real& M21, - real& S12) const throw() { + real& S12) const { GenPosition(true, a12, LATITUDE | LONGITUDE | AZIMUTH | DISTANCE | REDUCEDLENGTH | GEODESICSCALE | AREA, @@ -376,7 +404,7 @@ namespace GeographicLib { * See the documentation for GeodesicLine::ArcPosition. **********************************************************************/ void ArcPosition(real a12, real& lat2, real& lon2) - const throw() { + const { real t; GenPosition(true, a12, LATITUDE | LONGITUDE, @@ -388,7 +416,7 @@ namespace GeographicLib { **********************************************************************/ void ArcPosition(real a12, real& lat2, real& lon2, real& azi2) - const throw() { + const { real t; GenPosition(true, a12, LATITUDE | LONGITUDE | AZIMUTH, @@ -399,7 +427,7 @@ namespace GeographicLib { * See the documentation for GeodesicLine::ArcPosition. **********************************************************************/ void ArcPosition(real a12, real& lat2, real& lon2, real& azi2, - real& s12) const throw() { + real& s12) const { real t; GenPosition(true, a12, LATITUDE | LONGITUDE | AZIMUTH | DISTANCE, @@ -410,7 +438,7 @@ namespace GeographicLib { * See the documentation for GeodesicLine::ArcPosition. **********************************************************************/ void ArcPosition(real a12, real& lat2, real& lon2, real& azi2, - real& s12, real& m12) const throw() { + real& s12, real& m12) const { real t; GenPosition(true, a12, LATITUDE | LONGITUDE | AZIMUTH | @@ -423,7 +451,7 @@ namespace GeographicLib { **********************************************************************/ void ArcPosition(real a12, real& lat2, real& lon2, real& azi2, real& s12, real& M12, real& M21) - const throw() { + const { real t; GenPosition(true, a12, LATITUDE | LONGITUDE | AZIMUTH | @@ -436,7 +464,7 @@ namespace GeographicLib { **********************************************************************/ void ArcPosition(real a12, real& lat2, real& lon2, real& azi2, real& s12, real& m12, real& M12, real& M21) - const throw() { + const { real t; GenPosition(true, a12, LATITUDE | LONGITUDE | AZIMUTH | @@ -454,8 +482,8 @@ namespace GeographicLib { * GeodesicLine::ArcPosition are defined in terms of this function. * * @param[in] arcmode boolean flag determining the meaning of the second - * parameter; if arcmode is false, then the GeodesicLine object must have - * been constructed with \e caps |= GeodesicLine::DISTANCE_IN. + * parameter; if \e arcmode is false, then the GeodesicLine object must + * have been constructed with \e caps |= GeodesicLine::DISTANCE_IN. * @param[in] s12_a12 if \e arcmode is false, this is the distance between * point 1 and point 2 (meters); otherwise it is the arc length between * point 1 and point 2 (degrees); it can be negative. @@ -466,7 +494,7 @@ namespace GeographicLib { * GeodesicLine object was constructed with \e caps |= * GeodesicLine::LONGITUDE. * @param[out] azi2 (forward) azimuth at point 2 (degrees). - * @param[out] s12 distance between point 1 and point 2 (meters); requires + * @param[out] s12 distance from point 1 to point 2 (meters); requires * that the GeodesicLine object was constructed with \e caps |= * GeodesicLine::DISTANCE. * @param[out] m12 reduced length of geodesic (meters); requires that the @@ -481,7 +509,7 @@ namespace GeographicLib { * @param[out] S12 area under the geodesic (meters2); requires * that the GeodesicLine object was constructed with \e caps |= * GeodesicLine::AREA. - * @return \e a12 arc length of between point 1 and point 2 (degrees). + * @return \e a12 arc length from point 1 to point 2 (degrees). * * The GeodesicLine::mask values possible for \e outmask are * - \e outmask |= GeodesicLine::LATITUDE for the latitude \e lat2; @@ -493,18 +521,62 @@ namespace GeographicLib { * - \e outmask |= GeodesicLine::GEODESICSCALE for the geodesic scales \e * M12 and \e M21; * - \e outmask |= GeodesicLine::AREA for the area \e S12; - * - \e outmask |= GeodesicLine::ALL for all of the above. + * - \e outmask |= GeodesicLine::ALL for all of the above; + * - \e outmask |= GeodesicLine::LONG_UNROLL to unroll \e lon2 instead of + * reducing it into the range [−180°, 180°]. * . * Requesting a value which the GeodesicLine object is not capable of * computing is not an error; the corresponding argument will not be * altered. Note, however, that the arc length is always computed and * returned as the function value. + * + * With the GeodesicLine::LONG_UNROLL bit set, the quantity \e lon2 − + * \e lon1 indicates how many times and in what sense the geodesic + * encircles the ellipsoid. **********************************************************************/ Math::real GenPosition(bool arcmode, real s12_a12, unsigned outmask, real& lat2, real& lon2, real& azi2, real& s12, real& m12, real& M12, real& M21, - real& S12) const throw(); + real& S12) const; + ///@} + /** \name Setting point 3 + **********************************************************************/ + ///@{ + + /** + * Specify position of point 3 in terms of distance. + * + * @param[in] s13 the distance from point 1 to point 3 (meters); it + * can be negative. + * + * This is only useful if the GeodesicLine object has been constructed + * with \e caps |= GeodesicLine::DISTANCE_IN. + **********************************************************************/ + void SetDistance(real s13); + + /** + * Specify position of point 3 in terms of arc length. + * + * @param[in] a13 the arc length from point 1 to point 3 (degrees); it + * can be negative. + * + * The distance \e s13 is only set if the GeodesicLine object has been + * constructed with \e caps |= GeodesicLine::DISTANCE. + **********************************************************************/ + void SetArc(real a13); + + /** + * Specify position of point 3 in terms of either distance or arc length. + * + * @param[in] arcmode boolean flag determining the meaning of the second + * parameter; if \e arcmode is false, then the GeodesicLine object must + * have been constructed with \e caps |= GeodesicLine::DISTANCE_IN. + * @param[in] s13_a13 if \e arcmode is false, this is the distance from + * point 1 to point 3 (meters); otherwise it is the arc length from + * point 1 to point 3 (degrees); it can be negative. + **********************************************************************/ + void GenSetDistance(bool arcmode, real s13_a13); ///@} /** \name Inspector functions @@ -514,81 +586,113 @@ namespace GeographicLib { /** * @return true if the object has been initialized. **********************************************************************/ - bool Init() const throw() { return _caps != 0U; } + bool Init() const { return _caps != 0U; } /** * @return \e lat1 the latitude of point 1 (degrees). **********************************************************************/ - Math::real Latitude() const throw() - { return Init() ? _lat1 : Math::NaN(); } + Math::real Latitude() const + { return Init() ? _lat1 : Math::NaN(); } /** * @return \e lon1 the longitude of point 1 (degrees). **********************************************************************/ - Math::real Longitude() const throw() - { return Init() ? _lon1 : Math::NaN(); } + Math::real Longitude() const + { return Init() ? _lon1 : Math::NaN(); } /** * @return \e azi1 the azimuth (degrees) of the geodesic line at point 1. **********************************************************************/ - Math::real Azimuth() const throw() - { return Init() ? _azi1 : Math::NaN(); } + Math::real Azimuth() const + { return Init() ? _azi1 : Math::NaN(); } + + /** + * The sine and cosine of \e azi1. + * + * @param[out] sazi1 the sine of \e azi1. + * @param[out] cazi1 the cosine of \e azi1. + **********************************************************************/ + void Azimuth(real& sazi1, real& cazi1) const + { if (Init()) { sazi1 = _salp1; cazi1 = _calp1; } } /** * @return \e azi0 the azimuth (degrees) of the geodesic line as it crosses * the equator in a northward direction. + * + * The result lies in [−90°, 90°]. **********************************************************************/ - Math::real EquatorialAzimuth() const throw() { - return Init() ? - atan2(_salp0, _calp0) / Math::degree() : Math::NaN(); - } + Math::real EquatorialAzimuth() const + { return Init() ? Math::atan2d(_salp0, _calp0) : Math::NaN(); } + + /** + * The sine and cosine of \e azi0. + * + * @param[out] sazi0 the sine of \e azi0. + * @param[out] cazi0 the cosine of \e azi0. + **********************************************************************/ + void EquatorialAzimuth(real& sazi0, real& cazi0) const + { if (Init()) { sazi0 = _salp0; cazi0 = _calp0; } } /** * @return \e a1 the arc length (degrees) between the northward equatorial * crossing and point 1. + * + * The result lies in (−180°, 180°]. **********************************************************************/ - Math::real EquatorialArc() const throw() { - return Init() ? - atan2(_ssig1, _csig1) / Math::degree() : Math::NaN(); + Math::real EquatorialArc() const { + return Init() ? Math::atan2d(_ssig1, _csig1) : Math::NaN(); } /** * @return \e a the equatorial radius of the ellipsoid (meters). This is * the value inherited from the Geodesic object used in the constructor. **********************************************************************/ - Math::real MajorRadius() const throw() - { return Init() ? _a : Math::NaN(); } + Math::real MajorRadius() const + { return Init() ? _a : Math::NaN(); } /** * @return \e f the flattening of the ellipsoid. This is the value * inherited from the Geodesic object used in the constructor. **********************************************************************/ - Math::real Flattening() const throw() - { return Init() ? _f : Math::NaN(); } - - /// \cond SKIP - /** - * DEPRECATED - * @return \e r the inverse flattening of the ellipsoid. - **********************************************************************/ - Math::real InverseFlattening() const throw() - { return Init() ? 1/_f : Math::NaN(); } - /// \endcond + Math::real Flattening() const + { return Init() ? _f : Math::NaN(); } /** * @return \e caps the computational capabilities that this object was * constructed with. LATITUDE and AZIMUTH are always included. **********************************************************************/ - unsigned Capabilities() const throw() { return _caps; } + unsigned Capabilities() const { return _caps; } /** + * Test what capabilities are available. + * * @param[in] testcaps a set of bitor'ed GeodesicLine::mask values. * @return true if the GeodesicLine object has all these capabilities. **********************************************************************/ - bool Capabilities(unsigned testcaps) const throw() { + bool Capabilities(unsigned testcaps) const { testcaps &= OUT_ALL; return (_caps & testcaps) == testcaps; } + + /** + * The distance or arc length to point 3. + * + * @param[in] arcmode boolean flag determining the meaning of returned + * value. + * @return \e s13 if \e arcmode is false; \e a13 if \e arcmode is true. + **********************************************************************/ + Math::real GenDistance(bool arcmode) const + { return Init() ? (arcmode ? _a13 : _s13) : Math::NaN(); } + + /** + * @return \e s13, the distance to point 3 (meters). + **********************************************************************/ + Math::real Distance() const { return GenDistance(false); } + + /** + * @return \e a13, the arc length to point 3 (degrees). + **********************************************************************/ + Math::real Arc() const { return GenDistance(true); } ///@} }; diff --git a/gtsam/3rdparty/GeographicLib/include/GeographicLib/GeodesicLineExact.hpp b/gtsam/3rdparty/GeographicLib/include/GeographicLib/GeodesicLineExact.hpp index a2e19f845..c947fe3c6 100644 --- a/gtsam/3rdparty/GeographicLib/include/GeographicLib/GeodesicLineExact.hpp +++ b/gtsam/3rdparty/GeographicLib/include/GeographicLib/GeodesicLineExact.hpp @@ -2,9 +2,9 @@ * \file GeodesicLineExact.hpp * \brief Header for GeographicLib::GeodesicLineExact class * - * Copyright (c) Charles Karney (2012) and licensed under - * the MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ + * Copyright (c) Charles Karney (2012-2016) and licensed + * under the MIT/X11 License. For more information, see + * https://geographiclib.sourceforge.io/ **********************************************************************/ #if !defined(GEOGRAPHICLIB_GEODESICLINEEXACT_HPP) @@ -38,15 +38,26 @@ namespace GeographicLib { friend class GeodesicExact; static const int nC4_ = GeodesicExact::nC4_; + real tiny_; real _lat1, _lon1, _azi1; real _a, _f, _b, _c2, _f1, _e2, _salp0, _calp0, _k2, _salp1, _calp1, _ssig1, _csig1, _dn1, _stau1, _ctau1, _somg1, _comg1, _cchi1, _A4, _B41, _E0, _D0, _H0, _E1, _D1, _H1; + real _a13, _s13; real _C4a[nC4_]; // all the elements of _C4a are used EllipticFunction _E; unsigned _caps; + void LineInit(const GeodesicExact& g, + real lat1, real lon1, + real azi1, real salp1, real calp1, + unsigned caps); + GeodesicLineExact(const GeodesicExact& g, + real lat1, real lon1, + real azi1, real salp1, real calp1, + unsigned caps, bool arcmode, real s13_a13); + enum captype { CAP_NONE = GeodesicExact::CAP_NONE, CAP_E = GeodesicExact::CAP_E, @@ -54,7 +65,9 @@ namespace GeographicLib { CAP_H = GeodesicExact::CAP_H, CAP_C4 = GeodesicExact::CAP_C4, CAP_ALL = GeodesicExact::CAP_ALL, + CAP_MASK = GeodesicExact::CAP_MASK, OUT_ALL = GeodesicExact::OUT_ALL, + OUT_MASK = GeodesicExact::OUT_MASK, }; public: @@ -116,7 +129,13 @@ namespace GeographicLib { **********************************************************************/ AREA = GeodesicExact::AREA, /** - * All capabilities, calculate everything. + * Unroll \e lon2 in the direct calculation. + * @hideinitializer + **********************************************************************/ + LONG_UNROLL = GeodesicExact::LONG_UNROLL, + /** + * All capabilities, calculate everything. (LONG_UNROLL is not + * included in this mask.) * @hideinitializer **********************************************************************/ ALL = GeodesicExact::ALL, @@ -140,15 +159,14 @@ namespace GeographicLib { * possess, i.e., which quantities can be returned in calls to * GeodesicLine::Position. * - * \e lat1 should be in the range [−90°, 90°]; \e lon1 and \e - * azi1 should be in the range [−540°, 540°). + * \e lat1 should be in the range [−90°, 90°]. * * The GeodesicLineExact::mask values are * - \e caps |= GeodesicLineExact::LATITUDE for the latitude \e lat2; this * is added automatically; * - \e caps |= GeodesicLineExact::LONGITUDE for the latitude \e lon2; - * - \e caps |= GeodesicLineExact::AZIMUTH for the latitude \e azi2; this is - * added automatically; + * - \e caps |= GeodesicLineExact::AZIMUTH for the latitude \e azi2; this + * is added automatically; * - \e caps |= GeodesicLineExact::DISTANCE for the distance \e s12; * - \e caps |= GeodesicLineExact::REDUCEDLENGTH for the reduced length \e m12; @@ -167,8 +185,7 @@ namespace GeographicLib { * the limit ε → 0+. **********************************************************************/ GeodesicLineExact(const GeodesicExact& g, real lat1, real lon1, real azi1, - unsigned caps = ALL) - throw(); + unsigned caps = ALL); /** * A default constructor. If GeodesicLineExact::Position is called on the @@ -177,7 +194,7 @@ namespace GeographicLib { * GeodesicExact::Line. Use Init() to test whether object is still in this * uninitialized state. **********************************************************************/ - GeodesicLineExact() throw() : _caps(0U) {} + GeodesicLineExact() : _caps(0U) {} ///@} /** \name Position in terms of distance @@ -188,7 +205,7 @@ namespace GeographicLib { * Compute the position of point 2 which is a distance \e s12 (meters) * from point 1. * - * @param[in] s12 distance between point 1 and point 2 (meters); it can be + * @param[in] s12 distance from point 1 to point 2 (meters); it can be * signed. * @param[out] lat2 latitude of point 2 (degrees). * @param[out] lon2 longitude of point 2 (degrees); requires that the @@ -207,10 +224,10 @@ namespace GeographicLib { * @param[out] S12 area under the geodesic (meters2); requires * that the GeodesicLineExact object was constructed with \e caps |= * GeodesicLineExact::AREA. - * @return \e a12 arc length of between point 1 and point 2 (degrees). + * @return \e a12 arc length from point 1 to point 2 (degrees). * * The values of \e lon2 and \e azi2 returned are in the range - * [−180°, 180°). + * [−180°, 180°]. * * The GeodesicLineExact object \e must have been constructed with \e caps * |= GeodesicLineExact::DISTANCE_IN; otherwise Math::NaN() is returned and @@ -226,7 +243,7 @@ namespace GeographicLib { Math::real Position(real s12, real& lat2, real& lon2, real& azi2, real& m12, real& M12, real& M21, - real& S12) const throw() { + real& S12) const { real t; return GenPosition(false, s12, LATITUDE | LONGITUDE | AZIMUTH | @@ -237,7 +254,7 @@ namespace GeographicLib { /** * See the documentation for GeodesicLineExact::Position. **********************************************************************/ - Math::real Position(real s12, real& lat2, real& lon2) const throw() { + Math::real Position(real s12, real& lat2, real& lon2) const { real t; return GenPosition(false, s12, LATITUDE | LONGITUDE, @@ -248,7 +265,7 @@ namespace GeographicLib { * See the documentation for GeodesicLineExact::Position. **********************************************************************/ Math::real Position(real s12, real& lat2, real& lon2, - real& azi2) const throw() { + real& azi2) const { real t; return GenPosition(false, s12, LATITUDE | LONGITUDE | AZIMUTH, @@ -259,7 +276,7 @@ namespace GeographicLib { * See the documentation for GeodesicLineExact::Position. **********************************************************************/ Math::real Position(real s12, real& lat2, real& lon2, - real& azi2, real& m12) const throw() { + real& azi2, real& m12) const { real t; return GenPosition(false, s12, LATITUDE | LONGITUDE | @@ -272,7 +289,7 @@ namespace GeographicLib { **********************************************************************/ Math::real Position(real s12, real& lat2, real& lon2, real& azi2, real& M12, real& M21) - const throw() { + const { real t; return GenPosition(false, s12, LATITUDE | LONGITUDE | @@ -286,14 +303,13 @@ namespace GeographicLib { Math::real Position(real s12, real& lat2, real& lon2, real& azi2, real& m12, real& M12, real& M21) - const throw() { + const { real t; return GenPosition(false, s12, LATITUDE | LONGITUDE | AZIMUTH | REDUCEDLENGTH | GEODESICSCALE, lat2, lon2, azi2, t, m12, M12, M21, t); } - ///@} /** \name Position in terms of arc length @@ -304,14 +320,14 @@ namespace GeographicLib { * Compute the position of point 2 which is an arc length \e a12 (degrees) * from point 1. * - * @param[in] a12 arc length between point 1 and point 2 (degrees); it can + * @param[in] a12 arc length from point 1 to point 2 (degrees); it can * be signed. * @param[out] lat2 latitude of point 2 (degrees). * @param[out] lon2 longitude of point 2 (degrees); requires that the * GeodesicLineExact object was constructed with \e caps |= * GeodesicLineExact::LONGITUDE. * @param[out] azi2 (forward) azimuth at point 2 (degrees). - * @param[out] s12 distance between point 1 and point 2 (meters); requires + * @param[out] s12 distance from point 1 to point 2 (meters); requires * that the GeodesicLineExact object was constructed with \e caps |= * GeodesicLineExact::DISTANCE. * @param[out] m12 reduced length of geodesic (meters); requires that the @@ -328,7 +344,7 @@ namespace GeographicLib { * GeodesicLineExact::AREA. * * The values of \e lon2 and \e azi2 returned are in the range - * [−180°, 180°). + * [−180°, 180°]. * * Requesting a value which the GeodesicLineExact object is not capable of * computing is not an error; the corresponding argument will not be @@ -339,7 +355,7 @@ namespace GeographicLib { **********************************************************************/ void ArcPosition(real a12, real& lat2, real& lon2, real& azi2, real& s12, real& m12, real& M12, real& M21, - real& S12) const throw() { + real& S12) const { GenPosition(true, a12, LATITUDE | LONGITUDE | AZIMUTH | DISTANCE | REDUCEDLENGTH | GEODESICSCALE | AREA, @@ -350,7 +366,7 @@ namespace GeographicLib { * See the documentation for GeodesicLineExact::ArcPosition. **********************************************************************/ void ArcPosition(real a12, real& lat2, real& lon2) - const throw() { + const { real t; GenPosition(true, a12, LATITUDE | LONGITUDE, @@ -362,7 +378,7 @@ namespace GeographicLib { **********************************************************************/ void ArcPosition(real a12, real& lat2, real& lon2, real& azi2) - const throw() { + const { real t; GenPosition(true, a12, LATITUDE | LONGITUDE | AZIMUTH, @@ -373,7 +389,7 @@ namespace GeographicLib { * See the documentation for GeodesicLineExact::ArcPosition. **********************************************************************/ void ArcPosition(real a12, real& lat2, real& lon2, real& azi2, - real& s12) const throw() { + real& s12) const { real t; GenPosition(true, a12, LATITUDE | LONGITUDE | AZIMUTH | DISTANCE, @@ -384,7 +400,7 @@ namespace GeographicLib { * See the documentation for GeodesicLineExact::ArcPosition. **********************************************************************/ void ArcPosition(real a12, real& lat2, real& lon2, real& azi2, - real& s12, real& m12) const throw() { + real& s12, real& m12) const { real t; GenPosition(true, a12, LATITUDE | LONGITUDE | AZIMUTH | @@ -397,7 +413,7 @@ namespace GeographicLib { **********************************************************************/ void ArcPosition(real a12, real& lat2, real& lon2, real& azi2, real& s12, real& M12, real& M21) - const throw() { + const { real t; GenPosition(true, a12, LATITUDE | LONGITUDE | AZIMUTH | @@ -410,7 +426,7 @@ namespace GeographicLib { **********************************************************************/ void ArcPosition(real a12, real& lat2, real& lon2, real& azi2, real& s12, real& m12, real& M12, real& M21) - const throw() { + const { real t; GenPosition(true, a12, LATITUDE | LONGITUDE | AZIMUTH | @@ -428,8 +444,9 @@ namespace GeographicLib { * GeodesicLineExact::ArcPosition are defined in terms of this function. * * @param[in] arcmode boolean flag determining the meaning of the second - * parameter; if arcmode is false, then the GeodesicLineExact object must - * have been constructed with \e caps |= GeodesicLineExact::DISTANCE_IN. + * parameter; if \e arcmode is false, then the GeodesicLineExact object + * must have been constructed with \e caps |= + * GeodesicLineExact::DISTANCE_IN. * @param[in] s12_a12 if \e arcmode is false, this is the distance between * point 1 and point 2 (meters); otherwise it is the arc length between * point 1 and point 2 (degrees); it can be signed. @@ -440,7 +457,7 @@ namespace GeographicLib { * GeodesicLineExact object was constructed with \e caps |= * GeodesicLineExact::LONGITUDE. * @param[out] azi2 (forward) azimuth at point 2 (degrees). - * @param[out] s12 distance between point 1 and point 2 (meters); requires + * @param[out] s12 distance from point 1 to point 2 (meters); requires * that the GeodesicLineExact object was constructed with \e caps |= * GeodesicLineExact::DISTANCE. * @param[out] m12 reduced length of geodesic (meters); requires that the @@ -455,7 +472,7 @@ namespace GeographicLib { * @param[out] S12 area under the geodesic (meters2); requires * that the GeodesicLineExact object was constructed with \e caps |= * GeodesicLineExact::AREA. - * @return \e a12 arc length of between point 1 and point 2 (degrees). + * @return \e a12 arc length from point 1 to point 2 (degrees). * * The GeodesicLineExact::mask values possible for \e outmask are * - \e outmask |= GeodesicLineExact::LATITUDE for the latitude \e lat2; @@ -467,20 +484,64 @@ namespace GeographicLib { * - \e outmask |= GeodesicLineExact::GEODESICSCALE for the geodesic scales * \e M12 and \e M21; * - \e outmask |= GeodesicLineExact::AREA for the area \e S12; - * - \e outmask |= GeodesicLine::ALL for all of the above. + * - \e outmask |= GeodesicLineExact::ALL for all of the above; + * - \e outmask |= GeodesicLineExact::LONG_UNROLL to unroll \e lon2 instead + * of wrapping it into the range [−180°, 180°]. * . * Requesting a value which the GeodesicLineExact object is not capable of * computing is not an error; the corresponding argument will not be * altered. Note, however, that the arc length is always computed and * returned as the function value. + * + * With the GeodesicLineExact::LONG_UNROLL bit set, the quantity \e lon2 + * − \e lon1 indicates how many times and in what sense the geodesic + * encircles the ellipsoid. **********************************************************************/ Math::real GenPosition(bool arcmode, real s12_a12, unsigned outmask, real& lat2, real& lon2, real& azi2, real& s12, real& m12, real& M12, real& M21, - real& S12) const throw(); - + real& S12) const; ///@} + /** \name Setting point 3 + **********************************************************************/ + ///@{ + + /** + * Specify position of point 3 in terms of distance. + * + * @param[in] s13 the distance from point 1 to point 3 (meters); it + * can be negative. + * + * This is only useful if the GeodesicLineExact object has been constructed + * with \e caps |= GeodesicLineExact::DISTANCE_IN. + **********************************************************************/ + void SetDistance(real s13); + + /** + * Specify position of point 3 in terms of arc length. + * + * @param[in] a13 the arc length from point 1 to point 3 (degrees); it + * can be negative. + * + * The distance \e s13 is only set if the GeodesicLineExact object has been + * constructed with \e caps |= GeodesicLineExact::DISTANCE. + **********************************************************************/ + void SetArc(real a13); + + /** + * Specify position of point 3 in terms of either distance or arc length. + * + * @param[in] arcmode boolean flag determining the meaning of the second + * parameter; if \e arcmode is false, then the GeodesicLineExact object + * must have been constructed with \e caps |= + * GeodesicLineExact::DISTANCE_IN. + * @param[in] s13_a13 if \e arcmode is false, this is the distance from + * point 1 to point 3 (meters); otherwise it is the arc length from + * point 1 to point 3 (degrees); it can be negative. + **********************************************************************/ + void GenSetDistance(bool arcmode, real s13_a13); + /** \name Inspector functions **********************************************************************/ ///@{ @@ -488,42 +549,62 @@ namespace GeographicLib { /** * @return true if the object has been initialized. **********************************************************************/ - bool Init() const throw() { return _caps != 0U; } + bool Init() const { return _caps != 0U; } /** * @return \e lat1 the latitude of point 1 (degrees). **********************************************************************/ - Math::real Latitude() const throw() - { return Init() ? _lat1 : Math::NaN(); } + Math::real Latitude() const + { return Init() ? _lat1 : Math::NaN(); } /** * @return \e lon1 the longitude of point 1 (degrees). **********************************************************************/ - Math::real Longitude() const throw() - { return Init() ? _lon1 : Math::NaN(); } + Math::real Longitude() const + { return Init() ? _lon1 : Math::NaN(); } /** * @return \e azi1 the azimuth (degrees) of the geodesic line at point 1. **********************************************************************/ - Math::real Azimuth() const throw() - { return Init() ? _azi1 : Math::NaN(); } + Math::real Azimuth() const + { return Init() ? _azi1 : Math::NaN(); } + + /** + * The sine and cosine of \e azi1. + * + * @param[out] sazi1 the sine of \e azi1. + * @param[out] cazi1 the cosine of \e azi1. + **********************************************************************/ + void Azimuth(real& sazi1, real& cazi1) const + { if (Init()) { sazi1 = _salp1; cazi1 = _calp1; } } /** * @return \e azi0 the azimuth (degrees) of the geodesic line as it crosses - * the equator in a northward direction. + * the equator in a northward direction. + * + * The result lies in [−90°, 90°]. **********************************************************************/ - Math::real EquatorialAzimuth() const throw() { - return Init() ? - atan2(_salp0, _calp0) / Math::degree() : Math::NaN(); - } + Math::real EquatorialAzimuth() const + { return Init() ? Math::atan2d(_salp0, _calp0) : Math::NaN(); } + + /** + * The sine and cosine of \e azi0. + * + * @param[out] sazi0 the sine of \e azi0. + * @param[out] cazi0 the cosine of \e azi0. + **********************************************************************/ + void EquatorialAzimuth(real& sazi0, real& cazi0) const + { if (Init()) { sazi0 = _salp0; cazi0 = _calp0; } } /** * @return \e a1 the arc length (degrees) between the northward equatorial - * crossing and point 1. + * crossing and point 1. + * + * The result lies in (−180°, 180°]. **********************************************************************/ - Math::real EquatorialArc() const throw() { - return Init() ? - atan2(_ssig1, _csig1) / Math::degree() : Math::NaN(); + Math::real EquatorialArc() const { + using std::atan2; + return Init() ? atan2(_ssig1, _csig1) / Math::degree() : Math::NaN(); } /** @@ -531,39 +612,52 @@ namespace GeographicLib { * the value inherited from the GeodesicExact object used in the * constructor. **********************************************************************/ - Math::real MajorRadius() const throw() - { return Init() ? _a : Math::NaN(); } + Math::real MajorRadius() const + { return Init() ? _a : Math::NaN(); } /** * @return \e f the flattening of the ellipsoid. This is the value * inherited from the GeodesicExact object used in the constructor. **********************************************************************/ - Math::real Flattening() const throw() - { return Init() ? _f : Math::NaN(); } - - /// \cond SKIP - /** - * DEPRECATED - * @return \e r the inverse flattening of the ellipsoid. - **********************************************************************/ - Math::real InverseFlattening() const throw() - { return Init() ? 1/_f : Math::NaN(); } - /// \endcond + Math::real Flattening() const + { return Init() ? _f : Math::NaN(); } /** * @return \e caps the computational capabilities that this object was * constructed with. LATITUDE and AZIMUTH are always included. **********************************************************************/ - unsigned Capabilities() const throw() { return _caps; } + unsigned Capabilities() const { return _caps; } /** + * Test what capabilities are available. + * * @param[in] testcaps a set of bitor'ed GeodesicLineExact::mask values. * @return true if the GeodesicLineExact object has all these capabilities. **********************************************************************/ - bool Capabilities(unsigned testcaps) const throw() { + bool Capabilities(unsigned testcaps) const { testcaps &= OUT_ALL; return (_caps & testcaps) == testcaps; } + + /** + * The distance or arc length to point 3. + * + * @param[in] arcmode boolean flag determining the meaning of returned + * value. + * @return \e s13 if \e arcmode is false; \e a13 if \e arcmode is true. + **********************************************************************/ + Math::real GenDistance(bool arcmode) const + { return Init() ? (arcmode ? _a13 : _s13) : Math::NaN(); } + + /** + * @return \e s13, the distance to point 3 (meters). + **********************************************************************/ + Math::real Distance() const { return GenDistance(false); } + + /** + * @return \e a13, the arc length to point 3 (degrees). + **********************************************************************/ + Math::real Arc() const { return GenDistance(true); } ///@} }; diff --git a/gtsam/3rdparty/GeographicLib/include/GeographicLib/Geohash.hpp b/gtsam/3rdparty/GeographicLib/include/GeographicLib/Geohash.hpp index 0533afcd5..d7d1d8acf 100644 --- a/gtsam/3rdparty/GeographicLib/include/GeographicLib/Geohash.hpp +++ b/gtsam/3rdparty/GeographicLib/include/GeographicLib/Geohash.hpp @@ -2,9 +2,9 @@ * \file Geohash.hpp * \brief Header for GeographicLib::Geohash class * - * Copyright (c) Charles Karney (2012) and licensed under - * the MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ + * Copyright (c) Charles Karney (2012-2017) and licensed + * under the MIT/X11 License. For more information, see + * https://geographiclib.sourceforge.io/ **********************************************************************/ #if !defined(GEOGRAPHICLIB_GEOHASH_HPP) @@ -24,13 +24,14 @@ namespace GeographicLib { * \brief Conversions for geohashes * * Geohashes are described in - * - http://en.wikipedia.org/wiki/Geohash + * - https://en.wikipedia.org/wiki/Geohash * - http://geohash.org/ * . * They provide a compact string representation of a particular geographic * location (expressed as latitude and longitude), with the property that if * trailing characters are dropped from the string the geographic location - * remains nearby. + * remains nearby. The classes Georef and GARS implement similar compact + * representations. * * Example of use: * \include example-Geohash.cpp @@ -41,12 +42,8 @@ namespace GeographicLib { typedef Math::real real; static const int maxlen_ = 18; static const unsigned long long mask_ = 1ULL << 45; - static const int decprec_[]; - static const real loneps_; - static const real lateps_; - static const real shift_; - static const std::string lcdigits_; - static const std::string ucdigits_; + static const char* const lcdigits_; + static const char* const ucdigits_; Geohash(); // Disable constructor public: @@ -58,15 +55,14 @@ namespace GeographicLib { * @param[in] lon longitude of point (degrees). * @param[in] len the length of the resulting geohash. * @param[out] geohash the geohash. - * @exception GeographicErr if \e la is not in [−90°, + * @exception GeographicErr if \e lat is not in [−90°, * 90°]. - * @exception GeographicErr if \e lon is not in [−540°, - * 540°). * @exception std::bad_alloc if memory for \e geohash can't be allocated. * - * Internally, \e len is first put in the range [0, 18]. + * Internally, \e len is first put in the range [0, 18]. (\e len = 18 + * provides approximately 1μm precision.) * - * If \e lat or \e lon is NaN, the returned geohash is "nan". + * If \e lat or \e lon is NaN, the returned geohash is "invalid". **********************************************************************/ static void Forward(real lat, real lon, int len, std::string& geohash); @@ -81,11 +77,13 @@ namespace GeographicLib { * geohash location, otherwise return the south-west corner. * @exception GeographicErr if \e geohash contains illegal characters. * - * Only the first 18 characters for \e geohash are considered. The case of - * the letters in \e geohash is ignored. + * Only the first 18 characters for \e geohash are considered. (18 + * characters provides approximately 1μm precision.) The case of the + * letters in \e geohash is ignored. * - * If the first three characters in \e geohash are "nan", then \e lat and - * \e lon are set to NaN. + * If the first 3 characters of \e geohash are "inv", then \e lat and \e + * lon are set to NaN and \e len is unchanged. ("nan" is treated + * similarly.) **********************************************************************/ static void Reverse(const std::string& geohash, real& lat, real& lon, int& len, bool centerp = true); @@ -98,9 +96,10 @@ namespace GeographicLib { * * Internally, \e len is first put in the range [0, 18]. **********************************************************************/ - static Math::real LatitudeResolution(int len) throw() { + static Math::real LatitudeResolution(int len) { + using std::ldexp; len = (std::max)(0, (std::min)(int(maxlen_), len)); - return 180 * std::pow(0.5, 5 * len / 2); + return ldexp(real(180), -(5 * len / 2)); } /** @@ -111,9 +110,10 @@ namespace GeographicLib { * * Internally, \e len is first put in the range [0, 18]. **********************************************************************/ - static Math::real LongitudeResolution(int len) throw() { + static Math::real LongitudeResolution(int len) { + using std::ldexp; len = (std::max)(0, (std::min)(int(maxlen_), len)); - return 360 * std::pow(0.5, 5 * len - 5 * len / 2); + return ldexp(real(360), -(5 * len - 5 * len / 2)); } /** @@ -125,8 +125,8 @@ namespace GeographicLib { * * The returned length is in the range [0, 18]. **********************************************************************/ - static int GeohashLength(real res) throw() { - res = std::abs(res); + static int GeohashLength(real res) { + using std::abs; res = abs(res); for (int len = 0; len < maxlen_; ++len) if (LongitudeResolution(len) <= res) return len; @@ -142,9 +142,10 @@ namespace GeographicLib { * * The returned length is in the range [0, 18]. **********************************************************************/ - static int GeohashLength(real latres, real lonres) throw() { - latres = std::abs(latres); - lonres = std::abs(lonres); + static int GeohashLength(real latres, real lonres) { + using std::abs; + latres = abs(latres); + lonres = abs(lonres); for (int len = 0; len < maxlen_; ++len) if (LatitudeResolution(len) <= latres && LongitudeResolution(len) <= lonres) @@ -163,9 +164,9 @@ namespace GeographicLib { * Internally, \e len is first put in the range [0, 18]. The returned * decimal precision is in the range [−2, 12]. **********************************************************************/ - static int DecimalPrecision(int len) throw() { - return -int(std::floor(std::log(LatitudeResolution(len))/ - std::log(Math::real(10)))); + static int DecimalPrecision(int len) { + using std::floor; using std::log; + return -int(floor(log(LatitudeResolution(len))/log(Math::real(10)))); } }; diff --git a/gtsam/3rdparty/GeographicLib/include/GeographicLib/Geoid.hpp b/gtsam/3rdparty/GeographicLib/include/GeographicLib/Geoid.hpp index 0a4537206..75723675f 100644 --- a/gtsam/3rdparty/GeographicLib/include/GeographicLib/Geoid.hpp +++ b/gtsam/3rdparty/GeographicLib/include/GeographicLib/Geoid.hpp @@ -2,9 +2,9 @@ * \file Geoid.hpp * \brief Header for GeographicLib::Geoid class * - * Copyright (c) Charles Karney (2009-2012) and licensed + * Copyright (c) Charles Karney (2009-2015) and licensed * under the MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #if !defined(GEOGRAPHICLIB_GEOID_HPP) @@ -20,7 +20,7 @@ # pragma warning (disable: 4251 4127) #endif -#if !defined(PGM_PIXEL_WIDTH) +#if !defined(GEOGRAPHICLIB_GEOID_PGM_PIXEL_WIDTH) /** * The size of the pixel data in the pgm data files for the geoids. 2 is the * standard size corresponding to a maxval 216−1. Setting it @@ -28,15 +28,15 @@ * the data files from .pgm to .pgm4. Note that the format of these pgm4 files * is a non-standard extension of the pgm format. **********************************************************************/ -# define PGM_PIXEL_WIDTH 2 +# define GEOGRAPHICLIB_GEOID_PGM_PIXEL_WIDTH 2 #endif namespace GeographicLib { /** - * \brief Looking up the height of the geoid + * \brief Looking up the height of the geoid above the ellipsoid * - * This class evaluated the height of one of the standard geoids, EGM84, + * This class evaluates the height of one of the standard geoids, EGM84, * EGM96, or EGM2008 by bilinear or cubic interpolation into a rectangular * grid of data. These geoid models are documented in * - EGM84: @@ -51,18 +51,17 @@ namespace GeographicLib { * this class evaluates the height by interpolation into a grid of * precomputed values. * + * The height of the geoid above the ellipsoid, \e N, is sometimes called the + * geoid undulation. It can be used to convert a height above the ellipsoid, + * \e h, to the corresponding height above the geoid (the orthometric height, + * roughly the height above mean sea level), \e H, using the relations + * + *    \e h = \e N + \e H; + *   \e H = −\e N + \e h. + * * See \ref geoid for details of how to install the data sets, the data * format, estimates of the interpolation errors, and how to use caching. * - * In addition to returning the geoid height, the gradient of the geoid can - * be calculated. The gradient is defined as the rate of change of the geoid - * as a function of position on the ellipsoid. This uses the parameters for - * the WGS84 ellipsoid. The gradient defined in terms of the interpolated - * heights. As a result of the way that the geoid data is stored, the - * calculation of gradients can result in large quantization errors. This is - * particularly acute for fine grids, at high latitudes, and for the easterly - * gradient. - * * This class is typically \e not thread safe in that a single instantiation * cannot be safely used by multiple threads because of the way the object * reads the data set and because it maintains a single-cell cache. If @@ -83,7 +82,7 @@ namespace GeographicLib { class GEOGRAPHICLIB_EXPORT Geoid { private: typedef Math::real real; -#if PGM_PIXEL_WIDTH != 4 +#if GEOGRAPHICLIB_GEOID_PGM_PIXEL_WIDTH != 4 typedef unsigned short pixel_t; static const unsigned pixel_size_ = 2; static const unsigned pixel_max_ = 0xffffu; @@ -94,12 +93,12 @@ namespace GeographicLib { #endif static const unsigned stencilsize_ = 12; static const unsigned nterms_ = ((3 + 1) * (3 + 2))/2; // for a cubic fit - static const real c0_; - static const real c0n_; - static const real c0s_; - static const real c3_[stencilsize_ * nterms_]; - static const real c3n_[stencilsize_ * nterms_]; - static const real c3s_[stencilsize_ * nterms_]; + static const int c0_; + static const int c0n_; + static const int c0s_; + static const int c3_[stencilsize_ * nterms_]; + static const int c3n_[stencilsize_ * nterms_]; + static const int c3s_[stencilsize_ * nterms_]; std::string _name, _dir, _filename; const bool _cubic; @@ -146,7 +145,8 @@ namespace GeographicLib { } try { filepos(ix, iy); - char a, b; + // initial values to suppress warnings in case get fails + char a = 0, b = 0; _file.get(a); _file.get(b); unsigned r = ((unsigned char)(a) << 8) | (unsigned char)(b); @@ -170,8 +170,7 @@ namespace GeographicLib { } } } - real height(real lat, real lon, bool gradp, - real& grade, real& gradn) const; + real height(real lat, real lon) const; Geoid(const Geoid&); // copy constructor not allowed Geoid& operator=(const Geoid&); // copy assignment not allowed public: @@ -227,9 +226,11 @@ namespace GeographicLib { /** * Set up a cache. * - * @param[in] south latitude (degrees) of the south edge of the cached area. + * @param[in] south latitude (degrees) of the south edge of the cached + * area. * @param[in] west longitude (degrees) of the west edge of the cached area. - * @param[in] north latitude (degrees) of the north edge of the cached area. + * @param[in] north latitude (degrees) of the north edge of the cached + * area. * @param[in] east longitude (degrees) of the east edge of the cached area. * @exception GeographicErr if the memory necessary for caching the data * can't be allocated (in this case, you will have no cache and can try @@ -241,8 +242,7 @@ namespace GeographicLib { * parallels \e south and \e north and the meridians \e west and \e east. * \e east is always interpreted as being east of \e west, if necessary by * adding 360° to its value. \e south and \e north should be in - * the range [−90°, 90°]; \e west and \e east should - * be in the range [−540°, 540°). + * the range [−90°, 90°]. **********************************************************************/ void CacheArea(real south, real west, real north, real east) const; @@ -266,7 +266,7 @@ namespace GeographicLib { * Clear the cache. This never throws an error. (This does nothing with a * thread safe Geoid.) **********************************************************************/ - void CacheClear() const throw(); + void CacheClear() const; ///@} @@ -279,38 +279,14 @@ namespace GeographicLib { * @param[in] lat latitude of the point (degrees). * @param[in] lon longitude of the point (degrees). * @exception GeographicErr if there's a problem reading the data; this - * never happens if (\e lat, \e lon) is within a successfully cached area. - * @return geoid height (meters). + * never happens if (\e lat, \e lon) is within a successfully cached + * area. + * @return the height of the geoid above the ellipsoid (meters). * - * The latitude should be in [−90°, 90°] and - * longitude should be in [−540°, 540°). + * The latitude should be in [−90°, 90°]. **********************************************************************/ Math::real operator()(real lat, real lon) const { - real gradn, grade; - return height(lat, lon, false, gradn, grade); - } - - /** - * Compute the geoid height and gradient at a point - * - * @param[in] lat latitude of the point (degrees). - * @param[in] lon longitude of the point (degrees). - * @param[out] gradn northerly gradient (dimensionless). - * @param[out] grade easterly gradient (dimensionless). - * @exception GeographicErr if there's a problem reading the data; this - * never happens if (\e lat, \e lon) is within a successfully cached area. - * @return geoid height (meters). - * - * The latitude should be in [−90°, 90°] and - * longitude should be in [−540°, 540°). As a result - * of the way that the geoid data is stored, the calculation of gradients - * can result in large quantization errors. This is particularly acute for - * fine grids, at high latitudes, and for the easterly gradient. If you - * need to compute the direction of the acceleration due to gravity - * accurately, you should use GravityModel::Gravity. - **********************************************************************/ - Math::real operator()(real lat, real lon, real& gradn, real& grade) const { - return height(lat, lon, true, gradn, grade); + return height(lat, lon); } /** @@ -325,13 +301,13 @@ namespace GeographicLib { * geoid to a height above the ellipsoid; Geoid::ELLIPSOIDTOGEOID means * convert a height above the ellipsoid to a height above the geoid. * @exception GeographicErr if there's a problem reading the data; this - * never happens if (\e lat, \e lon) is within a successfully cached area. + * never happens if (\e lat, \e lon) is within a successfully cached + * area. * @return converted height (meters). **********************************************************************/ Math::real ConvertHeight(real lat, real lon, real h, convertflag d) const { - real gradn, grade; - return h + real(d) * height(lat, lon, true, gradn, grade); + return h + real(d) * height(lat, lon); } ///@} @@ -343,28 +319,28 @@ namespace GeographicLib { * @return geoid description, if available, in the data file; if * absent, return "NONE". **********************************************************************/ - const std::string& Description() const throw() { return _description; } + const std::string& Description() const { return _description; } /** * @return date of the data file; if absent, return "UNKNOWN". **********************************************************************/ - const std::string& DateTime() const throw() { return _datetime; } + const std::string& DateTime() const { return _datetime; } /** * @return full file name used to load the geoid data. **********************************************************************/ - const std::string& GeoidFile() const throw() { return _filename; } + const std::string& GeoidFile() const { return _filename; } /** * @return "name" used to load the geoid data (from the first argument of * the constructor). **********************************************************************/ - const std::string& GeoidName() const throw() { return _name; } + const std::string& GeoidName() const { return _name; } /** * @return directory used to load the geoid data. **********************************************************************/ - const std::string& GeoidDirectory() const throw() { return _dir; } + const std::string& GeoidDirectory() const { return _dir; } /** * @return interpolation method ("cubic" or "bilinear"). @@ -379,7 +355,7 @@ namespace GeographicLib { * This relies on the value being stored in the data file. If the value is * absent, return −1. **********************************************************************/ - Math::real MaxError() const throw() { return _maxerror; } + Math::real MaxError() const { return _maxerror; } /** * @return estimate of the RMS interpolation and quantization error @@ -388,7 +364,7 @@ namespace GeographicLib { * This relies on the value being stored in the data file. If the value is * absent, return −1. **********************************************************************/ - Math::real RMSError() const throw() { return _rmserror; } + Math::real RMSError() const { return _rmserror; } /** * @return offset (meters). @@ -396,7 +372,7 @@ namespace GeographicLib { * This in used in converting from the pixel values in the data file to * geoid heights. **********************************************************************/ - Math::real Offset() const throw() { return _offset; } + Math::real Offset() const { return _offset; } /** * @return scale (meters). @@ -404,22 +380,22 @@ namespace GeographicLib { * This in used in converting from the pixel values in the data file to * geoid heights. **********************************************************************/ - Math::real Scale() const throw() { return _scale; } + Math::real Scale() const { return _scale; } /** * @return true if the object is constructed to be thread safe. **********************************************************************/ - bool ThreadSafe() const throw() { return _threadsafe; } + bool ThreadSafe() const { return _threadsafe; } /** * @return true if a data cache is active. **********************************************************************/ - bool Cache() const throw() { return _cache; } + bool Cache() const { return _cache; } /** * @return west edge of the cached area; the cache includes this edge. **********************************************************************/ - Math::real CacheWest() const throw() { + Math::real CacheWest() const { return _cache ? ((_xoffset + (_xsize == _width ? 0 : _cubic) + _width/2) % _width - _width/2) / _rlonres : 0; @@ -428,7 +404,7 @@ namespace GeographicLib { /** * @return east edge of the cached area; the cache excludes this edge. **********************************************************************/ - Math::real CacheEast() const throw() { + Math::real CacheEast() const { return _cache ? CacheWest() + (_xsize - (_xsize == _width ? 0 : 1 + 2 * _cubic)) / _rlonres : @@ -438,7 +414,7 @@ namespace GeographicLib { /** * @return north edge of the cached area; the cache includes this edge. **********************************************************************/ - Math::real CacheNorth() const throw() { + Math::real CacheNorth() const { return _cache ? 90 - (_yoffset + _cubic) / _rlatres : 0; } @@ -446,7 +422,7 @@ namespace GeographicLib { * @return south edge of the cached area; the cache excludes this edge * unless it's the south pole. **********************************************************************/ - Math::real CacheSouth() const throw() { + Math::real CacheSouth() const { return _cache ? 90 - ( _yoffset + _ysize - 1 - _cubic) / _rlatres : 0; } @@ -456,8 +432,8 @@ namespace GeographicLib { * (The WGS84 value is returned because the supported geoid models are all * based on this ellipsoid.) **********************************************************************/ - Math::real MajorRadius() const throw() - { return Constants::WGS84_a(); } + Math::real MajorRadius() const + { return Constants::WGS84_a(); } /** * @return \e f the flattening of the WGS84 ellipsoid. @@ -465,37 +441,27 @@ namespace GeographicLib { * (The WGS84 value is returned because the supported geoid models are all * based on this ellipsoid.) **********************************************************************/ - Math::real Flattening() const throw() { return Constants::WGS84_f(); } + Math::real Flattening() const { return Constants::WGS84_f(); } ///@} - /// \cond SKIP - /** - * DEPRECATED - * @return \e r the inverse flattening of the WGS84 ellipsoid. - **********************************************************************/ - Math::real InverseFlattening() const throw() - { return 1/Constants::WGS84_f(); } - /// \endcond - /** * @return the default path for geoid data files. * - * This is the value of the environment variable GEOID_PATH, if set; - * otherwise, it is $GEOGRAPHICLIB_DATA/geoids if the environment variable - * GEOGRAPHICLIB_DATA is set; otherwise, it is a compile-time default - * (/usr/local/share/GeographicLib/geoids on non-Windows systems and - * C:/Documents and Settings/All Users/Application - * Data/GeographicLib/geoids on Windows systems). + * This is the value of the environment variable GEOGRAPHICLIB_GEOID_PATH, + * if set; otherwise, it is $GEOGRAPHICLIB_DATA/geoids if the environment + * variable GEOGRAPHICLIB_DATA is set; otherwise, it is a compile-time + * default (/usr/local/share/GeographicLib/geoids on non-Windows systems + * and C:/ProgramData/GeographicLib/geoids on Windows systems). **********************************************************************/ static std::string DefaultGeoidPath(); /** * @return the default name for the geoid. * - * This is the value of the environment variable GEOID_NAME, if set, - * otherwise, it is "egm96-5". The Geoid class does not use this function; - * it is just provided as a convenience for a calling program when - * constructing a Geoid object. + * This is the value of the environment variable GEOGRAPHICLIB_GEOID_NAME, + * if set; otherwise, it is "egm96-5". The Geoid class does not use this + * function; it is just provided as a convenience for a calling program + * when constructing a Geoid object. **********************************************************************/ static std::string DefaultGeoidName(); diff --git a/gtsam/3rdparty/GeographicLib/include/GeographicLib/Georef.hpp b/gtsam/3rdparty/GeographicLib/include/GeographicLib/Georef.hpp new file mode 100644 index 000000000..726b5d5a5 --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/include/GeographicLib/Georef.hpp @@ -0,0 +1,161 @@ +/** + * \file Georef.hpp + * \brief Header for GeographicLib::Georef class + * + * Copyright (c) Charles Karney (2015-2017) and licensed + * under the MIT/X11 License. For more information, see + * https://geographiclib.sourceforge.io/ + **********************************************************************/ + +#if !defined(GEOGRAPHICLIB_GEOREF_HPP) +#define GEOGRAPHICLIB_GEOREF_HPP 1 + +#include + +#if defined(_MSC_VER) +// Squelch warnings about dll vs string +# pragma warning (push) +# pragma warning (disable: 4251) +#endif + +namespace GeographicLib { + + /** + * \brief Conversions for the World Geographic Reference System (georef) + * + * The World Geographic Reference System is described in + * - https://en.wikipedia.org/wiki/Georef + * - http://earth-info.nga.mil/GandG/coordsys/grids/georef.pdf + * . + * It provides a compact string representation of a geographic area + * (expressed as latitude and longitude). The classes GARS and Geohash + * implement similar compact representations. + * + * Example of use: + * \include example-Georef.cpp + **********************************************************************/ + + class GEOGRAPHICLIB_EXPORT Georef { + private: + typedef Math::real real; + static const char* const digits_; + static const char* const lontile_; + static const char* const lattile_; + static const char* const degrees_; + enum { + tile_ = 15, // The size of tile in degrees + lonorig_ = -180, // Origin for longitude + latorig_ = -90, // Origin for latitude + base_ = 10, // Base for minutes + baselen_ = 4, + maxprec_ = 11, // approximately equivalent to MGRS class + maxlen_ = baselen_ + 2 * maxprec_, + }; + Georef(); // Disable constructor + + public: + + /** + * Convert from geographic coordinates to georef. + * + * @param[in] lat latitude of point (degrees). + * @param[in] lon longitude of point (degrees). + * @param[in] prec the precision of the resulting georef. + * @param[out] georef the georef string. + * @exception GeographicErr if \e lat is not in [−90°, + * 90°]. + * @exception std::bad_alloc if memory for \e georef can't be allocated. + * + * \e prec specifies the precision of \e georef as follows: + * - \e prec = −1 (min), 15° + * - \e prec = 0, 1° + * - \e prec = 1, converted to \e prec = 2 + * - \e prec = 2, 1' + * - \e prec = 3, 0.1' + * - \e prec = 4, 0.01' + * - \e prec = 5, 0.001' + * - … + * - \e prec = 11 (max), 10−9' + * + * If \e lat or \e lon is NaN, then \e georef is set to "INVALID". + **********************************************************************/ + static void Forward(real lat, real lon, int prec, std::string& georef); + + /** + * Convert from Georef to geographic coordinates. + * + * @param[in] georef the Georef. + * @param[out] lat latitude of point (degrees). + * @param[out] lon longitude of point (degrees). + * @param[out] prec the precision of \e georef. + * @param[in] centerp if true (the default) return the center + * \e georef, otherwise return the south-west corner. + * @exception GeographicErr if \e georef is illegal. + * + * The case of the letters in \e georef is ignored. \e prec is in the + * range [−1, 11] and gives the precision of \e georef as follows: + * - \e prec = −1 (min), 15° + * - \e prec = 0, 1° + * - \e prec = 1, not returned + * - \e prec = 2, 1' + * - \e prec = 3, 0.1' + * - \e prec = 4, 0.01' + * - \e prec = 5, 0.001' + * - … + * - \e prec = 11 (max), 10−9' + * + * If the first 3 characters of \e georef are "INV", then \e lat and \e lon + * are set to NaN and \e prec is unchanged. + **********************************************************************/ + static void Reverse(const std::string& georef, real& lat, real& lon, + int& prec, bool centerp = true); + + /** + * The angular resolution of a Georef. + * + * @param[in] prec the precision of the Georef. + * @return the latitude-longitude resolution (degrees). + * + * Internally, \e prec is first put in the range [−1, 11]. + **********************************************************************/ + static Math::real Resolution(int prec) { + if (prec < 1) + return real(prec < 0 ? 15 : 1); + else { + using std::pow; + // Treat prec = 1 as 2. + prec = (std::max)(2, (std::min)(int(maxprec_), prec)); + // Need extra real because, since C++11, pow(float, int) returns double + return 1/(60 * real(pow(real(base_), prec - 2))); + } + } + + /** + * The Georef precision required to meet a given geographic resolution. + * + * @param[in] res the minimum of resolution in latitude and longitude + * (degrees). + * @return Georef precision. + * + * The returned length is in the range [0, 11]. + **********************************************************************/ + static int Precision(real res) { + using std::abs; res = abs(res); + for (int prec = 0; prec < maxprec_; ++prec) { + if (prec == 1) + continue; + if (Resolution(prec) <= res) + return prec; + } + return maxprec_; + } + + }; + +} // namespace GeographicLib + +#if defined(_MSC_VER) +# pragma warning (pop) +#endif + +#endif // GEOGRAPHICLIB_GEOREF_HPP diff --git a/gtsam/3rdparty/GeographicLib/include/GeographicLib/Gnomonic.hpp b/gtsam/3rdparty/GeographicLib/include/GeographicLib/Gnomonic.hpp index 4b41d4ad5..6bc2d2209 100644 --- a/gtsam/3rdparty/GeographicLib/include/GeographicLib/Gnomonic.hpp +++ b/gtsam/3rdparty/GeographicLib/include/GeographicLib/Gnomonic.hpp @@ -2,9 +2,9 @@ * \file Gnomonic.hpp * \brief Header for GeographicLib::Gnomonic class * - * Copyright (c) Charles Karney (2010-2011) and licensed + * Copyright (c) Charles Karney (2010-2016) and licensed * under the MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #if !defined(GEOGRAPHICLIB_GNOMONIC_HPP) @@ -22,12 +22,13 @@ namespace GeographicLib { * %Gnomonic projection centered at an arbitrary position \e C on the * ellipsoid. This projection is derived in Section 8 of * - C. F. F. Karney, - * + * * Algorithms for geodesics, * J. Geodesy 87, 43--55 (2013); - * DOI: + * DOI: * 10.1007/s00190-012-0578-z; - * addenda: + * addenda: + * * geod-addenda.html. * . * The projection of \e P is defined as follows: compute the geodesic line @@ -66,9 +67,9 @@ namespace GeographicLib { * (r/2a)3 \e r. * * The conversions all take place using a Geodesic object (by default - * Geodesic::WGS84). For more information on geodesics see \ref geodesic. + * Geodesic::WGS84()). For more information on geodesics see \ref geodesic. * - * CAUTION: The definition of this projection for a sphere is + * \warning The definition of this projection for a sphere is * standard. However, there is no standard for how it should be extended to * an ellipsoid. The choices are: * - Declare that the projection is undefined for an ellipsoid. @@ -82,9 +83,9 @@ namespace GeographicLib { * sphere at the center point. This causes normal sections through the * center point to appear as straight lines in the projection; i.e., it * generalizes the spherical great circle to a normal section. This was - * proposed by I. G. Letoval'tsev, Generalization of the %Gnomonic - * Projection for a Spheroid and the Principal Geodetic Problems Involved - * in the Alignment of Surface Routes, Geodesy and Aerophotography (5), + * proposed by I. G. Letoval'tsev, Generalization of the gnomonic + * projection for a spheroid and the principal geodetic problems involved + * in the alignment of surface routes, Geodesy and Aerophotography (5), * 271--274 (1963). * - The projection given here. This causes geodesics close to the center * point to appear as straight lines in the projection; i.e., it @@ -101,10 +102,9 @@ namespace GeographicLib { class GEOGRAPHICLIB_EXPORT Gnomonic { private: typedef Math::real real; + real eps0_, eps_; Geodesic _earth; real _a, _f; - static const real eps0_; - static const real eps_; static const int numit_ = 10; public: @@ -114,12 +114,7 @@ namespace GeographicLib { * @param[in] earth the Geodesic object to use for geodesic calculations. * By default this uses the WGS84 ellipsoid. **********************************************************************/ - explicit Gnomonic(const Geodesic& earth = Geodesic::WGS84) - throw() - : _earth(earth) - , _a(_earth.MajorRadius()) - , _f(_earth.Flattening()) - {} + explicit Gnomonic(const Geodesic& earth = Geodesic::WGS84()); /** * Forward projection, from geographic to gnomonic. @@ -133,8 +128,7 @@ namespace GeographicLib { * @param[out] azi azimuth of geodesic at point (degrees). * @param[out] rk reciprocal of azimuthal scale at point. * - * \e lat0 and \e lat should be in the range [−90°, 90°] and - * \e lon0 and \e lon should be in the range [−540°, 540°). + * \e lat0 and \e lat should be in the range [−90°, 90°]. * The scale of the projection is 1/rk2 in the "radial" * direction, \e azi clockwise from true north, and is 1/\e rk in the * direction perpendicular to this. If the point lies "over the horizon", @@ -144,7 +138,7 @@ namespace GeographicLib { * (to within roundoff) provided the point in not over the horizon. **********************************************************************/ void Forward(real lat0, real lon0, real lat, real lon, - real& x, real& y, real& azi, real& rk) const throw(); + real& x, real& y, real& azi, real& rk) const; /** * Reverse projection, from gnomonic to geographic. @@ -158,26 +152,25 @@ namespace GeographicLib { * @param[out] azi azimuth of geodesic at point (degrees). * @param[out] rk reciprocal of azimuthal scale at point. * - * \e lat0 should be in the range [−90°, 90°] and \e - * lon0 should be in the range [−540°, 540°). \e lat - * will be in the range [−90°, 90°] and \e lon will - * be in the range [−180°, 180°). The scale of the - * projection is 1/\e rk2 in the "radial" direction, \e azi - * clockwise from true north, and is 1/\e rk in the direction perpendicular - * to this. Even though all inputs should return a valid \e lat and \e - * lon, it's possible that the procedure fails to converge for very large - * \e x or \e y; in this case NaNs are returned for all the output - * arguments. A call to Reverse followed by a call to Forward will return - * the original (\e x, \e y) (to roundoff). + * \e lat0 should be in the range [−90°, 90°]. \e lat will + * be in the range [−90°, 90°] and \e lon will be in the + * range [−180°, 180°]. The scale of the projection is + * 1/rk2 in the "radial" direction, \e azi clockwise from + * true north, and is 1/\e rk in the direction perpendicular to this. Even + * though all inputs should return a valid \e lat and \e lon, it's possible + * that the procedure fails to converge for very large \e x or \e y; in + * this case NaNs are returned for all the output arguments. A call to + * Reverse followed by a call to Forward will return the original (\e x, \e + * y) (to roundoff). **********************************************************************/ void Reverse(real lat0, real lon0, real x, real y, - real& lat, real& lon, real& azi, real& rk) const throw(); + real& lat, real& lon, real& azi, real& rk) const; /** * Gnomonic::Forward without returning the azimuth and scale. **********************************************************************/ void Forward(real lat0, real lon0, real lat, real lon, - real& x, real& y) const throw() { + real& x, real& y) const { real azi, rk; Forward(lat0, lon0, lat, lon, x, y, azi, rk); } @@ -186,7 +179,7 @@ namespace GeographicLib { * Gnomonic::Reverse without returning the azimuth and scale. **********************************************************************/ void Reverse(real lat0, real lon0, real x, real y, - real& lat, real& lon) const throw() { + real& lat, real& lon) const { real azi, rk; Reverse(lat0, lon0, x, y, lat, lon, azi, rk); } @@ -198,23 +191,15 @@ namespace GeographicLib { * @return \e a the equatorial radius of the ellipsoid (meters). This is * the value inherited from the Geodesic object used in the constructor. **********************************************************************/ - Math::real MajorRadius() const throw() { return _earth.MajorRadius(); } + Math::real MajorRadius() const { return _earth.MajorRadius(); } /** * @return \e f the flattening of the ellipsoid. This is the value * inherited from the Geodesic object used in the constructor. **********************************************************************/ - Math::real Flattening() const throw() { return _earth.Flattening(); } + Math::real Flattening() const { return _earth.Flattening(); } ///@} - /// \cond SKIP - /** - * DEPRECATED - * @return \e r the inverse flattening of the ellipsoid. - **********************************************************************/ - Math::real InverseFlattening() const throw() - { return _earth.InverseFlattening(); } - /// \endcond }; } // namespace GeographicLib diff --git a/gtsam/3rdparty/GeographicLib/include/GeographicLib/GravityCircle.hpp b/gtsam/3rdparty/GeographicLib/include/GeographicLib/GravityCircle.hpp index d11f98b83..c47c80f24 100644 --- a/gtsam/3rdparty/GeographicLib/include/GeographicLib/GravityCircle.hpp +++ b/gtsam/3rdparty/GeographicLib/include/GeographicLib/GravityCircle.hpp @@ -2,9 +2,9 @@ * \file GravityCircle.hpp * \brief Header for GeographicLib::GravityCircle class * - * Copyright (c) Charles Karney (2011) and licensed under - * the MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ + * Copyright (c) Charles Karney (2011-2016) and licensed + * under the MIT/X11 License. For more information, see + * https://geographiclib.sourceforge.io/ **********************************************************************/ #if !defined(GEOGRAPHICLIB_GRAVITYCIRCLE_HPP) @@ -67,7 +67,7 @@ namespace GeographicLib { : _caps(caps) , _a(a) , _f(f) - , _lat(lat) + , _lat(Math::LatFix(lat)) , _h(h) , _Z(Z) , _Px(P) @@ -89,13 +89,13 @@ namespace GeographicLib { {} friend class GravityModel; // GravityModel calls the private constructor - Math::real W(real clam, real slam, - real& gX, real& gY, real& gZ) const throw(); - Math::real V(real clam, real slam, - real& gX, real& gY, real& gZ) const throw(); - Math::real InternalT(real clam, real slam, + Math::real W(real slam, real clam, + real& gX, real& gY, real& gZ) const; + Math::real V(real slam, real clam, + real& gX, real& gY, real& gZ) const; + Math::real InternalT(real slam, real clam, real& deltaX, real& deltaY, real& deltaZ, - bool gradp, bool correct) const throw(); + bool gradp, bool correct) const; public: /** * A default constructor for the normal gravity. This sets up an @@ -117,11 +117,12 @@ namespace GeographicLib { * (m s−2). * @param[out] gz the upward component of the acceleration * (m s−2); this is usually negative. - * @return \e W the sum of the gravitational and centrifugal potentials. + * @return \e W the sum of the gravitational and centrifugal potentials + * (m2 s−2). * * The function includes the effects of the earth's rotation. **********************************************************************/ - Math::real Gravity(real lon, real& gx, real& gy, real& gz) const throw(); + Math::real Gravity(real lon, real& gx, real& gy, real& gz) const; /** * Evaluate the gravity disturbance vector. @@ -133,10 +134,11 @@ namespace GeographicLib { * (m s−2). * @param[out] deltaz the upward component of the disturbance vector * (m s−2). - * @return \e T the corresponding disturbing potential. + * @return \e T the corresponding disturbing potential + * (m2 s−2). **********************************************************************/ Math::real Disturbance(real lon, real& deltax, real& deltay, real& deltaz) - const throw(); + const; /** * Evaluate the geoid height. @@ -149,7 +151,7 @@ namespace GeographicLib { * results of the NGA codes are reproduced accurately. Details are given * in \ref gravitygeoid. **********************************************************************/ - Math::real GeoidHeight(real lon) const throw(); + Math::real GeoidHeight(real lon) const; /** * Evaluate the components of the gravity anomaly vector using the @@ -167,7 +169,7 @@ namespace GeographicLib { * approximations used here. Details are given in \ref gravitygeoid. **********************************************************************/ void SphericalAnomaly(real lon, real& Dg01, real& xi, real& eta) - const throw(); + const; /** * Evaluate the components of the acceleration due to gravity and the @@ -183,10 +185,10 @@ namespace GeographicLib { * @return \e W = \e V + Φ the sum of the gravitational and * centrifugal potentials (m2 s−2). **********************************************************************/ - Math::real W(real lon, real& gX, real& gY, real& gZ) const throw() { - real clam, slam; - CircularEngine::cossin(lon, clam, slam); - return W(clam, slam, gX, gY, gZ); + Math::real W(real lon, real& gX, real& gY, real& gZ) const { + real slam, clam; + Math::sincosd(lon, slam, clam); + return W(slam, clam, gX, gY, gZ); } /** @@ -203,10 +205,10 @@ namespace GeographicLib { * @return \e V = \e W - Φ the gravitational potential * (m2 s−2). **********************************************************************/ - Math::real V(real lon, real& GX, real& GY, real& GZ) const throw() { - real clam, slam; - CircularEngine::cossin(lon, clam, slam); - return V(clam, slam, GX, GY, GZ); + Math::real V(real lon, real& GX, real& GY, real& GZ) const { + real slam, clam; + Math::sincosd(lon, slam, clam); + return V(slam, clam, GX, GY, GZ); } /** @@ -224,10 +226,10 @@ namespace GeographicLib { * anomalous potential) (m2 s−2). **********************************************************************/ Math::real T(real lon, real& deltaX, real& deltaY, real& deltaZ) - const throw() { - real clam, slam; - CircularEngine::cossin(lon, clam, slam); - return InternalT(clam, slam, deltaX, deltaY, deltaZ, true, true); + const { + real slam, clam; + Math::sincosd(lon, slam, clam); + return InternalT(slam, clam, deltaX, deltaY, deltaZ, true, true); } /** @@ -237,10 +239,10 @@ namespace GeographicLib { * @return \e T = \e W - \e U the disturbing potential (also called the * anomalous potential) (m2 s−2). **********************************************************************/ - Math::real T(real lon) const throw() { - real clam, slam, dummy; - CircularEngine::cossin(lon, clam, slam); - return InternalT(clam, slam, dummy, dummy, dummy, false, true); + Math::real T(real lon) const { + real slam, clam, dummy; + Math::sincosd(lon, slam, clam); + return InternalT(slam, clam, dummy, dummy, dummy, false, true); } ///@} @@ -251,46 +253,46 @@ namespace GeographicLib { /** * @return true if the object has been initialized. **********************************************************************/ - bool Init() const throw() { return _a > 0; } + bool Init() const { return _a > 0; } /** * @return \e a the equatorial radius of the ellipsoid (meters). This is * the value inherited from the GravityModel object used in the * constructor. **********************************************************************/ - Math::real MajorRadius() const throw() - { return Init() ? _a : Math::NaN(); } + Math::real MajorRadius() const + { return Init() ? _a : Math::NaN(); } /** * @return \e f the flattening of the ellipsoid. This is the value * inherited from the GravityModel object used in the constructor. **********************************************************************/ - Math::real Flattening() const throw() - { return Init() ? _f : Math::NaN(); } + Math::real Flattening() const + { return Init() ? _f : Math::NaN(); } /** * @return the latitude of the circle (degrees). **********************************************************************/ - Math::real Latitude() const throw() - { return Init() ? _lat : Math::NaN(); } + Math::real Latitude() const + { return Init() ? _lat : Math::NaN(); } /** * @return the height of the circle (meters). **********************************************************************/ - Math::real Height() const throw() - { return Init() ? _h : Math::NaN(); } + Math::real Height() const + { return Init() ? _h : Math::NaN(); } /** * @return \e caps the computational capabilities that this object was * constructed with. **********************************************************************/ - unsigned Capabilities() const throw() { return _caps; } + unsigned Capabilities() const { return _caps; } /** - * @param[in] testcaps a set of bitor'ed GeodesicLine::mask values. - * @return true if the GeodesicLine object has all these capabilities. + * @param[in] testcaps a set of bitor'ed GravityModel::mask values. + * @return true if the GravityCircle object has all these capabilities. **********************************************************************/ - bool Capabilities(unsigned testcaps) const throw() { + bool Capabilities(unsigned testcaps) const { return (_caps & testcaps) == testcaps; } ///@} diff --git a/gtsam/3rdparty/GeographicLib/include/GeographicLib/GravityModel.hpp b/gtsam/3rdparty/GeographicLib/include/GeographicLib/GravityModel.hpp index e958eb667..fd867c791 100644 --- a/gtsam/3rdparty/GeographicLib/include/GeographicLib/GravityModel.hpp +++ b/gtsam/3rdparty/GeographicLib/include/GeographicLib/GravityModel.hpp @@ -2,9 +2,9 @@ * \file GravityModel.hpp * \brief Header for GeographicLib::GravityModel class * - * Copyright (c) Charles Karney (2011) and licensed under - * the MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ + * Copyright (c) Charles Karney (2011-2016) and licensed + * under the MIT/X11 License. For more information, see + * https://geographiclib.sourceforge.io/ **********************************************************************/ #if !defined(GEOGRAPHICLIB_GRAVITYMODEL_HPP) @@ -32,10 +32,10 @@ namespace GeographicLib { * models treat only the gravitational field exterior to the mass of the * earth. When computing the field at points near (but above) the surface of * the earth a small correction can be applied to account for the mass of the - * atomsphere above the point in question; see \ref gravityatmos. - * Determining the geoid height entails correcting for the mass of the earth - * above the geoid. The egm96 and egm2008 include separate correction terms - * to account for this mass. + * atmosphere above the point in question; see \ref gravityatmos. + * Determining the height of the geoid above the ellipsoid entails correcting + * for the mass of the earth above the geoid. The egm96 and egm2008 include + * separate correction terms to account for this mass. * * Definitions and terminology (from Heiskanen and Moritz, Sec 2-13): * - \e V = gravitational potential; @@ -51,13 +51,13 @@ namespace GeographicLib { * - γ = ∇\e U; * - δ = ∇\e T = gravity disturbance vector * = gPγP; - * - δ\e g = gravity disturbance = \e gP − + * - δ\e g = gravity disturbance = gP − * γP; * - Δg = gravity anomaly vector = gP * − γQ; here the line \e PQ is * perpendicular to ellipsoid and the potential at \e P equals the normal * potential at \e Q; - * - Δ\e g = gravity anomaly = \e gP − + * - Δ\e g = gravity anomaly = gP − * γQ; * - (ξ, η) deflection of the vertical, the difference in * directions of gP and @@ -66,7 +66,7 @@ namespace GeographicLib { * - \e x, \e y, \e z, local cartesian coordinates used to denote the east, * north and up directions. * - * See \ref gravity for details of how to install the gravity model and the + * See \ref gravity for details of how to install the gravity models and the * data format. * * References: @@ -97,7 +97,7 @@ namespace GeographicLib { void ReadMetadata(const std::string& name); Math::real InternalT(real X, real Y, real Z, real& deltaX, real& deltaY, real& deltaZ, - bool gradp, bool correct) const throw(); + bool gradp, bool correct) const; GravityModel(const GravityModel&); // copy constructor not allowed GravityModel& operator=(const GravityModel&); // nor copy assignment @@ -200,12 +200,13 @@ namespace GeographicLib { * (m s−2). * @param[out] gz the upward component of the acceleration * (m s−2); this is usually negative. - * @return \e W the sum of the gravitational and centrifugal potentials. + * @return \e W the sum of the gravitational and centrifugal potentials + * (m2 s−2). * * The function includes the effects of the earth's rotation. **********************************************************************/ Math::real Gravity(real lat, real lon, real h, - real& gx, real& gy, real& gz) const throw(); + real& gx, real& gy, real& gz) const; /** * Evaluate the gravity disturbance vector at an arbitrary point above (or @@ -220,11 +221,12 @@ namespace GeographicLib { * (m s−2). * @param[out] deltaz the upward component of the disturbance vector * (m s−2). - * @return \e T the corresponding disturbing potential. + * @return \e T the corresponding disturbing potential + * (m2 s−2). **********************************************************************/ Math::real Disturbance(real lat, real lon, real h, real& deltax, real& deltay, real& deltaz) - const throw(); + const; /** * Evaluate the geoid height. @@ -239,7 +241,7 @@ namespace GeographicLib { * results of the NGA codes are reproduced accurately. Details are given * in \ref gravitygeoid. **********************************************************************/ - Math::real GeoidHeight(real lat, real lon) const throw(); + Math::real GeoidHeight(real lat, real lon) const; /** * Evaluate the components of the gravity anomaly vector using the @@ -259,7 +261,7 @@ namespace GeographicLib { * approximations used here. Details are given in \ref gravitygeoid. **********************************************************************/ void SphericalAnomaly(real lat, real lon, real h, - real& Dg01, real& xi, real& eta) const throw(); + real& Dg01, real& xi, real& eta) const; ///@} /** \name Compute gravity in geocentric coordinates @@ -281,10 +283,10 @@ namespace GeographicLib { * @return \e W = \e V + Φ the sum of the gravitational and * centrifugal potentials (m2 s−2). * - * This calls NormalGravity::U for ReferenceEllipsoid(). + * This calls NormalGravity::U for ReferenceEllipsoid(). **********************************************************************/ Math::real W(real X, real Y, real Z, - real& gX, real& gY, real& gZ) const throw(); + real& gX, real& gY, real& gZ) const; /** * Evaluate the components of the acceleration due to gravity in geocentric @@ -303,7 +305,7 @@ namespace GeographicLib { * (m2 s−2). **********************************************************************/ Math::real V(real X, real Y, real Z, - real& GX, real& GY, real& GZ) const throw(); + real& GX, real& GY, real& GZ) const; /** * Evaluate the components of the gravity disturbance in geocentric @@ -322,7 +324,7 @@ namespace GeographicLib { * anomalous potential) (m2 s−2). **********************************************************************/ Math::real T(real X, real Y, real Z, - real& deltaX, real& deltaY, real& deltaZ) const throw() + real& deltaX, real& deltaY, real& deltaZ) const { return InternalT(X, Y, Z, deltaX, deltaY, deltaZ, true, true); } /** @@ -334,7 +336,7 @@ namespace GeographicLib { * @return \e T = \e W - \e U the disturbing potential (also called the * anomalous potential) (m2 s−2). **********************************************************************/ - Math::real T(real X, real Y, real Z) const throw() { + Math::real T(real X, real Y, real Z) const { real dummy; return InternalT(X, Y, Z, dummy, dummy, dummy, false, true); } @@ -356,10 +358,10 @@ namespace GeographicLib { * normal gravitational and centrifugal potentials * (m2 s−2). * - * This calls NormalGravity::U for ReferenceEllipsoid(). + * This calls NormalGravity::U for ReferenceEllipsoid(). **********************************************************************/ Math::real U(real X, real Y, real Z, - real& gammaX, real& gammaY, real& gammaZ) const throw() + real& gammaX, real& gammaY, real& gammaZ) const { return _earth.U(X, Y, Z, gammaX, gammaY, gammaZ); } /** @@ -374,9 +376,9 @@ namespace GeographicLib { * @return Φ the centrifugal potential (m2 * s−2). * - * This calls NormalGravity::Phi for ReferenceEllipsoid(). + * This calls NormalGravity::Phi for ReferenceEllipsoid(). **********************************************************************/ - Math::real Phi(real X, real Y, real& fX, real& fY) const throw() + Math::real Phi(real X, real Y, real& fX, real& fY) const { return _earth.Phi(X, Y, fX, fY); } ///@} @@ -425,39 +427,39 @@ namespace GeographicLib { /** * @return the NormalGravity object for the reference ellipsoid. **********************************************************************/ - const NormalGravity& ReferenceEllipsoid() const throw() { return _earth; } + const NormalGravity& ReferenceEllipsoid() const { return _earth; } /** * @return the description of the gravity model, if available, in the data * file; if absent, return "NONE". **********************************************************************/ - const std::string& Description() const throw() { return _description; } + const std::string& Description() const { return _description; } /** * @return date of the model; if absent, return "UNKNOWN". **********************************************************************/ - const std::string& DateTime() const throw() { return _date; } + const std::string& DateTime() const { return _date; } /** * @return full file name used to load the gravity model. **********************************************************************/ - const std::string& GravityFile() const throw() { return _filename; } + const std::string& GravityFile() const { return _filename; } /** * @return "name" used to load the gravity model (from the first argument * of the constructor, but this may be overridden by the model file). **********************************************************************/ - const std::string& GravityModelName() const throw() { return _name; } + const std::string& GravityModelName() const { return _name; } /** * @return directory used to load the gravity model. **********************************************************************/ - const std::string& GravityModelDirectory() const throw() { return _dir; } + const std::string& GravityModelDirectory() const { return _dir; } /** * @return \e a the equatorial radius of the ellipsoid (meters). **********************************************************************/ - Math::real MajorRadius() const throw() { return _earth.MajorRadius(); } + Math::real MajorRadius() const { return _earth.MajorRadius(); } /** * @return \e GM the mass constant of the model (m3 @@ -465,47 +467,48 @@ namespace GeographicLib { * constant and \e M the mass of the earth (usually including the mass of * the earth's atmosphere). **********************************************************************/ - Math::real MassConstant() const throw() { return _GMmodel; } + Math::real MassConstant() const { return _GMmodel; } /** * @return \e GM the mass constant of the ReferenceEllipsoid() * (m3 s−2). **********************************************************************/ - Math::real ReferenceMassConstant() const throw() + Math::real ReferenceMassConstant() const { return _earth.MassConstant(); } /** * @return ω the angular velocity of the model and the * ReferenceEllipsoid() (rad s−1). **********************************************************************/ - Math::real AngularVelocity() const throw() + Math::real AngularVelocity() const { return _earth.AngularVelocity(); } /** * @return \e f the flattening of the ellipsoid. **********************************************************************/ - Math::real Flattening() const throw() { return _earth.Flattening(); } + Math::real Flattening() const { return _earth.Flattening(); } ///@} /** * @return the default path for gravity model data files. * - * This is the value of the environment variable GRAVITY_PATH, if set; - * otherwise, it is $GEOGRAPHICLIB_DATA/gravity if the environment variable + * This is the value of the environment variable + * GEOGRAPHICLIB_GRAVITY_PATH, if set; otherwise, it is + * $GEOGRAPHICLIB_DATA/gravity if the environment variable * GEOGRAPHICLIB_DATA is set; otherwise, it is a compile-time default * (/usr/local/share/GeographicLib/gravity on non-Windows systems and - * C:/Documents and Settings/All Users/Application - * Data/GeographicLib/gravity on Windows systems). + * C:/ProgramData/GeographicLib/gravity on Windows systems). **********************************************************************/ static std::string DefaultGravityPath(); /** * @return the default name for the gravity model. * - * This is the value of the environment variable GRAVITY_NAME, if set, - * otherwise, it is "egm96". The GravityModel class does not use - * this function; it is just provided as a convenience for a calling - * program when constructing a GravityModel object. + * This is the value of the environment variable + * GEOGRAPHICLIB_GRAVITY_NAME, if set; otherwise, it is "egm96". The + * GravityModel class does not use this function; it is just provided as a + * convenience for a calling program when constructing a GravityModel + * object. **********************************************************************/ static std::string DefaultGravityName(); }; diff --git a/gtsam/3rdparty/GeographicLib/include/GeographicLib/LambertConformalConic.hpp b/gtsam/3rdparty/GeographicLib/include/GeographicLib/LambertConformalConic.hpp index 5f656f02e..3dd7b9982 100644 --- a/gtsam/3rdparty/GeographicLib/include/GeographicLib/LambertConformalConic.hpp +++ b/gtsam/3rdparty/GeographicLib/include/GeographicLib/LambertConformalConic.hpp @@ -2,9 +2,9 @@ * \file LambertConformalConic.hpp * \brief Header for GeographicLib::LambertConformalConic class * - * Copyright (c) Charles Karney (2010-2012) and licensed + * Copyright (c) Charles Karney (2010-2017) and licensed * under the MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #if !defined(GEOGRAPHICLIB_LAMBERTCONFORMALCONIC_HPP) @@ -42,7 +42,13 @@ namespace GeographicLib { * parallels where one is a pole is singular and is disallowed. The central * meridian (which is a trivial shift of the longitude) is specified as the * \e lon0 argument of the LambertConformalConic::Forward and - * LambertConformalConic::Reverse functions. There is no provision in this + * LambertConformalConic::Reverse functions. + * + * This class also returns the meridian convergence \e gamma and scale \e k. + * The meridian convergence is the bearing of grid north (the \e y axis) + * measured clockwise from true north. + * + * There is no provision in this * class for specifying a false easting or false northing or a different * latitude of origin. However these are can be simply included by the * calling function. For example the Pennsylvania South state coordinate @@ -57,26 +63,19 @@ namespace GeographicLib { class GEOGRAPHICLIB_EXPORT LambertConformalConic { private: typedef Math::real real; - real _a, _f, _fm, _e2, _e, _e2m; + real eps_, epsx_, ahypover_; + real _a, _f, _fm, _e2, _es; real _sign, _n, _nc, _t0nm1, _scale, _lat0, _k0; real _scbet0, _tchi0, _scchi0, _psi0, _nrho0, _drhomax; - static const real eps_; - static const real epsx_; - static const real tol_; - static const real ahypover_; static const int numit_ = 5; - static inline real hyp(real x) throw() { return Math::hypot(real(1), x); } - // e * atanh(e * x) = log( ((1 + e*x)/(1 - e*x))^(e/2) ) if f >= 0 - // - sqrt(-e2) * atan( sqrt(-e2) * x) if f < 0 - inline real eatanhe(real x) const throw() - { return _f >= 0 ? _e * Math::atanh(_e * x) : - _e * std::atan(_e * x); } + static real hyp(real x) { return Math::hypot(real(1), x); } // Divided differences // Definition: Df(x,y) = (f(x)-f(y))/(x-y) // See: // W. M. Kahan and R. J. Fateman, // Symbolic computation of divided differences, // SIGSAM Bull. 33(3), 7-28 (1999) - // http://dx.doi.org/10.1145/334714.334716 + // https://doi.org/10.1145/334714.334716 // http://www.cs.berkeley.edu/~fateman/papers/divdiff.pdf // // General rules @@ -87,41 +86,43 @@ namespace GeographicLib { // = Df(x,y)*(g(x)+g(y))/2 + Dg(x,y)*(f(x)+f(y))/2 // // hyp(x) = sqrt(1+x^2): Dhyp(x,y) = (x+y)/(hyp(x)+hyp(y)) - static inline real Dhyp(real x, real y, real hx, real hy) throw() + static real Dhyp(real x, real y, real hx, real hy) // hx = hyp(x) { return (x + y) / (hx + hy); } // sn(x) = x/sqrt(1+x^2): Dsn(x,y) = (x+y)/((sn(x)+sn(y))*(1+x^2)*(1+y^2)) - static inline real Dsn(real x, real y, real sx, real sy) throw() { + static real Dsn(real x, real y, real sx, real sy) { // sx = x/hyp(x) real t = x * y; return t > 0 ? (x + y) * Math::sq( (sx * sy)/t ) / (sx + sy) : (x - y != 0 ? (sx - sy) / (x - y) : 1); } - // Dlog1p(x,y) = log1p((x-y)/(1+y)/(x-y) - static inline real Dlog1p(real x, real y) throw() { + // Dlog1p(x,y) = log1p((x-y)/(1+y))/(x-y) + static real Dlog1p(real x, real y) { real t = x - y; if (t < 0) { t = -t; y = x; } return t != 0 ? Math::log1p(t / (1 + y)) / t : 1 / (1 + x); } // Dexp(x,y) = exp((x+y)/2) * 2*sinh((x-y)/2)/(x-y) - static inline real Dexp(real x, real y) throw() { + static real Dexp(real x, real y) { + using std::sinh; using std::exp; real t = (x - y)/2; - return (t != 0 ? sinh(t)/t : real(1)) * exp((x + y)/2); + return (t != 0 ? sinh(t)/t : 1) * exp((x + y)/2); } // Dsinh(x,y) = 2*sinh((x-y)/2)/(x-y) * cosh((x+y)/2) // cosh((x+y)/2) = (c+sinh(x)*sinh(y)/c)/2 // c=sqrt((1+cosh(x))*(1+cosh(y))) // cosh((x+y)/2) = sqrt( (sinh(x)*sinh(y) + cosh(x)*cosh(y) + 1)/2 ) - static inline real Dsinh(real x, real y, real sx, real sy, real cx, real cy) - // sx = sinh(x), cx = cosh(x) - throw() { + static real Dsinh(real x, real y, real sx, real sy, real cx, real cy) + // sx = sinh(x), cx = cosh(x) + { // real t = (x - y)/2, c = sqrt((1 + cx) * (1 + cy)); - // return (t != 0 ? sinh(t)/t : real(1)) * (c + sx * sy / c) /2; + // return (t ? sinh(t)/t : real(1)) * (c + sx * sy / c) /2; + using std::sinh; using std::sqrt; real t = (x - y)/2; - return (t != 0 ? sinh(t)/t : real(1)) * sqrt((sx * sy + cx * cy + 1) /2); + return (t != 0 ? sinh(t)/t : 1) * sqrt((sx * sy + cx * cy + 1) /2); } // Dasinh(x,y) = asinh((x-y)*(x+y)/(x*sqrt(1+y^2)+y*sqrt(1+x^2)))/(x-y) // = asinh((x*sqrt(1+y^2)-y*sqrt(1+x^2)))/(x-y) - static inline real Dasinh(real x, real y, real hx, real hy) throw() { + static real Dasinh(real x, real y, real hx, real hy) { // hx = hyp(x) real t = x - y; return t != 0 ? @@ -129,11 +130,11 @@ namespace GeographicLib { 1/hx; } // Deatanhe(x,y) = eatanhe((x-y)/(1-e^2*x*y))/(x-y) - inline real Deatanhe(real x, real y) const throw() { + real Deatanhe(real x, real y) const { real t = x - y, d = 1 - _e2 * x * y; - return t != 0 ? eatanhe(t / d) / t : _e2 / d; + return t != 0 ? Math::eatanhe(t / d, _es) / t : _e2 / d; } - void Init(real sphi1, real cphi1, real sphi2, real cphi2, real k1) throw(); + void Init(real sphi1, real cphi1, real sphi2, real cphi2, real k1); public: /** @@ -141,11 +142,10 @@ namespace GeographicLib { * * @param[in] a equatorial radius of ellipsoid (meters). * @param[in] f flattening of ellipsoid. Setting \e f = 0 gives a sphere. - * Negative \e f gives a prolate ellipsoid. If \e f > 1, set flattening - * to 1/\e f. + * Negative \e f gives a prolate ellipsoid. * @param[in] stdlat standard parallel (degrees), the circle of tangency. * @param[in] k0 scale on the standard parallel. - * @exception GeographicErr if \e a, (1 − \e f ) \e a, or \e k0 is + * @exception GeographicErr if \e a, (1 − \e f) \e a, or \e k0 is * not positive. * @exception GeographicErr if \e stdlat is not in [−90°, * 90°]. @@ -157,12 +157,11 @@ namespace GeographicLib { * * @param[in] a equatorial radius of ellipsoid (meters). * @param[in] f flattening of ellipsoid. Setting \e f = 0 gives a sphere. - * Negative \e f gives a prolate ellipsoid. If \e f > 1, set flattening - * to 1/\e f. + * Negative \e f gives a prolate ellipsoid. * @param[in] stdlat1 first standard parallel (degrees). * @param[in] stdlat2 second standard parallel (degrees). * @param[in] k1 scale on the standard parallels. - * @exception GeographicErr if \e a, (1 − \e f ) \e a, or \e k1 is + * @exception GeographicErr if \e a, (1 − \e f) \e a, or \e k1 is * not positive. * @exception GeographicErr if \e stdlat1 or \e stdlat2 is not in * [−90°, 90°], or if either \e stdlat1 or \e @@ -175,14 +174,13 @@ namespace GeographicLib { * * @param[in] a equatorial radius of ellipsoid (meters). * @param[in] f flattening of ellipsoid. Setting \e f = 0 gives a sphere. - * Negative \e f gives a prolate ellipsoid. If \e f > 1, set flattening - * to 1/\e f. + * Negative \e f gives a prolate ellipsoid. * @param[in] sinlat1 sine of first standard parallel. * @param[in] coslat1 cosine of first standard parallel. * @param[in] sinlat2 sine of second standard parallel. * @param[in] coslat2 cosine of second standard parallel. * @param[in] k1 scale on the standard parallels. - * @exception GeographicErr if \e a, (1 − \e f ) \e a, or \e k1 is + * @exception GeographicErr if \e a, (1 − \e f) \e a, or \e k1 is * not positive. * @exception GeographicErr if \e stdlat1 or \e stdlat2 is not in * [−90°, 90°], or if either \e stdlat1 or \e @@ -228,15 +226,14 @@ namespace GeographicLib { * * The latitude origin is given by LambertConformalConic::LatitudeOrigin(). * No false easting or northing is added and \e lat should be in the range - * [−90°, 90°]; \e lon and \e lon0 should be in the - * range [−540°, 540°). The error in the projection - * is less than about 10 nm (10 nanometers), true distance, and the errors - * in the meridian convergence and scale are consistent with this. The - * values of \e x and \e y returned for points which project to infinity - * (i.e., one or both of the poles) will be large but finite. + * [−90°, 90°]. The error in the projection is less than + * about 10 nm (10 nanometers), true distance, and the errors in the + * meridian convergence and scale are consistent with this. The values of + * \e x and \e y returned for points which project to infinity (i.e., one + * or both of the poles) will be large but finite. **********************************************************************/ void Forward(real lon0, real lat, real lon, - real& x, real& y, real& gamma, real& k) const throw(); + real& x, real& y, real& gamma, real& k) const; /** * Reverse projection, from Lambert conformal conic to geographic. @@ -250,22 +247,20 @@ namespace GeographicLib { * @param[out] k scale of projection at point. * * The latitude origin is given by LambertConformalConic::LatitudeOrigin(). - * No false easting or northing is added. \e lon0 should be in the range - * [−540°, 540°). The value of \e lon returned is in - * the range [−180°, 180°). The error in the - * projection is less than about 10 nm (10 nanometers), true distance, and - * the errors in the meridian convergence and scale are consistent with - * this. + * No false easting or northing is added. The value of \e lon returned is + * in the range [−180°, 180°]. The error in the projection + * is less than about 10 nm (10 nanometers), true distance, and the errors + * in the meridian convergence and scale are consistent with this. **********************************************************************/ void Reverse(real lon0, real x, real y, - real& lat, real& lon, real& gamma, real& k) const throw(); + real& lat, real& lon, real& gamma, real& k) const; /** * LambertConformalConic::Forward without returning the convergence and * scale. **********************************************************************/ void Forward(real lon0, real lat, real lon, - real& x, real& y) const throw() { + real& x, real& y) const { real gamma, k; Forward(lon0, lat, lon, x, y, gamma, k); } @@ -275,7 +270,7 @@ namespace GeographicLib { * scale. **********************************************************************/ void Reverse(real lon0, real x, real y, - real& lat, real& lon) const throw() { + real& lat, real& lon) const { real gamma, k; Reverse(lon0, x, y, lat, lon, gamma, k); } @@ -287,21 +282,13 @@ namespace GeographicLib { * @return \e a the equatorial radius of the ellipsoid (meters). This is * the value used in the constructor. **********************************************************************/ - Math::real MajorRadius() const throw() { return _a; } + Math::real MajorRadius() const { return _a; } /** * @return \e f the flattening of the ellipsoid. This is the * value used in the constructor. **********************************************************************/ - Math::real Flattening() const throw() { return _f; } - - /// \cond SKIP - /** - * DEPRECATED - * @return \e r the inverse flattening of the ellipsoid. - **********************************************************************/ - Math::real InverseFlattening() const throw() { return 1/_f; } - /// \endcond + Math::real Flattening() const { return _f; } /** * @return latitude of the origin for the projection (degrees). @@ -310,13 +297,13 @@ namespace GeographicLib { * 1-parallel constructor and lies between \e stdlat1 and \e stdlat2 in the * 2-parallel constructors. **********************************************************************/ - Math::real OriginLatitude() const throw() { return _lat0; } + Math::real OriginLatitude() const { return _lat0; } /** * @return central scale for the projection. This is the scale on the * latitude of origin. **********************************************************************/ - Math::real CentralScale() const throw() { return _k0; } + Math::real CentralScale() const { return _k0; } ///@} /** @@ -324,7 +311,7 @@ namespace GeographicLib { * ellipsoid, \e stdlat = 0, and \e k0 = 1. This degenerates to the * Mercator projection. **********************************************************************/ - static const LambertConformalConic Mercator; + static const LambertConformalConic& Mercator(); }; } // namespace GeographicLib diff --git a/gtsam/3rdparty/GeographicLib/include/GeographicLib/LocalCartesian.hpp b/gtsam/3rdparty/GeographicLib/include/GeographicLib/LocalCartesian.hpp index 9ce0b38f4..21ca4af16 100644 --- a/gtsam/3rdparty/GeographicLib/include/GeographicLib/LocalCartesian.hpp +++ b/gtsam/3rdparty/GeographicLib/include/GeographicLib/LocalCartesian.hpp @@ -2,9 +2,9 @@ * \file LocalCartesian.hpp * \brief Header for GeographicLib::LocalCartesian class * - * Copyright (c) Charles Karney (2008-2011) and licensed + * Copyright (c) Charles Karney (2008-2016) and licensed * under the MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #if !defined(GEOGRAPHICLIB_LOCALCARTESIAN_HPP) @@ -26,7 +26,7 @@ namespace GeographicLib { * due north. The plane \e z = - \e h0 is tangent to the ellipsoid. * * The conversions all take place via geocentric coordinates using a - * Geocentric object (by default Geocentric::WGS84). + * Geocentric object (by default Geocentric::WGS84()). * * Example of use: * \include example-LocalCartesian.cpp @@ -44,10 +44,10 @@ namespace GeographicLib { real _lat0, _lon0, _h0; real _x0, _y0, _z0, _r[dim2_]; void IntForward(real lat, real lon, real h, real& x, real& y, real& z, - real M[dim2_]) const throw(); + real M[dim2_]) const; void IntReverse(real x, real y, real z, real& lat, real& lon, real& h, - real M[dim2_]) const throw(); - void MatrixMultiply(real M[dim2_]) const throw(); + real M[dim2_]) const; + void MatrixMultiply(real M[dim2_]) const; public: /** @@ -57,13 +57,12 @@ namespace GeographicLib { * @param[in] lon0 longitude at origin (degrees). * @param[in] h0 height above ellipsoid at origin (meters); default 0. * @param[in] earth Geocentric object for the transformation; default - * Geocentric::WGS84. + * Geocentric::WGS84(). * - * \e lat0 should be in the range [−90°, 90°]; \e - * lon0 should be in the range [−540°, 540°). + * \e lat0 should be in the range [−90°, 90°]. **********************************************************************/ LocalCartesian(real lat0, real lon0, real h0 = 0, - const Geocentric& earth = Geocentric::WGS84) throw() + const Geocentric& earth = Geocentric::WGS84()) : _earth(earth) { Reset(lat0, lon0, h0); } @@ -71,12 +70,11 @@ namespace GeographicLib { * Default constructor. * * @param[in] earth Geocentric object for the transformation; default - * Geocentric::WGS84. + * Geocentric::WGS84(). * * Sets \e lat0 = 0, \e lon0 = 0, \e h0 = 0. **********************************************************************/ - explicit LocalCartesian(const Geocentric& earth = Geocentric::WGS84) - throw() + explicit LocalCartesian(const Geocentric& earth = Geocentric::WGS84()) : _earth(earth) { Reset(real(0), real(0), real(0)); } @@ -87,10 +85,9 @@ namespace GeographicLib { * @param[in] lon0 longitude at origin (degrees). * @param[in] h0 height above ellipsoid at origin (meters); default 0. * - * \e lat0 should be in the range [−90°, 90°]; \e - * lon0 should be in the range [−540°, 540°). + * \e lat0 should be in the range [−90°, 90°]. **********************************************************************/ - void Reset(real lat0, real lon0, real h0 = 0) throw(); + void Reset(real lat0, real lon0, real h0 = 0); /** * Convert from geodetic to local cartesian coordinates. @@ -102,11 +99,10 @@ namespace GeographicLib { * @param[out] y local cartesian coordinate (meters). * @param[out] z local cartesian coordinate (meters). * - * \e lat should be in the range [−90°, 90°]; \e lon - * should be in the range [−540°, 540°). + * \e lat should be in the range [−90°, 90°]. **********************************************************************/ void Forward(real lat, real lon, real h, real& x, real& y, real& z) - const throw() { + const { IntForward(lat, lon, h, x, y, z, NULL); } @@ -123,8 +119,7 @@ namespace GeographicLib { * @param[out] M if the length of the vector is 9, fill with the rotation * matrix in row-major order. * - * \e lat should be in the range [−90°, 90°]; \e lon - * should be in the range [−540°, 540°). + * \e lat should be in the range [−90°, 90°]. * * Let \e v be a unit vector located at (\e lat, \e lon, \e h). We can * express \e v as \e column vectors in one of two ways @@ -139,11 +134,11 @@ namespace GeographicLib { **********************************************************************/ void Forward(real lat, real lon, real h, real& x, real& y, real& z, std::vector& M) - const throw() { + const { if (M.end() == M.begin() + dim2_) { real t[dim2_]; IntForward(lat, lon, h, x, y, z, t); - copy(t, t + dim2_, M.begin()); + std::copy(t, t + dim2_, M.begin()); } else IntForward(lat, lon, h, x, y, z, NULL); } @@ -159,10 +154,10 @@ namespace GeographicLib { * @param[out] h height of point above the ellipsoid (meters). * * The value of \e lon returned is in the range [−180°, - * 180°). + * 180°]. **********************************************************************/ void Reverse(real x, real y, real z, real& lat, real& lon, real& h) - const throw() { + const { IntReverse(x, y, z, lat, lon, h, NULL); } @@ -188,16 +183,16 @@ namespace GeographicLib { * the local coordinate system at (\e lat0, \e lon0, \e h0)); call this * representation \e v0. * . - * Then we have \e v1 = \e MT ⋅ \e v0, where \e - * MT is the transpose of \e M. + * Then we have \e v1 = MT ⋅ \e v0, where + * MT is the transpose of \e M. **********************************************************************/ void Reverse(real x, real y, real z, real& lat, real& lon, real& h, std::vector& M) - const throw() { + const { if (M.end() == M.begin() + dim2_) { real t[dim2_]; IntReverse(x, y, z, lat, lon, h, t); - copy(t, t + dim2_, M.begin()); + std::copy(t, t + dim2_, M.begin()); } else IntReverse(x, y, z, lat, lon, h, NULL); } @@ -208,40 +203,32 @@ namespace GeographicLib { /** * @return latitude of the origin (degrees). **********************************************************************/ - Math::real LatitudeOrigin() const throw() { return _lat0; } + Math::real LatitudeOrigin() const { return _lat0; } /** * @return longitude of the origin (degrees). **********************************************************************/ - Math::real LongitudeOrigin() const throw() { return _lon0; } + Math::real LongitudeOrigin() const { return _lon0; } /** * @return height of the origin (meters). **********************************************************************/ - Math::real HeightOrigin() const throw() { return _h0; } + Math::real HeightOrigin() const { return _h0; } /** * @return \e a the equatorial radius of the ellipsoid (meters). This is * the value of \e a inherited from the Geocentric object used in the * constructor. **********************************************************************/ - Math::real MajorRadius() const throw() { return _earth.MajorRadius(); } + Math::real MajorRadius() const { return _earth.MajorRadius(); } /** * @return \e f the flattening of the ellipsoid. This is the value * inherited from the Geocentric object used in the constructor. **********************************************************************/ - Math::real Flattening() const throw() { return _earth.Flattening(); } + Math::real Flattening() const { return _earth.Flattening(); } ///@} - /// \cond SKIP - /** - * DEPRECATED - * @return \e r the inverse flattening of the ellipsoid. - **********************************************************************/ - Math::real InverseFlattening() const throw() - { return _earth.InverseFlattening(); } - /// \endcond }; } // namespace GeographicLib diff --git a/gtsam/3rdparty/GeographicLib/include/GeographicLib/MGRS.hpp b/gtsam/3rdparty/GeographicLib/include/GeographicLib/MGRS.hpp index e8ff0cbaf..88db8dc41 100644 --- a/gtsam/3rdparty/GeographicLib/include/GeographicLib/MGRS.hpp +++ b/gtsam/3rdparty/GeographicLib/include/GeographicLib/MGRS.hpp @@ -2,9 +2,9 @@ * \file MGRS.hpp * \brief Header for GeographicLib::MGRS class * - * Copyright (c) Charles Karney (2008-2011) and licensed + * Copyright (c) Charles Karney (2008-2017) and licensed * under the MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #if !defined(GEOGRAPHICLIB_MGRS_HPP) @@ -27,9 +27,16 @@ namespace GeographicLib { * MGRS is defined in Chapter 3 of * - J. W. Hager, L. L. Fry, S. S. Jacks, D. R. Hill, * - * Datums, Ellipsoids, Grids, and Grid Reference Systems, * Defense Mapping Agency, Technical Manual TM8358.1 (1990). + * . + * This document has been updated by the two NGA documents + * - + * Universal Grids and Grid Reference Systems, + * NGA.STND.0037_2.0.0_GRIDS (2014). + * - + * The Universal Grids and the Transverse Mercator and Polar Stereographic + * Map Projections, NGA.SIG.0012_2.0.0_UTMUPS (2014). * * This implementation has the following properties: * - The conversions are closed, i.e., output from Forward is legal input for @@ -39,6 +46,11 @@ namespace GeographicLib { * identity. (This is affected in predictable ways by errors in * determining the latitude band and by loss of precision in the MGRS * coordinates.) + * - The trailing digits produced by Forward are consistent as the precision + * is varied. Specifically, the digits are obtained by operating on the + * easting with ⌊106 x⌋ and extracting the + * required digits from the resulting number (and similarly for the + * northing). * - All MGRS coordinates truncate to legal 100 km blocks. All MGRS * coordinates with a legal 100 km block prefix are legal (even though the * latitude band letter may now belong to a neighboring band). @@ -62,18 +74,14 @@ namespace GeographicLib { class GEOGRAPHICLIB_EXPORT MGRS { private: typedef Math::real real; - // The smallest length s.t., 1.0e7 - eps_ < 1.0e7 (approx 1.9 nm) - static const real eps_; - // The smallest angle s.t., 90 - eps_ < 90 (approx 50e-12 arcsec) - static const real angeps_; - static const std::string hemispheres_; - static const std::string utmcols_[3]; - static const std::string utmrow_; - static const std::string upscols_[4]; - static const std::string upsrows_[2]; - static const std::string latband_; - static const std::string upsband_; - static const std::string digits_; + static const char* const hemispheres_; + static const char* const utmcols_[3]; + static const char* const utmrow_; + static const char* const upscols_[4]; + static const char* const upsrows_[2]; + static const char* const latband_; + static const char* const upsband_; + static const char* const digits_; static const int mineasting_[4]; static const int maxeasting_[4]; @@ -89,28 +97,32 @@ namespace GeographicLib { utmevenrowshift_ = 5, // Maximum precision is um maxprec_ = 5 + 6, + // For generating digits at maxprec + mult_ = 1000000, }; static void CheckCoords(bool utmp, bool& northp, real& x, real& y); - static int UTMRow(int iband, int icol, int irow) throw(); + static int UTMRow(int iband, int icol, int irow); friend class UTMUPS; // UTMUPS::StandardZone calls LatitudeBand // Return latitude band number [-10, 10) for the given latitude (degrees). // The bands are reckoned in include their southern edges. - static int LatitudeBand(real lat) throw() { - int ilat = int(std::floor(lat)); + static int LatitudeBand(real lat) { + using std::floor; + int ilat = int(floor(lat)); return (std::max)(-10, (std::min)(9, (ilat + 80)/8 - 10)); } // Return approximate latitude band number [-10, 10) for the given northing // (meters). With this rule, each 100km tile would have a unique band // letter corresponding to the latitude at the center of the tile. This // function isn't currently used. - static int ApproxLatitudeBand(real y) throw() { + static int ApproxLatitudeBand(real y) { // northing at tile center in units of tile = 100km - real ya = std::floor( (std::min)(real(88), std::abs(y/tile_)) ) + + using std::floor; using std::abs; + real ya = floor( (std::min)(real(88), abs(y/tile_)) ) + real(0.5); // convert to lat (mult by 90/100) and then to band (divide by 8) // the +1 fine tunes the boundary between bands 3 and 4 - int b = int(std::floor( ((ya * 9 + 1) / 10) / 8 )); + int b = int(floor( ((ya * 9 + 1) / 10) / 8 )); // For the northern hemisphere we have // band rows num // N 0 0:8 9 @@ -162,14 +174,16 @@ namespace GeographicLib { * allocated. * * \e prec specifies the precision of the MGRS string as follows: - * - prec = 0 (min), 100 km - * - prec = 1, 10 km - * - prec = 2, 1 km - * - prec = 3, 100 m - * - prec = 4, 10 m - * - prec = 5, 1 m - * - prec = 6, 0.1 m - * - prec = 11 (max), 1 μm + * - \e prec = −1 (min), only the grid zone is returned + * - \e prec = 0, 100 km + * - \e prec = 1, 10 km + * - \e prec = 2, 1 km + * - \e prec = 3, 100 m + * - \e prec = 4, 10 m + * - \e prec = 5, 1 m + * - \e prec = 6, 0.1 m + * - … + * - \e prec = 11 (max), 1 μm * * UTM eastings are allowed to be in the range [100 km, 900 km], northings * are allowed to be in in [0 km, 9500 km] for the northern hemisphere and @@ -182,7 +196,7 @@ namespace GeographicLib { * in the northern hemisphere and in [800 km, 3200 km] in the southern * hemisphere. * - * The ranges are 100 km more restrictive that for the conversion between + * The ranges are 100 km more restrictive than for the conversion between * geographic coordinates and UTM and UPS given by UTMUPS. These * restrictions are dictated by the allowed letters in MGRS coordinates. * The choice of 9500 km for the maximum northing for northern hemisphere @@ -197,7 +211,7 @@ namespace GeographicLib { * them \e within the allowed range. (This includes reducing a southern * hemisphere northing of 10000 km by 4 nm so that it is placed in latitude * band M.) The UTM or UPS coordinates are truncated to requested - * precision to determine the MGRS coordinate. Thus in UTM zone 38N, the + * precision to determine the MGRS coordinate. Thus in UTM zone 38n, the * square area with easting in [444 km, 445 km) and northing in [3688 km, * 3689 km) maps to MGRS coordinate 38SMB4488 (at \e prec = 2, 1 km), * Khulani Sq., Baghdad. @@ -214,6 +228,11 @@ namespace GeographicLib { * of a band boundary. For prec in [6, 11], the conversion is accurate to * roundoff. * + * If \e prec = −1, then the "grid zone designation", e.g., 18T, is + * returned. This consists of the UTM zone number (absent for UPS) and the + * first letter of the MGRS string which labels the latitude band for UTM + * and the hemisphere for UPS. + * * If \e x or \e y is NaN or if \e zone is UTMUPS::INVALID, the returned * MGRS string is "INVALID". * @@ -267,22 +286,29 @@ namespace GeographicLib { * zones 1--9.) In addition, MGRS coordinates with a neighboring * latitude band letter are permitted provided that some portion of the * 100 km block is within the given latitude band. Thus - * - 38VLS and 38WLS are allowed (latitude 64N intersects the square - * 38[VW]LS); but 38VMS is not permitted (all of 38VMS is north of 64N) - * - 38MPE and 38NPF are permitted (they straddle the equator); but 38NPE - * and 38MPF are not permitted (the equator does not intersect either - * block). - * - Similarly ZAB and YZB are permitted (they straddle the prime - * meridian); but YAB and ZZB are not (the prime meridian does not - * intersect either block). + * - 38VLS and 38WLS are allowed (latitude 64N intersects the square + * 38[VW]LS); but 38VMS is not permitted (all of 38WMS is north of 64N) + * - 38MPE and 38NPF are permitted (they straddle the equator); but 38NPE + * and 38MPF are not permitted (the equator does not intersect either + * block). + * - Similarly ZAB and YZB are permitted (they straddle the prime + * meridian); but YAB and ZZB are not (the prime meridian does not + * intersect either block). * * The UTM/UPS selection and the UTM zone is preserved in the conversion * from MGRS coordinate. The conversion is exact for prec in [0, 5]. With - * centerp = true the conversion from MGRS to geographic and back is + * \e centerp = true, the conversion from MGRS to geographic and back is * stable. This is not assured if \e centerp = false. * + * If a "grid zone designation" (for example, 18T or A) is given, then some + * suitable (but essentially arbitrary) point within that grid zone is + * returned. The main utility of the conversion is to allow \e zone and \e + * northp to be determined. In this case, the \e centerp parameter is + * ignored and \e prec is set to −1. + * * If the first 3 characters of \e mgrs are "INV", then \e x and \e y are - * set to NaN and \e zone is set to UTMUPS::INVALID. + * set to NaN, \e zone is set to UTMUPS::INVALID, and \e prec is set to + * −2. * * If an exception is thrown, then the arguments are unchanged. **********************************************************************/ @@ -299,7 +325,7 @@ namespace GeographicLib { * (The WGS84 value is returned because the UTM and UPS projections are * based on this ellipsoid.) **********************************************************************/ - static Math::real MajorRadius() throw() { return UTMUPS::MajorRadius(); } + static Math::real MajorRadius() { return UTMUPS::MajorRadius(); } /** * @return \e f the flattening of the WGS84 ellipsoid. @@ -307,17 +333,17 @@ namespace GeographicLib { * (The WGS84 value is returned because the UTM and UPS projections are * based on this ellipsoid.) **********************************************************************/ - static Math::real Flattening() throw() { return UTMUPS::Flattening(); } + static Math::real Flattening() { return UTMUPS::Flattening(); } ///@} - /// \cond SKIP /** - * DEPRECATED - * @return \e r the inverse flattening of the WGS84 ellipsoid. + * Perform some checks on the UTMUPS coordinates on this ellipsoid. Throw + * an error if any of the assumptions made in the MGRS class is not true. + * This check needs to be carried out if the ellipsoid parameters (or the + * UTM/UPS scales) are ever changed. **********************************************************************/ - static Math::real InverseFlattening() throw() - { return UTMUPS::InverseFlattening(); } - /// \endcond + static void Check(); + }; } // namespace GeographicLib diff --git a/gtsam/3rdparty/GeographicLib/include/GeographicLib/MagneticCircle.hpp b/gtsam/3rdparty/GeographicLib/include/GeographicLib/MagneticCircle.hpp index fd43043f9..041c4b44d 100644 --- a/gtsam/3rdparty/GeographicLib/include/GeographicLib/MagneticCircle.hpp +++ b/gtsam/3rdparty/GeographicLib/include/GeographicLib/MagneticCircle.hpp @@ -2,9 +2,9 @@ * \file MagneticCircle.hpp * \brief Header for GeographicLib::MagneticCircle class * - * Copyright (c) Charles Karney (2011) and licensed under - * the MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ + * Copyright (c) Charles Karney (2011-2015) and licensed + * under the MIT/X11 License. For more information, see + * https://geographiclib.sourceforge.io/ **********************************************************************/ #if !defined(GEOGRAPHICLIB_MAGNETICCIRCLE_HPP) @@ -39,8 +39,8 @@ namespace GeographicLib { typedef Math::real real; real _a, _f, _lat, _h, _t, _cphi, _sphi, _t1, _dt0; - bool _interpolate; - CircularEngine _circ0, _circ1; + bool _interpolate, _constterm; + CircularEngine _circ0, _circ1, _circ2; MagneticCircle(real a, real f, real lat, real h, real t, real cphi, real sphi, real t1, real dt0, @@ -48,6 +48,26 @@ namespace GeographicLib { const CircularEngine& circ0, const CircularEngine& circ1) : _a(a) , _f(f) + , _lat(Math::LatFix(lat)) + , _h(h) + , _t(t) + , _cphi(cphi) + , _sphi(sphi) + , _t1(t1) + , _dt0(dt0) + , _interpolate(interpolate) + , _constterm(false) + , _circ0(circ0) + , _circ1(circ1) + {} + + MagneticCircle(real a, real f, real lat, real h, real t, + real cphi, real sphi, real t1, real dt0, + bool interpolate, + const CircularEngine& circ0, const CircularEngine& circ1, + const CircularEngine& circ2) + : _a(a) + , _f(f) , _lat(lat) , _h(h) , _t(t) @@ -56,13 +76,15 @@ namespace GeographicLib { , _t1(t1) , _dt0(dt0) , _interpolate(interpolate) + , _constterm(true) , _circ0(circ0) , _circ1(circ1) + , _circ2(circ2) {} void Field(real lon, bool diffp, real& Bx, real& By, real& Bz, - real& Bxt, real& Byt, real& Bzt) const throw(); + real& Bxt, real& Byt, real& Bzt) const; friend class MagneticModel; // MagneticModel calls the private constructor @@ -84,11 +106,12 @@ namespace GeographicLib { * * @param[in] lon longitude of the point (degrees). * @param[out] Bx the easterly component of the magnetic field (nanotesla). - * @param[out] By the northerly component of the magnetic field (nanotesla). + * @param[out] By the northerly component of the magnetic field + * (nanotesla). * @param[out] Bz the vertical (up) component of the magnetic field * (nanotesla). **********************************************************************/ - void operator()(real lon, real& Bx, real& By, real& Bz) const throw() { + void operator()(real lon, real& Bx, real& By, real& Bz) const { real dummy; Field(lon, false, Bx, By, Bz, dummy, dummy, dummy); } @@ -99,7 +122,8 @@ namespace GeographicLib { * * @param[in] lon longitude of the point (degrees). * @param[out] Bx the easterly component of the magnetic field (nanotesla). - * @param[out] By the northerly component of the magnetic field (nanotesla). + * @param[out] By the northerly component of the magnetic field + * (nanotesla). * @param[out] Bz the vertical (up) component of the magnetic field * (nanotesla). * @param[out] Bxt the rate of change of \e Bx (nT/yr). @@ -107,7 +131,7 @@ namespace GeographicLib { * @param[out] Bzt the rate of change of \e Bz (nT/yr). **********************************************************************/ void operator()(real lon, real& Bx, real& By, real& Bz, - real& Bxt, real& Byt, real& Bzt) const throw() { + real& Bxt, real& Byt, real& Bzt) const { Field(lon, true, Bx, By, Bz, Bxt, Byt, Bzt); } ///@} @@ -118,35 +142,35 @@ namespace GeographicLib { /** * @return true if the object has been initialized. **********************************************************************/ - bool Init() const throw() { return _a > 0; } + bool Init() const { return _a > 0; } /** * @return \e a the equatorial radius of the ellipsoid (meters). This is * the value inherited from the MagneticModel object used in the * constructor. **********************************************************************/ - Math::real MajorRadius() const throw() - { return Init() ? _a : Math::NaN(); } + Math::real MajorRadius() const + { return Init() ? _a : Math::NaN(); } /** * @return \e f the flattening of the ellipsoid. This is the value * inherited from the MagneticModel object used in the constructor. **********************************************************************/ - Math::real Flattening() const throw() - { return Init() ? _f : Math::NaN(); } + Math::real Flattening() const + { return Init() ? _f : Math::NaN(); } /** * @return the latitude of the circle (degrees). **********************************************************************/ - Math::real Latitude() const throw() - { return Init() ? _lat : Math::NaN(); } + Math::real Latitude() const + { return Init() ? _lat : Math::NaN(); } /** * @return the height of the circle (meters). **********************************************************************/ - Math::real Height() const throw() - { return Init() ? _h : Math::NaN(); } + Math::real Height() const + { return Init() ? _h : Math::NaN(); } /** * @return the time (fractional years). **********************************************************************/ - Math::real Time() const throw() - { return Init() ? _t : Math::NaN(); } + Math::real Time() const + { return Init() ? _t : Math::NaN(); } ///@} }; diff --git a/gtsam/3rdparty/GeographicLib/include/GeographicLib/MagneticModel.hpp b/gtsam/3rdparty/GeographicLib/include/GeographicLib/MagneticModel.hpp index b0e0aaf7f..44de875a5 100644 --- a/gtsam/3rdparty/GeographicLib/include/GeographicLib/MagneticModel.hpp +++ b/gtsam/3rdparty/GeographicLib/include/GeographicLib/MagneticModel.hpp @@ -2,9 +2,9 @@ * \file MagneticModel.hpp * \brief Header for GeographicLib::MagneticModel class * - * Copyright (c) Charles Karney (2011) and licensed under - * the MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ + * Copyright (c) Charles Karney (2011-2015) and licensed + * under the MIT/X11 License. For more information, see + * https://geographiclib.sourceforge.io/ **********************************************************************/ #if !defined(GEOGRAPHICLIB_MAGNETICMODEL_HPP) @@ -33,22 +33,31 @@ namespace GeographicLib { * of currents in the ionosphere and magnetosphere which have daily and * annual variations. * - * See \ref magnetic for details of how to install the magnetic model and the - * data format. + * See \ref magnetic for details of how to install the magnetic models and + * the data format. * * See * - General information: * - http://geomag.org/models/index.html * - WMM2010: - * - http://ngdc.noaa.gov/geomag/WMM/DoDWMM.shtml - * - http://ngdc.noaa.gov/geomag/WMM/data/WMM2010/WMM2010COF.zip + * - https://ngdc.noaa.gov/geomag/WMM/DoDWMM.shtml + * - https://ngdc.noaa.gov/geomag/WMM/data/WMM2010/WMM2010COF.zip + * - WMM2015: + * - https://ngdc.noaa.gov/geomag/WMM/DoDWMM.shtml + * - https://ngdc.noaa.gov/geomag/WMM/data/WMM2015/WMM2015COF.zip * - IGRF11: - * - http://ngdc.noaa.gov/IAGA/vmod/igrf.html - * - http://ngdc.noaa.gov/IAGA/vmod/igrf11coeffs.txt - * - http://ngdc.noaa.gov/IAGA/vmod/geomag70_linux.tar.gz + * - https://ngdc.noaa.gov/IAGA/vmod/igrf.html + * - https://ngdc.noaa.gov/IAGA/vmod/igrf11coeffs.txt + * - https://ngdc.noaa.gov/IAGA/vmod/geomag70_linux.tar.gz * - EMM2010: - * - http://ngdc.noaa.gov/geomag/EMM/index.html - * - http://ngdc.noaa.gov/geomag/EMM/data/geomag/EMM2010_Sph_Windows_Linux.zip + * - https://ngdc.noaa.gov/geomag/EMM/index.html + * - https://ngdc.noaa.gov/geomag/EMM/data/geomag/EMM2010_Sph_Windows_Linux.zip + * - EMM2015: + * - https://ngdc.noaa.gov/geomag/EMM/index.html + * - https://www.ngdc.noaa.gov/geomag/EMM/data/geomag/EMM2015_Sph_Linux.zip + * - EMM2017: + * - https://ngdc.noaa.gov/geomag/EMM/index.html + * - https://www.ngdc.noaa.gov/geomag/EMM/data/geomag/EMM2017_Sph_Linux.zip * * Example of use: * \include example-MagneticModel.cpp @@ -63,7 +72,7 @@ namespace GeographicLib { static const int idlength_ = 8; std::string _name, _dir, _description, _date, _filename, _id; real _t0, _dt0, _tmin, _tmax, _a, _hmin, _hmax; - int _Nmodels; + int _Nmodels, _Nconstants; SphericalHarmonic::normalization _norm; Geocentric _earth; std::vector< std::vector > _G; @@ -71,7 +80,7 @@ namespace GeographicLib { std::vector _harm; void Field(real t, real lat, real lon, real h, bool diffp, real& Bx, real& By, real& Bz, - real& Bxt, real& Byt, real& Bzt) const throw(); + real& Bxt, real& Byt, real& Bzt) const; void ReadMetadata(const std::string& name); MagneticModel(const MagneticModel&); // copy constructor not allowed MagneticModel& operator=(const MagneticModel&); // nor copy assignment @@ -86,7 +95,7 @@ namespace GeographicLib { * @param[in] name the name of the model. * @param[in] path (optional) directory for data file. * @param[in] earth (optional) Geocentric object for converting - * coordinates; default Geocentric::WGS84. + * coordinates; default Geocentric::WGS84(). * @exception GeographicErr if the data file cannot be found, is * unreadable, or is corrupt. * @exception std::bad_alloc if the memory necessary for storing the model @@ -109,7 +118,7 @@ namespace GeographicLib { **********************************************************************/ explicit MagneticModel(const std::string& name, const std::string& path = "", - const Geocentric& earth = Geocentric::WGS84); + const Geocentric& earth = Geocentric::WGS84()); ///@} /** \name Compute the magnetic field @@ -123,12 +132,13 @@ namespace GeographicLib { * @param[in] lon longitude of the point (degrees). * @param[in] h the height of the point above the ellipsoid (meters). * @param[out] Bx the easterly component of the magnetic field (nanotesla). - * @param[out] By the northerly component of the magnetic field (nanotesla). + * @param[out] By the northerly component of the magnetic field + * (nanotesla). * @param[out] Bz the vertical (up) component of the magnetic field * (nanotesla). **********************************************************************/ void operator()(real t, real lat, real lon, real h, - real& Bx, real& By, real& Bz) const throw() { + real& Bx, real& By, real& Bz) const { real dummy; Field(t, lat, lon, h, false, Bx, By, Bz, dummy, dummy, dummy); } @@ -142,7 +152,8 @@ namespace GeographicLib { * @param[in] lon longitude of the point (degrees). * @param[in] h the height of the point above the ellipsoid (meters). * @param[out] Bx the easterly component of the magnetic field (nanotesla). - * @param[out] By the northerly component of the magnetic field (nanotesla). + * @param[out] By the northerly component of the magnetic field + * (nanotesla). * @param[out] Bz the vertical (up) component of the magnetic field * (nanotesla). * @param[out] Bxt the rate of change of \e Bx (nT/yr). @@ -151,7 +162,7 @@ namespace GeographicLib { **********************************************************************/ void operator()(real t, real lat, real lon, real h, real& Bx, real& By, real& Bz, - real& Bxt, real& Byt, real& Bzt) const throw() { + real& Bxt, real& Byt, real& Bzt) const { Field(t, lat, lon, h, true, Bx, By, Bz, Bxt, Byt, Bzt); } @@ -189,7 +200,7 @@ namespace GeographicLib { * horizontal). **********************************************************************/ static void FieldComponents(real Bx, real By, real Bz, - real& H, real& F, real& D, real& I) throw() { + real& H, real& F, real& D, real& I) { real Ht, Ft, Dt, It; FieldComponents(Bx, By, Bz, real(0), real(1), real(0), H, F, D, I, Ht, Ft, Dt, It); @@ -219,7 +230,7 @@ namespace GeographicLib { static void FieldComponents(real Bx, real By, real Bz, real Bxt, real Byt, real Bzt, real& H, real& F, real& D, real& I, - real& Ht, real& Ft, real& Dt, real& It) throw(); + real& Ht, real& Ft, real& Dt, real& It); ///@} /** \name Inspector functions @@ -229,29 +240,29 @@ namespace GeographicLib { * @return the description of the magnetic model, if available, from the * Description file in the data file; if absent, return "NONE". **********************************************************************/ - const std::string& Description() const throw() { return _description; } + const std::string& Description() const { return _description; } /** * @return date of the model, if available, from the ReleaseDate field in * the data file; if absent, return "UNKNOWN". **********************************************************************/ - const std::string& DateTime() const throw() { return _date; } + const std::string& DateTime() const { return _date; } /** * @return full file name used to load the magnetic model. **********************************************************************/ - const std::string& MagneticFile() const throw() { return _filename; } + const std::string& MagneticFile() const { return _filename; } /** * @return "name" used to load the magnetic model (from the first argument * of the constructor, but this may be overridden by the model file). **********************************************************************/ - const std::string& MagneticModelName() const throw() { return _name; } + const std::string& MagneticModelName() const { return _name; } /** * @return directory used to load the magnetic model. **********************************************************************/ - const std::string& MagneticModelDirectory() const throw() { return _dir; } + const std::string& MagneticModelDirectory() const { return _dir; } /** * @return the minimum height above the ellipsoid (in meters) for which @@ -262,7 +273,7 @@ namespace GeographicLib { * argument is made by MagneticModel::operator()() or * MagneticModel::Circle. **********************************************************************/ - Math::real MinHeight() const throw() { return _hmin; } + Math::real MinHeight() const { return _hmin; } /** * @return the maximum height above the ellipsoid (in meters) for which @@ -273,7 +284,7 @@ namespace GeographicLib { * argument is made by MagneticModel::operator()() or * MagneticModel::Circle. **********************************************************************/ - Math::real MaxHeight() const throw() { return _hmax; } + Math::real MaxHeight() const { return _hmax; } /** * @return the minimum time (in years) for which this MagneticModel should @@ -284,7 +295,7 @@ namespace GeographicLib { * argument is made by MagneticModel::operator()() or * MagneticModel::Circle. **********************************************************************/ - Math::real MinTime() const throw() { return _tmin; } + Math::real MinTime() const { return _tmin; } /** * @return the maximum time (in years) for which this MagneticModel should @@ -295,41 +306,42 @@ namespace GeographicLib { * argument is made by MagneticModel::operator()() or * MagneticModel::Circle. **********************************************************************/ - Math::real MaxTime() const throw() { return _tmax; } + Math::real MaxTime() const { return _tmax; } /** * @return \e a the equatorial radius of the ellipsoid (meters). This is * the value of \e a inherited from the Geocentric object used in the * constructor. **********************************************************************/ - Math::real MajorRadius() const throw() { return _earth.MajorRadius(); } + Math::real MajorRadius() const { return _earth.MajorRadius(); } /** * @return \e f the flattening of the ellipsoid. This is the value * inherited from the Geocentric object used in the constructor. **********************************************************************/ - Math::real Flattening() const throw() { return _earth.Flattening(); } + Math::real Flattening() const { return _earth.Flattening(); } ///@} /** * @return the default path for magnetic model data files. * - * This is the value of the environment variable MAGNETIC_PATH, if set; - * otherwise, it is $GEOGRAPHICLIB_DATA/magnetic if the environment - * variable GEOGRAPHICLIB_DATA is set; otherwise, it is a compile-time - * default (/usr/local/share/GeographicLib/magnetic on non-Windows systems - * and C:/Documents and Settings/All Users/Application - * Data/GeographicLib/magnetic on Windows systems). + * This is the value of the environment variable + * GEOGRAPHICLIB_MAGNETIC_PATH, if set; otherwise, it is + * $GEOGRAPHICLIB_DATA/magnetic if the environment variable + * GEOGRAPHICLIB_DATA is set; otherwise, it is a compile-time default + * (/usr/local/share/GeographicLib/magnetic on non-Windows systems and + * C:/ProgramData/GeographicLib/magnetic on Windows systems). **********************************************************************/ static std::string DefaultMagneticPath(); /** * @return the default name for the magnetic model. * - * This is the value of the environment variable MAGNETIC_NAME, if set, - * otherwise, it is "wmm2010". The MagneticModel class does not use this - * function; it is just provided as a convenience for a calling program - * when constructing a MagneticModel object. + * This is the value of the environment variable + * GEOGRAPHICLIB_MAGNETIC_NAME, if set; otherwise, it is "wmm2015". The + * MagneticModel class does not use this function; it is just provided as a + * convenience for a calling program when constructing a MagneticModel + * object. **********************************************************************/ static std::string DefaultMagneticName(); }; diff --git a/gtsam/3rdparty/GeographicLib/include/GeographicLib/Math.hpp b/gtsam/3rdparty/GeographicLib/include/GeographicLib/Math.hpp index 2ef649e96..48f1d7e04 100644 --- a/gtsam/3rdparty/GeographicLib/include/GeographicLib/Math.hpp +++ b/gtsam/3rdparty/GeographicLib/include/GeographicLib/Math.hpp @@ -2,9 +2,9 @@ * \file Math.hpp * \brief Header for GeographicLib::Math class * - * Copyright (c) Charles Karney (2008-2011) and licensed + * Copyright (c) Charles Karney (2008-2017) and licensed * under the MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ // Constants.hpp includes Math.hpp. Place this include outside Math.hpp's @@ -17,26 +17,31 @@ /** * Are C++11 math functions available? **********************************************************************/ -#if !defined(GEOGRAPHICLIB_CPLUSPLUS11_MATH) -# if defined(__GNUC__) && __GNUC__ == 4 && __GNUC_MINOR__ >= 7 \ - && __cplusplus >= 201103 && !(defined(__ANDROID__) || defined(ANDROID)) -// The android toolchain uses g++ and supports C++11, but not, apparently, the -// new mathematical functions introduced with C++11. Android toolchains might -// define __ANDROID__ or ANDROID; so need to check both. -# define GEOGRAPHICLIB_CPLUSPLUS11_MATH 1 +#if !defined(GEOGRAPHICLIB_CXX11_MATH) +// Recent versions of g++ -std=c++11 (4.7 and later?) set __cplusplus to 201103 +// and support the new C++11 mathematical functions, std::atanh, etc. However +// the Android toolchain, which uses g++ -std=c++11 (4.8 as of 2014-03-11, +// according to Pullan Lu), does not support std::atanh. Android toolchains +// might define __ANDROID__ or ANDROID; so need to check both. With OSX the +// version is GNUC version 4.2 and __cplusplus is set to 201103, so remove the +// version check on GNUC. +# if defined(__GNUC__) && __cplusplus >= 201103 && \ + !(defined(__ANDROID__) || defined(ANDROID) || defined(__CYGWIN__)) +# define GEOGRAPHICLIB_CXX11_MATH 1 +// Visual C++ 12 supports these functions # elif defined(_MSC_VER) && _MSC_VER >= 1800 -# define GEOGRAPHICLIB_CPLUSPLUS11_MATH 1 +# define GEOGRAPHICLIB_CXX11_MATH 1 # else -# define GEOGRAPHICLIB_CPLUSPLUS11_MATH 0 +# define GEOGRAPHICLIB_CXX11_MATH 0 # endif #endif -#if !defined(WORDS_BIGENDIAN) -# define WORDS_BIGENDIAN 0 +#if !defined(GEOGRAPHICLIB_WORDS_BIGENDIAN) +# define GEOGRAPHICLIB_WORDS_BIGENDIAN 0 #endif -#if !defined(HAVE_LONG_DOUBLE) -# define HAVE_LONG_DOUBLE 0 +#if !defined(GEOGRAPHICLIB_HAVE_LONG_DOUBLE) +# define GEOGRAPHICLIB_HAVE_LONG_DOUBLE 0 #endif #if !defined(GEOGRAPHICLIB_PRECISION) @@ -45,8 +50,9 @@ * float (single precision); 2 (the default) means double; 3 means long double; * 4 is reserved for quadruple precision. Nearly all the testing has been * carried out with doubles and that's the recommended configuration. In order - * for long double to be used, HAVE_LONG_DOUBLE needs to be defined. Note that - * with Microsoft Visual Studio, long double is the same as double. + * for long double to be used, GEOGRAPHICLIB_HAVE_LONG_DOUBLE needs to be + * defined. Note that with Microsoft Visual Studio, long double is the same as + * double. **********************************************************************/ # define GEOGRAPHICLIB_PRECISION 2 #endif @@ -54,8 +60,31 @@ #include #include #include -#if defined(_LIBCPP_VERSION) -#include + +#if GEOGRAPHICLIB_PRECISION == 4 +#include +#if BOOST_VERSION >= 105600 +#include +#endif +#include +#include +__float128 fmaq(__float128, __float128, __float128); +#elif GEOGRAPHICLIB_PRECISION == 5 +#include +#endif + +#if GEOGRAPHICLIB_PRECISION > 3 +// volatile keyword makes no sense for multiprec types +#define GEOGRAPHICLIB_VOLATILE +// Signal a convergence failure with multiprec types by throwing an exception +// at loop exit. +#define GEOGRAPHICLIB_PANIC \ + (throw GeographicLib::GeographicErr("Convergence failure"), false) +#else +#define GEOGRAPHICLIB_VOLATILE volatile +// Ignore convergence failures with standard floating points types by allowing +// loop to exit cleanly. +#define GEOGRAPHICLIB_PANIC false #endif namespace GeographicLib { @@ -73,14 +102,14 @@ namespace GeographicLib { class GEOGRAPHICLIB_EXPORT Math { private: void dummy() { - STATIC_ASSERT(GEOGRAPHICLIB_PRECISION >= 1 && - GEOGRAPHICLIB_PRECISION <= 3, - "Bad value of precision"); + GEOGRAPHICLIB_STATIC_ASSERT(GEOGRAPHICLIB_PRECISION >= 1 && + GEOGRAPHICLIB_PRECISION <= 5, + "Bad value of precision"); } Math(); // Disable constructor public: -#if HAVE_LONG_DOUBLE +#if GEOGRAPHICLIB_HAVE_LONG_DOUBLE /** * The extended precision type for real numbers, used for some testing. * This is long double on computers with this type; otherwise it is double. @@ -102,46 +131,96 @@ namespace GeographicLib { typedef float real; #elif GEOGRAPHICLIB_PRECISION == 3 typedef extended real; +#elif GEOGRAPHICLIB_PRECISION == 4 + typedef boost::multiprecision::float128 real; +#elif GEOGRAPHICLIB_PRECISION == 5 + typedef mpfr::mpreal real; #else typedef double real; #endif /** - * Number of additional decimal digits of precision of real relative to + * @return the number of bits of precision in a real number. + **********************************************************************/ + static int digits() { +#if GEOGRAPHICLIB_PRECISION != 5 + return std::numeric_limits::digits; +#else + return std::numeric_limits::digits(); +#endif + } + + /** + * Set the binary precision of a real number. + * + * @param[in] ndigits the number of bits of precision. + * @return the resulting number of bits of precision. + * + * This only has an effect when GEOGRAPHICLIB_PRECISION = 5. See also + * Utility::set_digits for caveats about when this routine should be + * called. + **********************************************************************/ + static int set_digits(int ndigits) { +#if GEOGRAPHICLIB_PRECISION != 5 + (void)ndigits; +#else + mpfr::mpreal::set_default_prec(ndigits >= 2 ? ndigits : 2); +#endif + return digits(); + } + + /** + * @return the number of decimal digits of precision in a real number. + **********************************************************************/ + static int digits10() { +#if GEOGRAPHICLIB_PRECISION != 5 + return std::numeric_limits::digits10; +#else + return std::numeric_limits::digits10(); +#endif + } + + /** + * Number of additional decimal digits of precision for real relative to * double (0 for float). **********************************************************************/ - static const int extradigits = - std::numeric_limits::digits10 > - std::numeric_limits::digits10 ? - std::numeric_limits::digits10 - - std::numeric_limits::digits10 : 0; + static int extra_digits() { + return + digits10() > std::numeric_limits::digits10 ? + digits10() - std::numeric_limits::digits10 : 0; + } /** * true if the machine is big-endian. **********************************************************************/ - static const bool bigendian = WORDS_BIGENDIAN; + static const bool bigendian = GEOGRAPHICLIB_WORDS_BIGENDIAN; /** * @tparam T the type of the returned value. * @return π. **********************************************************************/ - template static inline T pi() throw() - { return std::atan2(T(0), -T(1)); } + template static T pi() { + using std::atan2; + static const T pi = atan2(T(0), T(-1)); + return pi; + } /** * A synonym for pi(). **********************************************************************/ - static inline real pi() throw() { return pi(); } + static real pi() { return pi(); } /** * @tparam T the type of the returned value. * @return the number of radians in a degree. **********************************************************************/ - template static inline T degree() throw() - { return pi() / T(180); } + template static T degree() { + static const T degree = pi() / 180; + return degree; + } /** * A synonym for degree(). **********************************************************************/ - static inline real degree() throw() { return degree(); } + static real degree() { return degree(); } /** * Square a number. @@ -150,10 +229,9 @@ namespace GeographicLib { * @param[in] x * @return x2. **********************************************************************/ - template static inline T sq(T x) throw() + template static T sq(T x) { return x * x; } -#if defined(DOXYGEN) /** * The hypotenuse function avoiding underflow and overflow. * @@ -162,174 +240,101 @@ namespace GeographicLib { * @param[in] y * @return sqrt(x2 + y2). **********************************************************************/ - template static inline T hypot(T x, T y) throw() { - x = std::abs(x); y = std::abs(y); - T a = (std::max)(x, y), b = (std::min)(x, y) / (a ? a : 1); - return a * std::sqrt(1 + b * b); - // For an alternative (square-root free) method see - // C. Moler and D. Morrision (1983) http://dx.doi.org/10.1147/rd.276.0577 - // and A. A. Dubrulle (1983) http://dx.doi.org/10.1147/rd.276.0582 - } -#elif GEOGRAPHICLIB_CPLUSPLUS11_MATH || (defined(_MSC_VER) && _MSC_VER >= 1700) - template static inline T hypot(T x, T y) throw() - { return std::hypot(x, y); } -# if HAVE_LONG_DOUBLE && defined(_MSC_VER) && _MSC_VER == 1700 - // Visual C++ 11 doesn't have a long double overload for std::hypot -- - // reported to MS on 2013-07-18 - // http://connect.microsoft.com/VisualStudio/feedback/details/794416 - // suppress the resulting "loss of data warning" with - static inline long double hypot(long double x, long double y) throw() - { return std::hypot(double(x), double(y)); } -# endif -#elif defined(_MSC_VER) - static inline double hypot(double x, double y) throw() - { return _hypot(x, y); } -# if _MSC_VER < 1400 - // Visual C++ 7.1/VS .NET 2003 does not have _hypotf() - static inline float hypot(float x, float y) throw() - { return float(_hypot(x, y)); } -# else - static inline float hypot(float x, float y) throw() - { return _hypotf(x, y); } -# endif -# if HAVE_LONG_DOUBLE - static inline long double hypot(long double x, long double y) throw() - { return _hypot(double(x), double(y)); } // Suppress loss of data warning -# endif + template static T hypot(T x, T y) { +#if GEOGRAPHICLIB_CXX11_MATH + using std::hypot; return hypot(x, y); #else - // Use overloading to define generic versions - static inline double hypot(double x, double y) throw() - { return ::hypot(x, y); } - static inline float hypot(float x, float y) throw() - { return ::hypotf(x, y); } -# if HAVE_LONG_DOUBLE - static inline long double hypot(long double x, long double y) throw() - { return ::hypotl(x, y); } -# endif + using std::abs; using std::sqrt; + x = abs(x); y = abs(y); + if (x < y) std::swap(x, y); // Now x >= y >= 0 + y /= (x ? x : 1); + return x * sqrt(1 + y * y); + // For an alternative (square-root free) method see + // C. Moler and D. Morrision (1983) https://doi.org/10.1147/rd.276.0577 + // and A. A. Dubrulle (1983) https://doi.org/10.1147/rd.276.0582 #endif + } -#if defined(DOXYGEN) || (defined(_MSC_VER) && !GEOGRAPHICLIB_CPLUSPLUS11_MATH) /** - * exp(\e x) − 1 accurate near \e x = 0. This is taken from - * N. J. Higham, Accuracy and Stability of Numerical Algorithms, 2nd - * Edition (SIAM, 2002), Sec 1.14.1, p 19. + * exp(\e x) − 1 accurate near \e x = 0. * * @tparam T the type of the argument and the returned value. * @param[in] x * @return exp(\e x) − 1. **********************************************************************/ - template static inline T expm1(T x) throw() { - volatile T - y = std::exp(x), + template static T expm1(T x) { +#if GEOGRAPHICLIB_CXX11_MATH + using std::expm1; return expm1(x); +#else + using std::exp; using std::abs; using std::log; + GEOGRAPHICLIB_VOLATILE T + y = exp(x), z = y - 1; // The reasoning here is similar to that for log1p. The expression // mathematically reduces to exp(x) - 1, and the factor z/log(y) = (y - // 1)/log(y) is a slowly varying quantity near y = 1 and is accurately // computed. - return std::abs(x) > 1 ? z : (z == 0 ? x : x * z / std::log(y)); - } -#elif GEOGRAPHICLIB_CPLUSPLUS11_MATH - template static inline T expm1(T x) throw() - { return std::expm1(x); } -#else - static inline double expm1(double x) throw() { return ::expm1(x); } - static inline float expm1(float x) throw() { return ::expm1f(x); } -# if HAVE_LONG_DOUBLE - static inline long double expm1(long double x) throw() - { return ::expm1l(x); } -# endif + return abs(x) > 1 ? z : (z == 0 ? x : x * z / log(y)); #endif + } -#if defined(DOXYGEN) || (defined(_MSC_VER) && !GEOGRAPHICLIB_CPLUSPLUS11_MATH) /** * log(1 + \e x) accurate near \e x = 0. * - * This is taken from D. Goldberg, - * What every computer - * scientist should know about floating-point arithmetic (1991), - * Theorem 4. See also, Higham (op. cit.), Answer to Problem 1.5, p 528. - * * @tparam T the type of the argument and the returned value. * @param[in] x * @return log(1 + \e x). **********************************************************************/ - template static inline T log1p(T x) throw() { - volatile T + template static T log1p(T x) { +#if GEOGRAPHICLIB_CXX11_MATH + using std::log1p; return log1p(x); +#else + using std::log; + GEOGRAPHICLIB_VOLATILE T y = 1 + x, z = y - 1; // Here's the explanation for this magic: y = 1 + z, exactly, and z // approx x, thus log(y)/z (which is nearly constant near z = 0) returns // a good approximation to the true log(1 + x)/x. The multiplication x * // (log(y)/z) introduces little additional error. - return z == 0 ? x : x * std::log(y) / z; - } -#elif GEOGRAPHICLIB_CPLUSPLUS11_MATH - template static inline T log1p(T x) throw() - { return std::log1p(x); } -#else - static inline double log1p(double x) throw() { return ::log1p(x); } - static inline float log1p(float x) throw() { return ::log1pf(x); } -# if HAVE_LONG_DOUBLE - static inline long double log1p(long double x) throw() - { return ::log1pl(x); } -# endif + return z == 0 ? x : x * log(y) / z; #endif + } -#if defined(DOXYGEN) || (defined(_MSC_VER) && !GEOGRAPHICLIB_CPLUSPLUS11_MATH) /** - * The inverse hyperbolic sine function. This is defined in terms of - * Math::log1p(\e x) in order to maintain accuracy near \e x = 0. In - * addition, the odd parity of the function is enforced. + * The inverse hyperbolic sine function. * * @tparam T the type of the argument and the returned value. * @param[in] x * @return asinh(\e x). **********************************************************************/ - template static inline T asinh(T x) throw() { - T y = std::abs(x); // Enforce odd parity + template static T asinh(T x) { +#if GEOGRAPHICLIB_CXX11_MATH + using std::asinh; return asinh(x); +#else + using std::abs; T y = abs(x); // Enforce odd parity y = log1p(y * (1 + y/(hypot(T(1), y) + 1))); return x < 0 ? -y : y; - } -#elif GEOGRAPHICLIB_CPLUSPLUS11_MATH - template static inline T asinh(T x) throw() - { return std::asinh(x); } -#else - static inline double asinh(double x) throw() { return ::asinh(x); } - static inline float asinh(float x) throw() { return ::asinhf(x); } -# if HAVE_LONG_DOUBLE - static inline long double asinh(long double x) throw() - { return ::asinhl(x); } -# endif #endif + } -#if defined(DOXYGEN) || (defined(_MSC_VER) && !GEOGRAPHICLIB_CPLUSPLUS11_MATH) /** - * The inverse hyperbolic tangent function. This is defined in terms of - * Math::log1p(\e x) in order to maintain accuracy near \e x = 0. In - * addition, the odd parity of the function is enforced. + * The inverse hyperbolic tangent function. * * @tparam T the type of the argument and the returned value. * @param[in] x * @return atanh(\e x). **********************************************************************/ - template static inline T atanh(T x) throw() { - T y = std::abs(x); // Enforce odd parity + template static T atanh(T x) { +#if GEOGRAPHICLIB_CXX11_MATH + using std::atanh; return atanh(x); +#else + using std::abs; T y = abs(x); // Enforce odd parity y = log1p(2 * y/(1 - y))/2; return x < 0 ? -y : y; - } -#elif GEOGRAPHICLIB_CPLUSPLUS11_MATH - template static inline T atanh(T x) throw() - { return std::atanh(x); } -#else - static inline double atanh(double x) throw() { return ::atanh(x); } - static inline float atanh(float x) throw() { return ::atanhf(x); } -# if HAVE_LONG_DOUBLE - static inline long double atanh(long double x) throw() - { return ::atanhl(x); } -# endif #endif + } -#if defined(DOXYGEN) || (defined(_MSC_VER) && !GEOGRAPHICLIB_CPLUSPLUS11_MATH) /** * The cube root function. * @@ -337,20 +342,47 @@ namespace GeographicLib { * @param[in] x * @return the real cube root of \e x. **********************************************************************/ - template static inline T cbrt(T x) throw() { - T y = std::pow(std::abs(x), 1/T(3)); // Return the real cube root - return x < 0 ? -y : y; - } -#elif GEOGRAPHICLIB_CPLUSPLUS11_MATH - template static inline T cbrt(T x) throw() - { return std::cbrt(x); } + template static T cbrt(T x) { +#if GEOGRAPHICLIB_CXX11_MATH + using std::cbrt; return cbrt(x); #else - static inline double cbrt(double x) throw() { return ::cbrt(x); } - static inline float cbrt(float x) throw() { return ::cbrtf(x); } -# if HAVE_LONG_DOUBLE - static inline long double cbrt(long double x) throw() { return ::cbrtl(x); } -# endif + using std::abs; using std::pow; + T y = pow(abs(x), 1/T(3)); // Return the real cube root + return x < 0 ? -y : y; #endif + } + + /** + * Fused multiply and add. + * + * @tparam T the type of the arguments and the returned value. + * @param[in] x + * @param[in] y + * @param[in] z + * @return xy + z, correctly rounded (on those platforms with + * support for the fma instruction). + * + * On platforms without the fma instruction, no attempt is + * made to improve on the result of a rounded multiplication followed by a + * rounded addition. + **********************************************************************/ + template static T fma(T x, T y, T z) { +#if GEOGRAPHICLIB_CXX11_MATH + using std::fma; return fma(x, y, z); +#else + return x * y + z; +#endif + } + + /** + * Normalize a two-vector. + * + * @tparam T the type of the argument and the returned value. + * @param[in,out] x on output set to x/hypot(x, y). + * @param[in,out] y on output set to y/hypot(x, y). + **********************************************************************/ + template static void norm(T& x, T& y) + { T h = hypot(x, y); x /= h; y /= h; } /** * The error-free sum of two numbers. @@ -364,10 +396,10 @@ namespace GeographicLib { * See D. E. Knuth, TAOCP, Vol 2, 4.2.2, Theorem B. (Note that \e t can be * the same as one of the first two arguments.) **********************************************************************/ - template static inline T sum(T u, T v, T& t) throw() { - volatile T s = u + v; - volatile T up = s - v; - volatile T vpp = s - up; + template static T sum(T u, T v, T& t) { + GEOGRAPHICLIB_VOLATILE T s = u + v; + GEOGRAPHICLIB_VOLATILE T up = s - v; + GEOGRAPHICLIB_VOLATILE T vpp = s - up; up -= u; vpp -= v; t = -(up + vpp); @@ -377,28 +409,96 @@ namespace GeographicLib { } /** - * Normalize an angle (restricted input range). + * Evaluate a polynomial. * - * @tparam T the type of the argument and returned value. - * @param[in] x the angle in degrees. - * @return the angle reduced to the range [−180°, 180°). + * @tparam T the type of the arguments and returned value. + * @param[in] N the order of the polynomial. + * @param[in] p the coefficient array (of size \e N + 1). + * @param[in] x the variable. + * @return the value of the polynomial. * - * \e x must lie in [−540°, 540°). + * Evaluate y = ∑n=0..N + * pn xNn. + * Return 0 if \e N < 0. Return p0, if \e N = 0 (even + * if \e x is infinite or a nan). The evaluation uses Horner's method. **********************************************************************/ - template static inline T AngNormalize(T x) throw() - { return x >= 180 ? x - 360 : (x < -180 ? x + 360 : x); } + template static T polyval(int N, const T p[], T x) + // This used to employ Math::fma; but that's too slow and it seemed not to + // improve the accuracy noticeably. This might change when there's direct + // hardware support for fma. + { T y = N < 0 ? 0 : *p++; while (--N >= 0) y = y * x + *p++; return y; } /** - * Normalize an arbitrary angle. + * Normalize an angle. * * @tparam T the type of the argument and returned value. * @param[in] x the angle in degrees. - * @return the angle reduced to the range [−180°, 180°). + * @return the angle reduced to the range([−180°, 180°]. * * The range of \e x is unrestricted. **********************************************************************/ - template static inline T AngNormalize2(T x) throw() - { return AngNormalize(std::fmod(x, T(360))); } + template static T AngNormalize(T x) { +#if GEOGRAPHICLIB_CXX11_MATH && GEOGRAPHICLIB_PRECISION != 4 + using std::remainder; + x = remainder(x, T(360)); return x != -180 ? x : 180; +#else + using std::fmod; + T y = fmod(x, T(360)); +#if defined(_MSC_VER) && _MSC_VER < 1900 + // Before version 14 (2015), Visual Studio had problems dealing + // with -0.0. Specifically + // VC 10,11,12 and 32-bit compile: fmod(-0.0, 360.0) -> +0.0 + // sincosd has a similar fix. + // python 2.7 on Windows 32-bit machines has the same problem. + if (x == 0) y = x; +#endif + return y <= -180 ? y + 360 : (y <= 180 ? y : y - 360); +#endif + } + + /** + * Normalize a latitude. + * + * @tparam T the type of the argument and returned value. + * @param[in] x the angle in degrees. + * @return x if it is in the range [−90°, 90°], otherwise + * return NaN. + **********************************************************************/ + template static T LatFix(T x) + { using std::abs; return abs(x) > 90 ? NaN() : x; } + + /** + * The exact difference of two angles reduced to + * (−180°, 180°]. + * + * @tparam T the type of the arguments and returned value. + * @param[in] x the first angle in degrees. + * @param[in] y the second angle in degrees. + * @param[out] e the error term in degrees. + * @return \e d, the truncated value of \e y − \e x. + * + * This computes \e z = \e y − \e x exactly, reduced to + * (−180°, 180°]; and then sets \e z = \e d + \e e where \e d + * is the nearest representable number to \e z and \e e is the truncation + * error. If \e d = −180, then \e e > 0; If \e d = 180, then \e e + * ≤ 0. + **********************************************************************/ + template static T AngDiff(T x, T y, T& e) { +#if GEOGRAPHICLIB_CXX11_MATH && GEOGRAPHICLIB_PRECISION != 4 + using std::remainder; + T t, d = AngNormalize(sum(remainder(-x, T(360)), + remainder( y, T(360)), t)); +#else + T t, d = AngNormalize(sum(AngNormalize(-x), AngNormalize(y), t)); +#endif + // Here y - x = d + t (mod 360), exactly, where d is in (-180,180] and + // abs(t) <= eps (eps = 2^-45 for doubles). The only case where the + // addition of t takes the result outside the range (-180,180] is d = 180 + // and t > 0. The case, d = -180 + eps, t = -eps, can't happen, since + // sum would have returned the exact result in such a case (i.e., given t + // = 0). + return sum(d == 180 && t > 0 ? -180 : d, t, e); + } /** * Difference of two angles reduced to [−180°, 180°] @@ -409,22 +509,293 @@ namespace GeographicLib { * @return \e y − \e x, reduced to the range [−180°, * 180°]. * - * \e x and \e y must both lie in [−180°, 180°]. The result - * is equivalent to computing the difference exactly, reducing it to - * (−180°, 180°] and rounding the result. Note that this - * prescription allows −180° to be returned (e.g., if \e x is - * tiny and negative and \e y = 180°). + * The result is equivalent to computing the difference exactly, reducing + * it to (−180°, 180°] and rounding the result. Note that + * this prescription allows −180° to be returned (e.g., if \e x + * is tiny and negative and \e y = 180°). **********************************************************************/ - template static inline T AngDiff(T x, T y) throw() { - T t, d = sum(-x, y, t); - if ((d - T(180)) + t > T(0)) // y - x > 180 - d -= T(360); // exact - else if ((d + T(180)) + t <= T(0)) // y - x <= -180 - d += T(360); // exact - return d + t; + template static T AngDiff(T x, T y) + { T e; return AngDiff(x, y, e); } + + /** + * Coarsen a value close to zero. + * + * @tparam T the type of the argument and returned value. + * @param[in] x + * @return the coarsened value. + * + * The makes the smallest gap in \e x = 1/16 - nextafter(1/16, 0) = + * 1/257 for reals = 0.7 pm on the earth if \e x is an angle in + * degrees. (This is about 1000 times more resolution than we get with + * angles around 90°.) We use this to avoid having to deal with near + * singular cases when \e x is non-zero but tiny (e.g., + * 10−200). This converts -0 to +0; however tiny negative + * numbers get converted to -0. + **********************************************************************/ + template static T AngRound(T x) { + using std::abs; + static const T z = 1/T(16); + if (x == 0) return 0; + GEOGRAPHICLIB_VOLATILE T y = abs(x); + // The compiler mustn't "simplify" z - (z - y) to y + y = y < z ? z - (z - y) : y; + return x < 0 ? -y : y; } -#if defined(DOXYGEN) + /** + * Evaluate the sine and cosine function with the argument in degrees + * + * @tparam T the type of the arguments. + * @param[in] x in degrees. + * @param[out] sinx sin(x). + * @param[out] cosx cos(x). + * + * The results obey exactly the elementary properties of the trigonometric + * functions, e.g., sin 9° = cos 81° = − sin 123456789°. + * If x = −0, then \e sinx = −0; this is the only case where + * −0 is returned. + **********************************************************************/ + template static void sincosd(T x, T& sinx, T& cosx) { + // In order to minimize round-off errors, this function exactly reduces + // the argument to the range [-45, 45] before converting it to radians. + using std::sin; using std::cos; + T r; int q; +#if GEOGRAPHICLIB_CXX11_MATH && GEOGRAPHICLIB_PRECISION <= 3 && \ + !defined(__GNUC__) + // Disable for gcc because of bug in glibc version < 2.22, see + // https://sourceware.org/bugzilla/show_bug.cgi?id=17569 + // Once this fix is widely deployed, should insert a runtime test for the + // glibc version number. For example + // #include + // std::string version(gnu_get_libc_version()); => "2.22" + using std::remquo; + r = remquo(x, T(90), &q); +#else + using std::fmod; using std::floor; + r = fmod(x, T(360)); + q = int(floor(r / 90 + T(0.5))); + r -= 90 * q; +#endif + // now abs(r) <= 45 + r *= degree(); + // Possibly could call the gnu extension sincos + T s = sin(r), c = cos(r); +#if defined(_MSC_VER) && _MSC_VER < 1900 + // Before version 14 (2015), Visual Studio had problems dealing + // with -0.0. Specifically + // VC 10,11,12 and 32-bit compile: fmod(-0.0, 360.0) -> +0.0 + // VC 12 and 64-bit compile: sin(-0.0) -> +0.0 + // AngNormalize has a similar fix. + // python 2.7 on Windows 32-bit machines has the same problem. + if (x == 0) s = x; +#endif + switch (unsigned(q) & 3U) { + case 0U: sinx = s; cosx = c; break; + case 1U: sinx = c; cosx = -s; break; + case 2U: sinx = -s; cosx = -c; break; + default: sinx = -c; cosx = s; break; // case 3U + } + // Set sign of 0 results. -0 only produced for sin(-0) + if (x != 0) { sinx += T(0); cosx += T(0); } + } + + /** + * Evaluate the sine function with the argument in degrees + * + * @tparam T the type of the argument and the returned value. + * @param[in] x in degrees. + * @return sin(x). + **********************************************************************/ + template static T sind(T x) { + // See sincosd + using std::sin; using std::cos; + T r; int q; +#if GEOGRAPHICLIB_CXX11_MATH && GEOGRAPHICLIB_PRECISION <= 3 && \ + !defined(__GNUC__) + using std::remquo; + r = remquo(x, T(90), &q); +#else + using std::fmod; using std::floor; + r = fmod(x, T(360)); + q = int(floor(r / 90 + T(0.5))); + r -= 90 * q; +#endif + // now abs(r) <= 45 + r *= degree(); + unsigned p = unsigned(q); + r = p & 1U ? cos(r) : sin(r); + if (p & 2U) r = -r; + if (x != 0) r += T(0); + return r; + } + + /** + * Evaluate the cosine function with the argument in degrees + * + * @tparam T the type of the argument and the returned value. + * @param[in] x in degrees. + * @return cos(x). + **********************************************************************/ + template static T cosd(T x) { + // See sincosd + using std::sin; using std::cos; + T r; int q; +#if GEOGRAPHICLIB_CXX11_MATH && GEOGRAPHICLIB_PRECISION <= 3 && \ + !defined(__GNUC__) + using std::remquo; + r = remquo(x, T(90), &q); +#else + using std::fmod; using std::floor; + r = fmod(x, T(360)); + q = int(floor(r / 90 + T(0.5))); + r -= 90 * q; +#endif + // now abs(r) <= 45 + r *= degree(); + unsigned p = unsigned(q + 1); + r = p & 1U ? cos(r) : sin(r); + if (p & 2U) r = -r; + return T(0) + r; + } + + /** + * Evaluate the tangent function with the argument in degrees + * + * @tparam T the type of the argument and the returned value. + * @param[in] x in degrees. + * @return tan(x). + * + * If \e x = ±90°, then a suitably large (but finite) value is + * returned. + **********************************************************************/ + template static T tand(T x) { + static const T overflow = 1 / sq(std::numeric_limits::epsilon()); + T s, c; + sincosd(x, s, c); + return c != 0 ? s / c : (s < 0 ? -overflow : overflow); + } + + /** + * Evaluate the atan2 function with the result in degrees + * + * @tparam T the type of the arguments and the returned value. + * @param[in] y + * @param[in] x + * @return atan2(y, x) in degrees. + * + * The result is in the range (−180° 180°]. N.B., + * atan2d(±0, −1) = +180°; atan2d(−ε, + * −1) = −180°, for ε positive and tiny; + * atan2d(±0, +1) = ±0°. + **********************************************************************/ + template static T atan2d(T y, T x) { + // In order to minimize round-off errors, this function rearranges the + // arguments so that result of atan2 is in the range [-pi/4, pi/4] before + // converting it to degrees and mapping the result to the correct + // quadrant. + using std::atan2; using std::abs; + int q = 0; + if (abs(y) > abs(x)) { std::swap(x, y); q = 2; } + if (x < 0) { x = -x; ++q; } + // here x >= 0 and x >= abs(y), so angle is in [-pi/4, pi/4] + T ang = atan2(y, x) / degree(); + switch (q) { + // Note that atan2d(-0.0, 1.0) will return -0. However, we expect that + // atan2d will not be called with y = -0. If need be, include + // + // case 0: ang = 0 + ang; break; + // + // and handle mpfr as in AngRound. + case 1: ang = (y >= 0 ? 180 : -180) - ang; break; + case 2: ang = 90 - ang; break; + case 3: ang = -90 + ang; break; + } + return ang; + } + + /** + * Evaluate the atan function with the result in degrees + * + * @tparam T the type of the argument and the returned value. + * @param[in] x + * @return atan(x) in degrees. + **********************************************************************/ + template static T atand(T x) + { return atan2d(x, T(1)); } + + /** + * Evaluate e atanh(e x) + * + * @tparam T the type of the argument and the returned value. + * @param[in] x + * @param[in] es the signed eccentricity = sign(e2) + * sqrt(|e2|) + * @return e atanh(e x) + * + * If e2 is negative (e is imaginary), the + * expression is evaluated in terms of atan. + **********************************************************************/ + template static T eatanhe(T x, T es); + + /** + * Copy the sign. + * + * @tparam T the type of the argument. + * @param[in] x gives the magitude of the result. + * @param[in] y gives the sign of the result. + * @return value with the magnitude of \e x and with the sign of \e y. + * + * This routine correctly handles the case \e y = −0, returning + * &minus|x|. + **********************************************************************/ + template static T copysign(T x, T y) { +#if GEOGRAPHICLIB_CXX11_MATH + using std::copysign; return copysign(x, y); +#else + using std::abs; + // NaN counts as positive + return abs(x) * (y < 0 || (y == 0 && 1/y < 0) ? -1 : 1); +#endif + } + + /** + * tanχ in terms of tanφ + * + * @tparam T the type of the argument and the returned value. + * @param[in] tau τ = tanφ + * @param[in] es the signed eccentricity = sign(e2) + * sqrt(|e2|) + * @return τ′ = tanχ + * + * See Eqs. (7--9) of + * C. F. F. Karney, + * + * Transverse Mercator with an accuracy of a few nanometers, + * J. Geodesy 85(8), 475--485 (Aug. 2011) + * (preprint + * arXiv:1002.1417). + **********************************************************************/ + template static T taupf(T tau, T es); + + /** + * tanφ in terms of tanχ + * + * @tparam T the type of the argument and the returned value. + * @param[in] taup τ′ = tanχ + * @param[in] es the signed eccentricity = sign(e2) + * sqrt(|e2|) + * @return τ = tanφ + * + * See Eqs. (19--21) of + * C. F. F. Karney, + * + * Transverse Mercator with an accuracy of a few nanometers, + * J. Geodesy 85(8), 475--485 (Aug. 2011) + * (preprint + * arXiv:1002.1417). + **********************************************************************/ + template static T tauf(T taup, T es); + /** * Test for finiteness. * @@ -432,33 +803,23 @@ namespace GeographicLib { * @param[in] x * @return true if number is finite, false if NaN or infinite. **********************************************************************/ - template static inline bool isfinite(T x) throw() { - return std::abs(x) <= (std::numeric_limits::max)(); - } -#elif (defined(_MSC_VER) && !GEOGRAPHICLIB_CPLUSPLUS11_MATH) - template static inline bool isfinite(T x) throw() { - return _finite(double(x)) != 0; - } -#elif defined(_LIBCPP_VERSION) - // libc++ implements std::isfinite() as a template that only allows - // floating-point types. isfinite is invoked by Utility::str to format - // numbers conveniently and this allows integer arguments, so we need to - // allow Math::isfinite to work on integers. - template static inline - typename std::enable_if::value, bool>::type - isfinite(T x) throw() { - return std::isfinite(x); - } - template static inline - typename std::enable_if::value, bool>::type - isfinite(T /*x*/) throw() { - return true; - } + template static bool isfinite(T x) { +#if GEOGRAPHICLIB_CXX11_MATH + using std::isfinite; return isfinite(x); #else - template static inline bool isfinite(T x) throw() { - return std::isfinite(x); - } + using std::abs; +#if defined(_MSC_VER) + return abs(x) <= (std::numeric_limits::max)(); +#else + // There's a problem using MPFR C++ 3.6.3 and g++ -std=c++14 (reported on + // 2015-05-04) with the parens around std::numeric_limits::max. Of + // course, these parens are only needed to deal with Windows stupidly + // defining max as a macro. So don't insert the parens on non-Windows + // platforms. + return abs(x) <= std::numeric_limits::max(); #endif +#endif + } /** * The NaN (not a number) @@ -466,15 +827,21 @@ namespace GeographicLib { * @tparam T the type of the returned value. * @return NaN if available, otherwise return the max real of type T. **********************************************************************/ - template static inline T NaN() throw() { + template static T NaN() { +#if defined(_MSC_VER) return std::numeric_limits::has_quiet_NaN ? std::numeric_limits::quiet_NaN() : (std::numeric_limits::max)(); +#else + return std::numeric_limits::has_quiet_NaN ? + std::numeric_limits::quiet_NaN() : + std::numeric_limits::max(); +#endif } /** * A synonym for NaN(). **********************************************************************/ - static inline real NaN() throw() { return NaN(); } + static real NaN() { return NaN(); } /** * Test for NaN. @@ -483,11 +850,11 @@ namespace GeographicLib { * @param[in] x * @return true if argument is a NaN. **********************************************************************/ - template static inline bool isnan(T x) throw() { -#if defined(DOXYGEN) || (defined(_MSC_VER) && !GEOGRAPHICLIB_CPLUSPLUS11_MATH) - return x != x; + template static bool isnan(T x) { +#if GEOGRAPHICLIB_CXX11_MATH + using std::isnan; return isnan(x); #else - return std::isnan(x); + return x != x; #endif } @@ -497,15 +864,21 @@ namespace GeographicLib { * @tparam T the type of the returned value. * @return infinity if available, otherwise return the max real. **********************************************************************/ - template static inline T infinity() throw() { + template static T infinity() { +#if defined(_MSC_VER) return std::numeric_limits::has_infinity ? std::numeric_limits::infinity() : (std::numeric_limits::max)(); +#else + return std::numeric_limits::has_infinity ? + std::numeric_limits::infinity() : + std::numeric_limits::max(); +#endif } /** * A synonym for infinity(). **********************************************************************/ - static inline real infinity() throw() { return infinity(); } + static real infinity() { return infinity(); } /** * Swap the bytes of a quantity @@ -514,7 +887,7 @@ namespace GeographicLib { * @param[in] x * @return x with its bytes swapped. **********************************************************************/ - template static inline T swab(T x) { + template static T swab(T x) { union { T r; unsigned char c[sizeof(T)]; @@ -524,6 +897,47 @@ namespace GeographicLib { std::swap(b.c[i], b.c[sizeof(T) - 1 - i]); return b.r; } + +#if GEOGRAPHICLIB_PRECISION == 4 + typedef boost::math::policies::policy + < boost::math::policies::domain_error + , + boost::math::policies::pole_error + , + boost::math::policies::overflow_error + , + boost::math::policies::evaluation_error + > + boost_special_functions_policy; + + static real hypot(real x, real y) + { return boost::math::hypot(x, y, boost_special_functions_policy()); } + + static real expm1(real x) + { return boost::math::expm1(x, boost_special_functions_policy()); } + + static real log1p(real x) + { return boost::math::log1p(x, boost_special_functions_policy()); } + + static real asinh(real x) + { return boost::math::asinh(x, boost_special_functions_policy()); } + + static real atanh(real x) + { return boost::math::atanh(x, boost_special_functions_policy()); } + + static real cbrt(real x) + { return boost::math::cbrt(x, boost_special_functions_policy()); } + + static real fma(real x, real y, real z) + { return fmaq(__float128(x), __float128(y), __float128(z)); } + + static real copysign(real x, real y) + { return boost::math::copysign(x, y); } + + static bool isnan(real x) { return boost::math::isnan(x); } + + static bool isfinite(real x) { return boost::math::isfinite(x); } +#endif }; } // namespace GeographicLib diff --git a/gtsam/3rdparty/GeographicLib/include/GeographicLib/NearestNeighbor.hpp b/gtsam/3rdparty/GeographicLib/include/GeographicLib/NearestNeighbor.hpp new file mode 100644 index 000000000..12992331c --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/include/GeographicLib/NearestNeighbor.hpp @@ -0,0 +1,838 @@ +/** + * \file NearestNeighbor.hpp + * \brief Header for GeographicLib::NearestNeighbor class + * + * Copyright (c) Charles Karney (2016-2017) and licensed + * under the MIT/X11 License. For more information, see + * https://geographiclib.sourceforge.io/ + **********************************************************************/ + +#if !defined(GEOGRAPHICLIB_NEARESTNEIGHBOR_HPP) +#define GEOGRAPHICLIB_NEARESTNEIGHBOR_HPP 1 + +#include // for nth_element, max_element, etc. +#include +#include // for priority_queue +#include // for swap + pair +#include +#include +#include +#include +#include +// Only for GEOGRAPHICLIB_STATIC_ASSERT and GeographicLib::GeographicErr +#include + +#if defined(GEOGRAPHICLIB_HAVE_BOOST_SERIALIZATION) && \ + GEOGRAPHICLIB_HAVE_BOOST_SERIALIZATION +#include +#include +#include +#include +#endif + +#if defined(_MSC_VER) +// Squelch warnings about constant conditional expressions +# pragma warning (push) +# pragma warning (disable: 4127) +#endif + +namespace GeographicLib { + + /** + * \brief Nearest-neighbor calculations + * + * This class solves the nearest-neighbor problm using a vantage-point tree + * as described in \ref nearest. + * + * This class is templated so that it can handle arbitrary metric spaces as + * follows: + * + * @tparam dist_t the type used for measuring distances; it can be a real or + * signed integer type; in typical geodetic applications, \e dist_t might + * be double. + * @tparam pos_t the type for specifying the positions of points; geodetic + * application might bundled the latitude and longitude into a + * std::pair. + * @tparam distfun_t the type of a function object which takes takes two + * positions (of type \e pos_t) and returns the distance (of type \e + * dist_t); in geodetic applications, this might be a class which is + * constructed with a Geodesic object and which implements a member + * function with a signature dist_t operator() (const pos_t&, const + * pos_t&) const, which returns the geodesic distance between two + * points. + * + * \note The distance measure must satisfy the triangle inequality, \f$ + * d(a,c) \le d(a,b) + d(b,c) \f$ for all points \e a, \e b, \e c. The + * geodesic distance (given by Geodesic::Inverse) does, while the great + * ellipse distance and the rhumb line distance do not. If you use + * the ordinary Euclidean distance, i.e., \f$ \sqrt{(x_a-x_b)^2 + + * (y_a-y_b)^2} \f$ for two dimensions, don't be tempted to leave out the + * square root in the interests of "efficiency"; the squared distance does + * not satisfy the triangle inequality! + * + * This is a "header-only" implementation and, as such, depends in a minimal + * way on the rest of GeographicLib (the only dependency is through the use + * of GEOGRAPHICLIB_STATIC_ASSERT and GeographicLib::GeographicErr for + * handling run-time and compile-time exceptions). Therefore, it is easy to + * extract this class from the rest of GeographicLib and use it as a + * stand-alone facility. + * + * The \e dist_t type must support numeric_limits queries (specifically: + * is_signed, is_integer, max(), digits). + * + * The NearestNeighbor object is constructed with a vector of points (type \e + * pos_t) and a distance function (type \e distfun_t). However the object + * does \e not store the points. When querying the object with Search(), + * it's necessary to supply the same vector of points and the same distance + * function. + * + * There's no capability in this implementation to add or remove points from + * the set. Instead Initialize() should be called to re-initialize the + * object with the modified vector of points. + * + * Because of the overhead in constructing a NearestNeighbor object for a + * large set of points, functions Save() and Load() are provided to save the + * object to an external file. operator<<(), operator>>() and Boost + * serialization can also be used to save and restore a NearestNeighbor + * object. This is illustrated in the example. + * + * Example of use: + * \include example-NearestNeighbor.cpp + **********************************************************************/ + template + class NearestNeighbor { + // For tracking changes to the I/O format + static const int version = 1; + // This is what we get "free"; but if sizeof(dist_t) = 1 (unlikely), allow + // 4 slots (and this accommodates the default value bucket = 4). + static const int maxbucket = + (2 + ((4 * sizeof(dist_t)) / sizeof(int) >= 2 ? + (4 * sizeof(dist_t)) / sizeof(int) : 2)); + public: + + /** + * Default constructor for NearestNeighbor. + * + * This is equivalent to specifying an empty set of points. + **********************************************************************/ + NearestNeighbor() : _numpoints(0), _bucket(0), _cost(0) {} + + /** + * Constructor for NearestNeighbor. + * + * @param[in] pts a vector of points to include in the set. + * @param[in] dist the distance function object. + * @param[in] bucket the size of the buckets at the leaf nodes; this must + * lie in [0, 2 + 4*sizeof(dist_t)/sizeof(int)] (default 4). + * @exception GeographicErr if the value of \e bucket is out of bounds or + * the size of \e pts is too big for an int. + * @exception std::bad_alloc if memory for the tree can't be allocated. + * + * \e pts may contain coincident points (i.e., the distance between them + * vanishes); these are treated as distinct. + * + * The choice of \e bucket is a tradeoff between space and efficiency. A + * larger \e bucket decreases the size of the NearestNeighbor object which + * scales as pts.size() / max(1, bucket) and reduces the number of distance + * calculations to construct the object by log2(bucket) * pts.size(). + * However each search then requires about bucket additional distance + * calculations. + * + * \warning The distances computed by \e dist must satisfy the standard + * metric conditions. If not, the results are undefined. Neither the data + * in \e pts nor the query points should contain NaNs or infinities because + * such data violates the metric conditions. + * + * \warning The same arguments \e pts and \e dist must be provided + * to the Search() function. + **********************************************************************/ + NearestNeighbor(const std::vector& pts, const distfun_t& dist, + int bucket = 4) { + Initialize(pts, dist, bucket); + } + + /** + * Initialize or re-initialize NearestNeighbor. + * + * @param[in] pts a vector of points to include in the tree. + * @param[in] dist the distance function object. + * @param[in] bucket the size of the buckets at the leaf nodes; this must + * lie in [0, 2 + 4*sizeof(dist_t)/sizeof(int)] (default 4). + * @exception GeographicErr if the value of \e bucket is out of bounds or + * the size of \e pts is too big for an int. + * @exception std::bad_alloc if memory for the tree can't be allocated. + * + * See also the documentation on the constructor. + * + * If an exception is thrown, the state of the NearestNeighbor is + * unchanged. + **********************************************************************/ + void Initialize(const std::vector& pts, const distfun_t& dist, + int bucket = 4) { + GEOGRAPHICLIB_STATIC_ASSERT(std::numeric_limits::is_signed, + "dist_t must be a signed type"); + if (!( 0 <= bucket && bucket <= maxbucket )) + throw GeographicLib::GeographicErr + ("bucket must lie in [0, 2 + 4*sizeof(dist_t)/sizeof(int)]"); + if (pts.size() > size_t(std::numeric_limits::max())) + throw GeographicLib::GeographicErr("pts array too big"); + // the pair contains distance+id + std::vector ids(pts.size()); + for (int k = int(ids.size()); k--;) + ids[k] = std::make_pair(dist_t(0), k); + int cost = 0; + std::vector tree; + init(pts, dist, bucket, tree, ids, cost, + 0, int(ids.size()), int(ids.size()/2)); + _tree.swap(tree); + _numpoints = int(pts.size()); + _bucket = bucket; + _mc = _sc = 0; + _cost = cost; _c1 = _k = _cmax = 0; + _cmin = std::numeric_limits::max(); + } + + /** + * Search the NearestNeighbor. + * + * @param[in] pts the vector of points used for initialization. + * @param[in] dist the distance function object used for initialization. + * @param[in] query the query point. + * @param[out] ind a vector of indices to the closest points found. + * @param[in] k the number of points to search for (default = 1). + * @param[in] maxdist only return points with distances of \e maxdist or + * less from \e query (default is the maximum \e dist_t). + * @param[in] mindist only return points with distances of more than + * \e mindist from \e query (default = −1). + * @param[in] exhaustive whether to do an exhaustive search (default true). + * @param[in] tol the tolerance on the results (default 0). + * @return the distance to the closest point found (−1 if no points + * are found). + * @exception GeographicErr if \e pts has a different size from that used + * to construct the object. + * + * The indices returned in \e ind are sorted by distance from \e query + * (closest first). + * + * The simplest invocation is with just the 4 non-optional arguments. This + * returns the closest distance and the index to the closest point in + * ind0. If there are several points equally close, then + * ind0 gives the index of an arbirary one of them. If + * there's no closest point (because the set of points is empty), then \e + * ind is empty and −1 is returned. + * + * With \e exhaustive = true and \e tol = 0 (their default values), this + * finds the indices of \e k closest neighbors to \e query whose distances + * to \e query are in (\e mindist, \e maxdist]. If \e mindist and \e + * maxdist have their default values, then these bounds have no effect. If + * \e query is one of the points in the tree, then set \e mindist = 0 to + * prevent this point (and other coincident points) from being returned. + * + * If \e exhaustive = false, exit as soon as \e k results satisfying the + * distance criteria are found. If less than \e k results are returned + * then the search was exhaustive even if \e exhaustive = false. + * + * If \e tol is positive, do an approximate search; in this case the + * results are to be interpreted as follows: if the k'th distance is + * \e dk, then all results with distances less than or equal \e dk − + * \e tol are correct; all others are suspect — there may be other + * closer results with distances greater or equal to \e dk − \e tol. + * If less than \e k results are found, then the search is exact. + * + * \e mindist should be used to exclude a "small" neighborhood of the query + * point (relative to the average spacing of the data). If \e mindist is + * large, the efficiency of the search deteriorates. + * + * \note Only the shortest distance is returned (as as the function value). + * The distances to other points (indexed by indj + * for \e j > 0) can be found by invoking \e dist again. + * + * \warning The arguments \e pts and \e dist must be identical to those + * used to initialize the NearestNeighbor; if not, this function will + * return some meaningless result (however, if the size of \e pts is wrong, + * this function throw an exception). + * + * \warning The query point cannot be a NaN or infinite because then the + * metric conditions are violated. + **********************************************************************/ + dist_t Search(const std::vector& pts, const distfun_t& dist, + const pos_t& query, + std::vector& ind, + int k = 1, + dist_t maxdist = std::numeric_limits::max(), + dist_t mindist = -1, + bool exhaustive = true, + dist_t tol = 0) const { + if (_numpoints != int(pts.size())) + throw GeographicLib::GeographicErr("pts array has wrong size"); + std::priority_queue results; + if (_numpoints > 0 && k > 0 && maxdist > mindist) { + // distance to the kth closest point so far + dist_t tau = maxdist; + // first is negative of how far query is outside boundary of node + // +1 if on boundary or inside + // second is node index + std::priority_queue todo; + todo.push(std::make_pair(dist_t(1), int(_tree.size()) - 1)); + int c = 0; + while (!todo.empty()) { + int n = todo.top().second; + dist_t d = -todo.top().first; + todo.pop(); + dist_t tau1 = tau - tol; + // compare tau and d again since tau may have become smaller. + if (!( n >= 0 && tau1 >= d )) continue; + const Node& current = _tree[n]; + dist_t dst = 0; // to suppress warning about uninitialized variable + bool exitflag = false, leaf = current.index < 0; + for (int i = 0; i < (leaf ? _bucket : 1); ++i) { + int index = leaf ? current.leaves[i] : current.index; + if (index < 0) break; + dst = dist(pts[index], query); + ++c; + + if (dst > mindist && dst <= tau) { + if (int(results.size()) == k) results.pop(); + results.push(std::make_pair(dst, index)); + if (int(results.size()) == k) { + if (exhaustive) + tau = results.top().first; + else { + exitflag = true; + break; + } + if (tau <= tol) { + exitflag = true; + break; + } + } + } + } + if (exitflag) break; + + if (current.index < 0) continue; + tau1 = tau - tol; + for (int l = 0; l < 2; ++l) { + if (current.data.child[l] >= 0 && + dst + current.data.upper[l] >= mindist) { + if (dst < current.data.lower[l]) { + d = current.data.lower[l] - dst; + if (tau1 >= d) + todo.push(std::make_pair(-d, current.data.child[l])); + } else if (dst > current.data.upper[l]) { + d = dst - current.data.upper[l]; + if (tau1 >= d) + todo.push(std::make_pair(-d, current.data.child[l])); + } else + todo.push(std::make_pair(dist_t(1), current.data.child[l])); + } + } + } + ++_k; + _c1 += c; + double omc = _mc; + _mc += (c - omc) / _k; + _sc += (c - omc) * (c - _mc); + if (c > _cmax) _cmax = c; + if (c < _cmin) _cmin = c; + } + + dist_t d = -1; + ind.resize(results.size()); + + for (int i = int(ind.size()); i--;) { + ind[i] = int(results.top().second); + if (i == 0) d = results.top().first; + results.pop(); + } + return d; + + } + + /** + * @return the total number of points in the set. + **********************************************************************/ + int NumPoints() const { return _numpoints; } + + /** + * Write the object to an I/O stream. + * + * @param[in,out] os the stream to write to. + * @param[in] bin if true (the default) save in binary mode. + * @exception std::bad_alloc if memory for the string representation of the + * object can't be allocated. + * + * The counters tracking the statistics of searches are not saved; however + * the initializtion cost is saved. The format of the binary saves is \e + * not portable. + * + * \note + * Boost serialization can also be used to save and restore a + * NearestNeighbor object. This requires that the + * GEOGRAPHICLIB_HAVE_BOOST_SERIALIZATION macro be defined. + **********************************************************************/ + void Save(std::ostream& os, bool bin = true) const { + int realspec = std::numeric_limits::digits * + (std::numeric_limits::is_integer ? -1 : 1); + if (bin) { + char id[] = "NearestNeighbor_"; + os.write(id, 16); + int buf[6]; + buf[0] = version; + buf[1] = realspec; + buf[2] = _bucket; + buf[3] = _numpoints; + buf[4] = int(_tree.size()); + buf[5] = _cost; + os.write(reinterpret_cast(buf), 6 * sizeof(int)); + for (int i = 0; i < int(_tree.size()); ++i) { + const Node& node = _tree[i]; + os.write(reinterpret_cast(&node.index), sizeof(int)); + if (node.index >= 0) { + os.write(reinterpret_cast(node.data.lower), + 2 * sizeof(dist_t)); + os.write(reinterpret_cast(node.data.upper), + 2 * sizeof(dist_t)); + os.write(reinterpret_cast(node.data.child), + 2 * sizeof(int)); + } else { + os.write(reinterpret_cast(node.leaves), + _bucket * sizeof(int)); + } + } + } else { + std::stringstream ostring; + // Ensure enough precision for type dist_t. With C++11, max_digits10 + // can be used instead. + if (!std::numeric_limits::is_integer) { + static const int prec + = int(std::ceil(std::numeric_limits::digits * + std::log10(2.0) + 1)); + ostring.precision(prec); + } + ostring << version << " " << realspec << " " << _bucket << " " + << _numpoints << " " << _tree.size() << " " << _cost; + for (int i = 0; i < int(_tree.size()); ++i) { + const Node& node = _tree[i]; + ostring << "\n" << node.index; + if (node.index >= 0) { + for (int l = 0; l < 2; ++l) + ostring << " " << node.data.lower[l] << " " << node.data.upper[l] + << " " << node.data.child[l]; + } else { + for (int l = 0; l < _bucket; ++l) + ostring << " " << node.leaves[l]; + } + } + os << ostring.str(); + } + } + + /** + * Read the object from an I/O stream. + * + * @param[in,out] is the stream to read from + * @param[in] bin if true (the default) load in binary mode. + * @exception GeographicErr if the state read from \e is is illegal. + * @exception std::bad_alloc if memory for the tree can't be allocated. + * + * The counters tracking the statistics of searches are reset by this + * operation. Binary data must have been saved on a machine with the same + * architecture. If an exception is thrown, the state of the + * NearestNeighbor is unchanged. + * + * \note + * Boost serialization can also be used to save and restore a + * NearestNeighbor object. This requires that the + * GEOGRAPHICLIB_HAVE_BOOST_SERIALIZATION macro be defined. + * + * \warning The same arguments \e pts and \e dist used for + * initialization must be provided to the Search() function. + **********************************************************************/ + void Load(std::istream& is, bool bin = true) { + int version1, realspec, bucket, numpoints, treesize, cost; + if (bin) { + char id[17]; + is.read(id, 16); + id[16] = '\0'; + if (!(std::strcmp(id, "NearestNeighbor_") == 0)) + throw GeographicLib::GeographicErr("Bad ID"); + is.read(reinterpret_cast(&version1), sizeof(int)); + is.read(reinterpret_cast(&realspec), sizeof(int)); + is.read(reinterpret_cast(&bucket), sizeof(int)); + is.read(reinterpret_cast(&numpoints), sizeof(int)); + is.read(reinterpret_cast(&treesize), sizeof(int)); + is.read(reinterpret_cast(&cost), sizeof(int)); + } else { + if (!( is >> version1 >> realspec >> bucket >> numpoints >> treesize + >> cost )) + throw GeographicLib::GeographicErr("Bad header"); + } + if (!( version1 == version )) + throw GeographicLib::GeographicErr("Incompatible version"); + if (!( realspec == std::numeric_limits::digits * + (std::numeric_limits::is_integer ? -1 : 1) )) + throw GeographicLib::GeographicErr("Different dist_t types"); + if (!( 0 <= bucket && bucket <= maxbucket )) + throw GeographicLib::GeographicErr("Bad bucket size"); + if (!( 0 <= treesize && treesize <= numpoints )) + throw + GeographicLib::GeographicErr("Bad number of points or tree size"); + if (!( 0 <= cost )) + throw GeographicLib::GeographicErr("Bad value for cost"); + std::vector tree; + tree.reserve(treesize); + for (int i = 0; i < treesize; ++i) { + Node node; + if (bin) { + is.read(reinterpret_cast(&node.index), sizeof(int)); + if (node.index >= 0) { + is.read(reinterpret_cast(node.data.lower), + 2 * sizeof(dist_t)); + is.read(reinterpret_cast(node.data.upper), + 2 * sizeof(dist_t)); + is.read(reinterpret_cast(node.data.child), + 2 * sizeof(int)); + } else { + is.read(reinterpret_cast(node.leaves), + bucket * sizeof(int)); + for (int l = bucket; l < maxbucket; ++l) + node.leaves[l] = 0; + } + } else { + if (!( is >> node.index )) + throw GeographicLib::GeographicErr("Bad index"); + if (node.index >= 0) { + for (int l = 0; l < 2; ++l) { + if (!( is >> node.data.lower[l] >> node.data.upper[l] + >> node.data.child[l] )) + throw GeographicLib::GeographicErr("Bad node data"); + } + } else { + // Must be at least one valid leaf followed by a sequence end + // markers (-1). + for (int l = 0; l < bucket; ++l) { + if (!( is >> node.leaves[l] )) + throw GeographicLib::GeographicErr("Bad leaf data"); + } + for (int l = bucket; l < maxbucket; ++l) + node.leaves[l] = 0; + } + } + node.Check(numpoints, treesize, bucket); + tree.push_back(node); + } + _tree.swap(tree); + _numpoints = numpoints; + _bucket = bucket; + _mc = _sc = 0; + _cost = cost; _c1 = _k = _cmax = 0; + _cmin = std::numeric_limits::max(); + } + + /** + * Write the object to stream \e os as text. + * + * @param[in,out] os the output stream. + * @param[in] t the NearestNeighbor object to be saved. + * @exception std::bad_alloc if memory for the string representation of the + * object can't be allocated. + **********************************************************************/ + friend std::ostream& operator<<(std::ostream& os, const NearestNeighbor& t) + { t.Save(os, false); return os; } + + /** + * Read the object from stream \e is as text. + * + * @param[in,out] is the input stream. + * @param[out] t the NearestNeighbor object to be loaded. + * @exception GeographicErr if the state read from \e is is illegal. + * @exception std::bad_alloc if memory for the tree can't be allocated. + **********************************************************************/ + friend std::istream& operator>>(std::istream& is, NearestNeighbor& t) + { t.Load(is, false); return is; } + + /** + * Swap with another NearestNeighbor object. + * + * @param[in,out] t the NearestNeighbor object to swap with. + **********************************************************************/ + void swap(NearestNeighbor& t) { + std::swap(_numpoints, t._numpoints); + std::swap(_bucket, t._bucket); + std::swap(_cost, t._cost); + _tree.swap(t._tree); + std::swap(_mc, t._mc); + std::swap(_sc, t._sc); + std::swap(_c1, t._c1); + std::swap(_k, t._k); + std::swap(_cmin, t._cmin); + std::swap(_cmax, t._cmax); + } + + /** + * The accumulated statistics on the searches so far. + * + * @param[out] setupcost the cost of initializing the NearestNeighbor. + * @param[out] numsearches the number of calls to Search(). + * @param[out] searchcost the total cost of the calls to Search(). + * @param[out] mincost the minimum cost of a Search(). + * @param[out] maxcost the maximum cost of a Search(). + * @param[out] mean the mean cost of a Search(). + * @param[out] sd the standard deviation in the cost of a Search(). + * + * Here "cost" measures the number of distance calculations needed. Note + * that the accumulation of statistics is \e not thread safe. + **********************************************************************/ + void Statistics(int& setupcost, int& numsearches, int& searchcost, + int& mincost, int& maxcost, + double& mean, double& sd) const { + setupcost = _cost; numsearches = _k; searchcost = _c1; + mincost = _cmin; maxcost = _cmax; + mean = _mc; sd = std::sqrt(_sc / (_k - 1)); + } + + /** + * Reset the counters for the accumulated statistics on the searches so + * far. + **********************************************************************/ + void ResetStatistics() const { + _mc = _sc = 0; + _c1 = _k = _cmax = 0; + _cmin = std::numeric_limits::max(); + } + + private: + // Package up a dist_t and an int. We will want to sort on the dist_t so + // put it first. + typedef std::pair item; + // \cond SKIP + class Node { + public: + struct bounds { + dist_t lower[2], upper[2]; // bounds on inner/outer distances + int child[2]; + }; + union { + bounds data; + int leaves[maxbucket]; + }; + int index; + + Node() + : index(-1) + { + for (int i = 0; i < 2; ++i) { + data.lower[i] = data.upper[i] = 0; + data.child[i] = -1; + } + } + + // Sanity check on a Node + void Check(int numpoints, int treesize, int bucket) const { + if (!( -1 <= index && index < numpoints )) + throw GeographicLib::GeographicErr("Bad index"); + if (index >= 0) { + if (!( -1 <= data.child[0] && data.child[0] < treesize && + -1 <= data.child[1] && data.child[1] < treesize )) + throw GeographicLib::GeographicErr("Bad child pointers"); + if (!( 0 <= data.lower[0] && data.lower[0] <= data.upper[0] && + data.upper[0] <= data.lower[1] && + data.lower[1] <= data.upper[1] )) + throw GeographicLib::GeographicErr("Bad bounds"); + } else { + // Must be at least one valid leaf followed by a sequence end markers + // (-1). + bool start = true; + for (int l = 0; l < bucket; ++l) { + if (!( (start ? + ((l == 0 ? 0 : -1) <= leaves[l] && leaves[l] < numpoints) : + leaves[l] == -1) )) + throw GeographicLib::GeographicErr("Bad leaf data"); + start = leaves[l] >= 0; + } + for (int l = bucket; l < maxbucket; ++l) { + if (leaves[l] != 0) + throw GeographicLib::GeographicErr("Bad leaf data"); + } + } + } + +#if defined(GEOGRAPHICLIB_HAVE_BOOST_SERIALIZATION) && \ + GEOGRAPHICLIB_HAVE_BOOST_SERIALIZATION + friend class boost::serialization::access; + template + void save(Archive& ar, const unsigned int) const { + ar & boost::serialization::make_nvp("index", index); + if (index < 0) + ar & boost::serialization::make_nvp("leaves", leaves); + else + ar & boost::serialization::make_nvp("lower", data.lower) + & boost::serialization::make_nvp("upper", data.upper) + & boost::serialization::make_nvp("child", data.child); + } + template + void load(Archive& ar, const unsigned int) { + ar & boost::serialization::make_nvp("index", index); + if (index < 0) + ar & boost::serialization::make_nvp("leaves", leaves); + else + ar & boost::serialization::make_nvp("lower", data.lower) + & boost::serialization::make_nvp("upper", data.upper) + & boost::serialization::make_nvp("child", data.child); + } + template + void serialize(Archive& ar, const unsigned int file_version) + { boost::serialization::split_member(ar, *this, file_version); } +#endif + }; + // \endcond +#if defined(GEOGRAPHICLIB_HAVE_BOOST_SERIALIZATION) && \ + GEOGRAPHICLIB_HAVE_BOOST_SERIALIZATION + friend class boost::serialization::access; + template void save(Archive& ar, const unsigned) const { + int realspec = std::numeric_limits::digits * + (std::numeric_limits::is_integer ? -1 : 1); + // Need to use version1, otherwise load error in debug mode on Linux: + // undefined reference to GeographicLib::NearestNeighbor<...>::version. + int version1 = version; + ar & boost::serialization::make_nvp("version", version1) + & boost::serialization::make_nvp("realspec", realspec) + & boost::serialization::make_nvp("bucket", _bucket) + & boost::serialization::make_nvp("numpoints", _numpoints) + & boost::serialization::make_nvp("cost", _cost) + & boost::serialization::make_nvp("tree", _tree); + } + template void load(Archive& ar, const unsigned) { + int version1, realspec, bucket, numpoints, cost; + ar & boost::serialization::make_nvp("version", version1); + if (version1 != version) + throw GeographicLib::GeographicErr("Incompatible version"); + std::vector tree; + ar & boost::serialization::make_nvp("realspec", realspec); + if (!( realspec == std::numeric_limits::digits * + (std::numeric_limits::is_integer ? -1 : 1) )) + throw GeographicLib::GeographicErr("Different dist_t types"); + ar & boost::serialization::make_nvp("bucket", bucket); + if (!( 0 <= bucket && bucket <= maxbucket )) + throw GeographicLib::GeographicErr("Bad bucket size"); + ar & boost::serialization::make_nvp("numpoints", numpoints) + & boost::serialization::make_nvp("cost", cost) + & boost::serialization::make_nvp("tree", tree); + if (!( 0 <= int(tree.size()) && int(tree.size()) <= numpoints )) + throw + GeographicLib::GeographicErr("Bad number of points or tree size"); + for (int i = 0; i < int(tree.size()); ++i) + tree[i].Check(numpoints, int(tree.size()), bucket); + _tree.swap(tree); + _numpoints = numpoints; + _bucket = bucket; + _mc = _sc = 0; + _cost = cost; _c1 = _k = _cmax = 0; + _cmin = std::numeric_limits::max(); + } + template + void serialize(Archive& ar, const unsigned int file_version) + { boost::serialization::split_member(ar, *this, file_version); } +#endif + + int _numpoints, _bucket, _cost; + std::vector _tree; + // Counters to track stastistics on the cost of searches + mutable double _mc, _sc; + mutable int _c1, _k, _cmin, _cmax; + + int init(const std::vector& pts, const distfun_t& dist, int bucket, + std::vector& tree, std::vector& ids, int& cost, + int l, int u, int vp) { + + if (u == l) + return -1; + Node node; + + if (u - l > (bucket == 0 ? 1 : bucket)) { + + // choose a vantage point and move it to the start + int i = vp; + std::swap(ids[l], ids[i]); + + int m = (u + l + 1) / 2; + + for (int k = l + 1; k < u; ++k) { + ids[k].first = dist(pts[ids[l].second], pts[ids[k].second]); + ++cost; + } + // partition around the median distance + std::nth_element(ids.begin() + l + 1, + ids.begin() + m, + ids.begin() + u); + node.index = ids[l].second; + if (m > l + 1) { // node.child[0] is possibly empty + typename std::vector::iterator + t = std::min_element(ids.begin() + l + 1, ids.begin() + m); + node.data.lower[0] = t->first; + t = std::max_element(ids.begin() + l + 1, ids.begin() + m); + node.data.upper[0] = t->first; + // Use point with max distance as vantage point; this point act as a + // "corner" point and leads to a good partition. + node.data.child[0] = init(pts, dist, bucket, tree, ids, cost, + l + 1, m, int(t - ids.begin())); + } + typename std::vector::iterator + t = std::max_element(ids.begin() + m, ids.begin() + u); + node.data.lower[1] = ids[m].first; + node.data.upper[1] = t->first; + // Use point with max distance as vantage point here too + node.data.child[1] = init(pts, dist, bucket, tree, ids, cost, + m, u, int(t - ids.begin())); + } else { + if (bucket == 0) + node.index = ids[l].second; + else { + node.index = -1; + // Sort the bucket entries so that the tree is independent of the + // implementation of nth_element. + std::sort(ids.begin() + l, ids.begin() + u); + for (int i = l; i < u; ++i) + node.leaves[i-l] = ids[i].second; + for (int i = u - l; i < bucket; ++i) + node.leaves[i] = -1; + for (int i = bucket; i < maxbucket; ++i) + node.leaves[i] = 0; + } + } + + tree.push_back(node); + return int(tree.size()) - 1; + } + + }; + +} // namespace GeographicLib + +namespace std { + + /** + * Swap two GeographicLib::NearestNeighbor objects. + * + * @tparam dist_t the type used for measuring distances. + * @tparam pos_t the type for specifying the positions of points. + * @tparam distfun_t the type for a function object which calculates + * distances between points. + * @param[in,out] a the first GeographicLib::NearestNeighbor to swap. + * @param[in,out] b the second GeographicLib::NearestNeighbor to swap. + **********************************************************************/ + template + void swap(GeographicLib::NearestNeighbor& a, + GeographicLib::NearestNeighbor& b) { + a.swap(b); + } + +} // namespace std + +#if defined(_MSC_VER) +# pragma warning (pop) +#endif + +#endif // GEOGRAPHICLIB_NEARESTNEIGHBOR_HPP diff --git a/gtsam/3rdparty/GeographicLib/include/GeographicLib/NormalGravity.hpp b/gtsam/3rdparty/GeographicLib/include/GeographicLib/NormalGravity.hpp index 538422ce8..2c4955f74 100644 --- a/gtsam/3rdparty/GeographicLib/include/GeographicLib/NormalGravity.hpp +++ b/gtsam/3rdparty/GeographicLib/include/GeographicLib/NormalGravity.hpp @@ -2,9 +2,9 @@ * \file NormalGravity.hpp * \brief Header for GeographicLib::NormalGravity class * - * Copyright (c) Charles Karney (2011) and licensed under - * the MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ + * Copyright (c) Charles Karney (2011-2017) and licensed + * under the MIT/X11 License. For more information, see + * https://geographiclib.sourceforge.io/ **********************************************************************/ #if !defined(GEOGRAPHICLIB_NORMALGRAVITY_HPP) @@ -21,23 +21,36 @@ namespace GeographicLib { * "Normal" gravity refers to an idealization of the earth which is modeled * as an rotating ellipsoid. The eccentricity of the ellipsoid, the rotation * speed, and the distribution of mass within the ellipsoid are such that the - * surface of the ellipsoid is a surface of constant potential (gravitational - * plus centrifugal). The acceleration due to gravity is therefore - * perpendicular to the surface of the ellipsoid. + * ellipsoid is a "level ellipoid", a surface of constant potential + * (gravitational plus centrifugal). The acceleration due to gravity is + * therefore perpendicular to the surface of the ellipsoid. + * + * Because the distribution of mass within the ellipsoid is unspecified, only + * the potential exterior to the ellipsoid is well defined. In this class, + * the mass is assumed to be to concentrated on a "focal disc" of radius, + * (a2b2)1/2, where + * \e a is the equatorial radius of the ellipsoid and \e b is its polar + * semi-axis. In the case of an oblate ellipsoid, the mass is concentrated + * on a "focal rod" of length 2(b2 − + * a2)1/2. As a result the potential is well + * defined everywhere. * * There is a closed solution to this problem which is implemented here. * Series "approximations" are only used to evaluate certain combinations of * elementary functions where use of the closed expression results in a loss - * of accuracy for small arguments due to cancellation of the two leading - * terms. However these series include sufficient terms to give full machine + * of accuracy for small arguments due to cancellation of the leading terms. + * However these series include sufficient terms to give full machine * precision. * + * Although the formulation used in this class applies to ellipsoids with + * arbitrary flattening, in practice, its use should be limited to about + * b/\e a ∈ [0.01, 100] or \e f ∈ [−99, 0.99]. + * * Definitions: * - V0, the gravitational contribution to the normal * potential; * - Φ, the rotational contribution to the normal potential; - * - \e U = V0 + Φ, the total - * potential; + * - \e U = V0 + Φ, the total potential; * - Γ = ∇V0, the acceleration due to * mass of the earth; * - f = ∇Φ, the centrifugal acceleration; @@ -48,10 +61,16 @@ namespace GeographicLib { * north and up directions. * * References: + * - C. Somigliana, Teoria generale del campo gravitazionale dell'ellissoide + * di rotazione, Mem. Soc. Astron. Ital, 4, 541--599 (1929). * - W. A. Heiskanen and H. Moritz, Physical Geodesy (Freeman, San * Francisco, 1967), Secs. 1-19, 2-7, 2-8 (2-9, 2-10), 6-2 (6-3). + * - B. Hofmann-Wellenhof, H. Moritz, Physical Geodesy (Second edition, + * Springer, 2006) https://doi.org/10.1007/978-3-211-33545-1 * - H. Moritz, Geodetic Reference System 1980, J. Geodesy 54(3), 395-405 - * (1980) http://dx.doi.org/10.1007/BF02521480 + * (1980) https://doi.org/10.1007/BF02521480 + * + * For more information on normal gravity see \ref normalgravity. * * Example of use: * \include example-NormalGravity.cpp @@ -59,15 +78,32 @@ namespace GeographicLib { class GEOGRAPHICLIB_EXPORT NormalGravity { private: - static const int maxit_ = 10; + static const int maxit_ = 20; typedef Math::real real; friend class GravityModel; real _a, _GM, _omega, _f, _J2, _omega2, _aomega2; - real _e2, _ep2, _b, _E, _U0, _gammae, _gammap, _q0, _m, _k, _fstar; + real _e2, _ep2, _b, _E, _U0, _gammae, _gammap, _Q0, _k, _fstar; Geocentric _earth; - static Math::real qf(real ep2) throw(); - static Math::real qpf(real ep2) throw(); - Math::real Jn(int n) const throw(); + static real atanzz(real x, bool alt) { + // This routine obeys the identity + // atanzz(x, alt) = atanzz(-x/(1+x), !alt) + // + // Require x >= -1. Best to call with alt, s.t. x >= 0; this results in + // a call to atan, instead of asin, or to asinh, instead of atanh. + using std::sqrt; using std::abs; using std::atan; using std::asin; + real z = sqrt(abs(x)); + return x == 0 ? 1 : + (alt ? + (!(x < 0) ? Math::asinh(z) : asin(z)) / sqrt(abs(x) / (1 + x)) : + (!(x < 0) ? atan(z) : Math::atanh(z)) / z); + } + static real atan7series(real x); + static real atan5series(real x); + static real Qf(real x, bool alt); + static real Hf(real x, bool alt); + static real QH3f(real x, bool alt); + real Jn(int n) const; + void Initialize(real a, real GM, real omega, real f_J2, bool geometricp); public: /** \name Setting up the normal gravity @@ -82,14 +118,46 @@ namespace GeographicLib { * the gravitational constant and \e M the mass of the earth (usually * including the mass of the earth's atmosphere). * @param[in] omega the angular velocity (rad s−1). + * @param[in] f_J2 either the flattening of the ellipsoid \e f or the + * the dynamical form factor \e J2. + * @param[out] geometricp if true (the default), then \e f_J2 denotes the + * flattening, else it denotes the dynamical form factor \e J2. + * @exception if \e a is not positive or if the other parameters do not + * obey the restrictions given below. + * + * The shape of the ellipsoid can be given in one of two ways: + * - geometrically (\e geomtricp = true), the ellipsoid is defined by the + * flattening \e f = (\e a − \e b) / \e a, where \e a and \e b are + * the equatorial radius and the polar semi-axis. The parameters should + * obey \e a > 0, \e f < 1. There are no restrictions on \e GM or + * \e omega, in particular, \e GM need not be positive. + * - physically (\e geometricp = false), the ellipsoid is defined by the + * dynamical form factor J2 = (\e C − \e A) / + * Ma2, where \e A and \e C are the equatorial and + * polar moments of inertia and \e M is the mass of the earth. The + * parameters should obey \e a > 0, \e GM > 0 and \e J2 < 1/3 + * − (omega2a3/GM) + * 8/(45π). There is no restriction on \e omega. + **********************************************************************/ + NormalGravity(real a, real GM, real omega, real f_J2, + bool geometricp = true); + /** + * \deprecated Old constructor for the normal gravity. + * + * @param[in] a equatorial radius (meters). + * @param[in] GM mass constant of the ellipsoid + * (meters3/seconds2); this is the product of \e G + * the gravitational constant and \e M the mass of the earth (usually + * including the mass of the earth's atmosphere). + * @param[in] omega the angular velocity (rad s−1). * @param[in] f the flattening of the ellipsoid. - * @param[in] J2 dynamical form factor. + * @param[in] J2 the dynamical form factor. * @exception if \e a is not positive or the other constants are * inconsistent (see below). * - * Exactly one of \e f and \e J2 should be positive and this will be used - * to define the ellipsoid. The shape of the ellipsoid can be given in one - * of two ways: + * If \e omega is non-zero, then exactly one of \e f and \e J2 should be + * positive and this will be used to define the ellipsoid. The shape of + * the ellipsoid can be given in one of two ways: * - geometrically, the ellipsoid is defined by the flattening \e f = (\e a * − \e b) / \e a, where \e a and \e b are the equatorial radius * and the polar semi-axis. @@ -97,7 +165,11 @@ namespace GeographicLib { * J2 = (\e C − \e A) / Ma2, * where \e A and \e C are the equatorial and polar moments of inertia * and \e M is the mass of the earth. + * . + * If \e omega, \e f, and \e J2 are all zero, then the ellipsoid becomes a + * sphere. **********************************************************************/ + GEOGRAPHICLIB_DEPRECATED("Use new NormalGravity constructor") NormalGravity(real a, real GM, real omega, real f, real J2); /** @@ -123,7 +195,7 @@ namespace GeographicLib { * surface of the ellipsoid. It includes the effects of the earth's * rotation. **********************************************************************/ - Math::real SurfaceGravity(real lat) const throw(); + Math::real SurfaceGravity(real lat) const; /** * Evaluate the gravity at an arbitrary point above (or below) the @@ -135,7 +207,8 @@ namespace GeographicLib { * (m s−2). * @param[out] gammaz the upward component of the acceleration * (m s−2); this is usually negative. - * @return \e U the corresponding normal potential. + * @return \e U the corresponding normal potential + * (m2 s−2). * * Due to the axial symmetry of the ellipsoid, the result is independent of * the value of the longitude and the easterly component of the @@ -144,7 +217,7 @@ namespace GeographicLib { * 0 and the returned value matches that of NormalGravity::SurfaceGravity. **********************************************************************/ Math::real Gravity(real lat, real h, real& gammay, real& gammaz) - const throw(); + const; /** * Evaluate the components of the acceleration due to gravity and the @@ -167,21 +240,20 @@ namespace GeographicLib { * ∇V0 + ∇Φ = Γ + f. **********************************************************************/ Math::real U(real X, real Y, real Z, - real& gammaX, real& gammaY, real& gammaZ) const throw(); + real& gammaX, real& gammaY, real& gammaZ) const; /** - * Evaluate the components of the acceleration due to gravity alone in - * geocentric coordinates. + * Evaluate the components of the acceleration due to the gravitational + * force in geocentric coordinates. * * @param[in] X geocentric coordinate of point (meters). * @param[in] Y geocentric coordinate of point (meters). * @param[in] Z geocentric coordinate of point (meters). - * @param[out] GammaX the \e X component of the acceleration due to gravity - * (m s−2). - * @param[out] GammaY the \e Y component of the acceleration due to gravity - * (m s−2). - * @param[out] GammaZ the \e Z component of the acceleration due to gravity - * (m s−2). + * @param[out] GammaX the \e X component of the acceleration due to the + * gravitational force (m s−2). + * @param[out] GammaY the \e Y component of the acceleration due to the + * @param[out] GammaZ the \e Z component of the acceleration due to the + * gravitational force (m s−2). * @return V0 the gravitational potential * (m2 s−2). * @@ -191,7 +263,7 @@ namespace GeographicLib { * used. **********************************************************************/ Math::real V0(real X, real Y, real Z, - real& GammaX, real& GammaY, real& GammaZ) const throw(); + real& GammaX, real& GammaY, real& GammaZ) const; /** * Evaluate the centrifugal acceleration in geocentric coordinates. @@ -209,7 +281,7 @@ namespace GeographicLib { * NormalGravity::U sums the results of NormalGravity::V0 and * NormalGravity::Phi. **********************************************************************/ - Math::real Phi(real X, real Y, real& fX, real& fY) const throw(); + Math::real Phi(real X, real Y, real& fX, real& fY) const; ///@} /** \name Inspector functions @@ -218,94 +290,132 @@ namespace GeographicLib { /** * @return true if the object has been initialized. **********************************************************************/ - bool Init() const throw() { return _a > 0; } + bool Init() const { return _a > 0; } /** * @return \e a the equatorial radius of the ellipsoid (meters). This is * the value used in the constructor. **********************************************************************/ - Math::real MajorRadius() const throw() - { return Init() ? _a : Math::NaN(); } + Math::real MajorRadius() const + { return Init() ? _a : Math::NaN(); } /** * @return \e GM the mass constant of the ellipsoid * (m3 s−2). This is the value used in the * constructor. **********************************************************************/ - Math::real MassConstant() const throw() - { return Init() ? _GM : Math::NaN(); } + Math::real MassConstant() const + { return Init() ? _GM : Math::NaN(); } /** - * @return \e Jn the dynamical form factors of the ellipsoid. + * @return Jn the dynamical form factors of the + * ellipsoid. * * If \e n = 2 (the default), this is the value of J2 * used in the constructor. Otherwise it is the zonal coefficient of the * Legendre harmonic sum of the normal gravitational potential. Note that - * \e Jn = 0 if \e n is odd. In most gravity applications, - * fully normalized Legendre functions are used and the corresponding - * coefficient is Cn0 = −\e Jn / - * sqrt(2 \e n + 1). + * Jn = 0 if \e n is odd. In most gravity + * applications, fully normalized Legendre functions are used and the + * corresponding coefficient is Cn0 = + * −Jn / sqrt(2 \e n + 1). **********************************************************************/ - Math::real DynamicalFormFactor(int n = 2) const throw() - { return Init() ? ( n == 2 ? _J2 : Jn(n)) : Math::NaN(); } + Math::real DynamicalFormFactor(int n = 2) const + { return Init() ? ( n == 2 ? _J2 : Jn(n)) : Math::NaN(); } /** * @return ω the angular velocity of the ellipsoid (rad * s−1). This is the value used in the constructor. **********************************************************************/ - Math::real AngularVelocity() const throw() - { return Init() ? _omega : Math::NaN(); } + Math::real AngularVelocity() const + { return Init() ? _omega : Math::NaN(); } /** * @return f the flattening of the ellipsoid (\e a − \e b)/\e * a. **********************************************************************/ - Math::real Flattening() const throw() - { return Init() ? _f : Math::NaN(); } + Math::real Flattening() const + { return Init() ? _f : Math::NaN(); } /** * @return γe the normal gravity at equator (m * s−2). **********************************************************************/ - Math::real EquatorialGravity() const throw() - { return Init() ? _gammae : Math::NaN(); } + Math::real EquatorialGravity() const + { return Init() ? _gammae : Math::NaN(); } /** * @return γp the normal gravity at poles (m * s−2). **********************************************************************/ - Math::real PolarGravity() const throw() - { return Init() ? _gammap : Math::NaN(); } + Math::real PolarGravity() const + { return Init() ? _gammap : Math::NaN(); } /** * @return f* the gravity flattening (γp − * γe) / γe. **********************************************************************/ - Math::real GravityFlattening() const throw() - { return Init() ? _fstar : Math::NaN(); } + Math::real GravityFlattening() const + { return Init() ? _fstar : Math::NaN(); } /** * @return U0 the constant normal potential for the * surface of the ellipsoid (m2 s−2). **********************************************************************/ - Math::real SurfacePotential() const throw() - { return Init() ? _U0 : Math::NaN(); } + Math::real SurfacePotential() const + { return Init() ? _U0 : Math::NaN(); } /** * @return the Geocentric object used by this instance. **********************************************************************/ - const Geocentric& Earth() const throw() { return _earth; } + const Geocentric& Earth() const { return _earth; } ///@} /** * A global instantiation of NormalGravity for the WGS84 ellipsoid. **********************************************************************/ - static const NormalGravity WGS84; + static const NormalGravity& WGS84(); /** * A global instantiation of NormalGravity for the GRS80 ellipsoid. **********************************************************************/ - static const NormalGravity GRS80; + static const NormalGravity& GRS80(); + + /** + * Compute the flattening from the dynamical form factor. + * + * @param[in] a equatorial radius (meters). + * @param[in] GM mass constant of the ellipsoid + * (meters3/seconds2); this is the product of \e G + * the gravitational constant and \e M the mass of the earth (usually + * including the mass of the earth's atmosphere). + * @param[in] omega the angular velocity (rad s−1). + * @param[in] J2 the dynamical form factor. + * @return \e f the flattening of the ellipsoid. + * + * This routine requires \e a > 0, \e GM > 0, \e J2 < 1/3 − + * omega2a3/GM 8/(45π). A + * NaN is returned if these conditions do not hold. The restriction to + * positive \e GM is made because for negative \e GM two solutions are + * possible. + **********************************************************************/ + static Math::real J2ToFlattening(real a, real GM, real omega, real J2); + + /** + * Compute the dynamical form factor from the flattening. + * + * @param[in] a equatorial radius (meters). + * @param[in] GM mass constant of the ellipsoid + * (meters3/seconds2); this is the product of \e G + * the gravitational constant and \e M the mass of the earth (usually + * including the mass of the earth's atmosphere). + * @param[in] omega the angular velocity (rad s−1). + * @param[in] f the flattening of the ellipsoid. + * @return \e J2 the dynamical form factor. + * + * This routine requires \e a > 0, \e GM ≠ 0, \e f < 1. The + * values of these parameters are not checked. + **********************************************************************/ + static Math::real FlatteningToJ2(real a, real GM, real omega, real f); }; } // namespace GeographicLib diff --git a/gtsam/3rdparty/GeographicLib/include/GeographicLib/OSGB.hpp b/gtsam/3rdparty/GeographicLib/include/GeographicLib/OSGB.hpp index c055dd877..d44c9c097 100644 --- a/gtsam/3rdparty/GeographicLib/include/GeographicLib/OSGB.hpp +++ b/gtsam/3rdparty/GeographicLib/include/GeographicLib/OSGB.hpp @@ -2,9 +2,9 @@ * \file OSGB.hpp * \brief Header for GeographicLib::OSGB class * - * Copyright (c) Charles Karney (2010-2011) and licensed + * Copyright (c) Charles Karney (2010-2017) and licensed * under the MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #if !defined(GEOGRAPHICLIB_OSGB_HPP) @@ -33,7 +33,7 @@ namespace GeographicLib { * - * Guide to the National Grid * - * \b WARNING: the latitudes and longitudes for the Ordnance Survey grid + * \warning the latitudes and longitudes for the Ordnance Survey grid * system do not use the WGS84 datum. Do not use the values returned by this * class in the UTMUPS, MGRS, or Geoid classes without first converting the * datum (and vice versa). @@ -44,11 +44,9 @@ namespace GeographicLib { class GEOGRAPHICLIB_EXPORT OSGB { private: typedef Math::real real; - static const std::string letters_; - static const std::string digits_; - static const TransverseMercator OSGBTM_; - static real northoffset_; - static bool init_; + static const char* const letters_; + static const char* const digits_; + static const TransverseMercator& OSGBTM(); enum { base_ = 10, tile_ = 100000, @@ -63,7 +61,7 @@ namespace GeographicLib { // Maximum precision is um maxprec_ = 5 + 6, }; - static real computenorthoffset() throw(); + static real computenorthoffset(); static void CheckCoords(real x, real y); OSGB(); // Disable constructor public: @@ -78,12 +76,11 @@ namespace GeographicLib { * @param[out] gamma meridian convergence at point (degrees). * @param[out] k scale of projection at point. * - * \e lat should be in the range [−90°, 90°]; \e lon - * should be in the range [−540°, 540°). + * \e lat should be in the range [−90°, 90°]. **********************************************************************/ static void Forward(real lat, real lon, - real& x, real& y, real& gamma, real& k) throw() { - OSGBTM_.Forward(OriginLongitude(), lat, lon, x, y, gamma, k); + real& x, real& y, real& gamma, real& k) { + OSGBTM().Forward(OriginLongitude(), lat, lon, x, y, gamma, k); x += FalseEasting(); y += computenorthoffset(); } @@ -99,20 +96,20 @@ namespace GeographicLib { * @param[out] k scale of projection at point. * * The value of \e lon returned is in the range [−180°, - * 180°). + * 180°]. **********************************************************************/ static void Reverse(real x, real y, - real& lat, real& lon, real& gamma, real& k) throw() { + real& lat, real& lon, real& gamma, real& k) { x -= FalseEasting(); y -= computenorthoffset(); - OSGBTM_.Reverse(OriginLongitude(), x, y, lat, lon, gamma, k); + OSGBTM().Reverse(OriginLongitude(), x, y, lat, lon, gamma, k); } /** * OSGB::Forward without returning the convergence and scale. **********************************************************************/ - static void Forward(real lat, real lon, real& x, real& y) throw() { + static void Forward(real lat, real lon, real& x, real& y) { real gamma, k; Forward(lat, lon, x, y, gamma, k); } @@ -120,7 +117,7 @@ namespace GeographicLib { /** * OSGB::Reverse without returning the convergence and scale. **********************************************************************/ - static void Reverse(real x, real y, real& lat, real& lon) throw() { + static void Reverse(real x, real y, real& lat, real& lon) { real gamma, k; Reverse(x, y, lat, lon, gamma, k); } @@ -151,6 +148,8 @@ namespace GeographicLib { * northing must be in the range [−500 km, 2000 km). These bounds * are consistent with rules for the letter designations for the grid * system. + * + * If \e x or \e y is NaN, the returned grid reference is "INVALID". **********************************************************************/ static void GridReference(real x, real y, int prec, std::string& gridref); @@ -167,6 +166,9 @@ namespace GeographicLib { * * The grid reference must be of the form: two letters (not including I) * followed by an even number of digits (up to 22). + * + * If the first 2 characters of \e gridref are "IN", then \e x and \e y are + * set to NaN and \e prec is set to −2. **********************************************************************/ static void GridReference(const std::string& gridref, real& x, real& y, int& prec, @@ -179,12 +181,18 @@ namespace GeographicLib { * @return \e a the equatorial radius of the Airy 1830 ellipsoid (meters). * * This is 20923713 ft converted to meters using the rule 1 ft = - * 109.48401603−10 m. (The Airy 1830 value is returned - * because the OSGB projection is based on this ellipsoid.) + * 109.48401603−10 m. The Airy 1830 value is returned + * because the OSGB projection is based on this ellipsoid. The conversion + * factor from feet to meters is the one used for the 1936 retriangulation + * of Britain; see Section A.1 (p. 37) of A guide to coordinate systems + * in Great Britain, v2.2 (Dec. 2013). **********************************************************************/ - static Math::real MajorRadius() throw() + static Math::real MajorRadius() { // result is about 6377563.3960320664406 m - { return real(20923713) * std::pow(real(10), real(0.48401603L) - 1); } + using std::pow; + return pow(real(10), real(48401603 - 100000000) / 100000000) + * real(20923713); + } /** * @return \e f the inverse flattening of the Airy 1830 ellipsoid. @@ -194,46 +202,40 @@ namespace GeographicLib { * 7767/2324857 = 1/299.32496459... (The Airy 1830 value is returned * because the OSGB projection is based on this ellipsoid.) **********************************************************************/ - static Math::real Flattening() throw() + static Math::real Flattening() { return real(20923713 - 20853810) / real(20923713); } - /// \cond SKIP - /** - * DEPRECATED - * @return \e r the inverse flattening of the Airy 1830 ellipsoid. - **********************************************************************/ - static Math::real InverseFlattening() throw() { return 1/Flattening(); } - /// \endcond - /** * @return \e k0 central scale for the OSGB projection (0.9996012717...). * * C. J. Mugnier, Grids & Datums, PE&RS, Oct. 2003, states that * this is defined as 109.9998268−10. **********************************************************************/ - static Math::real CentralScale() throw() - { return std::pow(real(10), real(9998268 - 10000000) / real(10000000)); } + static Math::real CentralScale() { + using std::pow; + return pow(real(10), real(9998268 - 10000000) / 10000000); + } /** * @return latitude of the origin for the OSGB projection (49 degrees). **********************************************************************/ - static Math::real OriginLatitude() throw() { return real(49); } + static Math::real OriginLatitude() { return real(49); } /** * @return longitude of the origin for the OSGB projection (−2 * degrees). **********************************************************************/ - static Math::real OriginLongitude() throw() { return real(-2); } + static Math::real OriginLongitude() { return real(-2); } /** * @return false northing the OSGB projection (−100000 meters). **********************************************************************/ - static Math::real FalseNorthing() throw() { return real(-100000); } + static Math::real FalseNorthing() { return real(-100000); } /** * @return false easting the OSGB projection (400000 meters). **********************************************************************/ - static Math::real FalseEasting() throw() { return real(400000); } + static Math::real FalseEasting() { return real(400000); } ///@} }; diff --git a/gtsam/3rdparty/GeographicLib/include/GeographicLib/PolarStereographic.hpp b/gtsam/3rdparty/GeographicLib/include/GeographicLib/PolarStereographic.hpp index 0ff0d732e..ff06e6688 100644 --- a/gtsam/3rdparty/GeographicLib/include/GeographicLib/PolarStereographic.hpp +++ b/gtsam/3rdparty/GeographicLib/include/GeographicLib/PolarStereographic.hpp @@ -2,9 +2,9 @@ * \file PolarStereographic.hpp * \brief Header for GeographicLib::PolarStereographic class * - * Copyright (c) Charles Karney (2008-2011) and licensed + * Copyright (c) Charles Karney (2008-2016) and licensed * under the MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #if !defined(GEOGRAPHICLIB_POLARSTEREOGRAPHIC_HPP) @@ -26,28 +26,18 @@ namespace GeographicLib { * This is a straightforward implementation of the equations in Snyder except * that Newton's method is used to invert the projection. * + * This class also returns the meridian convergence \e gamma and scale \e k. + * The meridian convergence is the bearing of grid north (the \e y axis) + * measured clockwise from true north. + * * Example of use: * \include example-PolarStereographic.cpp **********************************************************************/ class GEOGRAPHICLIB_EXPORT PolarStereographic { private: typedef Math::real real; - // _Cx used to be _C but g++ 3.4 has a macro of that name - real _a, _f, _e2, _e, _e2m, _Cx, _c; + real _a, _f, _e2, _es, _e2m, _c; real _k0; - static const real tol_; - static const real overflow_; - static const int numit_ = 5; - // tan(x) for x in [-pi/2, pi/2] ensuring that the sign is right - static inline real tanx(real x) throw() { - real t = std::tan(x); - // Write the tests this way to ensure that tanx(NaN()) is NaN() - return x >= 0 ? (!(t < 0) ? t : overflow_) : (!(t >= 0) ? t : -overflow_); - } - // Return e * atanh(e * x) for f >= 0, else return - // - sqrt(-e2) * atan( sqrt(-e2) * x) for f < 0 - inline real eatanhe(real x) const throw() - { return _f >= 0 ? _e * Math::atanh(_e * x) : - _e * std::atan(_e * x); } public: /** @@ -55,10 +45,9 @@ namespace GeographicLib { * * @param[in] a equatorial radius (meters). * @param[in] f flattening of ellipsoid. Setting \e f = 0 gives a sphere. - * Negative \e f gives a prolate ellipsoid. If \e f > 1, set flattening - * to 1/\e f. + * Negative \e f gives a prolate ellipsoid. * @param[in] k0 central scale factor. - * @exception GeographicErr if \e a, (1 − \e f ) \e a, or \e k0 is + * @exception GeographicErr if \e a, (1 − \e f) \e a, or \e k0 is * not positive. **********************************************************************/ PolarStereographic(real a, real f, real k0); @@ -88,11 +77,10 @@ namespace GeographicLib { * * No false easting or northing is added. \e lat should be in the range * (−90°, 90°] for \e northp = true and in the range - * [−90°, 90°) for \e northp = false; \e lon should - * be in the range [−540°, 540°). + * [−90°, 90°) for \e northp = false. **********************************************************************/ void Forward(bool northp, real lat, real lon, - real& x, real& y, real& gamma, real& k) const throw(); + real& x, real& y, real& gamma, real& k) const; /** * Reverse projection, from polar stereographic to geographic. @@ -107,16 +95,16 @@ namespace GeographicLib { * @param[out] k scale of projection at point. * * No false easting or northing is added. The value of \e lon returned is - * in the range [−180°, 180°). + * in the range [−180°, 180°]. **********************************************************************/ void Reverse(bool northp, real x, real y, - real& lat, real& lon, real& gamma, real& k) const throw(); + real& lat, real& lon, real& gamma, real& k) const; /** * PolarStereographic::Forward without returning the convergence and scale. **********************************************************************/ void Forward(bool northp, real lat, real lon, - real& x, real& y) const throw() { + real& x, real& y) const { real gamma, k; Forward(northp, lat, lon, x, y, gamma, k); } @@ -125,7 +113,7 @@ namespace GeographicLib { * PolarStereographic::Reverse without returning the convergence and scale. **********************************************************************/ void Reverse(bool northp, real x, real y, - real& lat, real& lon) const throw() { + real& lat, real& lon) const { real gamma, k; Reverse(northp, x, y, lat, lon, gamma, k); } @@ -137,28 +125,20 @@ namespace GeographicLib { * @return \e a the equatorial radius of the ellipsoid (meters). This is * the value used in the constructor. **********************************************************************/ - Math::real MajorRadius() const throw() { return _a; } + Math::real MajorRadius() const { return _a; } /** * @return \e f the flattening of the ellipsoid. This is the value used in * the constructor. **********************************************************************/ - Math::real Flattening() const throw() { return _f; } - - /// \cond SKIP - /** - * DEPRECATED - * @return \e r the inverse flattening of the ellipsoid. - **********************************************************************/ - Math::real InverseFlattening() const throw() { return 1/_f; } - /// \endcond + Math::real Flattening() const { return _f; } /** * The central scale for the projection. This is the value of \e k0 used * in the constructor and is the scale at the pole unless overridden by * PolarStereographic::SetScale. **********************************************************************/ - Math::real CentralScale() const throw() { return _k0; } + Math::real CentralScale() const { return _k0; } ///@} /** @@ -166,7 +146,7 @@ namespace GeographicLib { * and the UPS scale factor. However, unlike UPS, no false easting or * northing is added. **********************************************************************/ - static const PolarStereographic UPS; + static const PolarStereographic& UPS(); }; } // namespace GeographicLib diff --git a/gtsam/3rdparty/GeographicLib/include/GeographicLib/PolygonArea.hpp b/gtsam/3rdparty/GeographicLib/include/GeographicLib/PolygonArea.hpp index cc1edf17f..479e5a8e6 100644 --- a/gtsam/3rdparty/GeographicLib/include/GeographicLib/PolygonArea.hpp +++ b/gtsam/3rdparty/GeographicLib/include/GeographicLib/PolygonArea.hpp @@ -1,17 +1,18 @@ /** * \file PolygonArea.hpp - * \brief Header for GeographicLib::PolygonArea class + * \brief Header for GeographicLib::PolygonAreaT class * - * Copyright (c) Charles Karney (2010-2011) and licensed + * Copyright (c) Charles Karney (2010-2016) and licensed * under the MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #if !defined(GEOGRAPHICLIB_POLYGONAREA_HPP) #define GEOGRAPHICLIB_POLYGONAREA_HPP 1 #include -#include +#include +#include #include namespace GeographicLib { @@ -22,86 +23,118 @@ namespace GeographicLib { * This computes the area of a polygon whose edges are geodesics using the * method given in Section 6 of * - C. F. F. Karney, - * + * * Algorithms for geodesics, * J. Geodesy 87, 43--55 (2013); - * DOI: + * DOI: * 10.1007/s00190-012-0578-z; - * addenda: + * addenda: + * * geod-addenda.html. * * This class lets you add vertices and edges one at a time to the polygon. * The sequence must start with a vertex and thereafter vertices and edges * can be added in any order. Any vertex after the first creates a new edge - * which is the ''shortest'' geodesic from the previous vertex. In some + * which is the \e shortest geodesic from the previous vertex. In some * cases there may be two or many such shortest geodesics and the area is * then not uniquely defined. In this case, either add an intermediate - * vertex or add the edge ''as'' an edge (by defining its direction and + * vertex or add the edge \e as an edge (by defining its direction and * length). * - * The area and perimeter are accumulated in two times the standard floating + * The area and perimeter are accumulated at two times the standard floating * point precision to guard against the loss of accuracy with many-sided * polygons. At any point you can ask for the perimeter and area so far. * There's an option to treat the points as defining a polyline instead of a * polygon; in that case, only the perimeter is computed. * + * This is a templated class to allow it to be used with Geodesic, + * GeodesicExact, and Rhumb. GeographicLib::PolygonArea, + * GeographicLib::PolygonAreaExact, and GeographicLib::PolygonAreaRhumb are + * typedefs for these cases. + * + * @tparam GeodType the geodesic class to use. + * * Example of use: * \include example-PolygonArea.cpp * * Planimeter is a command-line utility - * providing access to the functionality of PolygonArea. + * providing access to the functionality of PolygonAreaT. **********************************************************************/ - class GEOGRAPHICLIB_EXPORT PolygonArea { + template + class PolygonAreaT { private: typedef Math::real real; - Geodesic _earth; + GeodType _earth; real _area0; // Full ellipsoid area bool _polyline; // Assume polyline (don't close and skip area) unsigned _mask; unsigned _num; int _crossings; - Accumulator _areasum, _perimetersum; + Accumulator<> _areasum, _perimetersum; real _lat0, _lon0, _lat1, _lon1; - static inline int transit(real lon1, real lon2) throw() { + static int transit(real lon1, real lon2) { // Return 1 or -1 if crossing prime meridian in east or west direction. // Otherwise return zero. // Compute lon12 the same way as Geodesic::Inverse. lon1 = Math::AngNormalize(lon1); lon2 = Math::AngNormalize(lon2); real lon12 = Math::AngDiff(lon1, lon2); + // Treat 0 as negative in these tests. This balances +/- 180 being + // treated as positive, i.e., +180. int cross = - lon1 < 0 && lon2 >= 0 && lon12 > 0 ? 1 : - (lon2 < 0 && lon1 >= 0 && lon12 < 0 ? -1 : 0); + lon1 <= 0 && lon2 > 0 && lon12 > 0 ? 1 : + (lon2 <= 0 && lon1 > 0 && lon12 < 0 ? -1 : 0); return cross; } + // an alternate version of transit to deal with longitudes in the direct + // problem. + static int transitdirect(real lon1, real lon2) { + // We want to compute exactly + // int(floor(lon2 / 360)) - int(floor(lon1 / 360)) + // Since we only need the parity of the result we can use std::remquo; + // but this is buggy with g++ 4.8.3 (glibc version < 2.22), see + // https://sourceware.org/bugzilla/show_bug.cgi?id=17569 + // and requires C++11. So instead we do +#if GEOGRAPHICLIB_CXX11_MATH && GEOGRAPHICLIB_PRECISION != 4 + using std::remainder; + lon1 = remainder(lon1, real(720)); lon2 = remainder(lon2, real(720)); + return ( (lon2 >= 0 && lon2 < 360 ? 0 : 1) - + (lon1 >= 0 && lon1 < 360 ? 0 : 1) ); +#else + using std::fmod; + lon1 = fmod(lon1, real(720)); lon2 = fmod(lon2, real(720)); + return ( ((lon2 >= 0 && lon2 < 360) || lon2 < -360 ? 0 : 1) - + ((lon1 >= 0 && lon1 < 360) || lon1 < -360 ? 0 : 1) ); +#endif + } public: /** - * Constructor for PolygonArea. + * Constructor for PolygonAreaT. * * @param[in] earth the Geodesic object to use for geodesic calculations. - * By default this uses the WGS84 ellipsoid. * @param[in] polyline if true that treat the points as defining a polyline * instead of a polygon (default = false). **********************************************************************/ - PolygonArea(const Geodesic& earth, bool polyline = false) throw() + PolygonAreaT(const GeodType& earth, bool polyline = false) : _earth(earth) , _area0(_earth.EllipsoidArea()) , _polyline(polyline) - , _mask(Geodesic::LATITUDE | Geodesic::LONGITUDE | Geodesic::DISTANCE | - (_polyline ? Geodesic::NONE : Geodesic::AREA)) + , _mask(GeodType::LATITUDE | GeodType::LONGITUDE | GeodType::DISTANCE | + (_polyline ? GeodType::NONE : + GeodType::AREA | GeodType::LONG_UNROLL)) { Clear(); } /** - * Clear PolygonArea, allowing a new polygon to be started. + * Clear PolygonAreaT, allowing a new polygon to be started. **********************************************************************/ - void Clear() throw() { + void Clear() { _num = 0; _crossings = 0; _areasum = 0; _perimetersum = 0; - _lat0 = _lon0 = _lat1 = _lon1 = Math::NaN(); + _lat0 = _lon0 = _lat1 = _lon1 = Math::NaN(); } /** @@ -110,10 +143,9 @@ namespace GeographicLib { * @param[in] lat the latitude of the point (degrees). * @param[in] lon the longitude of the point (degrees). * - * \e lat should be in the range [−90°, 90°] and \e - * lon should be in the range [−540°, 540°). + * \e lat should be in the range [−90°, 90°]. **********************************************************************/ - void AddPoint(real lat, real lon) throw(); + void AddPoint(real lat, real lon); /** * Add an edge to the polygon or polyline. @@ -121,11 +153,10 @@ namespace GeographicLib { * @param[in] azi azimuth at current point (degrees). * @param[in] s distance from current point to next point (meters). * - * \e azi should be in the range [−540°, 540°). This does - * nothing if no points have been added yet. Use PolygonArea::CurrentPoint - * to determine the position of the new vertex. + * This does nothing if no points have been added yet. Use + * PolygonAreaT::CurrentPoint to determine the position of the new vertex. **********************************************************************/ - void AddEdge(real azi, real s) throw(); + void AddEdge(real azi, real s); /** * Return the results so far. @@ -140,9 +171,11 @@ namespace GeographicLib { * @param[out] area the area of the polygon (meters2); only set * if \e polyline is false in the constructor. * @return the number of points. + * + * More points can be added to the polygon after this call. **********************************************************************/ unsigned Compute(bool reverse, bool sign, - real& perimeter, real& area) const throw(); + real& perimeter, real& area) const; /** * Return the results assuming a tentative final test point is added; @@ -150,7 +183,7 @@ namespace GeographicLib { * a running result for the perimeter and area as the user moves the mouse * cursor. Ordinary floating point arithmetic is used to accumulate the * data for the test point; thus the area and perimeter returned are less - * accurate than if PolygonArea::AddPoint and PolygonArea::Compute are + * accurate than if PolygonAreaT::AddPoint and PolygonAreaT::Compute are * used. * * @param[in] lat the latitude of the test point (degrees). @@ -167,11 +200,10 @@ namespace GeographicLib { * constructor. * @return the number of points. * - * \e lat should be in the range [−90°, 90°] and \e - * lon should be in the range [−540°, 540°). + * \e lat should be in the range [−90°, 90°]. **********************************************************************/ unsigned TestPoint(real lat, real lon, bool reverse, bool sign, - real& perimeter, real& area) const throw(); + real& perimeter, real& area) const; /** * Return the results assuming a tentative final test point is added via an @@ -179,8 +211,8 @@ namespace GeographicLib { * This lets you report a running result for the perimeter and area as the * user moves the mouse cursor. Ordinary floating point arithmetic is used * to accumulate the data for the test point; thus the area and perimeter - * returned are less accurate than if PolygonArea::AddEdge and - * PolygonArea::Compute are used. + * returned are less accurate than if PolygonAreaT::AddEdge and + * PolygonAreaT::Compute are used. * * @param[in] azi azimuth at current point (degrees). * @param[in] s distance from current point to final test point (meters). @@ -195,22 +227,9 @@ namespace GeographicLib { * (meters2); only set if polyline is false in the * constructor. * @return the number of points. - * - * \e azi should be in the range [−540°, 540°). **********************************************************************/ unsigned TestEdge(real azi, real s, bool reverse, bool sign, - real& perimeter, real& area) const throw(); - - /// \cond SKIP - /** - * DEPRECATED - * The old name for PolygonArea::TestPoint. - **********************************************************************/ - unsigned TestCompute(real lat, real lon, bool reverse, bool sign, - real& perimeter, real& area) const throw() { - return TestPoint(lat, lon, reverse, sign, perimeter, area); - } - /// \endcond + real& perimeter, real& area) const; /** \name Inspector functions **********************************************************************/ @@ -220,13 +239,13 @@ namespace GeographicLib { * the value inherited from the Geodesic object used in the constructor. **********************************************************************/ - Math::real MajorRadius() const throw() { return _earth.MajorRadius(); } + Math::real MajorRadius() const { return _earth.MajorRadius(); } /** * @return \e f the flattening of the ellipsoid. This is the value * inherited from the Geodesic object used in the constructor. **********************************************************************/ - Math::real Flattening() const throw() { return _earth.Flattening(); } + Math::real Flattening() const { return _earth.Flattening(); } /** * Report the previous vertex added to the polygon or polyline. @@ -235,13 +254,37 @@ namespace GeographicLib { * @param[out] lon the longitude of the point (degrees). * * If no points have been added, then NaNs are returned. Otherwise, \e lon - * will be in the range [−180°, 180°). + * will be in the range [−180°, 180°]. **********************************************************************/ - void CurrentPoint(real& lat, real& lon) const throw() + void CurrentPoint(real& lat, real& lon) const { lat = _lat1; lon = _lon1; } ///@} }; + /** + * @relates PolygonAreaT + * + * Polygon areas using Geodesic. This should be used if the flattening is + * small. + **********************************************************************/ + typedef PolygonAreaT PolygonArea; + + /** + * @relates PolygonAreaT + * + * Polygon areas using GeodesicExact. (But note that the implementation of + * areas in GeodesicExact uses a high order series and this is only accurate + * for modest flattenings.) + **********************************************************************/ + typedef PolygonAreaT PolygonAreaExact; + + /** + * @relates PolygonAreaT + * + * Polygon areas using Rhumb. + **********************************************************************/ + typedef PolygonAreaT PolygonAreaRhumb; + } // namespace GeographicLib #endif // GEOGRAPHICLIB_POLYGONAREA_HPP diff --git a/gtsam/3rdparty/GeographicLib/include/GeographicLib/Rhumb.hpp b/gtsam/3rdparty/GeographicLib/include/GeographicLib/Rhumb.hpp new file mode 100644 index 000000000..e2409e0cf --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/include/GeographicLib/Rhumb.hpp @@ -0,0 +1,590 @@ +/** + * \file Rhumb.hpp + * \brief Header for GeographicLib::Rhumb and GeographicLib::RhumbLine classes + * + * Copyright (c) Charles Karney (2014-2017) and licensed + * under the MIT/X11 License. For more information, see + * https://geographiclib.sourceforge.io/ + **********************************************************************/ + +#if !defined(GEOGRAPHICLIB_RHUMB_HPP) +#define GEOGRAPHICLIB_RHUMB_HPP 1 + +#include +#include + +#if !defined(GEOGRAPHICLIB_RHUMBAREA_ORDER) +/** + * The order of the series approximation used in rhumb area calculations. + * GEOGRAPHICLIB_RHUMBAREA_ORDER can be set to any integer in [4, 8]. + **********************************************************************/ +# define GEOGRAPHICLIB_RHUMBAREA_ORDER \ + (GEOGRAPHICLIB_PRECISION == 2 ? 6 : \ + (GEOGRAPHICLIB_PRECISION == 1 ? 4 : 8)) +#endif + +namespace GeographicLib { + + class RhumbLine; + template class PolygonAreaT; + + /** + * \brief Solve of the direct and inverse rhumb problems. + * + * The path of constant azimuth between two points on a ellipsoid at (\e + * lat1, \e lon1) and (\e lat2, \e lon2) is called the rhumb line (also + * called the loxodrome). Its length is \e s12 and its azimuth is \e azi12. + * (The azimuth is the heading measured clockwise from north.) + * + * Given \e lat1, \e lon1, \e azi12, and \e s12, we can determine \e lat2, + * and \e lon2. This is the \e direct rhumb problem and its solution is + * given by the function Rhumb::Direct. + * + * Given \e lat1, \e lon1, \e lat2, and \e lon2, we can determine \e azi12 + * and \e s12. This is the \e inverse rhumb problem, whose solution is given + * by Rhumb::Inverse. This finds the shortest such rhumb line, i.e., the one + * that wraps no more than half way around the earth. If the end points are + * on opposite meridians, there are two shortest rhumb lines and the + * east-going one is chosen. + * + * These routines also optionally calculate the area under the rhumb line, \e + * S12. This is the area, measured counter-clockwise, of the rhumb line + * quadrilateral with corners (lat1,lon1), (0,lon1), + * (0,lon2), and (lat2,lon2). + * + * Note that rhumb lines may be appreciably longer (up to 50%) than the + * corresponding Geodesic. For example the distance between London Heathrow + * and Tokyo Narita via the rhumb line is 11400 km which is 18% longer than + * the geodesic distance 9600 km. + * + * For more information on rhumb lines see \ref rhumb. + * + * Example of use: + * \include example-Rhumb.cpp + **********************************************************************/ + + class GEOGRAPHICLIB_EXPORT Rhumb { + private: + typedef Math::real real; + friend class RhumbLine; + template friend class PolygonAreaT; + Ellipsoid _ell; + bool _exact; + real _c2; + static const int tm_maxord = GEOGRAPHICLIB_TRANSVERSEMERCATOR_ORDER; + static const int maxpow_ = GEOGRAPHICLIB_RHUMBAREA_ORDER; + // _R[0] unused + real _R[maxpow_ + 1]; + static real gd(real x) + { using std::atan; using std::sinh; return atan(sinh(x)); } + + // Use divided differences to determine (mu2 - mu1) / (psi2 - psi1) + // accurately + // + // Definition: Df(x,y,d) = (f(x) - f(y)) / (x - y) + // See: + // W. M. Kahan and R. J. Fateman, + // Symbolic computation of divided differences, + // SIGSAM Bull. 33(3), 7-28 (1999) + // https://doi.org/10.1145/334714.334716 + // http://www.cs.berkeley.edu/~fateman/papers/divdiff.pdf + + static real Dlog(real x, real y) { + real t = x - y; + return t != 0 ? 2 * Math::atanh(t / (x + y)) / t : 1 / x; + } + // N.B., x and y are in degrees + static real Dtan(real x, real y) { + real d = x - y, tx = Math::tand(x), ty = Math::tand(y), txy = tx * ty; + return d != 0 ? + (2 * txy > -1 ? (1 + txy) * Math::tand(d) : tx - ty) / + (d * Math::degree()) : + 1 + txy; + } + static real Datan(real x, real y) { + using std::atan; + real d = x - y, xy = x * y; + return d != 0 ? + (2 * xy > -1 ? atan( d / (1 + xy) ) : atan(x) - atan(y)) / d : + 1 / (1 + xy); + } + static real Dsin(real x, real y) { + using std::sin; using std::cos; + real d = (x - y) / 2; + return cos((x + y)/2) * (d != 0 ? sin(d) / d : 1); + } + static real Dsinh(real x, real y) { + using std::sinh; using std::cosh; + real d = (x - y) / 2; + return cosh((x + y) / 2) * (d != 0 ? sinh(d) / d : 1); + } + static real Dcosh(real x, real y) { + using std::sinh; + real d = (x - y) / 2; + return sinh((x + y) / 2) * (d != 0 ? sinh(d) / d : 1); + } + static real Dasinh(real x, real y) { + real d = x - y, + hx = Math::hypot(real(1), x), hy = Math::hypot(real(1), y); + return d != 0 ? Math::asinh(x*y > 0 ? d * (x + y) / (x*hy + y*hx) : + x*hy - y*hx) / d : + 1 / hx; + } + static real Dgd(real x, real y) { + using std::sinh; + return Datan(sinh(x), sinh(y)) * Dsinh(x, y); + } + // N.B., x and y are the tangents of the angles + static real Dgdinv(real x, real y) + { return Dasinh(x, y) / Datan(x, y); } + // Copied from LambertConformalConic... + // Deatanhe(x,y) = eatanhe((x-y)/(1-e^2*x*y))/(x-y) + real Deatanhe(real x, real y) const { + real t = x - y, d = 1 - _ell._e2 * x * y; + return t != 0 ? Math::eatanhe(t / d, _ell._es) / t : _ell._e2 / d; + } + // (E(x) - E(y)) / (x - y) -- E = incomplete elliptic integral of 2nd kind + real DE(real x, real y) const; + // (mux - muy) / (phix - phiy) using elliptic integrals + real DRectifying(real latx, real laty) const; + // (psix - psiy) / (phix - phiy) + real DIsometric(real latx, real laty) const; + + // (sum(c[j]*sin(2*j*x),j=1..n) - sum(c[j]*sin(2*j*x),j=1..n)) / (x - y) + static real SinCosSeries(bool sinp, + real x, real y, const real c[], int n); + // (mux - muy) / (chix - chiy) using Krueger's series + real DConformalToRectifying(real chix, real chiy) const; + // (chix - chiy) / (mux - muy) using Krueger's series + real DRectifyingToConformal(real mux, real muy) const; + + // (mux - muy) / (psix - psiy) + // N.B., psix and psiy are in degrees + real DIsometricToRectifying(real psix, real psiy) const; + // (psix - psiy) / (mux - muy) + real DRectifyingToIsometric(real mux, real muy) const; + + real MeanSinXi(real psi1, real psi2) const; + + // The following two functions (with lots of ignored arguments) mimic the + // interface to the corresponding Geodesic function. These are needed by + // PolygonAreaT. + void GenDirect(real lat1, real lon1, real azi12, + bool, real s12, unsigned outmask, + real& lat2, real& lon2, real&, real&, real&, real&, real&, + real& S12) const { + GenDirect(lat1, lon1, azi12, s12, outmask, lat2, lon2, S12); + } + void GenInverse(real lat1, real lon1, real lat2, real lon2, + unsigned outmask, real& s12, real& azi12, + real&, real& , real& , real& , real& S12) const { + GenInverse(lat1, lon1, lat2, lon2, outmask, s12, azi12, S12); + } + public: + + /** + * Bit masks for what calculations to do. They specify which results to + * return in the general routines Rhumb::GenDirect and Rhumb::GenInverse + * routines. RhumbLine::mask is a duplication of this enum. + **********************************************************************/ + enum mask { + /** + * No output. + * @hideinitializer + **********************************************************************/ + NONE = 0U, + /** + * Calculate latitude \e lat2. + * @hideinitializer + **********************************************************************/ + LATITUDE = 1U<<7, + /** + * Calculate longitude \e lon2. + * @hideinitializer + **********************************************************************/ + LONGITUDE = 1U<<8, + /** + * Calculate azimuth \e azi12. + * @hideinitializer + **********************************************************************/ + AZIMUTH = 1U<<9, + /** + * Calculate distance \e s12. + * @hideinitializer + **********************************************************************/ + DISTANCE = 1U<<10, + /** + * Calculate area \e S12. + * @hideinitializer + **********************************************************************/ + AREA = 1U<<14, + /** + * Unroll \e lon2 in the direct calculation. + * @hideinitializer + **********************************************************************/ + LONG_UNROLL = 1U<<15, + /** + * Calculate everything. (LONG_UNROLL is not included in this mask.) + * @hideinitializer + **********************************************************************/ + ALL = 0x7F80U, + }; + + /** + * Constructor for a ellipsoid with + * + * @param[in] a equatorial radius (meters). + * @param[in] f flattening of ellipsoid. Setting \e f = 0 gives a sphere. + * Negative \e f gives a prolate ellipsoid. + * @param[in] exact if true (the default) use an addition theorem for + * elliptic integrals to compute divided differences; otherwise use + * series expansion (accurate for |f| < 0.01). + * @exception GeographicErr if \e a or (1 − \e f) \e a is not + * positive. + * + * See \ref rhumb, for a detailed description of the \e exact parameter. + **********************************************************************/ + Rhumb(real a, real f, bool exact = true); + + /** + * Solve the direct rhumb problem returning also the area. + * + * @param[in] lat1 latitude of point 1 (degrees). + * @param[in] lon1 longitude of point 1 (degrees). + * @param[in] azi12 azimuth of the rhumb line (degrees). + * @param[in] s12 distance between point 1 and point 2 (meters); it can be + * negative. + * @param[out] lat2 latitude of point 2 (degrees). + * @param[out] lon2 longitude of point 2 (degrees). + * @param[out] S12 area under the rhumb line (meters2). + * + * \e lat1 should be in the range [−90°, 90°]. The value of + * \e lon2 returned is in the range [−180°, 180°]. + * + * If point 1 is a pole, the cosine of its latitude is taken to be + * 1/ε2 (where ε is 2-52). This + * position, which is extremely close to the actual pole, allows the + * calculation to be carried out in finite terms. If \e s12 is large + * enough that the rhumb line crosses a pole, the longitude of point 2 + * is indeterminate (a NaN is returned for \e lon2 and \e S12). + **********************************************************************/ + void Direct(real lat1, real lon1, real azi12, real s12, + real& lat2, real& lon2, real& S12) const { + GenDirect(lat1, lon1, azi12, s12, + LATITUDE | LONGITUDE | AREA, lat2, lon2, S12); + } + + /** + * Solve the direct rhumb problem without the area. + **********************************************************************/ + void Direct(real lat1, real lon1, real azi12, real s12, + real& lat2, real& lon2) const { + real t; + GenDirect(lat1, lon1, azi12, s12, LATITUDE | LONGITUDE, lat2, lon2, t); + } + + /** + * The general direct rhumb problem. Rhumb::Direct is defined in terms + * of this function. + * + * @param[in] lat1 latitude of point 1 (degrees). + * @param[in] lon1 longitude of point 1 (degrees). + * @param[in] azi12 azimuth of the rhumb line (degrees). + * @param[in] s12 distance between point 1 and point 2 (meters); it can be + * negative. + * @param[in] outmask a bitor'ed combination of Rhumb::mask values + * specifying which of the following parameters should be set. + * @param[out] lat2 latitude of point 2 (degrees). + * @param[out] lon2 longitude of point 2 (degrees). + * @param[out] S12 area under the rhumb line (meters2). + * + * The Rhumb::mask values possible for \e outmask are + * - \e outmask |= Rhumb::LATITUDE for the latitude \e lat2; + * - \e outmask |= Rhumb::LONGITUDE for the latitude \e lon2; + * - \e outmask |= Rhumb::AREA for the area \e S12; + * - \e outmask |= Rhumb::ALL for all of the above; + * - \e outmask |= Rhumb::LONG_UNROLL to unroll \e lon2 instead of wrapping + * it into the range [−180°, 180°]. + * . + * With the Rhumb::LONG_UNROLL bit set, the quantity \e lon2 − + * \e lon1 indicates how many times and in what sense the rhumb line + * encircles the ellipsoid. + **********************************************************************/ + void GenDirect(real lat1, real lon1, real azi12, real s12, + unsigned outmask, real& lat2, real& lon2, real& S12) const; + + /** + * Solve the inverse rhumb problem returning also the area. + * + * @param[in] lat1 latitude of point 1 (degrees). + * @param[in] lon1 longitude of point 1 (degrees). + * @param[in] lat2 latitude of point 2 (degrees). + * @param[in] lon2 longitude of point 2 (degrees). + * @param[out] s12 rhumb distance between point 1 and point 2 (meters). + * @param[out] azi12 azimuth of the rhumb line (degrees). + * @param[out] S12 area under the rhumb line (meters2). + * + * The shortest rhumb line is found. If the end points are on opposite + * meridians, there are two shortest rhumb lines and the east-going one is + * chosen. \e lat1 and \e lat2 should be in the range [−90°, + * 90°]. The value of \e azi12 returned is in the range + * [−180°, 180°]. + * + * If either point is a pole, the cosine of its latitude is taken to be + * 1/ε2 (where ε is 2-52). This + * position, which is extremely close to the actual pole, allows the + * calculation to be carried out in finite terms. + **********************************************************************/ + void Inverse(real lat1, real lon1, real lat2, real lon2, + real& s12, real& azi12, real& S12) const { + GenInverse(lat1, lon1, lat2, lon2, + DISTANCE | AZIMUTH | AREA, s12, azi12, S12); + } + + /** + * Solve the inverse rhumb problem without the area. + **********************************************************************/ + void Inverse(real lat1, real lon1, real lat2, real lon2, + real& s12, real& azi12) const { + real t; + GenInverse(lat1, lon1, lat2, lon2, DISTANCE | AZIMUTH, s12, azi12, t); + } + + /** + * The general inverse rhumb problem. Rhumb::Inverse is defined in terms + * of this function. + * + * @param[in] lat1 latitude of point 1 (degrees). + * @param[in] lon1 longitude of point 1 (degrees). + * @param[in] lat2 latitude of point 2 (degrees). + * @param[in] lon2 longitude of point 2 (degrees). + * @param[in] outmask a bitor'ed combination of Rhumb::mask values + * specifying which of the following parameters should be set. + * @param[out] s12 rhumb distance between point 1 and point 2 (meters). + * @param[out] azi12 azimuth of the rhumb line (degrees). + * @param[out] S12 area under the rhumb line (meters2). + * + * The Rhumb::mask values possible for \e outmask are + * - \e outmask |= Rhumb::DISTANCE for the latitude \e s12; + * - \e outmask |= Rhumb::AZIMUTH for the latitude \e azi12; + * - \e outmask |= Rhumb::AREA for the area \e S12; + * - \e outmask |= Rhumb::ALL for all of the above; + **********************************************************************/ + void GenInverse(real lat1, real lon1, real lat2, real lon2, + unsigned outmask, + real& s12, real& azi12, real& S12) const; + + /** + * Set up to compute several points on a single rhumb line. + * + * @param[in] lat1 latitude of point 1 (degrees). + * @param[in] lon1 longitude of point 1 (degrees). + * @param[in] azi12 azimuth of the rhumb line (degrees). + * @return a RhumbLine object. + * + * \e lat1 should be in the range [−90°, 90°]. + * + * If point 1 is a pole, the cosine of its latitude is taken to be + * 1/ε2 (where ε is 2-52). This + * position, which is extremely close to the actual pole, allows the + * calculation to be carried out in finite terms. + **********************************************************************/ + RhumbLine Line(real lat1, real lon1, real azi12) const; + + /** \name Inspector functions. + **********************************************************************/ + ///@{ + + /** + * @return \e a the equatorial radius of the ellipsoid (meters). This is + * the value used in the constructor. + **********************************************************************/ + Math::real MajorRadius() const { return _ell.MajorRadius(); } + + /** + * @return \e f the flattening of the ellipsoid. This is the + * value used in the constructor. + **********************************************************************/ + Math::real Flattening() const { return _ell.Flattening(); } + + Math::real EllipsoidArea() const { return _ell.Area(); } + + /** + * A global instantiation of Rhumb with the parameters for the WGS84 + * ellipsoid. + **********************************************************************/ + static const Rhumb& WGS84(); + }; + + /** + * \brief Find a sequence of points on a single rhumb line. + * + * RhumbLine facilitates the determination of a series of points on a single + * rhumb line. The starting point (\e lat1, \e lon1) and the azimuth \e + * azi12 are specified in the call to Rhumb::Line which returns a RhumbLine + * object. RhumbLine.Position returns the location of point 2 (and, + * optionally, the corresponding area, \e S12) a distance \e s12 along the + * rhumb line. + * + * There is no public constructor for this class. (Use Rhumb::Line to create + * an instance.) The Rhumb object used to create a RhumbLine must stay in + * scope as long as the RhumbLine. + * + * Example of use: + * \include example-RhumbLine.cpp + **********************************************************************/ + + class GEOGRAPHICLIB_EXPORT RhumbLine { + private: + typedef Math::real real; + friend class Rhumb; + const Rhumb& _rh; + bool _exact; + real _lat1, _lon1, _azi12, _salp, _calp, _mu1, _psi1, _r1; + RhumbLine& operator=(const RhumbLine&); // copy assignment not allowed + RhumbLine(const Rhumb& rh, real lat1, real lon1, real azi12, + bool exact); + public: + + /** + * This is a duplication of Rhumb::mask. + **********************************************************************/ + enum mask { + /** + * No output. + * @hideinitializer + **********************************************************************/ + NONE = Rhumb::NONE, + /** + * Calculate latitude \e lat2. + * @hideinitializer + **********************************************************************/ + LATITUDE = Rhumb::LATITUDE, + /** + * Calculate longitude \e lon2. + * @hideinitializer + **********************************************************************/ + LONGITUDE = Rhumb::LONGITUDE, + /** + * Calculate azimuth \e azi12. + * @hideinitializer + **********************************************************************/ + AZIMUTH = Rhumb::AZIMUTH, + /** + * Calculate distance \e s12. + * @hideinitializer + **********************************************************************/ + DISTANCE = Rhumb::DISTANCE, + /** + * Calculate area \e S12. + * @hideinitializer + **********************************************************************/ + AREA = Rhumb::AREA, + /** + * Unroll \e lon2 in the direct calculation. + * @hideinitializer + **********************************************************************/ + LONG_UNROLL = Rhumb::LONG_UNROLL, + /** + * Calculate everything. (LONG_UNROLL is not included in this mask.) + * @hideinitializer + **********************************************************************/ + ALL = Rhumb::ALL, + }; + + /** + * Compute the position of point 2 which is a distance \e s12 (meters) from + * point 1. The area is also computed. + * + * @param[in] s12 distance between point 1 and point 2 (meters); it can be + * negative. + * @param[out] lat2 latitude of point 2 (degrees). + * @param[out] lon2 longitude of point 2 (degrees). + * @param[out] S12 area under the rhumb line (meters2). + * + * The value of \e lon2 returned is in the range [−180°, + * 180°]. + * + * If \e s12 is large enough that the rhumb line crosses a pole, the + * longitude of point 2 is indeterminate (a NaN is returned for \e lon2 and + * \e S12). + **********************************************************************/ + void Position(real s12, real& lat2, real& lon2, real& S12) const { + GenPosition(s12, LATITUDE | LONGITUDE | AREA, lat2, lon2, S12); + } + + /** + * Compute the position of point 2 which is a distance \e s12 (meters) from + * point 1. The area is not computed. + **********************************************************************/ + void Position(real s12, real& lat2, real& lon2) const { + real t; + GenPosition(s12, LATITUDE | LONGITUDE, lat2, lon2, t); + } + + /** + * The general position routine. RhumbLine::Position is defined in term so + * this function. + * + * @param[in] s12 distance between point 1 and point 2 (meters); it can be + * negative. + * @param[in] outmask a bitor'ed combination of RhumbLine::mask values + * specifying which of the following parameters should be set. + * @param[out] lat2 latitude of point 2 (degrees). + * @param[out] lon2 longitude of point 2 (degrees). + * @param[out] S12 area under the rhumb line (meters2). + * + * The RhumbLine::mask values possible for \e outmask are + * - \e outmask |= RhumbLine::LATITUDE for the latitude \e lat2; + * - \e outmask |= RhumbLine::LONGITUDE for the latitude \e lon2; + * - \e outmask |= RhumbLine::AREA for the area \e S12; + * - \e outmask |= RhumbLine::ALL for all of the above; + * - \e outmask |= RhumbLine::LONG_UNROLL to unroll \e lon2 instead of + * wrapping it into the range [−180°, 180°]. + * . + * With the RhumbLine::LONG_UNROLL bit set, the quantity \e lon2 − \e + * lon1 indicates how many times and in what sense the rhumb line encircles + * the ellipsoid. + * + * If \e s12 is large enough that the rhumb line crosses a pole, the + * longitude of point 2 is indeterminate (a NaN is returned for \e lon2 and + * \e S12). + **********************************************************************/ + void GenPosition(real s12, unsigned outmask, + real& lat2, real& lon2, real& S12) const; + + /** \name Inspector functions + **********************************************************************/ + ///@{ + + /** + * @return \e lat1 the latitude of point 1 (degrees). + **********************************************************************/ + Math::real Latitude() const { return _lat1; } + + /** + * @return \e lon1 the longitude of point 1 (degrees). + **********************************************************************/ + Math::real Longitude() const { return _lon1; } + + /** + * @return \e azi12 the azimuth of the rhumb line (degrees). + **********************************************************************/ + Math::real Azimuth() const { return _azi12; } + + /** + * @return \e a the equatorial radius of the ellipsoid (meters). This is + * the value inherited from the Rhumb object used in the constructor. + **********************************************************************/ + Math::real MajorRadius() const { return _rh.MajorRadius(); } + + /** + * @return \e f the flattening of the ellipsoid. This is the value + * inherited from the Rhumb object used in the constructor. + **********************************************************************/ + Math::real Flattening() const { return _rh.Flattening(); } + }; + +} // namespace GeographicLib + +#endif // GEOGRAPHICLIB_RHUMB_HPP diff --git a/gtsam/3rdparty/GeographicLib/include/GeographicLib/SphericalEngine.hpp b/gtsam/3rdparty/GeographicLib/include/GeographicLib/SphericalEngine.hpp index 62b53c496..1c8465b82 100644 --- a/gtsam/3rdparty/GeographicLib/include/GeographicLib/SphericalEngine.hpp +++ b/gtsam/3rdparty/GeographicLib/include/GeographicLib/SphericalEngine.hpp @@ -2,9 +2,9 @@ * \file SphericalEngine.hpp * \brief Header for GeographicLib::SphericalEngine class * - * Copyright (c) Charles Karney (2011-2012) and licensed + * Copyright (c) Charles Karney (2011-2017) and licensed * under the MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #if !defined(GEOGRAPHICLIB_SPHERICALENGINE_HPP) @@ -40,15 +40,28 @@ namespace GeographicLib { class GEOGRAPHICLIB_EXPORT SphericalEngine { private: typedef Math::real real; - // A table of the square roots of integers - static std::vector root_; - friend class CircularEngine; // CircularEngine needs access to root_, scale_ + // CircularEngine needs access to sqrttable, scale + friend class CircularEngine; + // Return the table of the square roots of integers + static std::vector& sqrttable(); // An internal scaling of the coefficients to avoid overflow in // intermediate calculations. - static const real scale_; + static real scale() { + using std::pow; + static const real + // Need extra real because, since C++11, pow(float, int) returns double + s = real(pow(real(std::numeric_limits::radix), + -3 * (std::numeric_limits::max_exponent < (1<<14) ? + std::numeric_limits::max_exponent : (1<<14)) + / 5)); + return s; + } // Move latitudes near the pole off the axis by this amount. - static const real eps_; - static const std::vector Z_; + static real eps() { + using std::sqrt; + return std::numeric_limits::epsilon() * + sqrt(std::numeric_limits::epsilon()); + } SphericalEngine(); // Disable constructor public: /** @@ -69,11 +82,6 @@ namespace GeographicLib { * @hideinitializer **********************************************************************/ SCHMIDT = 1, - /// \cond SKIP - // These are deprecated... - full = FULL, - schmidt = SCHMIDT, - /// \endcond }; /** @@ -97,12 +105,7 @@ namespace GeographicLib { /** * A default constructor **********************************************************************/ - coeff() - : _Nx(-1) - , _nmx(-1) - , _mmx(-1) - , _Cnm(Z_.begin()) - , _Snm(Z_.begin()) {} + coeff() : _Nx(-1) , _nmx(-1) , _mmx(-1) {} /** * The general constructor. * @@ -165,15 +168,15 @@ namespace GeographicLib { /** * @return \e N the degree giving storage layout for \e C and \e S. **********************************************************************/ - inline int N() const throw() { return _Nx; } + int N() const { return _Nx; } /** * @return \e nmx the maximum degree to be used. **********************************************************************/ - inline int nmx() const throw() { return _nmx; } + int nmx() const { return _nmx; } /** * @return \e mmx the maximum order to be used. **********************************************************************/ - inline int mmx() const throw() { return _mmx; } + int mmx() const { return _mmx; } /** * The one-dimensional index into \e C and \e S. * @@ -181,7 +184,7 @@ namespace GeographicLib { * @param[in] m the order. * @return the one-dimensional index. **********************************************************************/ - inline int index(int n, int m) const throw() + int index(int n, int m) const { return m * _Nx - m * (m - 1) / 2 + n; } /** * An element of \e C. @@ -189,14 +192,14 @@ namespace GeographicLib { * @param[in] k the one-dimensional index. * @return the value of the \e C coefficient. **********************************************************************/ - inline Math::real Cv(int k) const { return *(_Cnm + k); } + Math::real Cv(int k) const { return *(_Cnm + k); } /** * An element of \e S. * * @param[in] k the one-dimensional index. * @return the value of the \e S coefficient. **********************************************************************/ - inline Math::real Sv(int k) const { return *(_Snm + (k - (_Nx + 1))); } + Math::real Sv(int k) const { return *(_Snm + (k - (_Nx + 1))); } /** * An element of \e C with checking. * @@ -207,7 +210,7 @@ namespace GeographicLib { * @return the value of the \e C coefficient multiplied by \e f in \e n * and \e m are in range else 0. **********************************************************************/ - inline Math::real Cv(int k, int n, int m, real f) const + Math::real Cv(int k, int n, int m, real f) const { return m > _mmx || n > _nmx ? 0 : *(_Cnm + k) * f; } /** * An element of \e S with checking. @@ -219,7 +222,7 @@ namespace GeographicLib { * @return the value of the \e S coefficient multiplied by \e f in \e n * and \e m are in range else 0. **********************************************************************/ - inline Math::real Sv(int k, int n, int m, real f) const + Math::real Sv(int k, int n, int m, real f) const { return m > _mmx || n > _nmx ? 0 : *(_Snm + (k - (_Nx + 1))) * f; } /** @@ -230,7 +233,7 @@ namespace GeographicLib { * @return the size of the vector of cosine terms as stored in column * major order. **********************************************************************/ - static inline int Csize(int N, int M) throw() + static int Csize(int N, int M) { return (M + 1) * (2 * N - M + 2) / 2; } /** @@ -241,7 +244,7 @@ namespace GeographicLib { * @return the size of the vector of cosine terms as stored in column * major order. **********************************************************************/ - static inline int Ssize(int N, int M) throw () + static int Ssize(int N, int M) { return Csize(N, M) - (N + 1); } /** @@ -301,7 +304,7 @@ namespace GeographicLib { template static Math::real Value(const coeff c[], const real f[], real x, real y, real z, real a, - real& gradx, real& grady, real& gradz) throw(); + real& gradx, real& grady, real& gradz); /** * Create a CircularEngine object @@ -354,12 +357,14 @@ namespace GeographicLib { * Clear the static table of square roots and release the memory. Call * this only when you are sure you no longer will be using SphericalEngine. * Your program will crash if you call SphericalEngine after calling this - * routine. It's safest not to call this routine at all. (The space - * used by the table is modest.) + * routine. + * + * \warning It's safest not to call this routine at all. (The space used + * by the table is modest.) **********************************************************************/ static void ClearRootTable() { std::vector temp(0); - root_.swap(temp); + sqrttable().swap(temp); } }; diff --git a/gtsam/3rdparty/GeographicLib/include/GeographicLib/SphericalHarmonic.hpp b/gtsam/3rdparty/GeographicLib/include/GeographicLib/SphericalHarmonic.hpp index a030c6927..f0a1e01fe 100644 --- a/gtsam/3rdparty/GeographicLib/include/GeographicLib/SphericalHarmonic.hpp +++ b/gtsam/3rdparty/GeographicLib/include/GeographicLib/SphericalHarmonic.hpp @@ -4,7 +4,7 @@ * * Copyright (c) Charles Karney (2011) and licensed under * the MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #if !defined(GEOGRAPHICLIB_SPHERICALHARMONIC_HPP) @@ -14,7 +14,6 @@ #include #include #include -#include namespace GeographicLib { @@ -32,10 +31,10 @@ namespace GeographicLib { * - \e q = a/r, * - θ = atan2(\e p, \e z) = the spherical \e colatitude, * - λ = atan2(\e y, \e x) = the longitude. - * - P\e nm(\e t) is the associated Legendre polynomial of degree - * \e n and order \e m. + * - Pnm(\e t) is the associated Legendre polynomial of + * degree \e n and order \e m. * - * Two normalizations are supported for P\e nm + * Two normalizations are supported for Pnm * - fully normalized denoted by SphericalHarmonic::FULL. * - Schmidt semi-normalized denoted by SphericalHarmonic::SCHMIDT. * @@ -45,18 +44,23 @@ namespace GeographicLib { * implementation. * * References: - * - C. W. Clenshaw, A note on the summation of Chebyshev series, + * - C. W. Clenshaw, + * + * A note on the summation of Chebyshev series, * %Math. Tables Aids Comput. 9(51), 118--120 (1955). * - R. E. Deakin, Derivatives of the earth's potentials, Geomatics * Research Australasia 68, 31--60, (June 1998). * - W. A. Heiskanen and H. Moritz, Physical Geodesy, (Freeman, San * Francisco, 1967). (See Sec. 1-14, for a definition of Pbar.) - * - S. A. Holmes and W. E. Featherstone, A unified approach to the Clenshaw - * summation and the recursive computation of very high degree and order - * normalised associated Legendre functions, J. Geodesy 76(5), - * 279--299 (2002). - * - C. C. Tscherning and K. Poder, Some geodetic applications of Clenshaw - * summation, Boll. Geod. Sci. Aff. 41(4), 349--375 (1982). + * - S. A. Holmes and W. E. Featherstone, + * + * A unified approach to the Clenshaw summation and the recursive + * computation of very high degree and order normalised associated Legendre + * functions, J. Geodesy 76(5), 279--299 (2002). + * - C. C. Tscherning and K. Poder, + * + * Some geodetic applications of Clenshaw summation, + * Boll. Geod. Sci. Aff. 41(4), 349--375 (1982). * * Example of use: * \include example-SphericalHarmonic.cpp @@ -71,9 +75,10 @@ namespace GeographicLib { /** * Fully normalized associated Legendre polynomials. * - * These are defined by Pnmfull(\e z) - * = (−1)m sqrt(\e k (2\e n + 1) (\e n − \e - * m)! / (\e n + \e m)!) + * These are defined by + * Pnmfull(\e z) + * = (−1)m + * sqrt(\e k (2\e n + 1) (\e n − \e m)! / (\e n + \e m)!) * Pnm(\e z), where * Pnm(\e z) is Ferrers * function (also known as the Legendre function on the cut or the @@ -92,10 +97,12 @@ namespace GeographicLib { /** * Schmidt semi-normalized associated Legendre polynomials. * - * These are defined by Pnmschmidt(\e - * z) = (−1)m sqrt(\e k (\e n − \e m)! / - * (\e n + \e m)!) Pnm(\e z), - * where Pnm(\e z) is Ferrers + * These are defined by + * Pnmschmidt(\e z) + * = (−1)m + * sqrt(\e k (\e n − \e m)! / (\e n + \e m)!) + * Pnm(\e z), where + * Pnm(\e z) is Ferrers * function (also known as the Legendre function on the cut or the * associated Legendre polynomial) http://dlmf.nist.gov/14.7.E10 and \e k * = 1 for \e m = 0 and \e k = 2 otherwise. @@ -109,11 +116,6 @@ namespace GeographicLib { * @hideinitializer **********************************************************************/ SCHMIDT = SphericalEngine::SCHMIDT, - /// \cond SKIP - // These are deprecated... - full = FULL, - schmidt = SCHMIDT, - /// \endcond }; private: @@ -126,22 +128,23 @@ namespace GeographicLib { /** * Constructor with a full set of coefficients specified. * - * @param[in] C the coefficients \e C\e nm. - * @param[in] S the coefficients \e S\e nm. + * @param[in] C the coefficients Cnm. + * @param[in] S the coefficients Snm. * @param[in] N the maximum degree and order of the sum * @param[in] a the reference radius appearing in the definition of the * sum. * @param[in] norm the normalization for the associated Legendre - * polynomials, either SphericalHarmonic::full (the default) or - * SphericalHarmonic::schmidt. + * polynomials, either SphericalHarmonic::FULL (the default) or + * SphericalHarmonic::SCHMIDT. * @exception GeographicErr if \e N does not satisfy \e N ≥ −1. * @exception GeographicErr if \e C or \e S is not big enough to hold the * coefficients. * - * The coefficients \e C\e nm and \e S\e nm are - * stored in the one-dimensional vectors \e C and \e S which must contain - * (\e N + 1)(\e N + 2)/2 and N (\e N + 1)/2 elements, respectively, stored - * in "column-major" order. Thus for \e N = 3, the order would be: + * The coefficients Cnm and + * Snm are stored in the one-dimensional vectors + * \e C and \e S which must contain (\e N + 1)(\e N + 2)/2 and \e N (\e N + + * 1)/2 elements, respectively, stored in "column-major" order. Thus for + * \e N = 3, the order would be: * C00, * C10, * C20, @@ -171,8 +174,8 @@ namespace GeographicLib { /** * Constructor with a subset of coefficients specified. * - * @param[in] C the coefficients \e C\e nm. - * @param[in] S the coefficients \e S\e nm. + * @param[in] C the coefficients Cnm. + * @param[in] S the coefficients Snm. * @param[in] N the degree used to determine the layout of \e C and \e S. * @param[in] nmx the maximum degree used in the sum. The sum over \e n is * from 0 thru \e nmx. @@ -218,7 +221,7 @@ namespace GeographicLib { * This routine requires constant memory and thus never throws an * exception. **********************************************************************/ - Math::real operator()(real x, real y, real z) const throw() { + Math::real operator()(real x, real y, real z) const { real f[] = {1}; real v = 0; real dummy; @@ -252,7 +255,7 @@ namespace GeographicLib { * an exception. **********************************************************************/ Math::real operator()(real x, real y, real z, - real& gradx, real& grady, real& gradz) const throw() { + real& gradx, real& grady, real& gradz) const { real f[] = {1}; real v = 0; switch (_norm) { @@ -281,8 +284,9 @@ namespace GeographicLib { * @return the CircularEngine object. * * SphericalHarmonic::operator()() exchanges the order of the sums in the - * definition, i.e., ∑n = 0..Nm = 0..n - * becomes ∑m = 0..Nn = m..N. + * definition, i.e., ∑n = 0..N + * ∑m = 0..n becomes ∑m = + * 0..Nn = m..N. * SphericalHarmonic::Circle performs the inner sum over degree \e n (which * entails about N2 operations). Calling * CircularEngine::operator()() on the returned object performs the outer @@ -341,7 +345,7 @@ namespace GeographicLib { /** * @return the zeroth SphericalEngine::coeff object. **********************************************************************/ - const SphericalEngine::coeff& Coefficients() const throw() + const SphericalEngine::coeff& Coefficients() const { return _c[0]; } }; diff --git a/gtsam/3rdparty/GeographicLib/include/GeographicLib/SphericalHarmonic1.hpp b/gtsam/3rdparty/GeographicLib/include/GeographicLib/SphericalHarmonic1.hpp index d46741bfe..543686eee 100644 --- a/gtsam/3rdparty/GeographicLib/include/GeographicLib/SphericalHarmonic1.hpp +++ b/gtsam/3rdparty/GeographicLib/include/GeographicLib/SphericalHarmonic1.hpp @@ -4,7 +4,7 @@ * * Copyright (c) Charles Karney (2011) and licensed under * the MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #if !defined(GEOGRAPHICLIB_SPHERICALHARMONIC1_HPP) @@ -21,8 +21,9 @@ namespace GeographicLib { * \brief Spherical harmonic series with a correction to the coefficients * * This classes is similar to SphericalHarmonic, except that the coefficients - * \e C\e nm are replaced by \e C\e nm + \e tau - * C'\e nm (and similarly for \e S\e nm). + * Cnm are replaced by + * Cnm + \e tau C'nm (and + * similarly for Snm). * * Example of use: * \include example-SphericalHarmonic1.cpp @@ -48,11 +49,6 @@ namespace GeographicLib { * @hideinitializer **********************************************************************/ SCHMIDT = SphericalEngine::SCHMIDT, - /// \cond SKIP - // These are deprecated... - full = FULL, - schmidt = SCHMIDT, - /// \endcond }; private: @@ -65,13 +61,14 @@ namespace GeographicLib { /** * Constructor with a full set of coefficients specified. * - * @param[in] C the coefficients \e C\e nm. - * @param[in] S the coefficients \e S\e nm. + * @param[in] C the coefficients Cnm. + * @param[in] S the coefficients Snm. * @param[in] N the maximum degree and order of the sum - * @param[in] C1 the coefficients \e C'\e nm. - * @param[in] S1 the coefficients \e S'\e nm. + * @param[in] C1 the coefficients C'nm. + * @param[in] S1 the coefficients S'nm. * @param[in] N1 the maximum degree and order of the correction - * coefficients \e C'\e nm and \e S'\e nm. + * coefficients C'nm and + * S'nm. * @param[in] a the reference radius appearing in the definition of the * sum. * @param[in] norm the normalization for the associated Legendre @@ -106,15 +103,15 @@ namespace GeographicLib { /** * Constructor with a subset of coefficients specified. * - * @param[in] C the coefficients \e C\e nm. - * @param[in] S the coefficients \e S\e nm. + * @param[in] C the coefficients Cnm. + * @param[in] S the coefficients Snm. * @param[in] N the degree used to determine the layout of \e C and \e S. * @param[in] nmx the maximum degree used in the sum. The sum over \e n is * from 0 thru \e nmx. * @param[in] mmx the maximum order used in the sum. The sum over \e m is * from 0 thru min(\e n, \e mmx). - * @param[in] C1 the coefficients \e C'\e nm. - * @param[in] S1 the coefficients \e S'\e nm. + * @param[in] C1 the coefficients C'nm. + * @param[in] S1 the coefficients S'nm. * @param[in] N1 the degree used to determine the layout of \e C' and \e * S'. * @param[in] nmx1 the maximum degree used for \e C' and \e S'. @@ -170,7 +167,7 @@ namespace GeographicLib { * This routine requires constant memory and thus never throws * an exception. **********************************************************************/ - Math::real operator()(real tau, real x, real y, real z) const throw() { + Math::real operator()(real tau, real x, real y, real z) const { real f[] = {1, tau}; real v = 0; real dummy; @@ -206,7 +203,7 @@ namespace GeographicLib { * an exception. **********************************************************************/ Math::real operator()(real tau, real x, real y, real z, - real& gradx, real& grady, real& gradz) const throw() { + real& gradx, real& grady, real& gradz) const { real f[] = {1, tau}; real v = 0; switch (_norm) { @@ -236,8 +233,9 @@ namespace GeographicLib { * @return the CircularEngine object. * * SphericalHarmonic1::operator()() exchanges the order of the sums in the - * definition, i.e., ∑n = 0..Nm = 0..n - * becomes ∑m = 0..Nn = m..N. + * definition, i.e., ∑n = 0..N + * ∑m = 0..n becomes ∑m = + * 0..Nn = m..N. * SphericalHarmonic1::Circle performs the inner sum over degree \e n * (which entails about N2 operations). Calling * CircularEngine::operator()() on the returned object performs the outer @@ -269,12 +267,12 @@ namespace GeographicLib { /** * @return the zeroth SphericalEngine::coeff object. **********************************************************************/ - const SphericalEngine::coeff& Coefficients() const throw() + const SphericalEngine::coeff& Coefficients() const { return _c[0]; } /** * @return the first SphericalEngine::coeff object. **********************************************************************/ - const SphericalEngine::coeff& Coefficients1() const throw() + const SphericalEngine::coeff& Coefficients1() const { return _c[1]; } }; diff --git a/gtsam/3rdparty/GeographicLib/include/GeographicLib/SphericalHarmonic2.hpp b/gtsam/3rdparty/GeographicLib/include/GeographicLib/SphericalHarmonic2.hpp index 7da1c53fe..9477dc63d 100644 --- a/gtsam/3rdparty/GeographicLib/include/GeographicLib/SphericalHarmonic2.hpp +++ b/gtsam/3rdparty/GeographicLib/include/GeographicLib/SphericalHarmonic2.hpp @@ -4,7 +4,7 @@ * * Copyright (c) Charles Karney (2011-2012) and licensed * under the MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #if !defined(GEOGRAPHICLIB_SPHERICALHARMONIC2_HPP) @@ -21,9 +21,10 @@ namespace GeographicLib { * \brief Spherical harmonic series with two corrections to the coefficients * * This classes is similar to SphericalHarmonic, except that the coefficients - * \e C\e nm are replaced by \e C\e nm + \e tau' - * C'\e nm + \e tau'' C''\e nm (and similarly for \e - * S\e nm). + * Cnm are replaced by + * Cnm + \e tau' C'nm + \e + * tau'' C''nm (and similarly for + * Snm). * * Example of use: * \include example-SphericalHarmonic2.cpp @@ -51,11 +52,6 @@ namespace GeographicLib { * @hideinitializer **********************************************************************/ SCHMIDT = SphericalEngine::SCHMIDT, - /// \cond SKIP - // These are deprecated... - full = FULL, - schmidt = SCHMIDT, - /// \endcond }; private: @@ -68,17 +64,19 @@ namespace GeographicLib { /** * Constructor with a full set of coefficients specified. * - * @param[in] C the coefficients \e C\e nm. - * @param[in] S the coefficients \e S\e nm. + * @param[in] C the coefficients Cnm. + * @param[in] S the coefficients Snm. * @param[in] N the maximum degree and order of the sum - * @param[in] C1 the coefficients \e C'\e nm. - * @param[in] S1 the coefficients \e S'\e nm. + * @param[in] C1 the coefficients C'nm. + * @param[in] S1 the coefficients S'nm. * @param[in] N1 the maximum degree and order of the first correction - * coefficients \e C'\e nm and \e S'\e nm. - * @param[in] C2 the coefficients \e C''\e nm. - * @param[in] S2 the coefficients \e S''\e nm. + * coefficients C'nm and + * S'nm. + * @param[in] C2 the coefficients C''nm. + * @param[in] S2 the coefficients S''nm. * @param[in] N2 the maximum degree and order of the second correction - * coefficients \e C'\e nm and \e S'\e nm. + * coefficients C'nm and + * S'nm. * @param[in] a the reference radius appearing in the definition of the * sum. * @param[in] norm the normalization for the associated Legendre @@ -118,21 +116,21 @@ namespace GeographicLib { /** * Constructor with a subset of coefficients specified. * - * @param[in] C the coefficients \e C\e nm. - * @param[in] S the coefficients \e S\e nm. + * @param[in] C the coefficients Cnm. + * @param[in] S the coefficients Snm. * @param[in] N the degree used to determine the layout of \e C and \e S. * @param[in] nmx the maximum degree used in the sum. The sum over \e n is * from 0 thru \e nmx. * @param[in] mmx the maximum order used in the sum. The sum over \e m is * from 0 thru min(\e n, \e mmx). - * @param[in] C1 the coefficients \e C'\e nm. - * @param[in] S1 the coefficients \e S'\e nm. + * @param[in] C1 the coefficients C'nm. + * @param[in] S1 the coefficients S'nm. * @param[in] N1 the degree used to determine the layout of \e C' and \e * S'. * @param[in] nmx1 the maximum degree used for \e C' and \e S'. * @param[in] mmx1 the maximum order used for \e C' and \e S'. - * @param[in] C2 the coefficients \e C''\e nm. - * @param[in] S2 the coefficients \e S''\e nm. + * @param[in] C2 the coefficients C''nm. + * @param[in] S2 the coefficients S''nm. * @param[in] N2 the degree used to determine the layout of \e C'' and \e * S''. * @param[in] nmx2 the maximum degree used for \e C'' and \e S''. @@ -185,7 +183,8 @@ namespace GeographicLib { * Compute a spherical harmonic sum with two correction terms. * * @param[in] tau1 multiplier for correction coefficients \e C' and \e S'. - * @param[in] tau2 multiplier for correction coefficients \e C'' and \e S''. + * @param[in] tau2 multiplier for correction coefficients \e C'' and \e + * S''. * @param[in] x cartesian coordinate. * @param[in] y cartesian coordinate. * @param[in] z cartesian coordinate. @@ -195,7 +194,7 @@ namespace GeographicLib { * exception. **********************************************************************/ Math::real operator()(real tau1, real tau2, real x, real y, real z) - const throw() { + const { real f[] = {1, tau1, tau2}; real v = 0; real dummy; @@ -217,7 +216,8 @@ namespace GeographicLib { * gradient. * * @param[in] tau1 multiplier for correction coefficients \e C' and \e S'. - * @param[in] tau2 multiplier for correction coefficients \e C'' and \e S''. + * @param[in] tau2 multiplier for correction coefficients \e C'' and \e + * S''. * @param[in] x cartesian coordinate. * @param[in] y cartesian coordinate. * @param[in] z cartesian coordinate. @@ -232,7 +232,7 @@ namespace GeographicLib { * an exception. **********************************************************************/ Math::real operator()(real tau1, real tau2, real x, real y, real z, - real& gradx, real& grady, real& gradz) const throw() { + real& gradx, real& grady, real& gradz) const { real f[] = {1, tau1, tau2}; real v = 0; switch (_norm) { @@ -253,7 +253,8 @@ namespace GeographicLib { * points on a circle of latitude at fixed values of \e tau1 and \e tau2. * * @param[in] tau1 multiplier for correction coefficients \e C' and \e S'. - * @param[in] tau2 multiplier for correction coefficients \e C'' and \e S''. + * @param[in] tau2 multiplier for correction coefficients \e C'' and \e + * S''. * @param[in] p the radius of the circle. * @param[in] z the height of the circle above the equatorial plane. * @param[in] gradp if true the returned object will be able to compute the @@ -263,8 +264,9 @@ namespace GeographicLib { * @return the CircularEngine object. * * SphericalHarmonic2::operator()() exchanges the order of the sums in the - * definition, i.e., ∑n = 0..Nm = 0..n - * becomes ∑m = 0..Nn = m..N.. + * definition, i.e., ∑n = 0..N + * ∑m = 0..n becomes ∑m = + * 0..Nn = m..N.. * SphericalHarmonic2::Circle performs the inner sum over degree \e n * (which entails about N2 operations). Calling * CircularEngine::operator()() on the returned object performs the outer @@ -297,17 +299,17 @@ namespace GeographicLib { /** * @return the zeroth SphericalEngine::coeff object. **********************************************************************/ - const SphericalEngine::coeff& Coefficients() const throw() + const SphericalEngine::coeff& Coefficients() const { return _c[0]; } /** * @return the first SphericalEngine::coeff object. **********************************************************************/ - const SphericalEngine::coeff& Coefficients1() const throw() + const SphericalEngine::coeff& Coefficients1() const { return _c[1]; } /** * @return the second SphericalEngine::coeff object. **********************************************************************/ - const SphericalEngine::coeff& Coefficients2() const throw() + const SphericalEngine::coeff& Coefficients2() const { return _c[2]; } }; diff --git a/gtsam/3rdparty/GeographicLib/include/GeographicLib/TransverseMercator.hpp b/gtsam/3rdparty/GeographicLib/include/GeographicLib/TransverseMercator.hpp index 7d8876d78..c0f6e743f 100644 --- a/gtsam/3rdparty/GeographicLib/include/GeographicLib/TransverseMercator.hpp +++ b/gtsam/3rdparty/GeographicLib/include/GeographicLib/TransverseMercator.hpp @@ -2,9 +2,9 @@ * \file TransverseMercator.hpp * \brief Header for GeographicLib::TransverseMercator class * - * Copyright (c) Charles Karney (2008-2011) and licensed + * Copyright (c) Charles Karney (2008-2016) and licensed * under the MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #if !defined(GEOGRAPHICLIB_TRANSVERSEMERCATOR_HPP) @@ -18,7 +18,8 @@ * GEOGRAPHICLIB_TRANSVERSEMERCATOR_ORDER can be set to any integer in [4, 8]. **********************************************************************/ # define GEOGRAPHICLIB_TRANSVERSEMERCATOR_ORDER \ - (GEOGRAPHICLIB_PRECISION == 2 ? 6 : (GEOGRAPHICLIB_PRECISION == 1 ? 4 : 8)) + (GEOGRAPHICLIB_PRECISION == 2 ? 6 : \ + (GEOGRAPHICLIB_PRECISION == 1 ? 4 : 8)) #endif namespace GeographicLib { @@ -29,24 +30,33 @@ namespace GeographicLib { * This uses Krüger's method which evaluates the projection and its * inverse in terms of a series. See * - L. Krüger, - * Konforme + * Konforme * Abbildung des Erdellipsoids in der Ebene (Conformal mapping of the * ellipsoidal earth to the plane), Royal Prussian Geodetic Institute, New * Series 52, 172 pp. (1912). * - C. F. F. Karney, - * + * * Transverse Mercator with an accuracy of a few nanometers, * J. Geodesy 85(8), 475--485 (Aug. 2011); * preprint - * arXiv:1002.1417. + * arXiv:1002.1417. * * Krüger's method has been extended from 4th to 6th order. The maximum * error is 5 nm (5 nanometers), ground distance, for all positions within 35 * degrees of the central meridian. The error in the convergence is 2 * × 10−15" and the relative error in the scale - * is 6 − 10−12%%. See Sec. 4 of - * arXiv:1002.1417 for details. + * is 6 × 10−12%%. See Sec. 4 of + * arXiv:1002.1417 for details. * The speed penalty in going to 6th order is only about 1%. + * + * There's a singularity in the projection at φ = 0°, λ + * − λ0 = ±(1 − \e e)90° (≈ + * ±82.6° for the WGS84 ellipsoid), where \e e is the + * eccentricity. Beyond this point, the series ceases to converge and the + * results from this method will be garbage. To be on the safe side, don't + * use this method if the angular distance from the central meridian exceeds + * (1 − 2e)90° (≈ 75° for the WGS84 ellipsoid) + * * TransverseMercatorExact is an alternative implementation of the projection * using exact formulas which yield accurate (to 8 nm) results over the * entire ellipsoid. @@ -64,6 +74,10 @@ namespace GeographicLib { * EPSG:7405) which requires the use of a latitude of origin. This is * implemented by the GeographicLib::OSGB class. * + * This class also returns the meridian convergence \e gamma and scale \e k. + * The meridian convergence is the bearing of grid north (the \e y axis) + * measured clockwise from true north. + * * See TransverseMercator.cpp for more information on the implementation. * * See \ref transversemercator for a discussion of this projection. @@ -80,25 +94,10 @@ namespace GeographicLib { private: typedef Math::real real; static const int maxpow_ = GEOGRAPHICLIB_TRANSVERSEMERCATOR_ORDER; - static const real tol_; - static const real overflow_; static const int numit_ = 5; - real _a, _f, _k0, _e2, _e, _e2m, _c, _n; + real _a, _f, _k0, _e2, _es, _e2m, _c, _n; // _alp[0] and _bet[0] unused real _a1, _b1, _alp[maxpow_ + 1], _bet[maxpow_ + 1]; - // tan(x) for x in [-pi/2, pi/2] ensuring that the sign is right - static inline real tanx(real x) throw() { - real t = std::tan(x); - // Write the tests this way to ensure that tanx(NaN()) is NaN() - return x >= 0 ? (!(t < 0) ? t : overflow_) : (!(t >= 0) ? t : -overflow_); - } - // Return e * atanh(e * x) for f >= 0, else return - // - sqrt(-e2) * atan( sqrt(-e2) * x) for f < 0 - inline real eatanhe(real x) const throw() - { return _f >= 0 ? _e * Math::atanh(_e * x) : - _e * std::atan(_e * x); } - real taupf(real tau) const throw(); - real tauf(real taup) const throw(); - friend class Ellipsoid; // For access to taupf, tauf. public: @@ -107,10 +106,9 @@ namespace GeographicLib { * * @param[in] a equatorial radius (meters). * @param[in] f flattening of ellipsoid. Setting \e f = 0 gives a sphere. - * Negative \e f gives a prolate ellipsoid. If \e f > 1, set flattening - * to 1/\e f. + * Negative \e f gives a prolate ellipsoid. * @param[in] k0 central scale factor. - * @exception GeographicErr if \e a, (1 − \e f ) \e a, or \e k0 is + * @exception GeographicErr if \e a, (1 − \e f) \e a, or \e k0 is * not positive. **********************************************************************/ TransverseMercator(real a, real f, real k0); @@ -127,11 +125,10 @@ namespace GeographicLib { * @param[out] k scale of projection at point. * * No false easting or northing is added. \e lat should be in the range - * [−90°, 90°]; \e lon and \e lon0 should be in the - * range [−540°, 540°). + * [−90°, 90°]. **********************************************************************/ void Forward(real lon0, real lat, real lon, - real& x, real& y, real& gamma, real& k) const throw(); + real& x, real& y, real& gamma, real& k) const; /** * Reverse projection, from transverse Mercator to geographic. @@ -144,18 +141,17 @@ namespace GeographicLib { * @param[out] gamma meridian convergence at point (degrees). * @param[out] k scale of projection at point. * - * No false easting or northing is added. \e lon0 should be in the range - * [−540°, 540°). The value of \e lon returned is in - * the range [−180°, 180°). + * No false easting or northing is added. The value of \e lon returned is + * in the range [−180°, 180°]. **********************************************************************/ void Reverse(real lon0, real x, real y, - real& lat, real& lon, real& gamma, real& k) const throw(); + real& lat, real& lon, real& gamma, real& k) const; /** * TransverseMercator::Forward without returning the convergence and scale. **********************************************************************/ void Forward(real lon0, real lat, real lon, - real& x, real& y) const throw() { + real& x, real& y) const { real gamma, k; Forward(lon0, lat, lon, x, y, gamma, k); } @@ -164,7 +160,7 @@ namespace GeographicLib { * TransverseMercator::Reverse without returning the convergence and scale. **********************************************************************/ void Reverse(real lon0, real x, real y, - real& lat, real& lon) const throw() { + real& lat, real& lon) const { real gamma, k; Reverse(lon0, x, y, lat, lon, gamma, k); } @@ -176,27 +172,19 @@ namespace GeographicLib { * @return \e a the equatorial radius of the ellipsoid (meters). This is * the value used in the constructor. **********************************************************************/ - Math::real MajorRadius() const throw() { return _a; } + Math::real MajorRadius() const { return _a; } /** * @return \e f the flattening of the ellipsoid. This is the value used in * the constructor. **********************************************************************/ - Math::real Flattening() const throw() { return _f; } - - /// \cond SKIP - /** - * DEPRECATED - * @return \e r the inverse flattening of the ellipsoid. - **********************************************************************/ - Math::real InverseFlattening() const throw() { return 1/_f; } - /// \endcond + Math::real Flattening() const { return _f; } /** * @return \e k0 central scale for the projection. This is the value of \e * k0 used in the constructor and is the scale on the central meridian. **********************************************************************/ - Math::real CentralScale() const throw() { return _k0; } + Math::real CentralScale() const { return _k0; } ///@} /** @@ -204,7 +192,7 @@ namespace GeographicLib { * and the UTM scale factor. However, unlike UTM, no false easting or * northing is added. **********************************************************************/ - static const TransverseMercator UTM; + static const TransverseMercator& UTM(); }; } // namespace GeographicLib diff --git a/gtsam/3rdparty/GeographicLib/include/GeographicLib/TransverseMercatorExact.hpp b/gtsam/3rdparty/GeographicLib/include/GeographicLib/TransverseMercatorExact.hpp index 2db9c412a..f9b4070b3 100644 --- a/gtsam/3rdparty/GeographicLib/include/GeographicLib/TransverseMercatorExact.hpp +++ b/gtsam/3rdparty/GeographicLib/include/GeographicLib/TransverseMercatorExact.hpp @@ -2,9 +2,9 @@ * \file TransverseMercatorExact.hpp * \brief Header for GeographicLib::TransverseMercatorExact class * - * Copyright (c) Charles Karney (2008-2011) and licensed + * Copyright (c) Charles Karney (2008-2016) and licensed * under the MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #if !defined(GEOGRAPHICLIB_TRANSVERSEMERCATOREXACT_HPP) @@ -20,7 +20,7 @@ namespace GeographicLib { * * Implementation of the Transverse Mercator Projection given in * - L. P. Lee, - * Conformal + * Conformal * Projections Based On Jacobian Elliptic Functions, Part V of * Conformal Projections Based on Elliptic Functions, * (B. V. Gutsell, Toronto, 1976), 128pp., @@ -28,11 +28,11 @@ namespace GeographicLib { * (also appeared as: * Monograph 16, Suppl. No. 1 to Canadian Cartographer, Vol 13). * - C. F. F. Karney, - * + * * Transverse Mercator with an accuracy of a few nanometers, * J. Geodesy 85(8), 475--485 (Aug. 2011); * preprint - * arXiv:1002.1417. + * arXiv:1002.1417. * * Lee gives the correct results for forward and reverse transformations * subject to the branch cut rules (see the description of the \e extendp @@ -41,7 +41,7 @@ namespace GeographicLib { * The error in the convergence is 2 × 10−15", * the relative error in the scale is 7 × 10−12%%. * See Sec. 3 of - * arXiv:1002.1417 for details. + * arXiv:1002.1417 for details. * The method is "exact" in the sense that the errors are close to the * round-off limit and that no changes are needed in the algorithms for them * to be used with reals of a higher precision. Thus the errors using long @@ -59,10 +59,14 @@ namespace GeographicLib { * taken to be the equator. See the documentation on TransverseMercator for * how to include a false easting, false northing, or a latitude of origin. * - * See tm-grid.kmz, for an * illustration of the transverse Mercator grid in Google Earth. * + * This class also returns the meridian convergence \e gamma and scale \e k. + * The meridian convergence is the bearing of grid north (the \e y axis) + * measured clockwise from true north. + * * See TransverseMercatorExact.cpp for more information on the * implementation. * @@ -79,51 +83,38 @@ namespace GeographicLib { class GEOGRAPHICLIB_EXPORT TransverseMercatorExact { private: typedef Math::real real; - static const real tol_; - static const real tol1_; - static const real tol2_; - static const real taytol_; - static const real overflow_; static const int numit_ = 10; + real tol_, tol2_, taytol_; real _a, _f, _k0, _mu, _mv, _e; bool _extendp; EllipticFunction _Eu, _Ev; - // tan(x) for x in [-pi/2, pi/2] ensuring that the sign is right - static inline real tanx(real x) throw() { - real t = std::tan(x); - // Write the tests this way to ensure that tanx(NaN()) is NaN() - return x >= 0 ? (!(t < 0) ? t : overflow_) : (!(t >= 0) ? t : -overflow_); - } - - real taup(real tau) const throw(); - real taupinv(real taup) const throw(); void zeta(real u, real snu, real cnu, real dnu, real v, real snv, real cnv, real dnv, - real& taup, real& lam) const throw(); + real& taup, real& lam) const; void dwdzeta(real u, real snu, real cnu, real dnu, real v, real snv, real cnv, real dnv, - real& du, real& dv) const throw(); + real& du, real& dv) const; - bool zetainv0(real psi, real lam, real& u, real& v) const throw(); - void zetainv(real taup, real lam, real& u, real& v) const throw(); + bool zetainv0(real psi, real lam, real& u, real& v) const; + void zetainv(real taup, real lam, real& u, real& v) const; void sigma(real u, real snu, real cnu, real dnu, real v, real snv, real cnv, real dnv, - real& xi, real& eta) const throw(); + real& xi, real& eta) const; void dwdsigma(real u, real snu, real cnu, real dnu, real v, real snv, real cnv, real dnv, - real& du, real& dv) const throw(); + real& du, real& dv) const; - bool sigmainv0(real xi, real eta, real& u, real& v) const throw(); - void sigmainv(real xi, real eta, real& u, real& v) const throw(); + bool sigmainv0(real xi, real eta, real& u, real& v) const; + void sigmainv(real xi, real eta, real& u, real& v) const; void Scale(real tau, real lam, real snu, real cnu, real dnu, real snv, real cnv, real dnv, - real& gamma, real& k) const throw(); + real& gamma, real& k) const; public: @@ -131,8 +122,7 @@ namespace GeographicLib { * Constructor for a ellipsoid with * * @param[in] a equatorial radius (meters). - * @param[in] f flattening of ellipsoid. If \e f > 1, set flattening - * to 1/\e f. + * @param[in] f flattening of ellipsoid. * @param[in] k0 central scale factor. * @param[in] extendp use extended domain. * @exception GeographicErr if \e a, \e f, or \e k0 is not positive. @@ -167,7 +157,7 @@ namespace GeographicLib { * a) in (−∞, 0] * . * See Sec. 5 of - * arXiv:1002.1417 for a full + * arXiv:1002.1417 for a full * discussion of the treatment of the branch cut. * * The method will work for all ellipsoids used in terrestrial geodesy. @@ -191,11 +181,10 @@ namespace GeographicLib { * @param[out] k scale of projection at point. * * No false easting or northing is added. \e lat should be in the range - * [−90°, 90°]; \e lon and \e lon0 should be in the - * range [−540°, 540°). + * [−90°, 90°]. **********************************************************************/ void Forward(real lon0, real lat, real lon, - real& x, real& y, real& gamma, real& k) const throw(); + real& x, real& y, real& gamma, real& k) const; /** * Reverse projection, from transverse Mercator to geographic. @@ -208,19 +197,18 @@ namespace GeographicLib { * @param[out] gamma meridian convergence at point (degrees). * @param[out] k scale of projection at point. * - * No false easting or northing is added. \e lon0 should be in the range - * [−540°, 540°). The value of \e lon returned is in - * the range [−180°, 180°). + * No false easting or northing is added. The value of \e lon returned is + * in the range [−180°, 180°]. **********************************************************************/ void Reverse(real lon0, real x, real y, - real& lat, real& lon, real& gamma, real& k) const throw(); + real& lat, real& lon, real& gamma, real& k) const; /** * TransverseMercatorExact::Forward without returning the convergence and * scale. **********************************************************************/ void Forward(real lon0, real lat, real lon, - real& x, real& y) const throw() { + real& x, real& y) const { real gamma, k; Forward(lon0, lat, lon, x, y, gamma, k); } @@ -230,7 +218,7 @@ namespace GeographicLib { * scale. **********************************************************************/ void Reverse(real lon0, real x, real y, - real& lat, real& lon) const throw() { + real& lat, real& lon) const { real gamma, k; Reverse(lon0, x, y, lat, lon, gamma, k); } @@ -242,27 +230,19 @@ namespace GeographicLib { * @return \e a the equatorial radius of the ellipsoid (meters). This is * the value used in the constructor. **********************************************************************/ - Math::real MajorRadius() const throw() { return _a; } + Math::real MajorRadius() const { return _a; } /** * @return \e f the flattening of the ellipsoid. This is the value used in * the constructor. **********************************************************************/ - Math::real Flattening() const throw() { return _f; } - - /// \cond SKIP - /** - * DEPRECATED - * @return \e r the inverse flattening of the ellipsoid. - **********************************************************************/ - Math::real InverseFlattening() const throw() { return 1/_f; } - /// \endcond + Math::real Flattening() const { return _f; } /** * @return \e k0 central scale for the projection. This is the value of \e * k0 used in the constructor and is the scale on the central meridian. **********************************************************************/ - Math::real CentralScale() const throw() { return _k0; } + Math::real CentralScale() const { return _k0; } ///@} /** @@ -270,7 +250,7 @@ namespace GeographicLib { * ellipsoid and the UTM scale factor. However, unlike UTM, no false * easting or northing is added. **********************************************************************/ - static const TransverseMercatorExact UTM; + static const TransverseMercatorExact& UTM(); }; } // namespace GeographicLib diff --git a/gtsam/3rdparty/GeographicLib/include/GeographicLib/UTMUPS.hpp b/gtsam/3rdparty/GeographicLib/include/GeographicLib/UTMUPS.hpp index 9fc19c66e..b662d3e82 100644 --- a/gtsam/3rdparty/GeographicLib/include/GeographicLib/UTMUPS.hpp +++ b/gtsam/3rdparty/GeographicLib/include/GeographicLib/UTMUPS.hpp @@ -2,9 +2,9 @@ * \file UTMUPS.hpp * \brief Header for GeographicLib::UTMUPS class * - * Copyright (c) Charles Karney (2008-2011) and licensed + * Copyright (c) Charles Karney (2008-2015) and licensed * under the MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #if !defined(GEOGRAPHICLIB_UTMUPS_HPP) @@ -29,6 +29,10 @@ namespace GeographicLib { * transverse Mercator and polar stereographic projections. Here we * substitute much more accurate algorithms given by * GeographicLib:TransverseMercator and GeographicLib:PolarStereographic. + * These are the algorithms recommended by the NGA document + * - + * The Universal Grids and the Transverse Mercator and Polar Stereographic + * Map Projections, NGA.SIG.0012_2.0.0_UTMUPS (2014). * * In this implementation, the conversions are closed, i.e., output from * Forward is legal input for Reverse and vice versa. The error is about 5nm @@ -55,27 +59,36 @@ namespace GeographicLib { * UPS coordinate is legal. A more systematic approach is taken here. * - The underlying projections are not very accurately implemented. * + * The GeographicLib::UTMUPS::EncodeZone encodes the UTM zone and hemisphere + * to allow UTM/UPS coordinated to be displayed as, for example, "38N 444500 + * 3688500". According to NGA.SIG.0012_2.0.0_UTMUPS the use of "N" to denote + * "north" in the context is not allowed (since a upper case letter in this + * context denotes the MGRS latitude band). Consequently, as of version + * 1.36, EncodeZone uses the lower case letters "n" and "s" to denote the + * hemisphere. In addition EncodeZone accepts an optional final argument \e + * abbrev, which, if false, results in the hemisphere being spelled out as in + * "38north". + * * Example of use: * \include example-UTMUPS.cpp **********************************************************************/ class GEOGRAPHICLIB_EXPORT UTMUPS { private: typedef Math::real real; - static const real falseeasting_[4]; - static const real falsenorthing_[4]; - static const real mineasting_[4]; - static const real maxeasting_[4]; - static const real minnorthing_[4]; - static const real maxnorthing_[4]; + static const int falseeasting_[4]; + static const int falsenorthing_[4]; + static const int mineasting_[4]; + static const int maxeasting_[4]; + static const int minnorthing_[4]; + static const int maxnorthing_[4]; static const int epsg01N = 32601; // EPSG code for UTM 01N static const int epsg60N = 32660; // EPSG code for UTM 60N static const int epsgN = 32661; // EPSG code for UPS N static const int epsg01S = 32701; // EPSG code for UTM 01S static const int epsg60S = 32760; // EPSG code for UTM 60S static const int epsgS = 32761; // EPSG code for UPS S - static real CentralMeridian(int zone) throw() + static real CentralMeridian(int zone) { return real(6 * zone - 183); } - static void CheckLatLon(real lat, real lon); // Throw an error if easting or northing are outside standard ranges. If // throwp = false, return bool instead. static bool CheckCoords(bool utmp, bool northp, real x, real y, @@ -181,8 +194,6 @@ namespace GeographicLib { * coordinates (default = false). * @exception GeographicErr if \e lat is not in [−90°, * 90°]. - * @exception GeographicErr if \e lon is not in [−540°, - * 540°). * @exception GeographicErr if the resulting \e x or \e y is out of allowed * range (see Reverse); in this case, these arguments are unchanged. * @@ -237,7 +248,7 @@ namespace GeographicLib { * [900km, 19600km] for the "southern" hemisphere. * * UPS eastings and northings are allowed to be in the range [1200km, - * 2800km] in the northern hemisphere and in [700km, 3100km] in the + * 2800km] in the northern hemisphere and in [700km, 3300km] in the * southern hemisphere. * * These ranges are 100km larger than allowed for the conversions to MGRS. @@ -318,20 +329,24 @@ namespace GeographicLib { * * For UTM, \e zonestr has the form of a zone number in the range * [UTMUPS::MINUTMZONE, UTMUPS::MAXUTMZONE] = [1, 60] followed by a - * hemisphere letter, N or S. For UPS, it consists just of the hemisphere - * letter. The returned value of \e zone is UTMUPS::UPS = 0 for UPS. Note - * well that "38S" indicates the southern hemisphere of zone 38 and not - * latitude band S, [32, 40]. N, 01S, 2N, 38S are legal. 0N, 001S, 61N, - * 38P are illegal. INV is a special value for which the returned value of - * \e is UTMUPS::INVALID. + * hemisphere letter, n or s (or "north" or "south" spelled out). For UPS, + * it consists just of the hemisphere letter (or the spelled out + * hemisphere). The returned value of \e zone is UTMUPS::UPS = 0 for UPS. + * Note well that "38s" indicates the southern hemisphere of zone 38 and + * not latitude band S, 32° ≤ \e lat < 40°. n, 01s, 2n, 38s, + * south, 3north are legal. 0n, 001s, +3n, 61n, 38P are illegal. INV is a + * special value for which the returned value of \e is UTMUPS::INVALID. **********************************************************************/ - static void DecodeZone(const std::string& zonestr, int& zone, bool& northp); + static void DecodeZone(const std::string& zonestr, + int& zone, bool& northp); /** * Encode a UTM/UPS zone string. * * @param[in] zone the UTM zone (zero means UPS). * @param[in] northp hemisphere (true means north, false means south). + * @param[in] abbrev if true (the default) use abbreviated (n/s) notation + * for hemisphere; otherwise spell out the hemisphere (north/south) * @exception GeographicErr if \e zone is out of range (see below). * @exception std::bad_alloc if memoy for the string can't be allocated. * @return string representation of zone and hemisphere. @@ -339,10 +354,10 @@ namespace GeographicLib { * \e zone must be in the range [UTMUPS::MINZONE, UTMUPS::MAXZONE] = [0, * 60] with \e zone = UTMUPS::UPS, 0, indicating UPS (but the resulting * string does not contain "0"). \e zone may also be UTMUPS::INVALID, in - * which case the returned string is "INV". This reverses + * which case the returned string is "inv". This reverses * UTMUPS::DecodeZone. **********************************************************************/ - static std::string EncodeZone(int zone, bool northp); + static std::string EncodeZone(int zone, bool northp, bool abbrev = true); /** * Decode EPSG. @@ -357,7 +372,7 @@ namespace GeographicLib { * of these projections, \e zone is set to UTMUPS::INVALID. See * http://spatialreference.org/ref/epsg/ **********************************************************************/ - static void DecodeEPSG(int epsg, int& zone, bool& northp) throw(); + static void DecodeEPSG(int epsg, int& zone, bool& northp); /** * Encode zone as EPSG. @@ -370,13 +385,13 @@ namespace GeographicLib { * Convert \e zone and \e northp to the corresponding EPSG (European * Petroleum Survery Group) codes **********************************************************************/ - static int EncodeEPSG(int zone, bool northp) throw(); + static int EncodeEPSG(int zone, bool northp); /** - * @return shift (meters) necessary to align N and S halves of a UTM zone - * (107). + * @return shift (meters) necessary to align north and south halves of a + * UTM zone (107). **********************************************************************/ - static Math::real UTMShift() throw(); + static Math::real UTMShift(); /** \name Inspector functions **********************************************************************/ @@ -387,8 +402,8 @@ namespace GeographicLib { * (The WGS84 value is returned because the UTM and UPS projections are * based on this ellipsoid.) **********************************************************************/ - static Math::real MajorRadius() throw() - { return Constants::WGS84_a(); } + static Math::real MajorRadius() + { return Constants::WGS84_a(); } /** * @return \e f the flattening of the WGS84 ellipsoid. @@ -396,18 +411,10 @@ namespace GeographicLib { * (The WGS84 value is returned because the UTM and UPS projections are * based on this ellipsoid.) **********************************************************************/ - static Math::real Flattening() throw() - { return Constants::WGS84_f(); } + static Math::real Flattening() + { return Constants::WGS84_f(); } ///@} - /// \cond SKIP - /** - * DEPRECATED - * @return \e r the inverse flattening of the WGS84 ellipsoid. - **********************************************************************/ - static Math::real InverseFlattening() throw() - { return 1/Constants::WGS84_f(); } - /// \endcond }; } // namespace GeographicLib diff --git a/gtsam/3rdparty/GeographicLib/include/GeographicLib/Utility.hpp b/gtsam/3rdparty/GeographicLib/include/GeographicLib/Utility.hpp index dfe3e5e01..9990e47e9 100644 --- a/gtsam/3rdparty/GeographicLib/include/GeographicLib/Utility.hpp +++ b/gtsam/3rdparty/GeographicLib/include/GeographicLib/Utility.hpp @@ -2,9 +2,9 @@ * \file Utility.hpp * \brief Header for GeographicLib::Utility class * - * Copyright (c) Charles Karney (2011-2012) and licensed + * Copyright (c) Charles Karney (2011-2017) and licensed * under the MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ #if !defined(GEOGRAPHICLIB_UTILITY_HPP) @@ -15,11 +15,13 @@ #include #include #include +#include +#include #if defined(_MSC_VER) -// Squelch warnings about constant conditional expressions +// Squelch warnings about constant conditional expressions and unsafe gmtime # pragma warning (push) -# pragma warning (disable: 4127) +# pragma warning (disable: 4127 4996) #endif namespace GeographicLib { @@ -55,7 +57,7 @@ namespace GeographicLib { * @param[in] d the day of the month (must be positive). Default = 1. * @return the sequential day number. **********************************************************************/ - static int day(int y, int m = 1, int d = 1) throw() { + static int day(int y, int m = 1, int d = 1) { // Convert from date to sequential day and vice versa // // Here is some code to convert a date to sequential day and vice @@ -98,8 +100,8 @@ namespace GeographicLib { (1461 * y) / 4 // Julian years converted to days. Julian year is 365 + // 1/4 = 1461/4 days. // Gregorian leap year corrections. The 2 offset with respect to the - // Julian calendar synchronizes the vernal equinox with that at the time - // of the Council of Nicea (325 AD). + // Julian calendar synchronizes the vernal equinox with that at the + // time of the Council of Nicea (325 AD). + (greg ? (y / 100) / 4 - (y / 100) + 2 : 0) + (153 * m + 2) / 5 // The zero-based start of the m'th month + d - 1 // The zero-based day @@ -141,7 +143,7 @@ namespace GeographicLib { * @param[out] m the month, Jan = 1, etc. * @param[out] d the day of the month. **********************************************************************/ - static void date(int s, int& y, int& m, int& d) throw() { + static void date(int s, int& y, int& m, int& d) { int c = 0; bool greg = gregorian(s); s += 305; // s = 0 on March 1, 1BC @@ -165,7 +167,8 @@ namespace GeographicLib { /** * Given a date as a string in the format yyyy, yyyy-mm, or yyyy-mm-dd, * return the numeric values for the year, month, and day. No checking is - * done on these values. + * done on these values. The string "now" is interpreted as the present + * date (in UTC). * * @param[in] s the date in string format. * @param[out] y the year. @@ -174,31 +177,39 @@ namespace GeographicLib { * @exception GeographicErr is \e s is malformed. **********************************************************************/ static void date(const std::string& s, int& y, int& m, int& d) { + if (s == "now") { + std::time_t t = std::time(0); + struct tm* now = gmtime(&t); + y = now->tm_year + 1900; + m = now->tm_mon + 1; + d = now->tm_mday; + return; + } int y1, m1 = 1, d1 = 1; const char* digits = "0123456789"; std::string::size_type p1 = s.find_first_not_of(digits); if (p1 == std::string::npos) - y1 = num(s); + y1 = val(s); else if (s[p1] != '-') throw GeographicErr("Delimiter not hyphen in date " + s); else if (p1 == 0) throw GeographicErr("Empty year field in date " + s); else { - y1 = num(s.substr(0, p1)); + y1 = val(s.substr(0, p1)); if (++p1 == s.size()) throw GeographicErr("Empty month field in date " + s); std::string::size_type p2 = s.find_first_not_of(digits, p1); if (p2 == std::string::npos) - m1 = num(s.substr(p1)); + m1 = val(s.substr(p1)); else if (s[p2] != '-') throw GeographicErr("Delimiter not hyphen in date " + s); else if (p2 == p1) throw GeographicErr("Empty month field in date " + s); else { - m1 = num(s.substr(p1, p2 - p1)); + m1 = val(s.substr(p1, p2 - p1)); if (++p2 == s.size()) throw GeographicErr("Empty day field in date " + s); - d1 = num(s.substr(p2)); + d1 = val(s.substr(p2)); } } y = y1; m = m1; d = d1; @@ -213,7 +224,7 @@ namespace GeographicLib { * @return the day of the week with Sunday, Monday--Saturday = 0, * 1--6. **********************************************************************/ - static int dow(int y, int m, int d) throw() { return dow(day(y, m, d)); } + static int dow(int y, int m, int d) { return dow(day(y, m, d)); } /** * Given the sequential day, return the day of the week. @@ -222,7 +233,7 @@ namespace GeographicLib { * @return the day of the week with Sunday, Monday--Saturday = 0, * 1--6. **********************************************************************/ - static int dow(int s) throw() { + static int dow(int s) { return (s + 5) % 7; // The 5 offset makes day 1 (0001-01-01) a Saturday. } @@ -241,10 +252,9 @@ namespace GeographicLib { **********************************************************************/ template static T fractionalyear(const std::string& s) { try { - return num(s); - } - catch (const std::exception&) { + return val(s); } + catch (const std::exception&) {} int y, m, d; date(s, y, m, d); int t = day(y, m, d, true); @@ -264,58 +274,137 @@ namespace GeographicLib { * precision. With p < 0, there is no manipulation of the format. **********************************************************************/ template static std::string str(T x, int p = -1) { - if (!std::numeric_limits::is_integer && !Math::isfinite(x)) - return x < 0 ? std::string("-inf") : - (x > 0 ? std::string("inf") : std::string("nan")); std::ostringstream s; if (p >= 0) s << std::fixed << std::setprecision(p); s << x; return s.str(); } /** - * Convert a string to an object of type T. + * Convert a Math::real object to a string. + * + * @param[in] x the value to be converted. + * @param[in] p the precision used (default −1). + * @exception std::bad_alloc if memory for the string can't be allocated. + * @return the string representation. + * + * If \e p ≥ 0, then the number fixed format is used with p bits of + * precision. With p < 0, there is no manipulation of the format. This is + * an overload of str which deals with inf and nan. + **********************************************************************/ + static std::string str(Math::real x, int p = -1) { + if (!Math::isfinite(x)) + return x < 0 ? std::string("-inf") : + (x > 0 ? std::string("inf") : std::string("nan")); + std::ostringstream s; +#if GEOGRAPHICLIB_PRECISION == 4 + // boost-quadmath treats precision == 0 as "use as many digits as + // necessary" (see https://svn.boost.org/trac/boost/ticket/10103), so... + using std::floor; using std::fmod; + if (p == 0) { + x += Math::real(0.5); + Math::real ix = floor(x); + // Implement the "round ties to even" rule + x = (ix == x && fmod(ix, Math::real(2)) == 1) ? ix - 1 : ix; + s << std::fixed << std::setprecision(1) << x; + std::string r(s.str()); + // strip off trailing ".0" + return r.substr(0, (std::max)(int(r.size()) - 2, 0)); + } +#endif + if (p >= 0) s << std::fixed << std::setprecision(p); + s << x; return s.str(); + } + + /** + * Trim the white space from the beginning and end of a string. + * + * @param[in] s the string to be trimmed + * @return the trimmed string + **********************************************************************/ + static std::string trim(const std::string& s) { + unsigned + beg = 0, + end = unsigned(s.size()); + while (beg < end && isspace(s[beg])) + ++beg; + while (beg < end && isspace(s[end - 1])) + --end; + return std::string(s, beg, end-beg); + } + + /** + * Convert a string to type T. * * @tparam T the type of the return value. * @param[in] s the string to be converted. * @exception GeographicErr is \e s is not readable as a T. - * @return object of type T + * @return object of type T. + * + * White space at the beginning and end of \e s is ignored. + * + * Special handling is provided for some types. + * + * If T is a floating point type, then inf and nan are recognized. + * + * If T is bool, then \e s should either be string a representing 0 (false) + * or 1 (true) or one of the strings + * - "false", "f", "nil", "no", "n", "off", or "" meaning false, + * - "true", "t", "yes", "y", or "on" meaning true; + * . + * case is ignored. + * + * If T is std::string, then \e s is returned (with the white space at the + * beginning and end removed). **********************************************************************/ - template static T num(const std::string& s) { + template static T val(const std::string& s) { + // If T is bool, then the specialization val() defined below is + // used. T x; - std::string errmsg; + std::string errmsg, t(trim(s)); do { // Executed once (provides the ability to break) - std::istringstream is(s); + std::istringstream is(t); if (!(is >> x)) { - errmsg = "Cannot decode " + s; + errmsg = "Cannot decode " + t; break; } int pos = int(is.tellg()); // Returns -1 at end of string? - if (!(pos < 0 || pos == int(s.size()))) { - errmsg = "Extra text " + s.substr(pos) + " at end of " + s; + if (!(pos < 0 || pos == int(t.size()))) { + errmsg = "Extra text " + t.substr(pos) + " at end of " + t; break; } return x; } while (false); - x = std::numeric_limits::is_integer ? 0 : nummatch(s); + x = std::numeric_limits::is_integer ? 0 : nummatch(t); if (x == 0) throw GeographicErr(errmsg); return x; } + /** + * \deprecated An old name for val(s). + **********************************************************************/ + template + // GEOGRAPHICLIB_DEPRECATED("Use new Utility::val(s)") + static T num(const std::string& s) { + return val(s); + } /** * Match "nan" and "inf" (and variants thereof) in a string. * - * @tparam T the type of the return value. + * @tparam T the type of the return value (this should be a floating point + * type). * @param[in] s the string to be matched. * @return appropriate special value (±∞, nan) or 0 if none is * found. + * + * White space is not allowed at the beginning or end of \e s. **********************************************************************/ template static T nummatch(const std::string& s) { if (s.length() < 3) return 0; - std::string t; - t.resize(s.length()); - std::transform(s.begin(), s.end(), t.begin(), (int(*)(int))std::toupper); + std::string t(s); + for (std::string::iterator p = t.begin(); p != t.end(); ++p) + *p = char(std::toupper(*p)); for (size_t i = s.length(); i--;) t[i] = char(std::toupper(s[i])); int sign = t[0] == '-' ? -1 : 1; @@ -338,16 +427,22 @@ namespace GeographicLib { * * @tparam T the type of the return value. * @param[in] s the string to be converted. - * @exception GeographicErr is \e s is not readable as a fraction of type T. + * @exception GeographicErr is \e s is not readable as a fraction of type + * T. * @return object of type T + * + * \note The msys shell under Windows converts arguments which look + * like pathnames into their Windows equivalents. As a result the argument + * "-1/300" gets mangled into something unrecognizable. A workaround is to + * use a floating point number in the numerator, i.e., "-1.0/300". **********************************************************************/ template static T fract(const std::string& s) { std::string::size_type delim = s.find('/'); return !(delim != std::string::npos && delim >= 1 && delim + 2 <= s.size()) ? - num(s) : + val(s) : // delim in [1, size() - 2] - num(s.substr(0, delim)) / num(s.substr(delim + 1)); + val(s.substr(0, delim)) / val(s.substr(delim + 1)); } /** @@ -361,11 +456,27 @@ namespace GeographicLib { * \e c is converted to upper case before search \e s. Therefore, it is * intended that \e s should not contain any lower case letters. **********************************************************************/ - static int lookup(const std::string& s, char c) throw() { + static int lookup(const std::string& s, char c) { std::string::size_type r = s.find(char(toupper(c))); return r == std::string::npos ? -1 : int(r); } + /** + * Lookup up a character in a char*. + * + * @param[in] s the char* string to be searched. + * @param[in] c the character to look for. + * @return the index of the first occurrence character in the string or + * −1 is the character is not present. + * + * \e c is converted to upper case before search \e s. Therefore, it is + * intended that \e s should not contain any lower case letters. + **********************************************************************/ + static int lookup(const char* s, char c) { + const char* p = std::strchr(s, toupper(c)); + return p != NULL ? int(p - s) : -1; + } + /** * Read data of type ExtT from a binary stream to an array of type IntT. * The data in the file is in (bigendp ? big : little)-endian format. @@ -380,36 +491,40 @@ namespace GeographicLib { * @exception GeographicErr if the data cannot be read. **********************************************************************/ template - static inline void readarray(std::istream& str, - IntT array[], size_t num) { + static void readarray(std::istream& str, IntT array[], size_t num) { +#if GEOGRAPHICLIB_PRECISION < 4 if (sizeof(IntT) == sizeof(ExtT) && std::numeric_limits::is_integer == - std::numeric_limits::is_integer) { - // Data is compatible (aside from the issue of endian-ness). - str.read(reinterpret_cast(array), num * sizeof(ExtT)); - if (!str.good()) - throw GeographicErr("Failure reading data"); - if (bigendp != Math::bigendian) { // endian mismatch -> swap bytes - for (size_t i = num; i--;) - array[i] = Math::swab(array[i]); - } - } else { - const int bufsize = 1024; // read this many values at a time - ExtT buffer[bufsize]; // temporary buffer - int k = int(num); // data values left to read - int i = 0; // index into output array - while (k) { - int n = (std::min)(k, bufsize); - str.read(reinterpret_cast(buffer), n * sizeof(ExtT)); + std::numeric_limits::is_integer) + { + // Data is compatible (aside from the issue of endian-ness). + str.read(reinterpret_cast(array), num * sizeof(ExtT)); if (!str.good()) throw GeographicErr("Failure reading data"); - for (int j = 0; j < n; ++j) - // fix endian-ness and cast to IntT - array[i++] = IntT(bigendp == Math::bigendian ? buffer[j] : - Math::swab(buffer[j])); - k -= n; + if (bigendp != Math::bigendian) { // endian mismatch -> swap bytes + for (size_t i = num; i--;) + array[i] = Math::swab(array[i]); + } + } + else +#endif + { + const int bufsize = 1024; // read this many values at a time + ExtT buffer[bufsize]; // temporary buffer + int k = int(num); // data values left to read + int i = 0; // index into output array + while (k) { + int n = (std::min)(k, bufsize); + str.read(reinterpret_cast(buffer), n * sizeof(ExtT)); + if (!str.good()) + throw GeographicErr("Failure reading data"); + for (int j = 0; j < n; ++j) + // fix endian-ness and cast to IntT + array[i++] = IntT(bigendp == Math::bigendian ? buffer[j] : + Math::swab(buffer[j])); + k -= n; + } } - } return; } @@ -427,9 +542,9 @@ namespace GeographicLib { * @exception GeographicErr if the data cannot be read. **********************************************************************/ template - static inline void readarray(std::istream& str, - std::vector& array) { - readarray(str, &array[0], array.size()); + static void readarray(std::istream& str, std::vector& array) { + if (array.size() > 0) + readarray(str, &array[0], array.size()); } /** @@ -445,33 +560,38 @@ namespace GeographicLib { * @exception GeographicErr if the data cannot be written. **********************************************************************/ template - static inline void writearray(std::ostream& str, - const IntT array[], size_t num) { + static void writearray(std::ostream& str, const IntT array[], size_t num) + { +#if GEOGRAPHICLIB_PRECISION < 4 if (sizeof(IntT) == sizeof(ExtT) && std::numeric_limits::is_integer == std::numeric_limits::is_integer && - bigendp == Math::bigendian) { - // Data is compatible (including endian-ness). - str.write(reinterpret_cast(array), num * sizeof(ExtT)); - if (!str.good()) - throw GeographicErr("Failure writing data"); - } else { - const int bufsize = 1024; // write this many values at a time - ExtT buffer[bufsize]; // temporary buffer - int k = int(num); // data values left to write - int i = 0; // index into output array - while (k) { - int n = (std::min)(k, bufsize); - for (int j = 0; j < n; ++j) - // cast to ExtT and fix endian-ness - buffer[j] = bigendp == Math::bigendian ? ExtT(array[i++]) : - Math::swab(ExtT(array[i++])); - str.write(reinterpret_cast(buffer), n * sizeof(ExtT)); + bigendp == Math::bigendian) + { + // Data is compatible (including endian-ness). + str.write(reinterpret_cast(array), num * sizeof(ExtT)); if (!str.good()) throw GeographicErr("Failure writing data"); - k -= n; } - } + else +#endif + { + const int bufsize = 1024; // write this many values at a time + ExtT buffer[bufsize]; // temporary buffer + int k = int(num); // data values left to write + int i = 0; // index into output array + while (k) { + int n = (std::min)(k, bufsize); + for (int j = 0; j < n; ++j) + // cast to ExtT and fix endian-ness + buffer[j] = bigendp == Math::bigendian ? ExtT(array[i++]) : + Math::swab(ExtT(array[i++])); + str.write(reinterpret_cast(buffer), n * sizeof(ExtT)); + if (!str.good()) + throw GeographicErr("Failure writing data"); + k -= n; + } + } return; } @@ -487,9 +607,9 @@ namespace GeographicLib { * @exception GeographicErr if the data cannot be written. **********************************************************************/ template - static inline void writearray(std::ostream& str, - std::vector& array) { - writearray(str, &array[0], array.size()); + static void writearray(std::ostream& str, std::vector& array) { + if (array.size() > 0) + writearray(str, &array[0], array.size()); } /** @@ -502,7 +622,7 @@ namespace GeographicLib { * allocated. * @return whether a key was found. * - * A # character and everything after it are discarded. If the results is + * A # character and everything after it are discarded. If the result is * just white space, the routine returns false (and \e key and \e val are * not set). Otherwise the first token is taken to be the key and the rest * of the line (trimmed of leading and trailing white space) is the value. @@ -510,8 +630,71 @@ namespace GeographicLib { static bool ParseLine(const std::string& line, std::string& key, std::string& val); + /** + * Set the binary precision of a real number. + * + * @param[in] ndigits the number of bits of precision. If ndigits is 0 + * (the default), then determine the precision from the environment + * variable GEOGRAPHICLIB_DIGITS. If this is undefined, use ndigits = + * 256 (i.e., about 77 decimal digits). + * @return the resulting number of bits of precision. + * + * This only has an effect when GEOGRAPHICLIB_PRECISION = 5. The + * precision should only be set once and before calls to any other + * GeographicLib functions. (Several functions, for example Math::pi(), + * cache the return value in a static local variable. The precision needs + * to be set before a call to any such functions.) In multi-threaded + * applications, it is necessary also to set the precision in each thread + * (see the example GeoidToGTX.cpp). + **********************************************************************/ + static int set_digits(int ndigits = 0); + }; + /** + * The specialization of Utility::val() for strings. + **********************************************************************/ + template<> inline std::string Utility::val(const std::string& s) + { return trim(s); } + + /** + * The specialization of Utility::val() for bools. + **********************************************************************/ + template<> inline bool Utility::val(const std::string& s) { + std::string t(trim(s)); + if (t.empty()) return false; + bool x; + std::istringstream is(t); + if (is >> x) { + int pos = int(is.tellg()); // Returns -1 at end of string? + if (!(pos < 0 || pos == int(t.size()))) + throw GeographicErr("Extra text " + t.substr(pos) + + " at end of " + t); + return x; + } + for (std::string::iterator p = t.begin(); p != t.end(); ++p) + *p = char(std::tolower(*p)); + switch (t[0]) { // already checked that t isn't empty + case 'f': + if (t == "f" || t == "false") return false; + break; + case 'n': + if (t == "n" || t == "nil" || t == "no") return false; + break; + case 'o': + if (t == "off") return false; + else if (t == "on") return true; + break; + case 't': + if (t == "t" || t == "true") return true; + break; + case 'y': + if (t == "y" || t == "yes") return true; + break; + } + throw GeographicErr("Cannot decode " + t + " as a bool"); + } + } // namespace GeographicLib #if defined(_MSC_VER) diff --git a/gtsam/3rdparty/GeographicLib/include/Makefile.am b/gtsam/3rdparty/GeographicLib/include/Makefile.am index 83988a446..369ca95aa 100644 --- a/gtsam/3rdparty/GeographicLib/include/Makefile.am +++ b/gtsam/3rdparty/GeographicLib/include/Makefile.am @@ -12,6 +12,7 @@ nobase_include_HEADERS = GeographicLib/Accumulator.hpp \ GeographicLib/DMS.hpp \ GeographicLib/Ellipsoid.hpp \ GeographicLib/EllipticFunction.hpp \ + GeographicLib/GARS.hpp \ GeographicLib/GeoCoords.hpp \ GeographicLib/Geocentric.hpp \ GeographicLib/Geodesic.hpp \ @@ -20,6 +21,7 @@ nobase_include_HEADERS = GeographicLib/Accumulator.hpp \ GeographicLib/GeodesicLineExact.hpp \ GeographicLib/Geohash.hpp \ GeographicLib/Geoid.hpp \ + GeographicLib/Georef.hpp \ GeographicLib/Gnomonic.hpp \ GeographicLib/GravityCircle.hpp \ GeographicLib/GravityModel.hpp \ @@ -29,10 +31,12 @@ nobase_include_HEADERS = GeographicLib/Accumulator.hpp \ GeographicLib/MagneticCircle.hpp \ GeographicLib/MagneticModel.hpp \ GeographicLib/Math.hpp \ + GeographicLib/NearestNeighbor.hpp \ GeographicLib/NormalGravity.hpp \ GeographicLib/OSGB.hpp \ GeographicLib/PolarStereographic.hpp \ GeographicLib/PolygonArea.hpp \ + GeographicLib/Rhumb.hpp \ GeographicLib/SphericalEngine.hpp \ GeographicLib/SphericalHarmonic.hpp \ GeographicLib/SphericalHarmonic1.hpp \ diff --git a/gtsam/3rdparty/GeographicLib/include/Makefile.in b/gtsam/3rdparty/GeographicLib/include/Makefile.in index 8a926b19b..58c97589b 100644 --- a/gtsam/3rdparty/GeographicLib/include/Makefile.in +++ b/gtsam/3rdparty/GeographicLib/include/Makefile.in @@ -1,7 +1,7 @@ -# Makefile.in generated by automake 1.12.2 from Makefile.am. +# Makefile.in generated by automake 1.15 from Makefile.am. # @configure_input@ -# Copyright (C) 1994-2012 Free Software Foundation, Inc. +# Copyright (C) 1994-2014 Free Software Foundation, Inc. # This Makefile.in is free software; the Free Software Foundation # gives unlimited permission to copy and/or distribute it, @@ -20,23 +20,61 @@ # Copyright (C) 2009, Francesco P. Lovergine VPATH = @srcdir@ -am__make_dryrun = \ - { \ - am__dry=no; \ +am__is_gnu_make = { \ + if test -z '$(MAKELEVEL)'; then \ + false; \ + elif test -n '$(MAKE_HOST)'; then \ + true; \ + elif test -n '$(MAKE_VERSION)' && test -n '$(CURDIR)'; then \ + true; \ + else \ + false; \ + fi; \ +} +am__make_running_with_option = \ + case $${target_option-} in \ + ?) ;; \ + *) echo "am__make_running_with_option: internal error: invalid" \ + "target option '$${target_option-}' specified" >&2; \ + exit 1;; \ + esac; \ + has_opt=no; \ + sane_makeflags=$$MAKEFLAGS; \ + if $(am__is_gnu_make); then \ + sane_makeflags=$$MFLAGS; \ + else \ case $$MAKEFLAGS in \ *\\[\ \ ]*) \ - echo 'am--echo: ; @echo "AM" OK' | $(MAKE) -f - 2>/dev/null \ - | grep '^AM OK$$' >/dev/null || am__dry=yes;; \ - *) \ - for am__flg in $$MAKEFLAGS; do \ - case $$am__flg in \ - *=*|--*) ;; \ - *n*) am__dry=yes; break;; \ - esac; \ - done;; \ + bs=\\; \ + sane_makeflags=`printf '%s\n' "$$MAKEFLAGS" \ + | sed "s/$$bs$$bs[$$bs $$bs ]*//g"`;; \ esac; \ - test $$am__dry = yes; \ - } + fi; \ + skip_next=no; \ + strip_trailopt () \ + { \ + flg=`printf '%s\n' "$$flg" | sed "s/$$1.*$$//"`; \ + }; \ + for flg in $$sane_makeflags; do \ + test $$skip_next = yes && { skip_next=no; continue; }; \ + case $$flg in \ + *=*|--*) continue;; \ + -*I) strip_trailopt 'I'; skip_next=yes;; \ + -*I?*) strip_trailopt 'I';; \ + -*O) strip_trailopt 'O'; skip_next=yes;; \ + -*O?*) strip_trailopt 'O';; \ + -*l) strip_trailopt 'l'; skip_next=yes;; \ + -*l?*) strip_trailopt 'l';; \ + -[dEDm]) skip_next=yes;; \ + -[JT]) skip_next=yes;; \ + esac; \ + case $$flg in \ + *$$target_option*) has_opt=yes; break;; \ + esac; \ + done; \ + test $$has_opt = yes +am__make_dryrun = (target_option=n; $(am__make_running_with_option)) +am__make_keepgoing = (target_option=k; $(am__make_running_with_option)) pkgdatadir = $(datadir)/@PACKAGE@ pkgincludedir = $(includedir)/@PACKAGE@ pkglibdir = $(libdir)/@PACKAGE@ @@ -57,19 +95,31 @@ build_triplet = @build@ host_triplet = @host@ target_triplet = @target@ subdir = include -DIST_COMMON = $(nobase_include_HEADERS) $(srcdir)/Makefile.am \ - $(srcdir)/Makefile.in ACLOCAL_M4 = $(top_srcdir)/aclocal.m4 am__aclocal_m4_deps = $(top_srcdir)/m4/libtool.m4 \ $(top_srcdir)/m4/ltoptions.m4 $(top_srcdir)/m4/ltsugar.m4 \ $(top_srcdir)/m4/ltversion.m4 $(top_srcdir)/m4/lt~obsolete.m4 \ - $(top_srcdir)/configure.ac + $(top_srcdir)/m4/pkg.m4 $(top_srcdir)/configure.ac am__configure_deps = $(am__aclocal_m4_deps) $(CONFIGURE_DEPENDENCIES) \ $(ACLOCAL_M4) +DIST_COMMON = $(srcdir)/Makefile.am $(nobase_include_HEADERS) \ + $(am__DIST_COMMON) mkinstalldirs = $(install_sh) -d CONFIG_HEADER = $(top_builddir)/include/GeographicLib/Config-ac.h CONFIG_CLEAN_FILES = CONFIG_CLEAN_VPATH_FILES = +AM_V_P = $(am__v_P_@AM_V@) +am__v_P_ = $(am__v_P_@AM_DEFAULT_V@) +am__v_P_0 = false +am__v_P_1 = : +AM_V_GEN = $(am__v_GEN_@AM_V@) +am__v_GEN_ = $(am__v_GEN_@AM_DEFAULT_V@) +am__v_GEN_0 = @echo " GEN " $@; +am__v_GEN_1 = +AM_V_at = $(am__v_at_@AM_V@) +am__v_at_ = $(am__v_at_@AM_DEFAULT_V@) +am__v_at_0 = @ +am__v_at_1 = SOURCES = DIST_SOURCES = am__can_run_installinfo = \ @@ -106,11 +156,30 @@ am__uninstall_files_from_dir = { \ } am__installdirs = "$(DESTDIR)$(includedir)" HEADERS = $(nobase_include_HEADERS) +am__tagged_files = $(HEADERS) $(SOURCES) $(TAGS_FILES) $(LISP) +# Read a list of newline-separated strings from the standard input, +# and print each of them once, without duplicates. Input order is +# *not* preserved. +am__uniquify_input = $(AWK) '\ + BEGIN { nonempty = 0; } \ + { items[$$0] = 1; nonempty = 1; } \ + END { if (nonempty) { for (i in items) print i; }; } \ +' +# Make sure the list of sources is unique. This is necessary because, +# e.g., the same source file might be shared among _SOURCES variables +# for different programs/libraries. +am__define_uniq_tagged_files = \ + list='$(am__tagged_files)'; \ + unique=`for i in $$list; do \ + if test -f "$$i"; then echo $$i; else echo $(srcdir)/$$i; fi; \ + done | $(am__uniquify_input)` ETAGS = etags CTAGS = ctags +am__DIST_COMMON = $(srcdir)/Makefile.in DISTFILES = $(DIST_COMMON) $(DIST_SOURCES) $(TEXINFOS) $(EXTRA_DIST) ACLOCAL = @ACLOCAL@ AMTAR = @AMTAR@ +AM_DEFAULT_VERBOSITY = @AM_DEFAULT_VERBOSITY@ AR = @AR@ AUTOCONF = @AUTOCONF@ AUTOHEADER = @AUTOHEADER@ @@ -159,6 +228,7 @@ LTLIBOBJS = @LTLIBOBJS@ LT_AGE = @LT_AGE@ LT_CURRENT = @LT_CURRENT@ LT_REVISION = @LT_REVISION@ +LT_SYS_LIBRARY_PATH = @LT_SYS_LIBRARY_PATH@ MAINT = @MAINT@ MAKEINFO = @MAKEINFO@ MANIFEST_TOOL = @MANIFEST_TOOL@ @@ -177,9 +247,11 @@ PACKAGE_TARNAME = @PACKAGE_TARNAME@ PACKAGE_URL = @PACKAGE_URL@ PACKAGE_VERSION = @PACKAGE_VERSION@ PATH_SEPARATOR = @PATH_SEPARATOR@ +PKG_CONFIG = @PKG_CONFIG@ +PKG_CONFIG_LIBDIR = @PKG_CONFIG_LIBDIR@ +PKG_CONFIG_PATH = @PKG_CONFIG_PATH@ POD2HTML = @POD2HTML@ POD2MAN = @POD2MAN@ -POW_LIB = @POW_LIB@ RANLIB = @RANLIB@ SED = @SED@ SET_MAKE = @SET_MAKE@ @@ -228,6 +300,7 @@ mandir = @mandir@ mkdir_p = @mkdir_p@ oldincludedir = @oldincludedir@ pdfdir = @pdfdir@ +pkgconfigdir = @pkgconfigdir@ prefix = @prefix@ program_transform_name = @program_transform_name@ psdir = @psdir@ @@ -252,6 +325,7 @@ nobase_include_HEADERS = GeographicLib/Accumulator.hpp \ GeographicLib/DMS.hpp \ GeographicLib/Ellipsoid.hpp \ GeographicLib/EllipticFunction.hpp \ + GeographicLib/GARS.hpp \ GeographicLib/GeoCoords.hpp \ GeographicLib/Geocentric.hpp \ GeographicLib/Geodesic.hpp \ @@ -260,6 +334,7 @@ nobase_include_HEADERS = GeographicLib/Accumulator.hpp \ GeographicLib/GeodesicLineExact.hpp \ GeographicLib/Geohash.hpp \ GeographicLib/Geoid.hpp \ + GeographicLib/Georef.hpp \ GeographicLib/Gnomonic.hpp \ GeographicLib/GravityCircle.hpp \ GeographicLib/GravityModel.hpp \ @@ -269,10 +344,12 @@ nobase_include_HEADERS = GeographicLib/Accumulator.hpp \ GeographicLib/MagneticCircle.hpp \ GeographicLib/MagneticModel.hpp \ GeographicLib/Math.hpp \ + GeographicLib/NearestNeighbor.hpp \ GeographicLib/NormalGravity.hpp \ GeographicLib/OSGB.hpp \ GeographicLib/PolarStereographic.hpp \ GeographicLib/PolygonArea.hpp \ + GeographicLib/Rhumb.hpp \ GeographicLib/SphericalEngine.hpp \ GeographicLib/SphericalHarmonic.hpp \ GeographicLib/SphericalHarmonic1.hpp \ @@ -300,7 +377,6 @@ $(srcdir)/Makefile.in: @MAINTAINER_MODE_TRUE@ $(srcdir)/Makefile.am $(am__confi echo ' cd $(top_srcdir) && $(AUTOMAKE) --gnu include/Makefile'; \ $(am__cd) $(top_srcdir) && \ $(AUTOMAKE) --gnu include/Makefile -.PRECIOUS: Makefile Makefile: $(srcdir)/Makefile.in $(top_builddir)/config.status @case '$?' in \ *config.status*) \ @@ -349,26 +425,15 @@ uninstall-nobase_includeHEADERS: $(am__nobase_strip_setup); files=`$(am__nobase_strip)`; \ dir='$(DESTDIR)$(includedir)'; $(am__uninstall_files_from_dir) -ID: $(HEADERS) $(SOURCES) $(LISP) $(TAGS_FILES) - list='$(SOURCES) $(HEADERS) $(LISP) $(TAGS_FILES)'; \ - unique=`for i in $$list; do \ - if test -f "$$i"; then echo $$i; else echo $(srcdir)/$$i; fi; \ - done | \ - $(AWK) '{ files[$$0] = 1; nonempty = 1; } \ - END { if (nonempty) { for (i in files) print i; }; }'`; \ - mkid -fID $$unique -tags: TAGS +ID: $(am__tagged_files) + $(am__define_uniq_tagged_files); mkid -fID $$unique +tags: tags-am +TAGS: tags -TAGS: $(HEADERS) $(SOURCES) $(TAGS_DEPENDENCIES) \ - $(TAGS_FILES) $(LISP) +tags-am: $(TAGS_DEPENDENCIES) $(am__tagged_files) set x; \ here=`pwd`; \ - list='$(SOURCES) $(HEADERS) $(LISP) $(TAGS_FILES)'; \ - unique=`for i in $$list; do \ - if test -f "$$i"; then echo $$i; else echo $(srcdir)/$$i; fi; \ - done | \ - $(AWK) '{ files[$$0] = 1; nonempty = 1; } \ - END { if (nonempty) { for (i in files) print i; }; }'`; \ + $(am__define_uniq_tagged_files); \ shift; \ if test -z "$(ETAGS_ARGS)$$*$$unique"; then :; else \ test -n "$$unique" || unique=$$empty_fix; \ @@ -380,15 +445,11 @@ TAGS: $(HEADERS) $(SOURCES) $(TAGS_DEPENDENCIES) \ $$unique; \ fi; \ fi -ctags: CTAGS -CTAGS: $(HEADERS) $(SOURCES) $(TAGS_DEPENDENCIES) \ - $(TAGS_FILES) $(LISP) - list='$(SOURCES) $(HEADERS) $(LISP) $(TAGS_FILES)'; \ - unique=`for i in $$list; do \ - if test -f "$$i"; then echo $$i; else echo $(srcdir)/$$i; fi; \ - done | \ - $(AWK) '{ files[$$0] = 1; nonempty = 1; } \ - END { if (nonempty) { for (i in files) print i; }; }'`; \ +ctags: ctags-am + +CTAGS: ctags +ctags-am: $(TAGS_DEPENDENCIES) $(am__tagged_files) + $(am__define_uniq_tagged_files); \ test -z "$(CTAGS_ARGS)$$unique" \ || $(CTAGS) $(CTAGSFLAGS) $(AM_CTAGSFLAGS) $(CTAGS_ARGS) \ $$unique @@ -397,9 +458,10 @@ GTAGS: here=`$(am__cd) $(top_builddir) && pwd` \ && $(am__cd) $(top_srcdir) \ && gtags -i $(GTAGS_ARGS) "$$here" +cscopelist: cscopelist-am -cscopelist: $(HEADERS) $(SOURCES) $(LISP) - list='$(SOURCES) $(HEADERS) $(LISP)'; \ +cscopelist-am: $(am__tagged_files) + list='$(am__tagged_files)'; \ case "$(srcdir)" in \ [\\/]* | ?:[\\/]*) sdir="$(srcdir)" ;; \ *) sdir=$(subdir)/$(srcdir) ;; \ @@ -550,18 +612,21 @@ uninstall-am: uninstall-nobase_includeHEADERS .MAKE: install-am install-strip -.PHONY: CTAGS GTAGS all all-am check check-am clean clean-generic \ - clean-libtool cscopelist ctags distclean distclean-generic \ - distclean-libtool distclean-tags distdir dvi dvi-am html \ - html-am info info-am install install-am install-data \ - install-data-am install-dvi install-dvi-am install-exec \ - install-exec-am install-html install-html-am install-info \ - install-info-am install-man install-nobase_includeHEADERS \ - install-pdf install-pdf-am install-ps install-ps-am \ - install-strip installcheck installcheck-am installdirs \ - maintainer-clean maintainer-clean-generic mostlyclean \ - mostlyclean-generic mostlyclean-libtool pdf pdf-am ps ps-am \ - tags uninstall uninstall-am uninstall-nobase_includeHEADERS +.PHONY: CTAGS GTAGS TAGS all all-am check check-am clean clean-generic \ + clean-libtool cscopelist-am ctags ctags-am distclean \ + distclean-generic distclean-libtool distclean-tags distdir dvi \ + dvi-am html html-am info info-am install install-am \ + install-data install-data-am install-dvi install-dvi-am \ + install-exec install-exec-am install-html install-html-am \ + install-info install-info-am install-man \ + install-nobase_includeHEADERS install-pdf install-pdf-am \ + install-ps install-ps-am install-strip installcheck \ + installcheck-am installdirs maintainer-clean \ + maintainer-clean-generic mostlyclean mostlyclean-generic \ + mostlyclean-libtool pdf pdf-am ps ps-am tags tags-am uninstall \ + uninstall-am uninstall-nobase_includeHEADERS + +.PRECIOUS: Makefile # Tell versions [3.59,3.63) of GNU make to not export all variables. diff --git a/gtsam/3rdparty/GeographicLib/include/Makefile.mk b/gtsam/3rdparty/GeographicLib/include/Makefile.mk index fbb9036eb..a9225cdbe 100644 --- a/gtsam/3rdparty/GeographicLib/include/Makefile.mk +++ b/gtsam/3rdparty/GeographicLib/include/Makefile.mk @@ -1,10 +1,12 @@ -MODULES = AlbersEqualArea \ +MODULES = Accumulator \ + AlbersEqualArea \ AzimuthalEquidistant \ CassiniSoldner \ CircularEngine \ DMS \ Ellipsoid \ EllipticFunction \ + GARS \ GeoCoords \ Geocentric \ Geodesic \ @@ -13,6 +15,7 @@ MODULES = AlbersEqualArea \ GeodesicLineExact \ Geohash \ Geoid \ + Georef \ Gnomonic \ GravityCircle \ GravityModel \ @@ -21,18 +24,19 @@ MODULES = AlbersEqualArea \ MGRS \ MagneticCircle \ MagneticModel \ + Math \ NormalGravity \ OSGB \ PolarStereographic \ PolygonArea \ + Rhumb \ SphericalEngine \ TransverseMercator \ TransverseMercatorExact \ UTMUPS \ Utility -EXTRAHEADERS = Accumulator \ - Constants \ - Math \ +EXTRAHEADERS = Constants \ + NearestNeighbor \ SphericalHarmonic \ SphericalHarmonic1 \ SphericalHarmonic2 diff --git a/gtsam/3rdparty/GeographicLib/install-sh b/gtsam/3rdparty/GeographicLib/install-sh index 377bb8687..0b0fdcbba 100755 --- a/gtsam/3rdparty/GeographicLib/install-sh +++ b/gtsam/3rdparty/GeographicLib/install-sh @@ -1,7 +1,7 @@ #!/bin/sh # install - install a program, script, or datafile -scriptversion=2011-11-20.07; # UTC +scriptversion=2013-12-25.23; # UTC # This originates from X11R5 (mit/util/scripts/install.sh), which was # later released in X11R6 (xc/config/util/install.sh) with the @@ -41,19 +41,15 @@ scriptversion=2011-11-20.07; # UTC # This script is compatible with the BSD install script, but was written # from scratch. +tab=' ' nl=' ' -IFS=" "" $nl" +IFS=" $tab$nl" -# set DOITPROG to echo to test this script +# Set DOITPROG to "echo" to test this script. -# Don't use :- since 4.3BSD and earlier shells don't like it. doit=${DOITPROG-} -if test -z "$doit"; then - doit_exec=exec -else - doit_exec=$doit -fi +doit_exec=${doit:-exec} # Put in absolute file names if you don't have them in your path; # or use environment vars. @@ -68,17 +64,6 @@ mvprog=${MVPROG-mv} rmprog=${RMPROG-rm} stripprog=${STRIPPROG-strip} -posix_glob='?' -initialize_posix_glob=' - test "$posix_glob" != "?" || { - if (set -f) 2>/dev/null; then - posix_glob= - else - posix_glob=: - fi - } -' - posix_mkdir= # Desired mode of installed file. @@ -97,7 +82,7 @@ dir_arg= dst_arg= copy_on_change=false -no_target_directory= +is_target_a_directory=possibly usage="\ Usage: $0 [OPTION]... [-T] SRCFILE DSTFILE @@ -137,46 +122,57 @@ while test $# -ne 0; do -d) dir_arg=true;; -g) chgrpcmd="$chgrpprog $2" - shift;; + shift;; --help) echo "$usage"; exit $?;; -m) mode=$2 - case $mode in - *' '* | *' '* | *' -'* | *'*'* | *'?'* | *'['*) - echo "$0: invalid mode: $mode" >&2 - exit 1;; - esac - shift;; + case $mode in + *' '* | *"$tab"* | *"$nl"* | *'*'* | *'?'* | *'['*) + echo "$0: invalid mode: $mode" >&2 + exit 1;; + esac + shift;; -o) chowncmd="$chownprog $2" - shift;; + shift;; -s) stripcmd=$stripprog;; - -t) dst_arg=$2 - # Protect names problematic for 'test' and other utilities. - case $dst_arg in - -* | [=\(\)!]) dst_arg=./$dst_arg;; - esac - shift;; + -t) + is_target_a_directory=always + dst_arg=$2 + # Protect names problematic for 'test' and other utilities. + case $dst_arg in + -* | [=\(\)!]) dst_arg=./$dst_arg;; + esac + shift;; - -T) no_target_directory=true;; + -T) is_target_a_directory=never;; --version) echo "$0 $scriptversion"; exit $?;; - --) shift - break;; + --) shift + break;; - -*) echo "$0: invalid option: $1" >&2 - exit 1;; + -*) echo "$0: invalid option: $1" >&2 + exit 1;; *) break;; esac shift done +# We allow the use of options -d and -T together, by making -d +# take the precedence; this is for compatibility with GNU install. + +if test -n "$dir_arg"; then + if test -n "$dst_arg"; then + echo "$0: target directory not allowed when installing a directory." >&2 + exit 1 + fi +fi + if test $# -ne 0 && test -z "$dir_arg$dst_arg"; then # When -d is used, all remaining arguments are directories to create. # When -t is used, the destination is already specified. @@ -207,6 +203,15 @@ if test $# -eq 0; then exit 0 fi +if test -z "$dir_arg"; then + if test $# -gt 1 || test "$is_target_a_directory" = always; then + if test ! -d "$dst_arg"; then + echo "$0: $dst_arg: Is not a directory." >&2 + exit 1 + fi + fi +fi + if test -z "$dir_arg"; then do_exit='(exit $ret); exit $ret' trap "ret=129; $do_exit" 1 @@ -223,16 +228,16 @@ if test -z "$dir_arg"; then *[0-7]) if test -z "$stripcmd"; then - u_plus_rw= + u_plus_rw= else - u_plus_rw='% 200' + u_plus_rw='% 200' fi cp_umask=`expr '(' 777 - $mode % 1000 ')' $u_plus_rw`;; *) if test -z "$stripcmd"; then - u_plus_rw= + u_plus_rw= else - u_plus_rw=,u+rw + u_plus_rw=,u+rw fi cp_umask=$mode$u_plus_rw;; esac @@ -269,41 +274,15 @@ do # If destination is a directory, append the input filename; won't work # if double slashes aren't ignored. if test -d "$dst"; then - if test -n "$no_target_directory"; then - echo "$0: $dst_arg: Is a directory" >&2 - exit 1 + if test "$is_target_a_directory" = never; then + echo "$0: $dst_arg: Is a directory" >&2 + exit 1 fi dstdir=$dst dst=$dstdir/`basename "$src"` dstdir_status=0 else - # Prefer dirname, but fall back on a substitute if dirname fails. - dstdir=` - (dirname "$dst") 2>/dev/null || - expr X"$dst" : 'X\(.*[^/]\)//*[^/][^/]*/*$' \| \ - X"$dst" : 'X\(//\)[^/]' \| \ - X"$dst" : 'X\(//\)$' \| \ - X"$dst" : 'X\(/\)' \| . 2>/dev/null || - echo X"$dst" | - sed '/^X\(.*[^/]\)\/\/*[^/][^/]*\/*$/{ - s//\1/ - q - } - /^X\(\/\/\)[^/].*/{ - s//\1/ - q - } - /^X\(\/\/\)$/{ - s//\1/ - q - } - /^X\(\/\).*/{ - s//\1/ - q - } - s/.*/./; q' - ` - + dstdir=`dirname "$dst"` test -d "$dstdir" dstdir_status=$? fi @@ -314,74 +293,74 @@ do if test $dstdir_status != 0; then case $posix_mkdir in '') - # Create intermediate dirs using mode 755 as modified by the umask. - # This is like FreeBSD 'install' as of 1997-10-28. - umask=`umask` - case $stripcmd.$umask in - # Optimize common cases. - *[2367][2367]) mkdir_umask=$umask;; - .*0[02][02] | .[02][02] | .[02]) mkdir_umask=22;; + # Create intermediate dirs using mode 755 as modified by the umask. + # This is like FreeBSD 'install' as of 1997-10-28. + umask=`umask` + case $stripcmd.$umask in + # Optimize common cases. + *[2367][2367]) mkdir_umask=$umask;; + .*0[02][02] | .[02][02] | .[02]) mkdir_umask=22;; - *[0-7]) - mkdir_umask=`expr $umask + 22 \ - - $umask % 100 % 40 + $umask % 20 \ - - $umask % 10 % 4 + $umask % 2 - `;; - *) mkdir_umask=$umask,go-w;; - esac + *[0-7]) + mkdir_umask=`expr $umask + 22 \ + - $umask % 100 % 40 + $umask % 20 \ + - $umask % 10 % 4 + $umask % 2 + `;; + *) mkdir_umask=$umask,go-w;; + esac - # With -d, create the new directory with the user-specified mode. - # Otherwise, rely on $mkdir_umask. - if test -n "$dir_arg"; then - mkdir_mode=-m$mode - else - mkdir_mode= - fi + # With -d, create the new directory with the user-specified mode. + # Otherwise, rely on $mkdir_umask. + if test -n "$dir_arg"; then + mkdir_mode=-m$mode + else + mkdir_mode= + fi - posix_mkdir=false - case $umask in - *[123567][0-7][0-7]) - # POSIX mkdir -p sets u+wx bits regardless of umask, which - # is incompatible with FreeBSD 'install' when (umask & 300) != 0. - ;; - *) - tmpdir=${TMPDIR-/tmp}/ins$RANDOM-$$ - trap 'ret=$?; rmdir "$tmpdir/d" "$tmpdir" 2>/dev/null; exit $ret' 0 + posix_mkdir=false + case $umask in + *[123567][0-7][0-7]) + # POSIX mkdir -p sets u+wx bits regardless of umask, which + # is incompatible with FreeBSD 'install' when (umask & 300) != 0. + ;; + *) + tmpdir=${TMPDIR-/tmp}/ins$RANDOM-$$ + trap 'ret=$?; rmdir "$tmpdir/d" "$tmpdir" 2>/dev/null; exit $ret' 0 - if (umask $mkdir_umask && - exec $mkdirprog $mkdir_mode -p -- "$tmpdir/d") >/dev/null 2>&1 - then - if test -z "$dir_arg" || { - # Check for POSIX incompatibilities with -m. - # HP-UX 11.23 and IRIX 6.5 mkdir -m -p sets group- or - # other-writable bit of parent directory when it shouldn't. - # FreeBSD 6.1 mkdir -m -p sets mode of existing directory. - ls_ld_tmpdir=`ls -ld "$tmpdir"` - case $ls_ld_tmpdir in - d????-?r-*) different_mode=700;; - d????-?--*) different_mode=755;; - *) false;; - esac && - $mkdirprog -m$different_mode -p -- "$tmpdir" && { - ls_ld_tmpdir_1=`ls -ld "$tmpdir"` - test "$ls_ld_tmpdir" = "$ls_ld_tmpdir_1" - } - } - then posix_mkdir=: - fi - rmdir "$tmpdir/d" "$tmpdir" - else - # Remove any dirs left behind by ancient mkdir implementations. - rmdir ./$mkdir_mode ./-p ./-- 2>/dev/null - fi - trap '' 0;; - esac;; + if (umask $mkdir_umask && + exec $mkdirprog $mkdir_mode -p -- "$tmpdir/d") >/dev/null 2>&1 + then + if test -z "$dir_arg" || { + # Check for POSIX incompatibilities with -m. + # HP-UX 11.23 and IRIX 6.5 mkdir -m -p sets group- or + # other-writable bit of parent directory when it shouldn't. + # FreeBSD 6.1 mkdir -m -p sets mode of existing directory. + ls_ld_tmpdir=`ls -ld "$tmpdir"` + case $ls_ld_tmpdir in + d????-?r-*) different_mode=700;; + d????-?--*) different_mode=755;; + *) false;; + esac && + $mkdirprog -m$different_mode -p -- "$tmpdir" && { + ls_ld_tmpdir_1=`ls -ld "$tmpdir"` + test "$ls_ld_tmpdir" = "$ls_ld_tmpdir_1" + } + } + then posix_mkdir=: + fi + rmdir "$tmpdir/d" "$tmpdir" + else + # Remove any dirs left behind by ancient mkdir implementations. + rmdir ./$mkdir_mode ./-p ./-- 2>/dev/null + fi + trap '' 0;; + esac;; esac if $posix_mkdir && ( - umask $mkdir_umask && - $doit_exec $mkdirprog $mkdir_mode -p -- "$dstdir" + umask $mkdir_umask && + $doit_exec $mkdirprog $mkdir_mode -p -- "$dstdir" ) then : else @@ -391,53 +370,51 @@ do # directory the slow way, step by step, checking for races as we go. case $dstdir in - /*) prefix='/';; - [-=\(\)!]*) prefix='./';; - *) prefix='';; + /*) prefix='/';; + [-=\(\)!]*) prefix='./';; + *) prefix='';; esac - eval "$initialize_posix_glob" - oIFS=$IFS IFS=/ - $posix_glob set -f + set -f set fnord $dstdir shift - $posix_glob set +f + set +f IFS=$oIFS prefixes= for d do - test X"$d" = X && continue + test X"$d" = X && continue - prefix=$prefix$d - if test -d "$prefix"; then - prefixes= - else - if $posix_mkdir; then - (umask=$mkdir_umask && - $doit_exec $mkdirprog $mkdir_mode -p -- "$dstdir") && break - # Don't fail if two instances are running concurrently. - test -d "$prefix" || exit 1 - else - case $prefix in - *\'*) qprefix=`echo "$prefix" | sed "s/'/'\\\\\\\\''/g"`;; - *) qprefix=$prefix;; - esac - prefixes="$prefixes '$qprefix'" - fi - fi - prefix=$prefix/ + prefix=$prefix$d + if test -d "$prefix"; then + prefixes= + else + if $posix_mkdir; then + (umask=$mkdir_umask && + $doit_exec $mkdirprog $mkdir_mode -p -- "$dstdir") && break + # Don't fail if two instances are running concurrently. + test -d "$prefix" || exit 1 + else + case $prefix in + *\'*) qprefix=`echo "$prefix" | sed "s/'/'\\\\\\\\''/g"`;; + *) qprefix=$prefix;; + esac + prefixes="$prefixes '$qprefix'" + fi + fi + prefix=$prefix/ done if test -n "$prefixes"; then - # Don't fail if two instances are running concurrently. - (umask $mkdir_umask && - eval "\$doit_exec \$mkdirprog $prefixes") || - test -d "$dstdir" || exit 1 - obsolete_mkdir_used=true + # Don't fail if two instances are running concurrently. + (umask $mkdir_umask && + eval "\$doit_exec \$mkdirprog $prefixes") || + test -d "$dstdir" || exit 1 + obsolete_mkdir_used=true fi fi fi @@ -472,15 +449,12 @@ do # If -C, don't bother to copy if it wouldn't change the file. if $copy_on_change && - old=`LC_ALL=C ls -dlL "$dst" 2>/dev/null` && - new=`LC_ALL=C ls -dlL "$dsttmp" 2>/dev/null` && - - eval "$initialize_posix_glob" && - $posix_glob set -f && + old=`LC_ALL=C ls -dlL "$dst" 2>/dev/null` && + new=`LC_ALL=C ls -dlL "$dsttmp" 2>/dev/null` && + set -f && set X $old && old=:$2:$4:$5:$6 && set X $new && new=:$2:$4:$5:$6 && - $posix_glob set +f && - + set +f && test "$old" = "$new" && $cmpprog "$dst" "$dsttmp" >/dev/null 2>&1 then @@ -493,24 +467,24 @@ do # to itself, or perhaps because mv is so ancient that it does not # support -f. { - # Now remove or move aside any old file at destination location. - # We try this two ways since rm can't unlink itself on some - # systems and the destination file might be busy for other - # reasons. In this case, the final cleanup might fail but the new - # file should still install successfully. - { - test ! -f "$dst" || - $doit $rmcmd -f "$dst" 2>/dev/null || - { $doit $mvcmd -f "$dst" "$rmtmp" 2>/dev/null && - { $doit $rmcmd -f "$rmtmp" 2>/dev/null; :; } - } || - { echo "$0: cannot unlink or rename $dst" >&2 - (exit 1); exit 1 - } - } && + # Now remove or move aside any old file at destination location. + # We try this two ways since rm can't unlink itself on some + # systems and the destination file might be busy for other + # reasons. In this case, the final cleanup might fail but the new + # file should still install successfully. + { + test ! -f "$dst" || + $doit $rmcmd -f "$dst" 2>/dev/null || + { $doit $mvcmd -f "$dst" "$rmtmp" 2>/dev/null && + { $doit $rmcmd -f "$rmtmp" 2>/dev/null; :; } + } || + { echo "$0: cannot unlink or rename $dst" >&2 + (exit 1); exit 1 + } + } && - # Now rename the file to the real destination. - $doit $mvcmd "$dsttmp" "$dst" + # Now rename the file to the real destination. + $doit $mvcmd "$dsttmp" "$dst" } fi || exit 1 diff --git a/gtsam/3rdparty/GeographicLib/java/README.txt b/gtsam/3rdparty/GeographicLib/java/README.txt index f58b00882..c32323bc3 100644 --- a/gtsam/3rdparty/GeographicLib/java/README.txt +++ b/gtsam/3rdparty/GeographicLib/java/README.txt @@ -3,12 +3,12 @@ This is a Java implementation of the geodesic algorithms described in C. F. F. Karney, Algorithms for geodesics, J. Geodesy 87, 43-55 (2013); - http://dx.doi.org/10.1007/s00190-012-0578-z - Addenda: http://geographiclib.sf.net/geod-addenda.html + https://doi.org/10.1007/s00190-012-0578-z + Addenda: https://geographiclib.sourceforge.io/geod-addenda.html For documentation, see - http://geographiclib.sourceforge.net/html/java/ + https://geographiclib.sourceforge.io/html/java/ The code in this directory is entirely self-contained. In particular, it does not depend on the C++ classes. You can build the example @@ -18,4 +18,9 @@ programs using, for example, javac -cp .:../../../../src/main/java Inverse.java echo -30 0 29.5 179.5 | java -cp .:../../../../src/main/java Inverse +On Windows, change this to + cd inverse\src\main\java + javac -cp .;../../../../src/main/java Inverse.java + echo -30 0 29.5 179.5 | java -cp .;../../../../src/main/java Inverse + Building with maven is also supported (see the documentation). diff --git a/gtsam/3rdparty/GeographicLib/java/direct/pom.xml b/gtsam/3rdparty/GeographicLib/java/direct/pom.xml index 0fd9053af..a75f7b14f 100644 --- a/gtsam/3rdparty/GeographicLib/java/direct/pom.xml +++ b/gtsam/3rdparty/GeographicLib/java/direct/pom.xml @@ -1,87 +1,88 @@ + xsi:schemaLocation="http://maven.apache.org/POM/4.0.0 + http://maven.apache.org/xsd/maven-4.0.0.xsd"> - 4.0.0 + 4.0.0 - net.sf.geographiclib.example - Direct - Direct - 1.31 + net.sf.geographiclib.example + Direct + Direct + 1.49-SNAPSHOT - jar + jar - - . - 1.6 - 2.9 - UTF-8 - 2.3.2 - 2.4 - 2.8 - 3.0 - + + . + 1.6 + 2.9 + UTF-8 + 2.3.2 + 2.4 + 2.8 + 3.0 + - - - net.sf.geographiclib - GeographicLib - 1.31 - - + + + net.sf.geographiclib + GeographicLib-Java + 1.49 + + - - - - org.apache.maven.plugins - maven-compiler-plugin - ${maven-compiler-plugin.version} - - ${java.version} - ${java.version} - - + + + + org.apache.maven.plugins + maven-compiler-plugin + ${maven-compiler-plugin.version} + + ${java.version} + ${java.version} + + - - org.apache.maven.plugins - maven-surefire-plugin - ${surefire-plugin.version} - - false - - + + org.apache.maven.plugins + maven-surefire-plugin + ${surefire-plugin.version} + + false + + - - org.apache.maven.plugins - maven-javadoc-plugin - ${maven-javadoc.version} - - public - true - - - - attach-javadocs - - jar - - - - + + org.apache.maven.plugins + maven-javadoc-plugin + ${maven-javadoc.version} + + public + true + + + + attach-javadocs + + jar + + + + - - org.codehaus.mojo - exec-maven-plugin - 1.2.1 - - Direct - - - - - + + org.codehaus.mojo + exec-maven-plugin + 1.2.1 + + Direct + + + + + - + diff --git a/gtsam/3rdparty/GeographicLib/java/inverse/pom.xml b/gtsam/3rdparty/GeographicLib/java/inverse/pom.xml index a6e025cec..920cee3fe 100644 --- a/gtsam/3rdparty/GeographicLib/java/inverse/pom.xml +++ b/gtsam/3rdparty/GeographicLib/java/inverse/pom.xml @@ -1,87 +1,88 @@ + xsi:schemaLocation="http://maven.apache.org/POM/4.0.0 + http://maven.apache.org/xsd/maven-4.0.0.xsd"> - 4.0.0 + 4.0.0 - net.sf.geographiclib.example - Inverse - Inverse - 1.31 + net.sf.geographiclib.example + Inverse + Inverse + 1.49-SNAPSHOT - jar + jar - - . - 1.6 - 2.9 - UTF-8 - 2.3.2 - 2.4 - 2.8 - 3.0 - + + . + 1.6 + 2.9 + UTF-8 + 2.3.2 + 2.4 + 2.8 + 3.0 + - - - net.sf.geographiclib - GeographicLib - 1.31 - - + + + net.sf.geographiclib + GeographicLib-Java + 1.49 + + - - - - org.apache.maven.plugins - maven-compiler-plugin - ${maven-compiler-plugin.version} - - ${java.version} - ${java.version} - - + + + + org.apache.maven.plugins + maven-compiler-plugin + ${maven-compiler-plugin.version} + + ${java.version} + ${java.version} + + - - org.apache.maven.plugins - maven-surefire-plugin - ${surefire-plugin.version} - - false - - + + org.apache.maven.plugins + maven-surefire-plugin + ${surefire-plugin.version} + + false + + - - org.apache.maven.plugins - maven-javadoc-plugin - ${maven-javadoc.version} - - public - true - - - - attach-javadocs - - jar - - - - + + org.apache.maven.plugins + maven-javadoc-plugin + ${maven-javadoc.version} + + public + true + + + + attach-javadocs + + jar + + + + - - org.codehaus.mojo - exec-maven-plugin - 1.2.1 - - Inverse - - - - - + + org.codehaus.mojo + exec-maven-plugin + 1.2.1 + + Inverse + + + + + - + diff --git a/gtsam/3rdparty/GeographicLib/java/planimeter/pom.xml b/gtsam/3rdparty/GeographicLib/java/planimeter/pom.xml index fe50ea2d9..06633eaf9 100644 --- a/gtsam/3rdparty/GeographicLib/java/planimeter/pom.xml +++ b/gtsam/3rdparty/GeographicLib/java/planimeter/pom.xml @@ -1,87 +1,88 @@ + xsi:schemaLocation="http://maven.apache.org/POM/4.0.0 + http://maven.apache.org/xsd/maven-4.0.0.xsd"> - 4.0.0 + 4.0.0 - net.sf.geographiclib.example - Planimeter - Planimeter - 1.31 + net.sf.geographiclib.example + Planimeter + Planimeter + 1.49-SNAPSHOT - jar + jar - - . - 1.6 - 2.9 - UTF-8 - 2.3.2 - 2.4 - 2.8 - 3.0 - + + . + 1.6 + 2.9 + UTF-8 + 2.3.2 + 2.4 + 2.8 + 3.0 + - - - net.sf.geographiclib - GeographicLib - 1.31 - - + + + net.sf.geographiclib + GeographicLib-Java + 1.49 + + - - - - org.apache.maven.plugins - maven-compiler-plugin - ${maven-compiler-plugin.version} - - ${java.version} - ${java.version} - - + + + + org.apache.maven.plugins + maven-compiler-plugin + ${maven-compiler-plugin.version} + + ${java.version} + ${java.version} + + - - org.apache.maven.plugins - maven-surefire-plugin - ${surefire-plugin.version} - - false - - + + org.apache.maven.plugins + maven-surefire-plugin + ${surefire-plugin.version} + + false + + - - org.apache.maven.plugins - maven-javadoc-plugin - ${maven-javadoc.version} - - public - true - - - - attach-javadocs - - jar - - - - + + org.apache.maven.plugins + maven-javadoc-plugin + ${maven-javadoc.version} + + public + true + + + + attach-javadocs + + jar + + + + - - org.codehaus.mojo - exec-maven-plugin - 1.2.1 - - Planimeter - - - - - + + org.codehaus.mojo + exec-maven-plugin + 1.2.1 + + Planimeter + + + + + - + diff --git a/gtsam/3rdparty/GeographicLib/java/pom.xml b/gtsam/3rdparty/GeographicLib/java/pom.xml index e6af2e0e5..0cf420232 100644 --- a/gtsam/3rdparty/GeographicLib/java/pom.xml +++ b/gtsam/3rdparty/GeographicLib/java/pom.xml @@ -1,90 +1,179 @@ + xsi:schemaLocation="http://maven.apache.org/POM/4.0.0 + http://maven.apache.org/xsd/maven-4.0.0.xsd"> - 4.0.0 + 4.0.0 - net.sf.geographiclib - GeographicLib - GeographicLib - 1.31 + net.sf.geographiclib + GeographicLib-Java + 1.49 - jar + jar - This is a Java implementation of the geodesic algorithms from GeographicLib. This is a self-contained library which makes it easy to do geodesic computations for an ellipsoid of revolution in a Java program. It requires Java version 1.1 or later. - + + + The MIT License(MIT) + http://opensource.org/licenses/MIT + + - - . - 1.6 - 2.9 - UTF-8 - 2.3.2 - 2.4 - 2.8 - 3.0 - + Java implementation of GeographicLib + + This is a Java implementation of the geodesic algorithms from + GeographicLib. This is a self-contained library which makes it + easy to do geodesic computations for an ellipsoid of revolution in + a Java program. It requires Java version 1.1 or later. + + https://geographiclib.sourceforge.io - - + + + Charles Karney + charles@karney.com + + + https://sourceforge.net/u/karney/profile/ + + + - + + . + 1.6 + 2.9 + UTF-8 + 2.3.2 + 2.4 + 2.8 + 3.0 + + + + + + org.apache.maven.plugins + maven-compiler-plugin + ${maven-compiler-plugin.version} + + ${java.version} + ${java.version} + + + + + org.apache.maven.plugins + maven-surefire-plugin + ${surefire-plugin.version} + + false + + + + + + + + + release + - - org.apache.maven.plugins - maven-compiler-plugin - ${maven-compiler-plugin.version} - - ${java.version} - ${java.version} - - - - org.apache.maven.plugins - maven-surefire-plugin - ${surefire-plugin.version} - - false - - + + org.apache.maven.plugins + maven-javadoc-plugin + ${maven-javadoc.version} + + public + true + + + + attach-javadocs + + jar + + + + + + + org.apache.maven.plugins + maven-source-plugin + 2.2.1 + + + attach-sources + + jar-no-fork + + + + + + + org.sonatype.plugins + nexus-staging-maven-plugin + 1.6.3 + true + + ossrh + https://oss.sonatype.org/ + true + + + + + org.apache.maven.plugins + maven-gpg-plugin + 1.5 + + + sign-artifacts + verify + + sign + + + + - - org.apache.maven.plugins - maven-javadoc-plugin - ${maven-javadoc.version} - - public - true - - - - attach-javadocs - - jar - - - - + + + - + + + ossrh + https://oss.sonatype.org/content/repositories/snapshots + + + ossrh + https://oss.sonatype.org/service/local/staging/deploy/maven2 + + - - + + + scm:git://git.code.sourceforge.net/p/geographiclib/code + + + scm:git:https://git.code.sourceforge.net/p/geographiclib/code + + + https://sourceforge.net/p/geographiclib/code/ci/master/tree/ + + - - - scm:git:http:// - - - scm:git:https:// - - devel - - http:// - - + + + junit + junit + 4.12 + test + + diff --git a/gtsam/3rdparty/GeographicLib/java/src/main/java/net/sf/geographiclib/Accumulator.java b/gtsam/3rdparty/GeographicLib/java/src/main/java/net/sf/geographiclib/Accumulator.java index bcba4b7d6..a773f4a7a 100644 --- a/gtsam/3rdparty/GeographicLib/java/src/main/java/net/sf/geographiclib/Accumulator.java +++ b/gtsam/3rdparty/GeographicLib/java/src/main/java/net/sf/geographiclib/Accumulator.java @@ -3,7 +3,7 @@ * * Copyright (c) Charles Karney (2013) and licensed * under the MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ package net.sf.geographiclib; @@ -15,12 +15,12 @@ package net.sf.geographiclib; * about 32 decimal places. *

* The implementation follows J. R. Shewchuk, - * Adaptive Precision + * Adaptive Precision * Floating-Point Arithmetic and Fast Robust Geometric Predicates, - * Discrete & Computational Geometry 18(3) 305–363 (1997). + * Discrete & Computational Geometry 18(3) 305–363 (1997). *

- * In the documentation of the member functions, sum stands for the value - * currently held in the accumulator. + * In the documentation of the member functions, sum stands for the + * value currently held in the accumulator. ***********************************************************************/ public class Accumulator { // _s + _t accumulators for the sum. diff --git a/gtsam/3rdparty/GeographicLib/java/src/main/java/net/sf/geographiclib/Constants.java b/gtsam/3rdparty/GeographicLib/java/src/main/java/net/sf/geographiclib/Constants.java index 047667842..6914994b8 100644 --- a/gtsam/3rdparty/GeographicLib/java/src/main/java/net/sf/geographiclib/Constants.java +++ b/gtsam/3rdparty/GeographicLib/java/src/main/java/net/sf/geographiclib/Constants.java @@ -3,7 +3,7 @@ * * Copyright (c) Charles Karney (2013) and licensed * under the MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ package net.sf.geographiclib; diff --git a/gtsam/3rdparty/GeographicLib/java/src/main/java/net/sf/geographiclib/GeoMath.java b/gtsam/3rdparty/GeographicLib/java/src/main/java/net/sf/geographiclib/GeoMath.java index 80631eb95..48d395739 100644 --- a/gtsam/3rdparty/GeographicLib/java/src/main/java/net/sf/geographiclib/GeoMath.java +++ b/gtsam/3rdparty/GeographicLib/java/src/main/java/net/sf/geographiclib/GeoMath.java @@ -1,9 +1,9 @@ /** * Implementation of the net.sf.geographiclib.GeoMath class * - * Copyright (c) Charles Karney (2013) and licensed + * Copyright (c) Charles Karney (2013-2017) and licensed * under the MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ package net.sf.geographiclib; @@ -29,11 +29,6 @@ public class GeoMath { * version 1.6 and later, Double.MIN_NORMAL can be used. **********************************************************************/ public static final double min = Math.pow(0.5, 1022); - /** - * The number of radians in a degree. In Java version 1.2 and later, - * Math.toRadians and Math.toDegrees can be used. - **********************************************************************/ - public static final double degree = Math.PI / 180; /** * Square a number. @@ -56,8 +51,8 @@ public class GeoMath { double a = Math.max(x, y), b = Math.min(x, y) / (a != 0 ? a : 1); return a * Math.sqrt(1 + b * b); // For an alternative method see - // C. Moler and D. Morrision (1983) http://dx.doi.org/10.1147/rd.276.0577 - // and A. A. Dubrulle (1983) http://dx.doi.org/10.1147/rd.276.0582 + // C. Moler and D. Morrision (1983) https://doi.org/10.1147/rd.276.0577 + // and A. A. Dubrulle (1983) https://doi.org/10.1147/rd.276.0582 } /** @@ -65,7 +60,7 @@ public class GeoMath { * later, Math.log1p can be used. *

* This is taken from D. Goldberg, - * What every computer + * What every computer * scientist should know about floating-point arithmetic (1991), * Theorem 4. See also, N. J. Higham, Accuracy and Stability of Numerical * Algorithms, 2nd Edition (SIAM, 2002), Answer to Problem 1.5, p 528. @@ -98,6 +93,18 @@ public class GeoMath { return x < 0 ? -y : y; } + /** + * Copy the sign. In Java version 1.6 and later, Math.copysign can be used. + *

+ * @param x gives the magitude of the result. + * @param y gives the sign of the result. + * @return value with the magnitude of x and with the sign of + * y. + **********************************************************************/ + public static double copysign(double x, double y) { + return Math.abs(x) * (y < 0 || (y == 0 && 1/y < 0) ? -1 : 1); + } + /** * The cube root function. In Java version 1.5 and later, Math.cbrt can be * used. @@ -110,6 +117,11 @@ public class GeoMath { return x < 0 ? -y : y; } + public static Pair norm(double sinx, double cosx) { + double r = hypot(sinx, cosx); + return new Pair(sinx/r, cosx/r); + } + /** * The error-free sum of two numbers. *

@@ -133,50 +145,156 @@ public class GeoMath { } /** - * Normalize an angle (restricted input range). + * Evaluate a polynomial. *

- * @param x the angle in degrees. - * @return the angle reduced to the range [−180°, 180°). - *

- * x must lie in [−540°, 540°). + * @param N the order of the polynomial. + * @param p the coefficient array (of size N + s + 1 or more). + * @param s starting index for the array. + * @param x the variable. + * @return the value of the polynomial. + * + * Evaluate y = ∑n=0..N + * ps+n + * xNn. Return 0 if N < 0. + * Return ps, if N = 0 (even if x is + * infinite or a nan). The evaluation uses Horner's method. **********************************************************************/ - public static double AngNormalize(double x) - { return x >= 180 ? x - 360 : (x < -180 ? x + 360 : x); } + public static double polyval(int N, double p[], int s, double x) { + double y = N < 0 ? 0 : p[s++]; + while (--N >= 0) y = y * x + p[s++]; + return y; + } + + public static double AngRound(double x) { + // The makes the smallest gap in x = 1/16 - nextafter(1/16, 0) = 1/2^57 + // for reals = 0.7 pm on the earth if x is an angle in degrees. (This + // is about 1000 times more resolution than we get with angles around 90 + // degrees.) We use this to avoid having to deal with near singular + // cases when x is non-zero but tiny (e.g., 1.0e-200). This converts -0 to + // +0; however tiny negative numbers get converted to -0. + final double z = 1/16.0; + if (x == 0) return 0; + double y = Math.abs(x); + // The compiler mustn't "simplify" z - (z - y) to y + y = y < z ? z - (z - y) : y; + return x < 0 ? -y : y; + } /** - * Normalize an arbitrary angle. + * Normalize an angle (restricted input range). *

* @param x the angle in degrees. * @return the angle reduced to the range [−180°, 180°). *

* The range of x is unrestricted. **********************************************************************/ - public static double AngNormalize2(double x) - { return AngNormalize(x % 360.0); } + public static double AngNormalize(double x) { + x = x % 360.0; + return x <= -180 ? x + 360 : (x <= 180 ? x : x - 360); + } /** - * Difference of two angles reduced to [−180°, 180°] + * Normalize a latitude. + *

+ * @param x the angle in degrees. + * @return x if it is in the range [−90°, 90°], otherwise + * return NaN. + **********************************************************************/ + public static double LatFix(double x) { + return Math.abs(x) > 90 ? Double.NaN : x; + } + + /** + * The exact difference of two angles reduced to (−180°, 180°]. *

* @param x the first angle in degrees. * @param y the second angle in degrees. - * @return yx, reduced to the range [−180°, - * 180°]. + * @return Pair(d, e) with d being the rounded + * difference and e being the error. *

- * x and y must both lie in [−180°, 180°]. The - * result is equivalent to computing the difference exactly, reducing it to - * (−180°, 180°] and rounding the result. Note that this - * prescription allows −180° to be returned (e.g., if x is - * tiny and negative and y = 180°). + * The computes z = yx exactly, reduced to + * (−180°, 180°]; and then sets z = d + e + * where d is the nearest representable number to z and + * e is the truncation error. If d = −180, then e + * > 0; If d = 180, then e ≤ 0. **********************************************************************/ - public static double AngDiff(double x, double y) { + public static Pair AngDiff(double x, double y) { double d, t; - { Pair r = sum(-x, y); d = r.first; t = r.second; } - if ((d - 180.0) + t > 0.0) // y - x > 180 - d -= 360.0; // exact - else if ((d + 180.0) + t <= 0.0) // y - x <= -180 - d += 360.0; // exact - return d + t; + { + Pair r = sum(AngNormalize(-x), AngNormalize(y)); + d = AngNormalize(r.first); t = r.second; + } + return sum(d == 180 && t > 0 ? -180 : d, t); } + + /** + * Evaluate the sine and cosine function with the argument in degrees + * + * @param x in degrees. + * @return Pair(s, t) with s = sin(x) and + * c = cos(x). + * + * The results obey exactly the elementary properties of the trigonometric + * functions, e.g., sin 9° = cos 81° = − sin 123456789°. + **********************************************************************/ + public static Pair sincosd(double x) { + // In order to minimize round-off errors, this function exactly reduces + // the argument to the range [-45, 45] before converting it to radians. + double r; int q; + r = x % 360.0; + q = (int)Math.floor(r / 90 + 0.5); + r -= 90 * q; + // now abs(r) <= 45 + r = Math.toRadians(r); + // Possibly could call the gnu extension sincos + double s = Math.sin(r), c = Math.cos(r); + double sinx, cosx; + switch (q & 3) { + case 0: sinx = s; cosx = c; break; + case 1: sinx = c; cosx = -s; break; + case 2: sinx = -s; cosx = -c; break; + default: sinx = -c; cosx = s; break; // case 3 + } + if (x != 0) { sinx += 0.0; cosx += 0.0; } + return new Pair(sinx, cosx); + } + + /** + * Evaluate the atan2 function with the result in degrees + * + * @param y the sine of the angle + * @param x the cosine of the angle + * @return atan2(y, x) in degrees. + * + * The result is in the range (−180° 180°]. N.B., + * atan2d(±0, −1) = +180°; atan2d(−ε, + * −1) = −180°, for ε positive and tiny; + * atan2d(±0, 1) = ±0°. + **********************************************************************/ + public static double atan2d(double y, double x) { + // In order to minimize round-off errors, this function rearranges the + // arguments so that result of atan2 is in the range [-pi/4, pi/4] before + // converting it to degrees and mapping the result to the correct + // quadrant. + int q = 0; + if (Math.abs(y) > Math.abs(x)) { double t; t = x; x = y; y = t; q = 2; } + if (x < 0) { x = -x; ++q; } + // here x >= 0 and x >= abs(y), so angle is in [-pi/4, pi/4] + double ang = Math.toDegrees(Math.atan2(y, x)); + switch (q) { + // Note that atan2d(-0.0, 1.0) will return -0. However, we expect that + // atan2d will not be called with y = -0. If need be, include + // + // case 0: ang = 0 + ang; break; + // + // and handle mpfr as in AngRound. + case 1: ang = (y >= 0 ? 180 : -180) - ang; break; + case 2: ang = 90 - ang; break; + case 3: ang = -90 + ang; break; + } + return ang; + } + /** * Test for finiteness. *

diff --git a/gtsam/3rdparty/GeographicLib/java/src/main/java/net/sf/geographiclib/Geodesic.java b/gtsam/3rdparty/GeographicLib/java/src/main/java/net/sf/geographiclib/Geodesic.java index 4fe5a9694..265ff204c 100644 --- a/gtsam/3rdparty/GeographicLib/java/src/main/java/net/sf/geographiclib/Geodesic.java +++ b/gtsam/3rdparty/GeographicLib/java/src/main/java/net/sf/geographiclib/Geodesic.java @@ -1,9 +1,9 @@ /** * Implementation of the net.sf.geographiclib.Geodesic class * - * Copyright (c) Charles Karney (2013) and licensed + * Copyright (c) Charles Karney (2013-2017) and licensed * under the MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ package net.sf.geographiclib; @@ -124,38 +124,38 @@ package net.sf.geographiclib; * lat1 = −lat2 (with neither point at a pole). If * azi1 = azi2, the geodesic is unique. Otherwise there are * two geodesics and the second one is obtained by setting [azi1, - * azi2] = [azi2, azi1], [M12, M21] = - * [M21, M12], S12 = −S12. (This occurs - * when the longitude difference is near ±180° for oblate - * ellipsoids.) + * azi2] → [azi2, azi1], [M12, M21] + * → [M21, M12], S12 → −S12. + * (This occurs when the longitude difference is near ±180° for + * oblate ellipsoids.) *

  • * lon2 = lon1 ± 180° (with neither point at a * pole). If azi1 = 0° or ±180°, the geodesic is * unique. Otherwise there are two geodesics and the second one is obtained - * by setting [ azi1, azi2] = [−azi1, - * −azi2], S12 = − S12. (This occurs when - * lat2 is near −lat1 for prolate ellipsoids.) + * by setting [ azi1, azi2] → [−azi1, + * −azi2], S12 → − S12. (This occurs + * when lat2 is near −lat1 for prolate ellipsoids.) *
  • * Points 1 and 2 at opposite poles. There are infinitely many geodesics - * which can be generated by setting [azi1, azi2] = + * which can be generated by setting [azi1, azi2] → * [azi1, azi2] + [d, −d], for arbitrary * d. (For spheres, this prescription applies when points 1 and 2 are * antipodal.) *
  • - * s12 = 0 (coincident points). There are infinitely many geodesics which - * can be generated by setting [azi1, azi2] = [azi1, - * azi2] + [d, d], for arbitrary d. + * s12 = 0 (coincident points). There are infinitely many geodesics + * which can be generated by setting [azi1, azi2] → + * [azi1, azi2] + [d, d], for arbitrary d. * *

    * The calculations are accurate to better than 15 nm (15 nanometers) for the * WGS84 ellipsoid. See Sec. 9 of - * arXiv:1102.1215v1 for + * arXiv:1102.1215v1 for * details. The algorithms used by this class are based on series expansions * using the flattening f as a small parameter. These are only accurate * for |f| < 0.02; however reasonably accurate results will be * obtained for |f| < 0.2. Here is a table of the approximate * maximum error (expressed as a distance) for an ellipsoid with the same - * major radius as the WGS84 ellipsoid and different values of the + * equatorial radius as the WGS84 ellipsoid and different values of the * flattening.

      *     |f|      error
      *     0.01     25 nm
    @@ -167,13 +167,10 @@ package net.sf.geographiclib;
      * The algorithms are described in
      * 
      * 

    * Example of use: @@ -237,24 +234,6 @@ public class Geodesic { private static final double tolb_ = tol0_ * tol2_; private static final double xthresh_ = 1000 * tol2_; - protected static double AngRound(double x) { - // The makes the smallest gap in x = 1/16 - nextafter(1/16, 0) = 1/2^57 - // for reals = 0.7 pm on the earth if x is an angle in degrees. (This - // is about 1000 times more resolution than we get with angles around 90 - // degrees.) We use this to avoid having to deal with near singular - // cases when x is non-zero but tiny (e.g., 1.0e-200). - final double z = 1/16.0; - double y = Math.abs(x); - // The compiler mustn't "simplify" z - (z - y) to y - y = y < z ? z - (z - y) : y; - return x < 0 ? -y : y; - } - - protected static Pair SinCosNorm(double sinx, double cosx) { - double r = GeoMath.hypot(sinx, cosx); - return new Pair(sinx/r, cosx/r); - } - protected double _a, _f, _f1, _e2, _ep2, _b, _c2; private double _n, _etol2; private double _A3x[], _C3x[], _C4x[]; @@ -264,17 +243,16 @@ public class Geodesic { *

    * @param a equatorial radius (meters). * @param f flattening of ellipsoid. Setting f = 0 gives a sphere. - * Negative f gives a prolate ellipsoid. If f > 1, set - * flattening to 1/f. + * Negative f gives a prolate ellipsoid. * @exception GeographicErr if a or (1 − f ) a is * not positive. **********************************************************************/ public Geodesic(double a, double f) { _a = a; - _f = f <= 1 ? f : 1/f; + _f = f; _f1 = 1 - _f; _e2 = _f * (2 - _f); - _ep2 = _e2 / GeoMath.sq(_f1); // e2 / (1 - e2) + _ep2 = _e2 / GeoMath.sq(_f1); // e2 / (1 - e2) _n = _f / ( 2 - _f); _b = _a * _f1; _c2 = (GeoMath.sq(_a) + GeoMath.sq(_b) * @@ -296,9 +274,9 @@ public class Geodesic { Math.sqrt( Math.max(0.001, Math.abs(_f)) * Math.min(1.0, 1 - _f/2) / 2 ); if (!(GeoMath.isfinite(_a) && _a > 0)) - throw new GeographicErr("Major radius is not positive"); + throw new GeographicErr("Equatorial radius is not positive"); if (!(GeoMath.isfinite(_b) && _b > 0)) - throw new GeographicErr("Minor radius is not positive"); + throw new GeographicErr("Polar semi-axis is not positive"); _A3x = new double[nA3x_]; _C3x = new double[nC3x_]; _C4x = new double[nC4x_]; @@ -321,10 +299,9 @@ public class Geodesic { * lat1, lon1, azi1, lat2, lon2, * azi2, s12, a12. *

    - * lat1 should be in the range [−90°, 90°]; lon1 - * and azi1 should be in the range [−540°, 540°). The - * values of lon2 and azi2 returned are in the range - * [−180°, 180°). + * lat1 should be in the range [−90°, 90°]. The values + * of lon2 and azi2 returned are in the range [−180°, + * 180°]. *

    * If either point is at a pole, the azimuth is defined by keeping the * longitude fixed, writing lat = ±(90° − ε), @@ -335,9 +312,7 @@ public class Geodesic { **********************************************************************/ public GeodesicData Direct(double lat1, double lon1, double azi1, double s12) { - return Direct(lat1, lon1, azi1, false, s12, - GeodesicMask.LATITUDE | GeodesicMask.LONGITUDE | - GeodesicMask.AZIMUTH); + return Direct(lat1, lon1, azi1, false, s12, GeodesicMask.STANDARD); } /** * Solve the direct geodesic problem where the length of the geodesic is @@ -355,7 +330,9 @@ public class Geodesic { * outmask computed. *

    * lat1, lon1, azi1, s12, and a12 are - * always included in the returned result. + * always included in the returned result. The value of lon2 returned + * is in the range [−180°, 180°], unless the outmask + * includes the {@link GeodesicMask#LONG_UNROLL} flag. **********************************************************************/ public GeodesicData Direct(double lat1, double lon1, double azi1, double s12, int outmask) { @@ -375,10 +352,9 @@ public class Geodesic { * lat1, lon1, azi1, lat2, lon2, * azi2, s12, a12. *

    - * lat1 should be in the range [−90°, 90°]; lon1 - * and azi1 should be in the range [−540°, 540°). The - * values of lon2 and azi2 returned are in the range - * [−180°, 180°). + * lat1 should be in the range [−90°, 90°]. The values + * of lon2 and azi2 returned are in the range [−180°, + * 180°]. *

    * If either point is at a pole, the azimuth is defined by keeping the * longitude fixed, writing lat = ±(90° − ε), @@ -389,9 +365,7 @@ public class Geodesic { **********************************************************************/ public GeodesicData ArcDirect(double lat1, double lon1, double azi1, double a12) { - return Direct(lat1, lon1, azi1, true, a12, - GeodesicMask.LATITUDE | GeodesicMask.LONGITUDE | - GeodesicMask.AZIMUTH | GeodesicMask.DISTANCE); + return Direct(lat1, lon1, azi1, true, a12, GeodesicMask.STANDARD); } /** @@ -410,7 +384,9 @@ public class Geodesic { * outmask computed. *

    * lat1, lon1, azi1, and a12 are always included - * in the returned result. + * in the returned result. The value of lon2 returned is in the range + * [−180°, 180°], unless the outmask includes the {@link + * GeodesicMask#LONG_UNROLL} flag. **********************************************************************/ public GeodesicData ArcDirect(double lat1, double lon1, double azi1, double a12, int outmask) { @@ -437,23 +413,33 @@ public class Geodesic { * The {@link GeodesicMask} values possible for outmask are *

      *
    • - * outmask |= GeodesicMask.LATITUDE for the latitude lat2; + * outmask |= {@link GeodesicMask#LATITUDE} for the latitude + * lat2; *
    • - * outmask |= GeodesicMask.LONGITUDE for the latitude lon2; + * outmask |= {@link GeodesicMask#LONGITUDE} for the latitude + * lon2; *
    • - * outmask |= GeodesicMask.AZIMUTH for the latitude azi2; + * outmask |= {@link GeodesicMask#AZIMUTH} for the latitude + * azi2; *
    • - * outmask |= GeodesicMask.DISTANCE for the distance s12; + * outmask |= {@link GeodesicMask#DISTANCE} for the distance + * s12; *
    • - * outmask |= GeodesicMask.REDUCEDLENGTH for the reduced length - * m12; + * outmask |= {@link GeodesicMask#REDUCEDLENGTH} for the reduced + * length m12; *
    • - * outmask |= GeodesicMask.GEODESICSCALE for the geodesic scales - * M12 and M21; + * outmask |= {@link GeodesicMask#GEODESICSCALE} for the geodesic + * scales M12 and M21; *
    • - * outmask |= GeodesicMask.AREA for the area S12; + * outmask |= {@link GeodesicMask#AREA} for the area S12; *
    • - * outmask |= GeodesicMask.ALL for all of the above. + * outmask |= {@link GeodesicMask#ALL} for all of the above; + *
    • + * outmask |= {@link GeodesicMask#LONG_UNROLL}, if set then + * lon1 is unchanged and lon2lon1 indicates + * how many times and in what sense the geodesic encircles the ellipsoid. + * Otherwise lon1 and lon2 are both reduced to the range + * [−180°, 180°]. *
    *

    * The function value a12 is always computed and returned and this @@ -465,14 +451,143 @@ public class Geodesic { **********************************************************************/ public GeodesicData Direct(double lat1, double lon1, double azi1, boolean arcmode, double s12_a12, int outmask) { - return new GeodesicLine(this, lat1, lon1, azi1, - // Automatically supply DISTANCE_IN if necessary - outmask | (arcmode ? GeodesicMask.NONE : - GeodesicMask.DISTANCE_IN)) + // Automatically supply DISTANCE_IN if necessary + if (!arcmode) outmask |= GeodesicMask.DISTANCE_IN; + return new GeodesicLine(this, lat1, lon1, azi1, outmask) . // Note the dot! Position(arcmode, s12_a12, outmask); } + /** + * Define a {@link GeodesicLine} in terms of the direct geodesic problem + * specified in terms of distance with all capabilities included. + *

    + * @param lat1 latitude of point 1 (degrees). + * @param lon1 longitude of point 1 (degrees). + * @param azi1 azimuth at point 1 (degrees). + * @param s12 distance between point 1 and point 2 (meters); it can be + * negative. + * @return a {@link GeodesicLine} object. + *

    + * This function sets point 3 of the GeodesicLine to correspond to point 2 + * of the direct geodesic problem. + *

    + * lat1 should be in the range [−90°, 90°]. + **********************************************************************/ + public GeodesicLine DirectLine(double lat1, double lon1, double azi1, + double s12) { + return DirectLine(lat1, lon1, azi1, s12, GeodesicMask.ALL); + } + + /** + * Define a {@link GeodesicLine} in terms of the direct geodesic problem + * specified in terms of distance with a subset of the capabilities included. + *

    + * @param lat1 latitude of point 1 (degrees). + * @param lon1 longitude of point 1 (degrees). + * @param azi1 azimuth at point 1 (degrees). + * @param s12 distance between point 1 and point 2 (meters); it can be + * negative. + * @param caps bitor'ed combination of {@link GeodesicMask} values + * specifying the capabilities the GeodesicLine object should possess, + * i.e., which quantities can be returned in calls to + * {@link GeodesicLine#Position GeodesicLine.Position}. + * @return a {@link GeodesicLine} object. + *

    + * This function sets point 3 of the GeodesicLine to correspond to point 2 + * of the direct geodesic problem. + *

    + * lat1 should be in the range [−90°, 90°]. + **********************************************************************/ + public GeodesicLine DirectLine(double lat1, double lon1, double azi1, + double s12, int caps) { + return GenDirectLine(lat1, lon1, azi1, false, s12, caps); + } + + /** + * Define a {@link GeodesicLine} in terms of the direct geodesic problem + * specified in terms of arc length with all capabilities included. + *

    + * @param lat1 latitude of point 1 (degrees). + * @param lon1 longitude of point 1 (degrees). + * @param azi1 azimuth at point 1 (degrees). + * @param a12 arc length between point 1 and point 2 (degrees); it can + * be negative. + * @return a {@link GeodesicLine} object. + *

    + * This function sets point 3 of the GeodesicLine to correspond to point 2 + * of the direct geodesic problem. + *

    + * lat1 should be in the range [−90°, 90°]. + **********************************************************************/ + public GeodesicLine ArcDirectLine(double lat1, double lon1, double azi1, + double a12) { + return ArcDirectLine(lat1, lon1, azi1, a12, GeodesicMask.ALL); + } + + /** + * Define a {@link GeodesicLine} in terms of the direct geodesic problem + * specified in terms of arc length with a subset of the capabilities + * included. + *

    + * @param lat1 latitude of point 1 (degrees). + * @param lon1 longitude of point 1 (degrees). + * @param azi1 azimuth at point 1 (degrees). + * @param a12 arc length between point 1 and point 2 (degrees); it can + * be negative. + * @param caps bitor'ed combination of {@link GeodesicMask} values + * specifying the capabilities the GeodesicLine object should possess, + * i.e., which quantities can be returned in calls to + * {@link GeodesicLine#Position GeodesicLine.Position}. + * @return a {@link GeodesicLine} object. + *

    + * This function sets point 3 of the GeodesicLine to correspond to point 2 + * of the direct geodesic problem. + *

    + * lat1 should be in the range [−90°, 90°]. + **********************************************************************/ + public GeodesicLine ArcDirectLine(double lat1, double lon1, double azi1, + double a12, int caps) { + return GenDirectLine(lat1, lon1, azi1, true, a12, caps); + } + + /** + * Define a {@link GeodesicLine} in terms of the direct geodesic problem + * specified in terms of either distance or arc length with a subset of the + * capabilities included. + *

    + * @param lat1 latitude of point 1 (degrees). + * @param lon1 longitude of point 1 (degrees). + * @param azi1 azimuth at point 1 (degrees). + * @param arcmode boolean flag determining the meaning of the s12_a12. + * @param s12_a12 if arcmode is false, this is the distance between + * point 1 and point 2 (meters); otherwise it is the arc length between + * point 1 and point 2 (degrees); it can be negative. + * @param caps bitor'ed combination of {@link GeodesicMask} values + * specifying the capabilities the GeodesicLine object should possess, + * i.e., which quantities can be returned in calls to + * {@link GeodesicLine#Position GeodesicLine.Position}. + * @return a {@link GeodesicLine} object. + *

    + * This function sets point 3 of the GeodesicLine to correspond to point 2 + * of the direct geodesic problem. + *

    + * lat1 should be in the range [−90°, 90°]. + **********************************************************************/ + public GeodesicLine GenDirectLine(double lat1, double lon1, double azi1, + boolean arcmode, double s12_a12, int caps) + { + azi1 = GeoMath.AngNormalize(azi1); + double salp1, calp1; + // Guard against underflow in salp0. Also -0 is converted to +0. + { Pair p = GeoMath.sincosd(GeoMath.AngRound(azi1)); + salp1 = p.first; calp1 = p.second; } + // Automatically supply DISTANCE_IN if necessary + if (!arcmode) caps |= GeodesicMask.DISTANCE_IN; + return new GeodesicLine(this, lat1, lon1, azi1, salp1, calp1, + caps, arcmode, s12_a12); + } + /** * Solve the inverse geodesic problem. *

    @@ -485,9 +600,8 @@ public class Geodesic { * azi2, s12, a12. *

    * lat1 and lat2 should be in the range [−90°, - * 90°]; lon1 and lon2 should be in the range - * [−540°, 540°). The values of azi1 and azi2 - * returned are in the range [−180°, 180°). + * 90°]. The values of azi1 and azi2 returned are in the + * range [−180°, 180°]. *

    * If either point is at a pole, the azimuth is defined by keeping the * longitude fixed, writing lat = ±(90° − ε), @@ -500,66 +614,52 @@ public class Geodesic { **********************************************************************/ public GeodesicData Inverse(double lat1, double lon1, double lat2, double lon2) { - return Inverse(lat1, lon1, lat2, lon2, - GeodesicMask.DISTANCE | GeodesicMask.AZIMUTH); + return Inverse(lat1, lon1, lat2, lon2, GeodesicMask.STANDARD); } - /** - * Solve the inverse geodesic problem with a subset of the geodesic results - * returned. - *

    - * @param lat1 latitude of point 1 (degrees). - * @param lon1 longitude of point 1 (degrees). - * @param lat2 latitude of point 2 (degrees). - * @param lon2 longitude of point 2 (degrees). - * @param outmask a bitor'ed combination of {@link GeodesicMask} values - * specifying which results should be returned. - * @return a {@link GeodesicData} object with the fields specified by - * outmask computed. - *

    - * The {@link GeodesicMask} values possible for outmask are - *

      - *
    • - * outmask |= GeodesicMask.DISTANCE for the distance s12; - *
    • - * outmask |= GeodesicMask.AZIMUTH for the latitude azi2; - *
    • - * outmask |= GeodesicMask.REDUCEDLENGTH for the reduced length - * m12; - *
    • - * outmask |= GeodesicMask.GEODESICSCALE for the geodesic scales - * M12 and M21; - *
    • - * outmask |= GeodesicMask.AREA for the area S12; - *
    • - * outmask |= GeodesicMask.ALL for all of the above. - *
    - *

    - * lat1, lon1, lat2, lon2, and a12 are - * always included in the returned result. - **********************************************************************/ - public GeodesicData Inverse(double lat1, double lon1, - double lat2, double lon2, int outmask) { - outmask &= GeodesicMask.OUT_ALL; - GeodesicData r = new GeodesicData(); - lon1 = GeoMath.AngNormalize(lon1); - lon2 = GeoMath.AngNormalize(lon2); + private class InverseData { + private GeodesicData g; + private double salp1, calp1, salp2, calp2; + private InverseData() { + g = new GeodesicData(); + salp1 = calp1 = salp2 = calp2 = Double.NaN; + } + } + + private InverseData InverseInt(double lat1, double lon1, + double lat2, double lon2, int outmask) { + InverseData result = new InverseData(); + GeodesicData r = result.g; // Compute longitude difference (AngDiff does this carefully). Result is // in [-180, 180] but -180 is only for west-going geodesics. 180 is for // east-going and meridional geodesics. - double lon12 = GeoMath.AngDiff(lon1, lon2); - // If very close to being on the same half-meridian, then make it so. - lon12 = AngRound(lon12); + r.lat1 = lat1 = GeoMath.LatFix(lat1); r.lat2 = lat2 = GeoMath.LatFix(lat2); + // If really close to the equator, treat as on equator. + lat1 = GeoMath.AngRound(lat1); + lat2 = GeoMath.AngRound(lat2); + double lon12, lon12s; + { + Pair p = GeoMath.AngDiff(lon1, lon2); + lon12 = p.first; lon12s = p.second; + } + if ((outmask & GeodesicMask.LONG_UNROLL) != 0) { + r.lon1 = lon1; r.lon2 = (lon1 + lon12) + lon12s; + } else { + r.lon1 = GeoMath.AngNormalize(lon1); r.lon2 = GeoMath.AngNormalize(lon2); + } // Make longitude difference positive. int lonsign = lon12 >= 0 ? 1 : -1; - lon12 *= lonsign; - // If really close to the equator, treat as on equator. - lat1 = AngRound(lat1); - lat2 = AngRound(lat2); - // Save input parameters post normalization - r.lat1 = lat1; r.lon1 = lon1; r.lat2 = lat2; r.lon2 = lon2; + // If very close to being on the same half-meridian, then make it so. + lon12 = lonsign * GeoMath.AngRound(lon12); + lon12s = GeoMath.AngRound((180 - lon12) - lonsign * lon12s); + double + lam12 = Math.toRadians(lon12), slam12, clam12; + { Pair p = GeoMath.sincosd(lon12 > 90 ? lon12s : lon12); + slam12 = p.first; clam12 = (lon12 > 90 ? -1 : 1) * p.second; } + // Swap points so that point with higher (abs) latitude is point 1 - int swapp = Math.abs(lat1) >= Math.abs(lat2) ? 1 : -1; + // If one latitude is a nan, then it becomes lat1. + int swapp = Math.abs(lat1) < Math.abs(lat2) ? -1 : 1; if (swapp < 0) { lonsign *= -1; { double t = lat1; lat1 = lat2; lat2 = t; } @@ -580,22 +680,21 @@ public class Geodesic { // check, e.g., on verifying quadrants in atan2. In addition, this // enforces some symmetries in the results returned. - double phi, sbet1, cbet1, sbet2, cbet2, s12x, m12x; + double sbet1, cbet1, sbet2, cbet2, s12x, m12x; s12x = m12x = Double.NaN; - phi = lat1 * GeoMath.degree; - // Ensure cbet1 = +epsilon at poles - sbet1 = _f1 * Math.sin(phi); - cbet1 = lat1 == -90 ? tiny_ : Math.cos(phi); - { Pair p = SinCosNorm(sbet1, cbet1); - sbet1 = p.first; cbet1 = p.second; } + { Pair p = GeoMath.sincosd(lat1); + sbet1 = _f1 * p.first; cbet1 = p.second; } + // Ensure cbet1 = +epsilon at poles; doing the fix on beta means that sig12 + // will be <= 2*tiny for two points at the same pole. + { Pair p = GeoMath.norm(sbet1, cbet1); sbet1 = p.first; cbet1 = p.second; } + cbet1 = Math.max(tiny_, cbet1); - phi = lat2 * GeoMath.degree; + { Pair p = GeoMath.sincosd(lat2); + sbet2 = _f1 * p.first; cbet2 = p.second; } // Ensure cbet2 = +epsilon at poles - sbet2 = _f1 * Math.sin(phi); - cbet2 = Math.abs(lat2) == 90 ? tiny_ : Math.cos(phi); - { Pair p = SinCosNorm(sbet2, cbet2); - sbet2 = p.first; cbet2 = p.second; } + { Pair p = GeoMath.norm(sbet2, cbet2); sbet2 = p.first; cbet2 = p.second; } + cbet2 = Math.max(tiny_, cbet2); // If cbet1 < -sbet1, then cbet2 - cbet1 is a sensitive measure of the // |bet1| - |bet2|. Alternatively (cbet1 >= -sbet1), abs(sbet2) + sbet1 is @@ -617,11 +716,6 @@ public class Geodesic { dn1 = Math.sqrt(1 + _ep2 * GeoMath.sq(sbet1)), dn2 = Math.sqrt(1 + _ep2 * GeoMath.sq(sbet2)); - double - lam12 = lon12 * GeoMath.degree, - slam12 = Math.abs(lon12) == 180 ? 0 : Math.sin(lam12), - clam12 = Math.cos(lam12); // lon12 == 90 isn't interesting - double a12, sig12, calp1, salp1, calp2, salp2; a12 = sig12 = calp1 = salp1 = calp2 = salp2 = Double.NaN; // index zero elements of these arrays are unused @@ -645,13 +739,14 @@ public class Geodesic { ssig2 = sbet2, csig2 = calp2 * cbet2; // sig12 = sig2 - sig1 - sig12 = Math.atan2(Math.max(csig1 * ssig2 - ssig1 * csig2, 0.0), - csig1 * csig2 + ssig1 * ssig2); + sig12 = Math.atan2(Math.max(0.0, csig1 * ssig2 - ssig1 * csig2), + csig1 * csig2 + ssig1 * ssig2); { LengthsV v = - Lengths(_n, sig12, ssig1, csig1, dn1, ssig2, csig2, dn2, - cbet1, cbet2, - (outmask & GeodesicMask.GEODESICSCALE) != 0, C1a, C2a); + Lengths(_n, sig12, ssig1, csig1, dn1, + ssig2, csig2, dn2, cbet1, cbet2, + outmask | GeodesicMask.DISTANCE | GeodesicMask.REDUCEDLENGTH, + C1a, C2a); s12x = v.s12b; m12x = v.m12b; if ((outmask & GeodesicMask.GEODESICSCALE) != 0) { r.M12 = v.M12; r.M21 = v.M21; @@ -665,19 +760,22 @@ public class Geodesic { // In fact, we will have sig12 > pi/2 for meridional geodesic which is // not a shortest path. if (sig12 < 1 || m12x >= 0) { + // Need at least 2, to handle 90 0 90 180 + if (sig12 < 3 * tiny_) + sig12 = m12x = s12x = 0; m12x *= _b; s12x *= _b; - a12 = sig12 / GeoMath.degree; + a12 = Math.toDegrees(sig12); } else // m12 < 0, i.e., prolate and too close to anti-podal meridian = false; } - double omg12 = Double.NaN; + double omg12 = Double.NaN, somg12 = 2, comg12 = Double.NaN; if (!meridian && sbet1 == 0 && // and sbet2 == 0 // Mimic the way Lambda12 works with calp1 = 0 - (_f <= 0 || lam12 <= Math.PI - _f * Math.PI)) { + (_f <= 0 || lon12s >= _f * 180)) { // Geodesic runs along equator calp1 = calp2 = 0; salp1 = salp2 = 1; @@ -698,7 +796,7 @@ public class Geodesic { { InverseStartV v = InverseStart(sbet1, cbet1, dn1, sbet2, cbet2, dn2, - lam12, + lam12, slam12, clam12, C1a, C2a); sig12 = v.sig12; salp1 = v.salp1; calp1 = v.calp1; @@ -712,7 +810,7 @@ public class Geodesic { m12x = GeoMath.sq(dnm) * _b * Math.sin(sig12 / dnm); if ((outmask & GeodesicMask.GEODESICSCALE) != 0) r.M12 = r.M21 = Math.cos(sig12 / dnm); - a12 = sig12 / GeoMath.degree; + a12 = Math.toDegrees(sig12); omg12 = lam12 / (_f1 * dnm); } else { @@ -727,8 +825,8 @@ public class Geodesic { // value of alp1 is then further from the solution) or if the new // estimate of alp1 lies outside (0,pi); in this case, the new starting // guess is taken to be (alp1a + alp1b) / 2. - double ssig1, csig1, ssig2, csig2, eps; - ssig1 = csig1 = ssig2 = csig2 = eps = Double.NaN; + double ssig1, csig1, ssig2, csig2, eps, domg12; + ssig1 = csig1 = ssig2 = csig2 = eps = domg12 = Double.NaN; int numit = 0; // Bracketing range double salp1a = tiny_, calp1a = 1, salp1b = tiny_, calp1b = -1; @@ -739,18 +837,18 @@ public class Geodesic { { Lambda12V w = Lambda12(sbet1, cbet1, dn1, sbet2, cbet2, dn2, salp1, calp1, - numit < maxit1_, C1a, C2a, C3a); - v = w.lam12 - lam12; + slam12, clam12, numit < maxit1_, C1a, C2a, C3a); + v = w.lam12; salp2 = w.salp2; calp2 = w.calp2; sig12 = w.sig12; ssig1 = w.ssig1; csig1 = w.csig1; ssig2 = w.ssig2; csig2 = w.csig2; - eps = w.eps; omg12 = w.domg12; + eps = w.eps; domg12 = w.domg12; dv = w.dlam12; } // 2 * tol0 is approximately 1 ulp for a number in [0, pi]. // Reversed test to allow escape with NaNs - if (tripb || !(Math.abs(v) >= (tripn ? 8 : 2) * tol0_)) break; + if (tripb || !(Math.abs(v) >= (tripn ? 8 : 1) * tol0_)) break; // Update bracketing values if (v > 0 && (numit > maxit1_ || calp1/salp1 > calp1b/salp1b)) { salp1b = salp1; calp1b = calp1; } @@ -765,7 +863,7 @@ public class Geodesic { if (nsalp1 > 0 && Math.abs(dalp1) < Math.PI) { calp1 = calp1 * cdalp1 - salp1 * sdalp1; salp1 = nsalp1; - { Pair p = SinCosNorm(salp1, calp1); + { Pair p = GeoMath.norm(salp1, calp1); salp1 = p.first; calp1 = p.second; } // In some regimes we don't get quadratic convergence because // slope -> 0. So use convergence conditions based on epsilon @@ -774,7 +872,7 @@ public class Geodesic { continue; } } - // Either dv was not postive or updated value was outside legal + // Either dv was not positive or updated value was outside legal // range. Use the midpoint of the bracket as the next estimate. // This mechanism is not needed for the WGS84 ellipsoid, but it does // catch problems with more eccentric ellipsoids. Its efficacy is @@ -784,17 +882,23 @@ public class Geodesic { // WGS84 and random input: mean = 4.74, sd = 0.99 salp1 = (salp1a + salp1b)/2; calp1 = (calp1a + calp1b)/2; - { Pair p = SinCosNorm(salp1, calp1); + { Pair p = GeoMath.norm(salp1, calp1); salp1 = p.first; calp1 = p.second; } tripn = false; tripb = (Math.abs(salp1a - salp1) + (calp1a - calp1) < tolb_ || Math.abs(salp1 - salp1b) + (calp1 - calp1b) < tolb_); } { + // Ensure that the reduced length and geodesic scale are computed in + // a "canonical" way, with the I2 integral. + int lengthmask = outmask | + ((outmask & + (GeodesicMask.REDUCEDLENGTH | GeodesicMask.GEODESICSCALE)) != 0 ? + GeodesicMask.DISTANCE : GeodesicMask.NONE); LengthsV v = - Lengths(eps, sig12, ssig1, csig1, dn1, ssig2, csig2, dn2, - cbet1, cbet2, - (outmask & GeodesicMask.GEODESICSCALE) != 0, C1a, C2a); + Lengths(eps, sig12, + ssig1, csig1, dn1, ssig2, csig2, dn2, cbet1, cbet2, + lengthmask, C1a, C2a); s12x = v.s12b; m12x = v.m12b; if ((outmask & GeodesicMask.GEODESICSCALE) != 0) { r.M12 = v.M12; r.M21 = v.M21; @@ -802,8 +906,13 @@ public class Geodesic { } m12x *= _b; s12x *= _b; - a12 = sig12 / GeoMath.degree; - omg12 = lam12 - omg12; + a12 = Math.toDegrees(sig12); + if ((outmask & GeodesicMask.AREA) != 0) { + // omg12 = lam12 - domg12 + double sdomg12 = Math.sin(domg12), cdomg12 = Math.cos(domg12); + somg12 = slam12 * cdomg12 - clam12 * sdomg12; + comg12 = clam12 * cdomg12 + slam12 * sdomg12; + } } } @@ -828,9 +937,9 @@ public class Geodesic { eps = k2 / (2 * (1 + Math.sqrt(1 + k2)) + k2), // Multiplier = a^2 * e^2 * cos(alpha0) * sin(alpha0). A4 = GeoMath.sq(_a) * calp0 * salp0 * _e2; - { Pair p = SinCosNorm(ssig1, csig1); + { Pair p = GeoMath.norm(ssig1, csig1); ssig1 = p.first; csig1 = p.second; } - { Pair p = SinCosNorm(ssig2, csig2); + { Pair p = GeoMath.norm(ssig2, csig2); ssig2 = p.first; csig2 = p.second; } double C4a[] = new double[nC4_]; C4f(eps, C4a); @@ -842,15 +951,18 @@ public class Geodesic { // Avoid problems with indeterminate sig1, sig2 on equator r.S12 = 0; + if (!meridian && somg12 > 1) { + somg12 = Math.sin(omg12); comg12 = Math.cos(omg12); + } + if (!meridian && - omg12 < 0.75 * Math.PI && // Long difference too big - sbet2 - sbet1 < 1.75) { // Lat difference too big + comg12 > -0.7071 && // Long difference not too big + sbet2 - sbet1 < 1.75) { // Lat difference not too big // Use tan(Gamma/2) = tan(omg12/2) // * (tan(bet1/2)+tan(bet2/2))/(1+tan(bet1/2)*tan(bet2/2)) // with tan(x/2) = sin(x)/(1+cos(x)) double - somg12 = Math.sin(omg12), domg12 = 1 + Math.cos(omg12), - dbet1 = 1 + cbet1, dbet2 = 1 + cbet2; + domg12 = 1 + comg12, dbet1 = 1 + cbet1, dbet2 = 1 + cbet2; alp12 = 2 * Math.atan2( somg12 * ( sbet1 * dbet2 + sbet2 * dbet1 ), domg12 * ( sbet1 * sbet2 + dbet1 * dbet2 ) ); } else { @@ -885,27 +997,131 @@ public class Geodesic { salp1 *= swapp * lonsign; calp1 *= swapp * latsign; salp2 *= swapp * lonsign; calp2 *= swapp * latsign; - if ((outmask & GeodesicMask.AZIMUTH) != 0) { - // minus signs give range [-180, 180). 0- converts -0 to +0. - r.azi1 = 0 - Math.atan2(-salp1, calp1) / GeoMath.degree; - r.azi2 = 0 - Math.atan2(-salp2, calp2) / GeoMath.degree; - } // Returned value in [0, 180] r.a12 = a12; + result.salp1 = salp1; result.calp1 = calp1; + result.salp2 = salp2; result.calp2 = calp2; + return result; + } + + /** + * Solve the inverse geodesic problem with a subset of the geodesic results + * returned. + *

    + * @param lat1 latitude of point 1 (degrees). + * @param lon1 longitude of point 1 (degrees). + * @param lat2 latitude of point 2 (degrees). + * @param lon2 longitude of point 2 (degrees). + * @param outmask a bitor'ed combination of {@link GeodesicMask} values + * specifying which results should be returned. + * @return a {@link GeodesicData} object with the fields specified by + * outmask computed. + *

    + * The {@link GeodesicMask} values possible for outmask are + *

      + *
    • + * outmask |= {@link GeodesicMask#DISTANCE} for the distance + * s12; + *
    • + * outmask |= {@link GeodesicMask#AZIMUTH} for the latitude + * azi2; + *
    • + * outmask |= {@link GeodesicMask#REDUCEDLENGTH} for the reduced + * length m12; + *
    • + * outmask |= {@link GeodesicMask#GEODESICSCALE} for the geodesic + * scales M12 and M21; + *
    • + * outmask |= {@link GeodesicMask#AREA} for the area S12; + *
    • + * outmask |= {@link GeodesicMask#ALL} for all of the above. + *
    • + * outmask |= {@link GeodesicMask#LONG_UNROLL}, if set then + * lon1 is unchanged and lon2lon1 indicates + * whether the geodesic is east going or west going. Otherwise lon1 + * and lon2 are both reduced to the range [−180°, + * 180°]. + *
    + *

    + * lat1, lon1, lat2, lon2, and a12 are + * always included in the returned result. + **********************************************************************/ + public GeodesicData Inverse(double lat1, double lon1, + double lat2, double lon2, int outmask) { + outmask &= GeodesicMask.OUT_MASK; + InverseData result = InverseInt(lat1, lon1, lat2, lon2, outmask); + GeodesicData r = result.g; + if ((outmask & GeodesicMask.AZIMUTH) != 0) { + r.azi1 = GeoMath.atan2d(result.salp1, result.calp1); + r.azi2 = GeoMath.atan2d(result.salp2, result.calp2); + } return r; } /** - * Set up to compute several points on a single geodesic. + * Define a {@link GeodesicLine} in terms of the inverse geodesic problem + * with all capabilities included. + *

    + * @param lat1 latitude of point 1 (degrees). + * @param lon1 longitude of point 1 (degrees). + * @param lat2 latitude of point 2 (degrees). + * @param lon2 longitude of point 2 (degrees). + * @return a {@link GeodesicLine} object. + *

    + * This function sets point 3 of the GeodesicLine to correspond to point 2 + * of the inverse geodesic problem. + *

    + * lat1 and lat2 should be in the range [−90°, + * 90°]. + **********************************************************************/ + public GeodesicLine InverseLine(double lat1, double lon1, + double lat2, double lon2) { + return InverseLine(lat1, lon1, lat2, lon2, GeodesicMask.ALL); + } + + /** + * Define a {@link GeodesicLine} in terms of the inverse geodesic problem + * with a subset of the capabilities included. + *

    + * @param lat1 latitude of point 1 (degrees). + * @param lon1 longitude of point 1 (degrees). + * @param lat2 latitude of point 2 (degrees). + * @param lon2 longitude of point 2 (degrees). + * @param caps bitor'ed combination of {@link GeodesicMask} values specifying + * the capabilities the GeodesicLine object should possess, i.e., which + * quantities can be returned in calls to + * {@link GeodesicLine#Position GeodesicLine.Position}. + * @return a {@link GeodesicLine} object. + *

    + * This function sets point 3 of the GeodesicLine to correspond to point 2 + * of the inverse geodesic problem. + *

    + * lat1 and lat2 should be in the range [−90°, + * 90°]. + **********************************************************************/ + public GeodesicLine InverseLine(double lat1, double lon1, + double lat2, double lon2, int caps) { + InverseData result = InverseInt(lat1, lon1, lat2, lon2, 0); + double salp1 = result.salp1, calp1 = result.calp1, + azi1 = GeoMath.atan2d(salp1, calp1), a12 = result.g.a12; + // Ensure that a12 can be converted to a distance + if ((caps & (GeodesicMask.OUT_MASK & GeodesicMask.DISTANCE_IN)) != 0) + caps |= GeodesicMask.DISTANCE; + return new GeodesicLine(this, lat1, lon1, azi1, salp1, calp1, caps, + true, a12); + } + + /** + * Set up to compute several points on a single geodesic with all + * capabilities included. *

    * @param lat1 latitude of point 1 (degrees). * @param lon1 longitude of point 1 (degrees). * @param azi1 azimuth at point 1 (degrees). * @return a {@link GeodesicLine} object. *

    - * lat1 should be in the range [−90°, 90°]; lon1 - * and azi1 should be in the range [−540°, 540°). The - * full set of capabilities is included. + * lat1 should be in the range [−90°, 90°]. The full + * set of capabilities is included. *

    * If the point is at a pole, the azimuth is defined by keeping the * lon1 fixed, writing lat1 = ±(90 − ε), @@ -930,29 +1146,31 @@ public class Geodesic { * The {@link GeodesicMask} values are *

      *
    • - * caps |= GeodesicMask.LATITUDE for the latitude lat2; this - * is added automatically; + * caps |= {@link GeodesicMask#LATITUDE} for the latitude + * lat2; this is added automatically; *
    • - * caps |= GeodesicMask.LONGITUDE for the latitude lon2; + * caps |= {@link GeodesicMask#LONGITUDE} for the latitude + * lon2; *
    • - * caps |= GeodesicMask.AZIMUTH for the azimuth azi2; this is - * added automatically; + * caps |= {@link GeodesicMask#AZIMUTH} for the azimuth azi2; + * this is added automatically; *
    • - * caps |= GeodesicMask.DISTANCE for the distance s12; + * caps |= {@link GeodesicMask#DISTANCE} for the distance + * s12; *
    • - * caps |= GeodesicMask.REDUCEDLENGTH for the reduced length + * caps |= {@link GeodesicMask#REDUCEDLENGTH} for the reduced length * m12; *
    • - * caps |= GeodesicMask.GEODESICSCALE for the geodesic scales - * M12 and M21; + * caps |= {@link GeodesicMask#GEODESICSCALE} for the geodesic + * scales M12 and M21; *
    • - * caps |= GeodesicMask.AREA for the area S12; + * caps |= {@link GeodesicMask#AREA} for the area S12; *
    • - * caps |= GeodesicMask.DISTANCE_IN permits the length of the - * geodesic to be given in terms of s12; without this capability the - * length can only be specified in terms of arc length; + * caps |= {@link GeodesicMask#DISTANCE_IN} permits the length of + * the geodesic to be given in terms of s12; without this capability + * the length can only be specified in terms of arc length; *
    • - * caps |= GeodesicMask.ALL for all of the above. + * caps |= {@link GeodesicMask#ALL} for all of the above. *
    *

    * If the point is at a pole, the azimuth is defined by keeping lon1 @@ -987,7 +1205,7 @@ public class Geodesic { * ellipsoid. **********************************************************************/ public static final Geodesic WGS84 = - new Geodesic(Constants.WGS84_a, Constants.WGS84_f); + new Geodesic(Constants.WGS84_a, Constants.WGS84_f); // This is a reformulation of the geodesic problem. The notation is as // follows: @@ -1016,7 +1234,9 @@ public class Geodesic { // sum(c[i] * cos((2*i+1) * x), i, 0, n-1) // using Clenshaw summation. N.B. c[0] is unused for sin series // Approx operation count = (n + 5) mult and (2 * n + 2) add - int k = c.length, n = k - (sinp ? 1 : 0); + int + k = c.length, // Point to one beyond last element + n = k - (sinp ? 1 : 0); double ar = 2 * (cosx - sinx) * (cosx + sinx), // 2 * cos(2 * x) y0 = (n & 1) != 0 ? c[--k] : 0, y1 = 0; // accumulators for sum @@ -1043,31 +1263,56 @@ public class Geodesic { double ssig1, double csig1, double dn1, double ssig2, double csig2, double dn2, double cbet1, double cbet2, - boolean scalep, + int outmask, // Scratch areas of the right size double C1a[], double C2a[]) { // Return m12b = (reduced length)/_b; also calculate s12b = distance/_b, // and m0 = coefficient of secular term in expression for reduced length. + outmask &= GeodesicMask.OUT_MASK; LengthsV v = new LengthsV(); // To hold s12b, m12b, m0, M12, M21; - C1f(eps, C1a); - C2f(eps, C2a); - double - A1m1 = A1m1f(eps), - AB1 = (1 + A1m1) * (SinCosSeries(true, ssig2, csig2, C1a) - - SinCosSeries(true, ssig1, csig1, C1a)), - A2m1 = A2m1f(eps), - AB2 = (1 + A2m1) * (SinCosSeries(true, ssig2, csig2, C2a) - - SinCosSeries(true, ssig1, csig1, C2a)); - v.m0 = A1m1 - A2m1; - double J12 = v.m0 * sig12 + (AB1 - AB2); - // Missing a factor of _b. - // Add parens around (csig1 * ssig2) and (ssig1 * csig2) to ensure accurate - // cancellation in the case of coincident points. - v.m12b = dn2 * (csig1 * ssig2) - dn1 * (ssig1 * csig2) - - csig1 * csig2 * J12; - // Missing a factor of _b - v.s12b = (1 + A1m1) * sig12 + AB1; - if (scalep) { + + double m0x = 0, J12 = 0, A1 = 0, A2 = 0; + if ((outmask & (GeodesicMask.DISTANCE | GeodesicMask.REDUCEDLENGTH | + GeodesicMask.GEODESICSCALE)) != 0) { + A1 = A1m1f(eps); + C1f(eps, C1a); + if ((outmask & (GeodesicMask.REDUCEDLENGTH | + GeodesicMask.GEODESICSCALE)) != 0) { + A2 = A2m1f(eps); + C2f(eps, C2a); + m0x = A1 - A2; + A2 = 1 + A2; + } + A1 = 1 + A1; + } + if ((outmask & GeodesicMask.DISTANCE) != 0) { + double B1 = SinCosSeries(true, ssig2, csig2, C1a) - + SinCosSeries(true, ssig1, csig1, C1a); + // Missing a factor of _b + v.s12b = A1 * (sig12 + B1); + if ((outmask & (GeodesicMask.REDUCEDLENGTH | + GeodesicMask.GEODESICSCALE)) != 0) { + double B2 = SinCosSeries(true, ssig2, csig2, C2a) - + SinCosSeries(true, ssig1, csig1, C2a); + J12 = m0x * sig12 + (A1 * B1 - A2 * B2); + } + } else if ((outmask & (GeodesicMask.REDUCEDLENGTH | + GeodesicMask.GEODESICSCALE)) != 0) { + // Assume here that nC1_ >= nC2_ + for (int l = 1; l <= nC2_; ++l) + C2a[l] = A1 * C1a[l] - A2 * C2a[l]; + J12 = m0x * sig12 + (SinCosSeries(true, ssig2, csig2, C2a) - + SinCosSeries(true, ssig1, csig1, C2a)); + } + if ((outmask & GeodesicMask.REDUCEDLENGTH) != 0) { + v.m0 = m0x; + // Missing a factor of _b. + // Add parens around (csig1 * ssig2) and (ssig1 * csig2) to ensure + // accurate cancellation in the case of coincident points. + v.m12b = dn2 * (csig1 * ssig2) - dn1 * (ssig1 * csig2) - + csig1 * csig2 * J12; + } + if ((outmask & GeodesicMask.GEODESICSCALE) != 0) { double csig12 = csig1 * csig2 + ssig1 * ssig2; double t = _ep2 * (cbet1 - cbet2) * (cbet1 + cbet2) / (dn1 + dn2); v.M12 = csig12 + (t * ssig2 - csig2 * J12) * ssig1 / dn1; @@ -1091,7 +1336,7 @@ public class Geodesic { S = p * q / 4, // S = r^3 * s r2 = GeoMath.sq(r), r3 = r * r2, - // The discrimant of the quadratic equation for T3. This is zero on + // The discriminant of the quadratic equation for T3. This is zero on // the evolute curve p^(1/3)+q^(1/3) = 1 disc = S * (S + 2 * r3); double u = r; @@ -1142,6 +1387,7 @@ public class Geodesic { private InverseStartV InverseStart(double sbet1, double cbet1, double dn1, double sbet2, double cbet2, double dn2, double lam12, + double slam12, double clam12, // Scratch areas of the right size double C1a[], double C2a[]) { // Return a starting point for Newton's method in salp1 and calp1 (function @@ -1158,16 +1404,18 @@ public class Geodesic { double sbet12a = sbet2 * cbet1 + cbet2 * sbet1; boolean shortline = cbet12 >= 0 && sbet12 < 0.5 && cbet2 * lam12 < 0.5; - double omg12 = lam12; + double somg12, comg12; if (shortline) { double sbetm2 = GeoMath.sq(sbet1 + sbet2); // sin((bet1+bet2)/2)^2 // = (sbet1 + sbet2)^2 / ((sbet1 + sbet2)^2 + (cbet1 + cbet2)^2) sbetm2 /= sbetm2 + GeoMath.sq(cbet1 + cbet2); w.dnm = Math.sqrt(1 + _ep2 * sbetm2); - omg12 /= _f1 * w.dnm; + double omg12 = lam12 / (_f1 * w.dnm); + somg12 = Math.sin(omg12); comg12 = Math.cos(omg12); + } else { + somg12 = slam12; comg12 = clam12; } - double somg12 = Math.sin(omg12), comg12 = Math.cos(omg12); w.salp1 = cbet2 * somg12; w.calp1 = comg12 >= 0 ? @@ -1183,7 +1431,7 @@ public class Geodesic { w.salp2 = cbet1 * somg12; w.calp2 = sbet12 - cbet1 * sbet2 * (comg12 >= 0 ? GeoMath.sq(somg12) / (1 + comg12) : 1 - comg12); - { Pair p = SinCosNorm(w.salp2, w.calp2); + { Pair p = GeoMath.norm(w.salp2, w.calp2); w.salp2 = p.first; w.calp2 = p.second; } // Set return value w.sig12 = Math.atan2(ssig12, csig12); @@ -1199,6 +1447,7 @@ public class Geodesic { // 56.320923501171 0 -56.320923501171 179.664747671772880215 // which otherwise fails with g++ 4.4.4 x86 -O3 double x; + double lam12x = Math.atan2(-slam12, -clam12); // lam12 - pi if (_f >= 0) { // In fact f == 0 does not get here // x = dlong, y = dlat { @@ -1209,7 +1458,7 @@ public class Geodesic { } betscale = lamscale * cbet1; - x = (lam12 - Math.PI) / lamscale; + x = lam12x / lamscale; y = sbet12a / betscale; } else { // _f < 0 // x = dlat, y = dlong @@ -1222,14 +1471,14 @@ public class Geodesic { LengthsV v = Lengths(_n, Math.PI + bet12a, sbet1, -cbet1, dn1, sbet2, cbet2, dn2, - cbet1, cbet2, false, C1a, C2a); + cbet1, cbet2, GeodesicMask.REDUCEDLENGTH, C1a, C2a); m12b = v.m12b; m0 = v.m0; x = -1 + m12b / (cbet1 * cbet2 * m0 * Math.PI); betscale = x < -0.01 ? sbet12a / x : -_f * GeoMath.sq(cbet1) * Math.PI; lamscale = betscale / cbet1; - y = (lam12 - Math.PI) / lamscale; + y = lam12x / lamscale; } if (y > -tol1_ && x > -1 - xthresh_) { @@ -1285,8 +1534,9 @@ public class Geodesic { w.calp1 = sbet12a - cbet2 * sbet1 * GeoMath.sq(somg12) / (1 - comg12); } } - if (w.salp1 > 0) // Sanity check on starting guess - { Pair p = SinCosNorm(w.salp1, w.calp1); + // Sanity check on starting guess. Backwards check allows NaN through. + if (!(w.salp1 <= 0)) + { Pair p = GeoMath.norm(w.salp1, w.calp1); w.salp1 = p.first; w.calp1 = p.second; } else { w.salp1 = 1; w.calp1 = 0; @@ -1306,6 +1556,7 @@ public class Geodesic { private Lambda12V Lambda12(double sbet1, double cbet1, double dn1, double sbet2, double cbet2, double dn2, double salp1, double calp1, + double slam120, double clam120, boolean diffp, // Scratch areas of the right size double C1a[], double C2a[], double C3a[]) { @@ -1324,14 +1575,14 @@ public class Geodesic { salp0 = salp1 * cbet1, calp0 = GeoMath.hypot(calp1, salp1 * sbet1); // calp0 > 0 - double somg1, comg1, somg2, comg2, omg12; + double somg1, comg1, somg2, comg2, somg12, comg12; // tan(bet1) = tan(sig1) * cos(alp1) // tan(omg1) = sin(alp0) * tan(sig1) = tan(omg1)=tan(alp1)*sin(bet1) w.ssig1 = sbet1; somg1 = salp0 * sbet1; w.csig1 = comg1 = calp1 * cbet1; - { Pair p = SinCosNorm(w.ssig1, w.csig1); + { Pair p = GeoMath.norm(w.ssig1, w.csig1); w.ssig1 = p.first; w.csig1 = p.second; } - // SinCosNorm(somg1, comg1); -- don't need to normalize! + // GeoMath.norm(somg1, comg1); -- don't need to normalize! // Enforce symmetries in the case abs(bet2) = -bet1. Need to be careful // about this case, since this can yield singularities in the Newton @@ -1352,35 +1603,36 @@ public class Geodesic { // tan(omg2) = sin(alp0) * tan(sig2). w.ssig2 = sbet2; somg2 = salp0 * sbet2; w.csig2 = comg2 = w.calp2 * cbet2; - { Pair p = SinCosNorm(w.ssig2, w.csig2); + { Pair p = GeoMath.norm(w.ssig2, w.csig2); w.ssig2 = p.first; w.csig2 = p.second; } - // SinCosNorm(somg2, comg2); -- don't need to normalize! + // GeoMath.norm(somg2, comg2); -- don't need to normalize! // sig12 = sig2 - sig1, limit to [0, pi] - w.sig12 = Math.atan2(Math.max(w.csig1 * w.ssig2 - w.ssig1 * w.csig2, 0.0), - w.csig1 * w.csig2 + w.ssig1 * w.ssig2); + w.sig12 = Math.atan2(Math.max(0.0, w.csig1 * w.ssig2 - w.ssig1 * w.csig2), + w.csig1 * w.csig2 + w.ssig1 * w.ssig2); // omg12 = omg2 - omg1, limit to [0, pi] - omg12 = Math.atan2(Math.max(comg1 * somg2 - somg1 * comg2, 0.0), - comg1 * comg2 + somg1 * somg2); - double B312, h0; + somg12 = Math.max(0.0, comg1 * somg2 - somg1 * comg2); + comg12 = comg1 * comg2 + somg1 * somg2; + // eta = omg12 - lam120 + double eta = Math.atan2(somg12 * clam120 - comg12 * slam120, + comg12 * clam120 + somg12 * slam120); + double B312; double k2 = GeoMath.sq(calp0) * _ep2; w.eps = k2 / (2 * (1 + Math.sqrt(1 + k2)) + k2); C3f(w.eps, C3a); B312 = (SinCosSeries(true, w.ssig2, w.csig2, C3a) - SinCosSeries(true, w.ssig1, w.csig1, C3a)); - h0 = -_f * A3f(w.eps); - w.domg12 = salp0 * h0 * (w.sig12 + B312); - w.lam12 = omg12 + w.domg12; + w.domg12 = -_f * A3f(w.eps) * salp0 * (w.sig12 + B312); + w.lam12 = eta + w.domg12; if (diffp) { if (w.calp2 == 0) w.dlam12 = - 2 * _f1 * dn1 / sbet1; else { - double dummy; LengthsV v = Lengths(w.eps, w.sig12, w.ssig1, w.csig1, dn1, w.ssig2, w.csig2, dn2, - cbet1, cbet2, false, C1a, C2a); + cbet1, cbet2, GeodesicMask.REDUCEDLENGTH, C1a, C2a); w.dlam12 = v.m12b; w.dlam12 *= _f1 / (w.calp2 * cbet2); } @@ -1390,174 +1642,262 @@ public class Geodesic { } protected double A3f(double eps) { - // Evaluate sum(_A3x[k] * eps^k, k, 0, nA3x_-1) by Horner's method - double v = 0; - for (int i = nA3x_; i > 0; ) - v = eps * v + _A3x[--i]; - return v; + // Evaluate A3 + return GeoMath.polyval(nA3_ - 1, _A3x, 0, eps); } protected void C3f(double eps, double c[]) { - // Evaluate C3 coeffs by Horner's method + // Evaluate C3 coeffs // Elements c[1] thru c[nC3_ - 1] are set - for (int j = nC3x_, k = nC3_ - 1; k > 0; ) { - double t = 0; - for (int i = nC3_ - k; i > 0; --i) - t = eps * t + _C3x[--j]; - c[k--] = t; - } - double mult = 1; - for (int k = 1; k < nC3_; ) { + int o = 0; + for (int l = 1; l < nC3_; ++l) { // l is index of C3[l] + int m = nC3_ - l - 1; // order of polynomial in eps mult *= eps; - c[k++] *= mult; + c[l] = mult * GeoMath.polyval(m, _C3x, o, eps); + o += m + 1; } } protected void C4f(double eps, double c[]) { - // Evaluate C4 coeffs by Horner's method + // Evaluate C4 coeffs // Elements c[0] thru c[nC4_ - 1] are set - for (int j = nC4x_, k = nC4_; k > 0; ) { - double t = 0; - for (int i = nC4_ - k + 1; i > 0; --i) - t = eps * t + _C4x[--j]; - c[--k] = t; - } - double mult = 1; - for (int k = 1; k < nC4_; ) { + int o = 0; + for (int l = 0; l < nC4_; ++l) { // l is index of C4[l] + int m = nC4_ - l - 1; // order of polynomial in eps + c[l] = mult * GeoMath.polyval(m, _C4x, o, eps); + o += m + 1; mult *= eps; - c[k++] *= mult; } } - // Generated by Maxima on 2010-09-04 10:26:17-04:00 - // The scale factor A1-1 = mean value of (d/dsigma)I1 - 1 protected static double A1m1f(double eps) { - double - eps2 = GeoMath.sq(eps), - t; - t = eps2*(eps2*(eps2+4)+64)/256; + final double coeff[] = { + // (1-eps)*A1-1, polynomial in eps2 of order 3 + 1, 4, 64, 0, 256, + }; + int m = nA1_/2; + double t = GeoMath.polyval(m, coeff, 0, GeoMath.sq(eps)) / coeff[m + 1]; return (t + eps) / (1 - eps); } // The coefficients C1[l] in the Fourier expansion of B1 protected static void C1f(double eps, double c[]) { + final double coeff[] = { + // C1[1]/eps^1, polynomial in eps2 of order 2 + -1, 6, -16, 32, + // C1[2]/eps^2, polynomial in eps2 of order 2 + -9, 64, -128, 2048, + // C1[3]/eps^3, polynomial in eps2 of order 1 + 9, -16, 768, + // C1[4]/eps^4, polynomial in eps2 of order 1 + 3, -5, 512, + // C1[5]/eps^5, polynomial in eps2 of order 0 + -7, 1280, + // C1[6]/eps^6, polynomial in eps2 of order 0 + -7, 2048, + }; double eps2 = GeoMath.sq(eps), d = eps; - c[1] = d*((6-eps2)*eps2-16)/32; - d *= eps; - c[2] = d*((64-9*eps2)*eps2-128)/2048; - d *= eps; - c[3] = d*(9*eps2-16)/768; - d *= eps; - c[4] = d*(3*eps2-5)/512; - d *= eps; - c[5] = -7*d/1280; - d *= eps; - c[6] = -7*d/2048; + int o = 0; + for (int l = 1; l <= nC1_; ++l) { // l is index of C1p[l] + int m = (nC1_ - l) / 2; // order of polynomial in eps^2 + c[l] = d * GeoMath.polyval(m, coeff, o, eps2) / coeff[o + m + 1]; + o += m + 2; + d *= eps; + } } // The coefficients C1p[l] in the Fourier expansion of B1p protected static void C1pf(double eps, double c[]) { + final double coeff[] = { + // C1p[1]/eps^1, polynomial in eps2 of order 2 + 205, -432, 768, 1536, + // C1p[2]/eps^2, polynomial in eps2 of order 2 + 4005, -4736, 3840, 12288, + // C1p[3]/eps^3, polynomial in eps2 of order 1 + -225, 116, 384, + // C1p[4]/eps^4, polynomial in eps2 of order 1 + -7173, 2695, 7680, + // C1p[5]/eps^5, polynomial in eps2 of order 0 + 3467, 7680, + // C1p[6]/eps^6, polynomial in eps2 of order 0 + 38081, 61440, + }; double eps2 = GeoMath.sq(eps), d = eps; - c[1] = d*(eps2*(205*eps2-432)+768)/1536; - d *= eps; - c[2] = d*(eps2*(4005*eps2-4736)+3840)/12288; - d *= eps; - c[3] = d*(116-225*eps2)/384; - d *= eps; - c[4] = d*(2695-7173*eps2)/7680; - d *= eps; - c[5] = 3467*d/7680; - d *= eps; - c[6] = 38081*d/61440; + int o = 0; + for (int l = 1; l <= nC1p_; ++l) { // l is index of C1p[l] + int m = (nC1p_ - l) / 2; // order of polynomial in eps^2 + c[l] = d * GeoMath.polyval(m, coeff, o, eps2) / coeff[o + m + 1]; + o += m + 2; + d *= eps; + } } // The scale factor A2-1 = mean value of (d/dsigma)I2 - 1 protected static double A2m1f(double eps) { - double - eps2 = GeoMath.sq(eps), - t; - t = eps2*(eps2*(25*eps2+36)+64)/256; - return t * (1 - eps) - eps; + final double coeff[] = { + // (eps+1)*A2-1, polynomial in eps2 of order 3 + -11, -28, -192, 0, 256, + }; + int m = nA2_/2; + double t = GeoMath.polyval(m, coeff, 0, GeoMath.sq(eps)) / coeff[m + 1]; + return (t - eps) / (1 + eps); } // The coefficients C2[l] in the Fourier expansion of B2 protected static void C2f(double eps, double c[]) { + final double coeff[] = { + // C2[1]/eps^1, polynomial in eps2 of order 2 + 1, 2, 16, 32, + // C2[2]/eps^2, polynomial in eps2 of order 2 + 35, 64, 384, 2048, + // C2[3]/eps^3, polynomial in eps2 of order 1 + 15, 80, 768, + // C2[4]/eps^4, polynomial in eps2 of order 1 + 7, 35, 512, + // C2[5]/eps^5, polynomial in eps2 of order 0 + 63, 1280, + // C2[6]/eps^6, polynomial in eps2 of order 0 + 77, 2048, + }; double eps2 = GeoMath.sq(eps), d = eps; - c[1] = d*(eps2*(eps2+2)+16)/32; - d *= eps; - c[2] = d*(eps2*(35*eps2+64)+384)/2048; - d *= eps; - c[3] = d*(15*eps2+80)/768; - d *= eps; - c[4] = d*(7*eps2+35)/512; - d *= eps; - c[5] = 63*d/1280; - d *= eps; - c[6] = 77*d/2048; + int o = 0; + for (int l = 1; l <= nC2_; ++l) { // l is index of C2[l] + int m = (nC2_ - l) / 2; // order of polynomial in eps^2 + c[l] = d * GeoMath.polyval(m, coeff, o, eps2) / coeff[o + m + 1]; + o += m + 2; + d *= eps; + } } // The scale factor A3 = mean value of (d/dsigma)I3 protected void A3coeff() { - _A3x[0] = 1; - _A3x[1] = (_n-1)/2; - _A3x[2] = (_n*(3*_n-1)-2)/8; - _A3x[3] = ((-_n-3)*_n-1)/16; - _A3x[4] = (-2*_n-3)/64; - _A3x[5] = -3/128.0; + final double coeff[] = { + // A3, coeff of eps^5, polynomial in n of order 0 + -3, 128, + // A3, coeff of eps^4, polynomial in n of order 1 + -2, -3, 64, + // A3, coeff of eps^3, polynomial in n of order 2 + -1, -3, -1, 16, + // A3, coeff of eps^2, polynomial in n of order 2 + 3, -1, -2, 8, + // A3, coeff of eps^1, polynomial in n of order 1 + 1, -1, 2, + // A3, coeff of eps^0, polynomial in n of order 0 + 1, 1, + }; + int o = 0, k = 0; + for (int j = nA3_ - 1; j >= 0; --j) { // coeff of eps^j + int m = Math.min(nA3_ - j - 1, j); // order of polynomial in n + _A3x[k++] = GeoMath.polyval(m, coeff, o, _n) / coeff[o + m + 1]; + o += m + 2; + } } // The coefficients C3[l] in the Fourier expansion of B3 protected void C3coeff() { - _C3x[0] = (1-_n)/4; - _C3x[1] = (1-_n*_n)/8; - _C3x[2] = ((3-_n)*_n+3)/64; - _C3x[3] = (2*_n+5)/128; - _C3x[4] = 3/128.0; - _C3x[5] = ((_n-3)*_n+2)/32; - _C3x[6] = ((-3*_n-2)*_n+3)/64; - _C3x[7] = (_n+3)/128; - _C3x[8] = 5/256.0; - _C3x[9] = (_n*(5*_n-9)+5)/192; - _C3x[10] = (9-10*_n)/384; - _C3x[11] = 7/512.0; - _C3x[12] = (7-14*_n)/512; - _C3x[13] = 7/512.0; - _C3x[14] = 21/2560.0; + final double coeff[] = { + // C3[1], coeff of eps^5, polynomial in n of order 0 + 3, 128, + // C3[1], coeff of eps^4, polynomial in n of order 1 + 2, 5, 128, + // C3[1], coeff of eps^3, polynomial in n of order 2 + -1, 3, 3, 64, + // C3[1], coeff of eps^2, polynomial in n of order 2 + -1, 0, 1, 8, + // C3[1], coeff of eps^1, polynomial in n of order 1 + -1, 1, 4, + // C3[2], coeff of eps^5, polynomial in n of order 0 + 5, 256, + // C3[2], coeff of eps^4, polynomial in n of order 1 + 1, 3, 128, + // C3[2], coeff of eps^3, polynomial in n of order 2 + -3, -2, 3, 64, + // C3[2], coeff of eps^2, polynomial in n of order 2 + 1, -3, 2, 32, + // C3[3], coeff of eps^5, polynomial in n of order 0 + 7, 512, + // C3[3], coeff of eps^4, polynomial in n of order 1 + -10, 9, 384, + // C3[3], coeff of eps^3, polynomial in n of order 2 + 5, -9, 5, 192, + // C3[4], coeff of eps^5, polynomial in n of order 0 + 7, 512, + // C3[4], coeff of eps^4, polynomial in n of order 1 + -14, 7, 512, + // C3[5], coeff of eps^5, polynomial in n of order 0 + 21, 2560, + }; + int o = 0, k = 0; + for (int l = 1; l < nC3_; ++l) { // l is index of C3[l] + for (int j = nC3_ - 1; j >= l; --j) { // coeff of eps^j + int m = Math.min(nC3_ - j - 1, j); // order of polynomial in n + _C3x[k++] = GeoMath.polyval(m, coeff, o, _n) / coeff[o + m + 1]; + o += m + 2; + } + } } - // Generated by Maxima on 2012-10-19 08:02:34-04:00 - - // The coefficients C4[l] in the Fourier expansion of I4 protected void C4coeff() { - _C4x[0] = (_n*(_n*(_n*(_n*(100*_n+208)+572)+3432)-12012)+30030)/45045; - _C4x[1] = (_n*(_n*(_n*(64*_n+624)-4576)+6864)-3003)/15015; - _C4x[2] = (_n*((14144-10656*_n)*_n-4576)-858)/45045; - _C4x[3] = ((-224*_n-4784)*_n+1573)/45045; - _C4x[4] = (1088*_n+156)/45045; - _C4x[5] = 97/15015.0; - _C4x[6] = (_n*(_n*((-64*_n-624)*_n+4576)-6864)+3003)/135135; - _C4x[7] = (_n*(_n*(5952*_n-11648)+9152)-2574)/135135; - _C4x[8] = (_n*(5792*_n+1040)-1287)/135135; - _C4x[9] = (468-2944*_n)/135135; - _C4x[10] = 1/9009.0; - _C4x[11] = (_n*((4160-1440*_n)*_n-4576)+1716)/225225; - _C4x[12] = ((4992-8448*_n)*_n-1144)/225225; - _C4x[13] = (1856*_n-936)/225225; - _C4x[14] = 8/10725.0; - _C4x[15] = (_n*(3584*_n-3328)+1144)/315315; - _C4x[16] = (1024*_n-208)/105105; - _C4x[17] = -136/63063.0; - _C4x[18] = (832-2560*_n)/405405; - _C4x[19] = -128/135135.0; - _C4x[20] = 128/99099.0; + final double coeff[] = { + // C4[0], coeff of eps^5, polynomial in n of order 0 + 97, 15015, + // C4[0], coeff of eps^4, polynomial in n of order 1 + 1088, 156, 45045, + // C4[0], coeff of eps^3, polynomial in n of order 2 + -224, -4784, 1573, 45045, + // C4[0], coeff of eps^2, polynomial in n of order 3 + -10656, 14144, -4576, -858, 45045, + // C4[0], coeff of eps^1, polynomial in n of order 4 + 64, 624, -4576, 6864, -3003, 15015, + // C4[0], coeff of eps^0, polynomial in n of order 5 + 100, 208, 572, 3432, -12012, 30030, 45045, + // C4[1], coeff of eps^5, polynomial in n of order 0 + 1, 9009, + // C4[1], coeff of eps^4, polynomial in n of order 1 + -2944, 468, 135135, + // C4[1], coeff of eps^3, polynomial in n of order 2 + 5792, 1040, -1287, 135135, + // C4[1], coeff of eps^2, polynomial in n of order 3 + 5952, -11648, 9152, -2574, 135135, + // C4[1], coeff of eps^1, polynomial in n of order 4 + -64, -624, 4576, -6864, 3003, 135135, + // C4[2], coeff of eps^5, polynomial in n of order 0 + 8, 10725, + // C4[2], coeff of eps^4, polynomial in n of order 1 + 1856, -936, 225225, + // C4[2], coeff of eps^3, polynomial in n of order 2 + -8448, 4992, -1144, 225225, + // C4[2], coeff of eps^2, polynomial in n of order 3 + -1440, 4160, -4576, 1716, 225225, + // C4[3], coeff of eps^5, polynomial in n of order 0 + -136, 63063, + // C4[3], coeff of eps^4, polynomial in n of order 1 + 1024, -208, 105105, + // C4[3], coeff of eps^3, polynomial in n of order 2 + 3584, -3328, 1144, 315315, + // C4[4], coeff of eps^5, polynomial in n of order 0 + -128, 135135, + // C4[4], coeff of eps^4, polynomial in n of order 1 + -2560, 832, 405405, + // C4[5], coeff of eps^5, polynomial in n of order 0 + 128, 99099, + }; + int o = 0, k = 0; + for (int l = 0; l < nC4_; ++l) { // l is index of C4[l] + for (int j = nC4_ - 1; j >= l; --j) { // coeff of eps^j + int m = nC4_ - j - 1; // order of polynomial in n + _C4x[k++] = GeoMath.polyval(m, coeff, o, _n) / coeff[o + m + 1]; + o += m + 2; + } + } } } diff --git a/gtsam/3rdparty/GeographicLib/java/src/main/java/net/sf/geographiclib/GeodesicData.java b/gtsam/3rdparty/GeographicLib/java/src/main/java/net/sf/geographiclib/GeodesicData.java index 1a667a5ed..0f07946d7 100644 --- a/gtsam/3rdparty/GeographicLib/java/src/main/java/net/sf/geographiclib/GeodesicData.java +++ b/gtsam/3rdparty/GeographicLib/java/src/main/java/net/sf/geographiclib/GeodesicData.java @@ -3,7 +3,7 @@ * * Copyright (c) Charles Karney (2013) and licensed * under the MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ package net.sf.geographiclib; diff --git a/gtsam/3rdparty/GeographicLib/java/src/main/java/net/sf/geographiclib/GeodesicLine.java b/gtsam/3rdparty/GeographicLib/java/src/main/java/net/sf/geographiclib/GeodesicLine.java index 61d29de6b..58c849515 100644 --- a/gtsam/3rdparty/GeographicLib/java/src/main/java/net/sf/geographiclib/GeodesicLine.java +++ b/gtsam/3rdparty/GeographicLib/java/src/main/java/net/sf/geographiclib/GeodesicLine.java @@ -1,9 +1,9 @@ /** * Implementation of the net.sf.geographiclib.GeodesicLine class * - * Copyright (c) Charles Karney (2013) and licensed + * Copyright (c) Charles Karney (2013-2017) and licensed * under the MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ package net.sf.geographiclib; @@ -12,14 +12,28 @@ package net.sf.geographiclib; *

    * GeodesicLine facilitates the determination of a series of points on a single * geodesic. The starting point (lat1, lon1) and the azimuth - * azi1 are specified in the constructor. {@link #Position Position} - * returns the location of point 2 a distance s12 along the geodesic. - * Alternatively {@link #ArcPosition ArcPosition} gives the position of point 2 - * an arc length a12 along the geodesic. + * azi1 are specified in the constructor; alternatively, the {@link + * Geodesic#Line Geodesic.Line} method can be used to create a GeodesicLine. + * {@link #Position Position} returns the location of point 2 a distance + * s12 along the geodesic. Alternatively {@link #ArcPosition + * ArcPosition} gives the position of point 2 an arc length a12 along + * the geodesic. + *

    + * You can register the position of a reference point 3 a distance (arc + * length), s13 (a13) along the geodesic with the + * {@link #SetDistance SetDistance} ({@link #SetArc SetArc}) functions. Points + * a fractional distance along the line can be found by providing, for example, + * 0.5 * {@link #Distance} as an argument to {@link #Position Position}. The + * {@link Geodesic#InverseLine Geodesic.InverseLine} or + * {@link Geodesic#DirectLine Geodesic.DirectLine} methods return GeodesicLine + * objects with point 3 set to the point 2 of the corresponding geodesic + * problem. GeodesicLine objects created with the public constructor or with + * {@link Geodesic#Line Geodesic.Line} have s13 and a13 set to + * NaNs. *

    * The calculations are accurate to better than 15 nm (15 nanometers). See * Sec. 9 of - * arXiv:1102.1215v1 for + * arXiv:1102.1215v1 for * details. The algorithms used by this class are based on series expansions * using the flattening f as a small parameter. These are only accurate * for |f| < 0.02; however reasonably accurate results will be @@ -29,13 +43,10 @@ package net.sf.geographiclib; *

    *

    * Here's an example of using this class @@ -49,30 +60,30 @@ package net.sf.geographiclib; * double * lat1 = 40.640, lon1 = -73.779, // JFK * lat2 = 1.359, lon2 = 103.989; // SIN - * GeodesicData g = geod.Inverse(lat1, lon1, lat2, lon2, - * GeodesicMask.DISTANCE | GeodesicMask.AZIMUTH); - * GeodesicLine line = new GeodesicLine(geod, lat1, lon1, g.azi1, - * GeodesicMask.DISTANCE_IN | GeodesicMask.LONGITUDE); - * double - * s12 = g.s12, - * a12 = g.a12, - * ds0 = 500e3; // Nominal distance between points = 500 km - * int num = (int)(Math.ceil(s12 / ds0)); // The number of intervals + * GeodesicLine line = geod.InverseLine(lat1, lon1, lat2, lon2, + * GeodesicMask.DISTANCE_IN | + * GeodesicMask.LATITUDE | + * GeodesicMask.LONGITUDE); + * double ds0 = 500e3; // Nominal distance between points = 500 km + * // The number of intervals + * int num = (int)(Math.ceil(line.Distance() / ds0)); * { * // Use intervals of equal length - * double ds = s12 / num; + * double ds = line.Distance() / num; * for (int i = 0; i <= num; ++i) { - * g = line.Position(i * ds, - * GeodesicMask.LATITUDE | GeodesicMask.LONGITUDE); + * GeodesicData g = line.Position(i * ds, + * GeodesicMask.LATITUDE | + * GeodesicMask.LONGITUDE); * System.out.println(i + " " + g.lat2 + " " + g.lon2); * } * } * { * // Slightly faster, use intervals of equal arc length - * double da = a12 / num; + * double da = line.Arc() / num; * for (int i = 0; i <= num; ++i) { - * g = line.ArcPosition(i * da, - * GeodesicMask.LATITUDE | GeodesicMask.LONGITUDE); + * GeodesicData g = line.ArcPosition(i * da, + * GeodesicMask.LATITUDE | + * GeodesicMask.LONGITUDE); * System.out.println(i + " " + g.lat2 + " " + g.lon2); * } * } @@ -91,6 +102,7 @@ public class GeodesicLine { private double _a, _f, _b, _c2, _f1, _salp0, _calp0, _k2, _salp1, _calp1, _ssig1, _csig1, _dn1, _stau1, _ctau1, _somg1, _comg1, _A1m1, _A2m1, _A3c, _B11, _B21, _B31, _A4, _B41; + private double _a13, _s13; // index zero elements of _C1a, _C1pa, _C2a, _C3a are unused private double _C1a[], _C1pa[], _C2a[], _C3a[], _C4a[]; // all the elements of _C4a are used @@ -106,8 +118,7 @@ public class GeodesicLine { * @param lon1 longitude of point 1 (degrees). * @param azi1 azimuth at point 1 (degrees). *

    - * lat1 should be in the range [−90°, 90°]; lon1 - * and azi1 should be in the range [−540°, 540°). + * lat1 should be in the range [−90°, 90°]. *

    * If the point is at a pole, the azimuth is defined by keeping lon1 * fixed, writing lat1 = ±(90° − ε), and @@ -136,61 +147,66 @@ public class GeodesicLine { * The {@link GeodesicMask} values are *

      *
    • - * caps |= GeodesicMask.LATITUDE for the latitude lat2; this - * is added automatically; + * caps |= {@link GeodesicMask#LATITUDE} for the latitude + * lat2; this is added automatically; *
    • - * caps |= GeodesicMask.LONGITUDE for the latitude lon2; + * caps |= {@link GeodesicMask#LONGITUDE} for the latitude + * lon2; *
    • - * caps |= GeodesicMask.AZIMUTH for the latitude azi2; this - * is added automatically; + * caps |= {@link GeodesicMask#AZIMUTH} for the latitude + * azi2; this is added automatically; *
    • - * caps |= GeodesicMask.DISTANCE for the distance s12; + * caps |= {@link GeodesicMask#DISTANCE} for the distance + * s12; *
    • - * caps |= GeodesicMask.REDUCEDLENGTH for the reduced length + * caps |= {@link GeodesicMask#REDUCEDLENGTH} for the reduced length * m12; *
    • - * caps |= GeodesicMask.GEODESICSCALE for the geodesic scales - * M12 and M21; + * caps |= {@link GeodesicMask#GEODESICSCALE} for the geodesic + * scales M12 and M21; *
    • - * caps |= GeodesicMask.AREA for the area S12; + * caps |= {@link GeodesicMask#AREA} for the area S12; *
    • - * caps |= GeodesicMask.DISTANCE_IN permits the length of the - * geodesic to be given in terms of s12; without this capability the - * length can only be specified in terms of arc length; + * caps |= {@link GeodesicMask#DISTANCE_IN} permits the length of + * the geodesic to be given in terms of s12; without this capability + * the length can only be specified in terms of arc length; *
    • - * caps |= GeodesicMask.ALL for all of the above; + * caps |= {@link GeodesicMask#ALL} for all of the above. *
    **********************************************************************/ public GeodesicLine(Geodesic g, double lat1, double lon1, double azi1, int caps) { + azi1 = GeoMath.AngNormalize(azi1); + double salp1, calp1; + // Guard against underflow in salp0 + { Pair p = GeoMath.sincosd(GeoMath.AngRound(azi1)); + salp1 = p.first; calp1 = p.second; } + LineInit(g, lat1, lon1, azi1, salp1, calp1, caps); + } + + private void LineInit(Geodesic g, + double lat1, double lon1, + double azi1, double salp1, double calp1, + int caps) { _a = g._a; _f = g._f; _b = g._b; _c2 = g._c2; _f1 = g._f1; - // Always allow latitude and azimuth - _caps = caps | GeodesicMask.LATITUDE | GeodesicMask.AZIMUTH; + // Always allow latitude and azimuth and unrolling the longitude + _caps = caps | GeodesicMask.LATITUDE | GeodesicMask.AZIMUTH | + GeodesicMask.LONG_UNROLL; - // Guard against underflow in salp0 - azi1 = Geodesic.AngRound(GeoMath.AngNormalize(azi1)); - lon1 = GeoMath.AngNormalize(lon1); - _lat1 = lat1; + _lat1 = GeoMath.LatFix(lat1); _lon1 = lon1; - _azi1 = azi1; - // alp1 is in [0, pi] - double alp1 = azi1 * GeoMath.degree; - // Enforce sin(pi) == 0 and cos(pi/2) == 0. Better to face the ensuing - // problems directly than to skirt them. - _salp1 = azi1 == -180 ? 0 : Math.sin(alp1); - _calp1 = Math.abs(azi1) == 90 ? 0 : Math.cos(alp1); - double cbet1, sbet1, phi; - phi = lat1 * GeoMath.degree; + _azi1 = azi1; _salp1 = salp1; _calp1 = calp1; + double cbet1, sbet1; + { Pair p = GeoMath.sincosd(GeoMath.AngRound(_lat1)); + sbet1 = _f1 * p.first; cbet1 = p.second; } // Ensure cbet1 = +epsilon at poles - sbet1 = _f1 * Math.sin(phi); - cbet1 = Math.abs(lat1) == 90 ? Geodesic.tiny_ : Math.cos(phi); - { Pair p = Geodesic.SinCosNorm(sbet1, cbet1); - sbet1 = p.first; cbet1 = p.second; } + { Pair p = GeoMath.norm(sbet1, cbet1); + sbet1 = p.first; cbet1 = Math.max(Geodesic.tiny_, p.second); } _dn1 = Math.sqrt(1 + g._ep2 * GeoMath.sq(sbet1)); // Evaluate alp0 from sin(alp1) * cos(bet1) = sin(alp0), @@ -209,9 +225,9 @@ public class GeodesicLine { // With alp0 = 0, omg1 = 0 for alp1 = 0, omg1 = pi for alp1 = pi. _ssig1 = sbet1; _somg1 = _salp0 * sbet1; _csig1 = _comg1 = sbet1 != 0 || _calp1 != 0 ? cbet1 * _calp1 : 1; - { Pair p = Geodesic.SinCosNorm(_ssig1, _csig1); + { Pair p = GeoMath.norm(_ssig1, _csig1); _ssig1 = p.first; _csig1 = p.second; } // sig1 in (-pi, pi] - // Geodesic.SinCosNorm(_somg1, _comg1); -- don't need to normalize! + // GeoMath.norm(_somg1, _comg1); -- don't need to normalize! _k2 = GeoMath.sq(_calp0) * g._ep2; double eps = _k2 / (2 * (1 + Math.sqrt(1 + _k2)) + _k2); @@ -257,6 +273,14 @@ public class GeodesicLine { } } + protected GeodesicLine(Geodesic g, + double lat1, double lon1, + double azi1, double salp1, double calp1, + int caps, boolean arcmode, double s13_a13) { + LineInit(g, lat1, lon1, azi1, salp1, calp1, caps); + GenSetDistance(arcmode, s13_a13); + } + /** * A default constructor. If GeodesicLine.Position is called on the * resulting object, it returns immediately (without doing any calculations). @@ -271,7 +295,7 @@ public class GeodesicLine { * Compute the position of point 2 which is a distance s12 (meters) * from point 1. *

    - * @param s12 distance between point 1 and point 2 (meters); it can be + * @param s12 distance from point 1 to point 2 (meters); it can be * negative. * @return a {@link GeodesicData} object with the following fields: * lat1, lon1, azi1, lat2, lon2, @@ -279,21 +303,19 @@ public class GeodesicLine { * missing if the GeodesicLine did not include the relevant capability. *

    * The values of lon2 and azi2 returned are in the range - * [−180°, 180°). + * [−180°, 180°]. *

    * The GeodesicLine object must have been constructed with caps * |= {@link GeodesicMask#DISTANCE_IN}; otherwise no parameters are set. **********************************************************************/ public GeodesicData Position(double s12) { - return Position(false, s12, - GeodesicMask.LATITUDE | GeodesicMask.LONGITUDE | - GeodesicMask.AZIMUTH); + return Position(false, s12, GeodesicMask.STANDARD); } /** * Compute the position of point 2 which is a distance s12 (meters) * from point 1 and with a subset of the geodesic results returned. *

    - * @param s12 distance between point 1 and point 2 (meters); it can be + * @param s12 distance from point 1 to point 2 (meters); it can be * negative. * @param outmask a bitor'ed combination of {@link GeodesicMask} values * specifying which results should be returned. @@ -302,7 +324,12 @@ public class GeodesicLine { * The GeodesicLine object must have been constructed with caps * |= {@link GeodesicMask#DISTANCE_IN}; otherwise no parameters are set. * Requesting a value which the GeodesicLine object is not capable of - * computing is not an error (no parameters will be set). + * computing is not an error (no parameters will be set). The value of + * lon2 returned is normally in the range [−180°, 180°]; + * however if the outmask includes the + * {@link GeodesicMask#LONG_UNROLL} flag, the longitude is "unrolled" so that + * the quantity lon2lon1 indicates how many times and + * in what sense the geodesic encircles the ellipsoid. **********************************************************************/ public GeodesicData Position(double s12, int outmask) { return Position(false, s12, outmask); @@ -312,7 +339,7 @@ public class GeodesicLine { * Compute the position of point 2 which is an arc length a12 * (degrees) from point 1. *

    - * @param a12 arc length between point 1 and point 2 (degrees); it can + * @param a12 arc length from point 1 to point 2 (degrees); it can * be negative. * @return a {@link GeodesicData} object with the following fields: * lat1, lon1, azi1, lat2, lon2, @@ -320,31 +347,29 @@ public class GeodesicLine { * missing if the GeodesicLine did not include the relevant capability. *

    * The values of lon2 and azi2 returned are in the range - * [−180°, 180°). + * [−180°, 180°]. *

    * The GeodesicLine object must have been constructed with caps * |= {@link GeodesicMask#DISTANCE_IN}; otherwise no parameters are set. **********************************************************************/ public GeodesicData ArcPosition(double a12) { - return Position(true, a12, - GeodesicMask.LATITUDE | GeodesicMask.LONGITUDE | - GeodesicMask.AZIMUTH | GeodesicMask.DISTANCE); + return Position(true, a12, GeodesicMask.STANDARD); } /** * Compute the position of point 2 which is an arc length a12 * (degrees) from point 1 and with a subset of the geodesic results returned. *

    - * @param a12 arc length between point 1 and point 2 (degrees); it can + * @param a12 arc length from point 1 to point 2 (degrees); it can * be negative. * @param outmask a bitor'ed combination of {@link GeodesicMask} values * specifying which results should be returned. * @return a {@link GeodesicData} object giving lat1, lon2, * azi2, and a12. *

    - * The GeodesicLine object must have been constructed with caps - * |= {@link GeodesicMask#DISTANCE_IN}; otherwise no parameters are set. * Requesting a value which the GeodesicLine object is not capable of - * computing is not an error (no parameters will be set). + * computing is not an error (no parameters will be set). The value of + * lon2 returned is in the range [−180°, 180°], unless + * the outmask includes the {@link GeodesicMask#LONG_UNROLL} flag. **********************************************************************/ public GeodesicData ArcPosition(double a12, int outmask) { return Position(true, a12, outmask); @@ -368,21 +393,28 @@ public class GeodesicLine { * The {@link GeodesicMask} values possible for outmask are *

      *
    • - * outmask |= GeodesicMask.LATITUDE for the latitude lat2. + * outmask |= {@link GeodesicMask#LATITUDE} for the latitude + * lat2; *
    • - * outmask |= GeodesicMask.LONGITUDE for the latitude lon2. + * outmask |= {@link GeodesicMask#LONGITUDE} for the latitude + * lon2; *
    • - * outmask |= GeodesicMask.AZIMUTH for the latitude azi2. + * outmask |= {@link GeodesicMask#AZIMUTH} for the latitude + * azi2; *
    • - * outmask |= GeodesicMask.DISTANCE for the distance s12. + * outmask |= {@link GeodesicMask#DISTANCE} for the distance + * s12; *
    • - * outmask |= GeodesicMask.REDUCEDLENGTH for the reduced length - * m12. + * outmask |= {@link GeodesicMask#REDUCEDLENGTH} for the reduced + * length m12; *
    • - * outmask |= GeodesicMask.GEODESICSCALE for the geodesic scales - * M12 and M21. + * outmask |= {@link GeodesicMask#GEODESICSCALE} for the geodesic + * scales M12 and M21; *
    • - * outmask |= GeodesicMask.AREA for the area S12. + * outmask |= {@link GeodesicMask#ALL} for all of the above; + *
    • + * outmask |= {@link GeodesicMask#LONG_UNROLL} to unroll lon2 + * (instead of reducing it to the range [−180°, 180°]). *
    *

    * Requesting a value which the GeodesicLine object is not capable of @@ -390,25 +422,26 @@ public class GeodesicLine { **********************************************************************/ public GeodesicData Position(boolean arcmode, double s12_a12, int outmask) { - outmask &= _caps & GeodesicMask.OUT_ALL; + outmask &= _caps & GeodesicMask.OUT_MASK; GeodesicData r = new GeodesicData(); if (!( Init() && (arcmode || - (_caps & GeodesicMask.DISTANCE_IN & GeodesicMask.OUT_ALL) != 0) )) + (_caps & (GeodesicMask.OUT_MASK & GeodesicMask.DISTANCE_IN)) != 0) + )) // Uninitialized or impossible distance calculation requested return r; - r.lat1 = _lat1; r.lon1 = _lon1; r.azi1 = _azi1; + r.lat1 = _lat1; r.azi1 = _azi1; + r.lon1 = ((outmask & GeodesicMask.LONG_UNROLL) != 0) ? _lon1 : + GeoMath.AngNormalize(_lon1); // Avoid warning about uninitialized B12. double sig12, ssig12, csig12, B12 = 0, AB1 = 0; if (arcmode) { // Interpret s12_a12 as spherical arc length r.a12 = s12_a12; - sig12 = s12_a12 * GeoMath.degree; - double s12a = Math.abs(s12_a12); - s12a -= 180 * Math.floor(s12a / 180); - ssig12 = s12a == 0 ? 0 : Math.sin(sig12); - csig12 = s12a == 90 ? 0 : Math.cos(sig12); + sig12 = Math.toRadians(s12_a12); + { Pair p = GeoMath.sincosd(s12_a12); + ssig12 = p.first; csig12 = p.second; } } else { // Interpret s12_a12 as distance r.s12 = s12_a12; @@ -422,7 +455,6 @@ public class GeodesicLine { _ctau1 * c - _stau1 * s, _C1pa); sig12 = tau12 - (B12 - _B11); - r.a12 = sig12 / GeoMath.degree; ssig12 = Math.sin(sig12); csig12 = Math.cos(sig12); if (Math.abs(_f) > 0.01) { // Reverted distance series is inaccurate for |f| > 1/100, so correct @@ -431,7 +463,8 @@ public class GeodesicLine { // GeodesicExact. // erri = the error in the inverse solution (nm) // errd = the error in the direct solution (series only) (nm) - // errda = the error in the direct solution (series + 1 Newton) (nm) + // errda = the error in the direct solution + // (series + 1 Newton) (nm) // // f erri errd errda // -1/5 12e6 1.2e9 69e6 @@ -455,10 +488,10 @@ public class GeodesicLine { ssig12 = Math.sin(sig12); csig12 = Math.cos(sig12); // Update B12 below } + r.a12 = Math.toDegrees(sig12); } - double omg12, lam12, lon12; - double ssig2, csig2, sbet2, cbet2, somg2, comg2, salp2, calp2; + double ssig2, csig2, sbet2, cbet2, salp2, calp2; // sig2 = sig1 + sig12 ssig2 = _ssig1 * csig12 + _csig1 * ssig12; csig2 = _csig1 * csig12 - _ssig1 * ssig12; @@ -476,34 +509,36 @@ public class GeodesicLine { if (cbet2 == 0) // I.e., salp0 = 0, csig2 = 0. Break the degeneracy in this case cbet2 = csig2 = Geodesic.tiny_; - // tan(omg2) = sin(alp0) * tan(sig2) - somg2 = _salp0 * ssig2; comg2 = csig2; // No need to normalize // tan(alp0) = cos(sig2)*tan(alp2) salp2 = _salp0; calp2 = _calp0 * csig2; // No need to normalize - // omg12 = omg2 - omg1 - omg12 = Math.atan2(somg2 * _comg1 - comg2 * _somg1, - comg2 * _comg1 + somg2 * _somg1); if ((outmask & GeodesicMask.DISTANCE) != 0 && arcmode) r.s12 = _b * ((1 + _A1m1) * sig12 + AB1); if ((outmask & GeodesicMask.LONGITUDE) != 0) { - lam12 = omg12 + _A3c * + // tan(omg2) = sin(alp0) * tan(sig2) + double somg2 = _salp0 * ssig2, comg2 = csig2, // No need to normalize + E = GeoMath.copysign(1, _salp0); // east or west going? + // omg12 = omg2 - omg1 + double omg12 = ((outmask & GeodesicMask.LONG_UNROLL) != 0) + ? E * (sig12 + - (Math.atan2( ssig2, csig2) - Math.atan2( _ssig1, _csig1)) + + (Math.atan2(E*somg2, comg2) - Math.atan2(E*_somg1, _comg1))) + : Math.atan2(somg2 * _comg1 - comg2 * _somg1, + comg2 * _comg1 + somg2 * _somg1); + double lam12 = omg12 + _A3c * ( sig12 + (Geodesic.SinCosSeries(true, ssig2, csig2, _C3a) - _B31)); - lon12 = lam12 / GeoMath.degree; - // Use GeoMath.AngNormalize2 because longitude might have wrapped - // multiple times. - lon12 = GeoMath.AngNormalize2(lon12); - r.lon2 = GeoMath.AngNormalize(_lon1 + lon12); + double lon12 = Math.toDegrees(lam12); + r.lon2 = ((outmask & GeodesicMask.LONG_UNROLL) != 0) ? _lon1 + lon12 : + GeoMath.AngNormalize(r.lon1 + GeoMath.AngNormalize(lon12)); } if ((outmask & GeodesicMask.LATITUDE) != 0) - r.lat2 = Math.atan2(sbet2, _f1 * cbet2) / GeoMath.degree; + r.lat2 = GeoMath.atan2d(sbet2, _f1 * cbet2); if ((outmask & GeodesicMask.AZIMUTH) != 0) - // minus signs give range [-180, 180). 0- converts -0 to +0. - r.azi2 = 0 - Math.atan2(-salp2, calp2) / GeoMath.degree; + r.azi2 = GeoMath.atan2d(salp2, calp2); if ((outmask & (GeodesicMask.REDUCEDLENGTH | GeodesicMask.GEODESICSCALE)) != 0) { @@ -528,17 +563,9 @@ public class GeodesicLine { B42 = Geodesic.SinCosSeries(false, ssig2, csig2, _C4a); double salp12, calp12; if (_calp0 == 0 || _salp0 == 0) { - // alp12 = alp2 - alp1, used in atan2 so no need to normalized + // alp12 = alp2 - alp1, used in atan2 so no need to normalize salp12 = salp2 * _calp1 - calp2 * _salp1; calp12 = calp2 * _calp1 + salp2 * _salp1; - // The right thing appears to happen if alp1 = +/-180 and alp2 = 0, viz - // salp12 = -0 and alp12 = -180. However this depends on the sign - // being attached to 0 correctly. The following ensures the correct - // behavior. - if (salp12 == 0 && calp12 < 0) { - salp12 = Geodesic.tiny_ * _calp1; - calp12 = -1; - } } else { // tan(alp) = tan(alp0) * sec(sig) // tan(alp2-alp1) = (tan(alp2) -tan(alp1)) / (tan(alp2)*tan(alp1)+1) @@ -559,6 +586,54 @@ public class GeodesicLine { return r; } + /** + * Specify position of point 3 in terms of distance. + * + * @param s13 the distance from point 1 to point 3 (meters); it + * can be negative. + * + * This is only useful if the GeodesicLine object has been constructed + * with caps |= {@link GeodesicMask#DISTANCE_IN}. + **********************************************************************/ + public void SetDistance(double s13) { + _s13 = s13; + GeodesicData g = Position(false, _s13, 0); + _a13 = g.a12; + } + + /** + * Specify position of point 3 in terms of arc length. + * + * @param a13 the arc length from point 1 to point 3 (degrees); it + * can be negative. + * + * The distance s13 is only set if the GeodesicLine object has been + * constructed with caps |= {@link GeodesicMask#DISTANCE}. + **********************************************************************/ + void SetArc(double a13) { + _a13 = a13; + GeodesicData g = Position(true, _a13, GeodesicMask.DISTANCE); + _s13 = g.s12; + } + + /** + * Specify position of point 3 in terms of either distance or arc length. + * + * @param arcmode boolean flag determining the meaning of the second + * parameter; if arcmode is false, then the GeodesicLine object must + * have been constructed with caps |= + * {@link GeodesicMask#DISTANCE_IN}. + * @param s13_a13 if arcmode is false, this is the distance from + * point 1 to point 3 (meters); otherwise it is the arc length from + * point 1 to point 3 (degrees); it can be negative. + **********************************************************************/ + public void GenSetDistance(boolean arcmode, double s13_a13) { + if (arcmode) + SetArc(s13_a13); + else + SetDistance(s13_a13); + } + /** * @return true if the object has been initialized. **********************************************************************/ @@ -582,13 +657,31 @@ public class GeodesicLine { public double Azimuth() { return Init() ? _azi1 : Double.NaN; } + /** + * @return pair of sine and cosine of azi1 the azimuth (degrees) of + * the geodesic line at point 1. + **********************************************************************/ + public Pair AzimuthCosines() { + return new Pair(Init() ? _salp1 : Double.NaN, + Init() ? _calp1 : Double.NaN); + } + /** * @return azi0 the azimuth (degrees) of the geodesic line as it * crosses the equator in a northward direction. **********************************************************************/ public double EquatorialAzimuth() { return Init() ? - Math.atan2(_salp0, _calp0) / GeoMath.degree : Double.NaN; + GeoMath.atan2d(_salp0, _calp0) : Double.NaN; + } + + /** + * @return pair of sine and cosine of azi0 the azimuth of the geodesic + * line as it crosses the equator in a northward direction. + **********************************************************************/ + public Pair EquatorialAzimuthCosines() { + return new Pair(Init() ? _salp0 : Double.NaN, + Init() ? _calp0 : Double.NaN); } /** @@ -597,7 +690,7 @@ public class GeodesicLine { **********************************************************************/ public double EquatorialArc() { return Init() ? - Math.atan2(_ssig1, _csig1) / GeoMath.degree : Double.NaN; + GeoMath.atan2d(_ssig1, _csig1) : Double.NaN; } /** @@ -629,4 +722,25 @@ public class GeodesicLine { return (_caps & testcaps) == testcaps; } + /** + * The distance or arc length to point 3. + * + * @param arcmode boolean flag determining the meaning of returned + * value. + * @return s13 if arcmode is false; a13 if + * arcmode is true. + **********************************************************************/ + public double GenDistance(boolean arcmode) + { return Init() ? (arcmode ? _a13 : _s13) : Double.NaN; } + + /** + * @return s13, the distance to point 3 (meters). + **********************************************************************/ + public double Distance() { return GenDistance(false); } + + /** + * @return a13, the arc length to point 3 (degrees). + **********************************************************************/ + public double Arc() { return GenDistance(true); } + } diff --git a/gtsam/3rdparty/GeographicLib/java/src/main/java/net/sf/geographiclib/GeodesicMask.java b/gtsam/3rdparty/GeographicLib/java/src/main/java/net/sf/geographiclib/GeodesicMask.java index 6b72ea79c..fff888e78 100644 --- a/gtsam/3rdparty/GeographicLib/java/src/main/java/net/sf/geographiclib/GeodesicMask.java +++ b/gtsam/3rdparty/GeographicLib/java/src/main/java/net/sf/geographiclib/GeodesicMask.java @@ -1,9 +1,9 @@ /** * Implementation of the net.sf.geographiclib.GeodesicMask class * - * Copyright (c) Charles Karney (2013) and licensed + * Copyright (c) Charles Karney (2013-2014) and licensed * under the MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ package net.sf.geographiclib; @@ -28,7 +28,9 @@ public class GeodesicMask { protected static final int CAP_C3 = 1<<3; protected static final int CAP_C4 = 1<<4; protected static final int CAP_ALL = 0x1F; + protected static final int CAP_MASK = CAP_ALL; protected static final int OUT_ALL = 0x7F80; + protected static final int OUT_MASK = 0xFF80; // Include LONG_UNROLL /** * No capabilities, no output. @@ -53,6 +55,11 @@ public class GeodesicMask { * Calculate distance s12. **********************************************************************/ public static final int DISTANCE = 1<<10 | CAP_C1; + /** + * All of the above, the "standard" output and capabilities. + **********************************************************************/ + public static final int STANDARD = LATITUDE | LONGITUDE | + AZIMUTH | DISTANCE; /** * Allow distance s12 to be used as input in the direct * geodesic problem. @@ -71,7 +78,12 @@ public class GeodesicMask { **********************************************************************/ public static final int AREA = 1<<14 | CAP_C4; /** - * All capabilities, calculate everything. + * All capabilities, calculate everything. (LONG_UNROLL is not included in + * this mask.) **********************************************************************/ public static final int ALL = OUT_ALL| CAP_ALL; + /** + * Unroll lon2. + **********************************************************************/ + public static final int LONG_UNROLL = 1<<15; } diff --git a/gtsam/3rdparty/GeographicLib/java/src/main/java/net/sf/geographiclib/GeographicErr.java b/gtsam/3rdparty/GeographicLib/java/src/main/java/net/sf/geographiclib/GeographicErr.java index d437a000c..106974d20 100644 --- a/gtsam/3rdparty/GeographicLib/java/src/main/java/net/sf/geographiclib/GeographicErr.java +++ b/gtsam/3rdparty/GeographicLib/java/src/main/java/net/sf/geographiclib/GeographicErr.java @@ -3,7 +3,7 @@ * * Copyright (c) Charles Karney (2013) and licensed * under the MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ package net.sf.geographiclib; diff --git a/gtsam/3rdparty/GeographicLib/java/src/main/java/net/sf/geographiclib/Gnomonic.java b/gtsam/3rdparty/GeographicLib/java/src/main/java/net/sf/geographiclib/Gnomonic.java new file mode 100644 index 000000000..40d5649f7 --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/java/src/main/java/net/sf/geographiclib/Gnomonic.java @@ -0,0 +1,280 @@ +/** + * Implementation of the net.sf.geographiclib.Gnomonic class + * + * Copyright (c) BMW Car IT GmbH (2014-2017) + * and licensed under the MIT/X11 License. For more information, see + * https://geographiclib.sourceforge.io/ + **********************************************************************/ +package net.sf.geographiclib; + +/** + * Gnomonic projection. + *

    + * Note: Gnomonic.java has been ported to Java from its C++ equivalent + * Gnomonic.cpp, authored by C. F. F. Karney and licensed under MIT/X11 + * license. The following documentation is mostly the same as for its C++ + * equivalent, but has been adopted to apply to this Java implementation. + *

    + * Gnomonic projection centered at an arbitrary position C on the + * ellipsoid. This projection is derived in Section 8 of + *

    + *

    + * The gnomonic projection of a point P on the ellipsoid is defined as + * follows: compute the geodesic line from C to P; compute the + * reduced length m12, geodesic scale M12, and ρ = + * m12/M12; finally, this gives the coordinates x and + * y of P in gnomonic projection with x = ρ sin + * azi1; y = ρ cos azi1, where azi1 is the + * azimuth of the geodesic at C. The method + * {@link Gnomonic#Forward(double, double, double, double)} performs the + * forward projection and + * {@link Gnomonic#Reverse(double, double, double, double)} is the + * inverse of the projection. The methods also return the azimuth + * azi of the geodesic at P and reciprocal scale + * rk in the azimuthal direction. The scale in the radial + * direction is 1/rk2. + *

    + * For a sphere, ρ reduces to a tan(s12/a), where + * s12 is the length of the geodesic from C to P, and the + * gnomonic projection has the property that all geodesics appear as straight + * lines. For an ellipsoid, this property holds only for geodesics interesting + * the centers. However geodesic segments close to the center are approximately + * straight. + *

    + * Consider a geodesic segment of length l. Let T be the point on + * the geodesic (extended if necessary) closest to C, the center of the + * projection, and t, be the distance CT. To lowest order, the + * maximum deviation (as a true distance) of the corresponding gnomonic line + * segment (i.e., with the same end points) from the geodesic is
    + *
    + * (K(T) − K(C)) + * l2 t / 32. + *
    + *
    + * where K is the Gaussian curvature. + *

    + * This result applies for any surface. For an ellipsoid of revolution, + * consider all geodesics whose end points are within a distance r of + * C. For a given r, the deviation is maximum when the latitude + * of C is 45°, when endpoints are a distance r away, and + * when their azimuths from the center are ± 45° or ± + * 135°. To lowest order in r and the flattening f, the + * deviation is f (r/2a)3 r. + *

    + * CAUTION: The definition of this projection for a sphere is standard. + * However, there is no standard for how it should be extended to an ellipsoid. + * The choices are: + *

      + *
    • + * Declare that the projection is undefined for an ellipsoid. + *
    • + *
    • + * Project to a tangent plane from the center of the ellipsoid. This causes + * great ellipses to appear as straight lines in the projection; i.e., it + * generalizes the spherical great circle to a great ellipse. This was proposed + * by independently by Bowring and Williams in 1997. + *
    • + *
    • + * Project to the conformal sphere with the constant of integration chosen so + * that the values of the latitude match for the center point and perform a + * central projection onto the plane tangent to the conformal sphere at the + * center point. This causes normal sections through the center point to appear + * as straight lines in the projection; i.e., it generalizes the spherical + * great circle to a normal section. This was proposed by I. G. Letoval'tsev, + * Generalization of the gnomonic projection for a spheroid and the principal + * geodetic problems involved in the alignment of surface routes, Geodesy and + * Aerophotography (5), 271–274 (1963). + *
    • + *
    • + * The projection given here. This causes geodesics close to the center point + * to appear as straight lines in the projection; i.e., it generalizes the + * spherical great circle to a geodesic. + *
    • + *
    + *

    + * Example of use: + * + *

    + * // Example of using the Gnomonic.java class
    + * import net.sf.geographiclib.Geodesic;
    + * import net.sf.geographiclib.Gnomonic;
    + * import net.sf.geographiclib.GnomonicData;
    + * public class ExampleGnomonic {
    + *   public static void main(String[] args) {
    + *     Geodesic geod = Geodesic.WGS84;
    + *     double lat0 = 48 + 50 / 60.0, lon0 = 2 + 20 / 60.0; // Paris
    + *     Gnomonic gnom = new Gnomonic(geod);
    + *     {
    + *       // Sample forward calculation
    + *       double lat = 50.9, lon = 1.8; // Calais
    + *       GnomonicData proj = gnom.Forward(lat0, lon0, lat, lon);
    + *       System.out.println(proj.x + " " + proj.y);
    + *     }
    + *     {
    + *       // Sample reverse calculation
    + *       double x = -38e3, y = 230e3;
    + *       GnomonicData proj = gnom.Reverse(lat0, lon0, x, y);
    + *       System.out.println(proj.lat + " " + proj.lon);
    + *     }
    + *   }
    + * }
    + * 
    + */ + +public class Gnomonic { + private static final double eps_ = 0.01 * Math.sqrt(GeoMath.epsilon); + private static final int numit_ = 10; + private Geodesic _earth; + private double _a, _f; + + /** + * Constructor for Gnomonic. + *

    + * @param earth the {@link Geodesic} object to use for geodesic + * calculations. + */ + public Gnomonic(Geodesic earth) { + _earth = earth; + _a = _earth.MajorRadius(); + _f = _earth.Flattening(); + } + + /** + * Forward projection, from geographic to gnomonic. + *

    + * @param lat0 latitude of center point of projection (degrees). + * @param lon0 longitude of center point of projection (degrees). + * @param lat latitude of point (degrees). + * @param lon longitude of point (degrees). + * @return {@link GnomonicData} object with the following fields: + * lat0, lon0, lat, lon, x, y, + * azi, rk. + *

    + * lat0 and lat should be in the range [−90°, + * 90°] and lon0 and lon should be in the range + * [−540°, 540°). The scale of the projection is + * 1/rk2 in the "radial" direction, azi clockwise + * from true north, and is 1/rk in the direction perpendicular to + * this. If the point lies "over the horizon", i.e., if rk ≤ 0, + * then NaNs are returned for x and y (the correct values are + * returned for azi and rk). A call to Forward followed by a + * call to Reverse will return the original (lat, lon) (to + * within roundoff) provided the point in not over the horizon. + */ + public GnomonicData Forward(double lat0, double lon0, double lat, double lon) + { + GeodesicData inv = + _earth.Inverse(lat0, lon0, lat, lon, + GeodesicMask.AZIMUTH | GeodesicMask.GEODESICSCALE | + GeodesicMask.REDUCEDLENGTH); + GnomonicData fwd = + new GnomonicData(lat0, lon0, lat, lon, Double.NaN, Double.NaN, + inv.azi2, inv.M12); + + if (inv.M12 > 0) { + double rho = inv.m12 / inv.M12; + Pair p = GeoMath.sincosd(inv.azi1); + fwd.x = rho * p.first; + fwd.y = rho * p.second; + } + + return fwd; + } + + /** + * Reverse projection, from gnomonic to geographic. + *

    + * @param lat0 latitude of center point of projection (degrees). + * @param lon0 longitude of center point of projection (degrees). + * @param x easting of point (meters). + * @param y northing of point (meters). + * @return {@link GnomonicData} object with the following fields: + * lat0, lon0, lat, lon, x, y, + * azi, rk. + *

    + * lat0 should be in the range [−90°, 90°] and + * lon0 should be in the range [−540°, 540°). + * lat will be in the range [−90°, 90°] and lon + * will be in the range [−180°, 180°]. The scale of the + * projection is 1/rk2 in the "radial" direction, + * azi clockwise from true north, and is 1/rk in the direction + * perpendicular to this. Even though all inputs should return a valid + * lat and lon, it's possible that the procedure fails to + * converge for very large x or y; in this case NaNs are + * returned for all the output arguments. A call to Reverse followed by a + * call to Forward will return the original (x, y) (to + * roundoff). + */ + public GnomonicData Reverse(double lat0, double lon0, double x, double y) { + GnomonicData rev = + new GnomonicData(lat0, lon0, Double.NaN, Double.NaN, x, y, Double.NaN, + Double.NaN); + + double azi0 = GeoMath.atan2d(x, y); + double rho = Math.hypot(x, y); + double s = _a * Math.atan(rho / _a); + boolean little = rho <= _a; + + if (!little) + rho = 1 / rho; + + GeodesicLine line = + _earth.Line(lat0, lon0, azi0, GeodesicMask.LATITUDE + | GeodesicMask.LONGITUDE | GeodesicMask.AZIMUTH + | GeodesicMask.DISTANCE_IN | GeodesicMask.REDUCEDLENGTH + | GeodesicMask.GEODESICSCALE); + + int count = numit_, trip = 0; + GeodesicData pos = null; + + while (count-- > 0) { + pos = + line.Position(s, GeodesicMask.LONGITUDE | GeodesicMask.LATITUDE + | GeodesicMask.AZIMUTH | GeodesicMask.DISTANCE_IN + | GeodesicMask.REDUCEDLENGTH + | GeodesicMask.GEODESICSCALE); + + if (trip > 0) + break; + + double ds = + little ? ((pos.m12 / pos.M12) - rho) * pos.M12 * pos.M12 + : (rho - (pos.M12 / pos.m12)) * pos.m12 * pos.m12; + s -= ds; + + if (Math.abs(ds) <= eps_ * _a) + trip++; + } + + if (trip == 0) + return rev; + + rev.lat = pos.lat2; + rev.lon = pos.lon2; + rev.azi = pos.azi2; + rev.rk = pos.M12; + + return rev; + } + + /** + * @return a the equatorial radius of the ellipsoid (meters). This is + * the value inherited from the Geodesic object used in the constructor. + **********************************************************************/ + public double MajorRadius() { return _a; } + + /** + * @return f the flattening of the ellipsoid. This is + * the value inherited from the Geodesic object used in the constructor. + **********************************************************************/ + public double Flattening() { return _f; } +} diff --git a/gtsam/3rdparty/GeographicLib/java/src/main/java/net/sf/geographiclib/GnomonicData.java b/gtsam/3rdparty/GeographicLib/java/src/main/java/net/sf/geographiclib/GnomonicData.java new file mode 100644 index 000000000..70a0c8fd2 --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/java/src/main/java/net/sf/geographiclib/GnomonicData.java @@ -0,0 +1,98 @@ +/** + * Implementation of the net.sf.geographiclib.GnomonicData class + * + * Copyright (c) BMW Car IT GmbH (2014-2016) + * and licensed under the MIT/X11 License. For more information, see + * https://geographiclib.sourceforge.io/ + **********************************************************************/ +package net.sf.geographiclib; + +/** + * The results of gnomonic projection. + *

    + + * This is used to return the results for a gnomonic projection of a point + * (lat, lon) given a center point of projection (lat0, + * lon0). The returned GnomonicData objects always include the + * parameters provided to + * {@link Gnomonic#Forward Gnomonic.Forward} + * and + * {@link Gnomonic#Reverse Gnomonic.Reverse} + * and it always includes the fields x, y, azi. and + * rk. + **********************************************************************/ +public class GnomonicData { + /** + * latitude of center point of projection (degrees). + **********************************************************************/ + public double lat0; + /** + * longitude of center point of projection (degrees). + **********************************************************************/ + public double lon0; + /** + * latitude of point (degrees). + **********************************************************************/ + public double lat; + /** + * longitude of point (degrees). + **********************************************************************/ + public double lon; + /** + * easting of point (meters). + **********************************************************************/ + public double x; + /** + * northing of point (meters). + **********************************************************************/ + public double y; + /** + * azimuth of geodesic at point (degrees). + **********************************************************************/ + public double azi; + /** + * reciprocal of azimuthal scale at point. + **********************************************************************/ + public double rk; + + /** + * Initialize all the fields to Double.NaN. + **********************************************************************/ + public GnomonicData() { + lat0 = lon0 = lat = lon = x = y = azi = rk = Double.NaN; + } + + /** + * Constructor initializing all the fields for gnomonic projection of a point + * (lat, lon) given a center point of projection (lat0, + * lon0). + *

    + * @param lat0 + * latitude of center point of projection (degrees). + * @param lon0 + * longitude of center point of projection (degrees). + * @param lat + * latitude of point (degrees). + * @param lon + * longitude of point (degrees). + * @param x + * easting of point (meters). + * @param y + * northing of point (meters). + * @param azi + * azimuth of geodesic at point (degrees). + * @param rk + * reciprocal of azimuthal scale at point. + */ + public GnomonicData(double lat0, double lon0, double lat, double lon, + double x, double y, double azi, double rk) { + this.lat0 = lat0; + this.lon0 = lon0; + this.lat = lat; + this.lon = lon; + this.x = x; + this.y = y; + this.azi = azi; + this.rk = rk; + } +} diff --git a/gtsam/3rdparty/GeographicLib/java/src/main/java/net/sf/geographiclib/Pair.java b/gtsam/3rdparty/GeographicLib/java/src/main/java/net/sf/geographiclib/Pair.java index 1e1140b49..76accdef4 100644 --- a/gtsam/3rdparty/GeographicLib/java/src/main/java/net/sf/geographiclib/Pair.java +++ b/gtsam/3rdparty/GeographicLib/java/src/main/java/net/sf/geographiclib/Pair.java @@ -3,7 +3,7 @@ * * Copyright (c) Charles Karney (2013) and licensed * under the MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ package net.sf.geographiclib; diff --git a/gtsam/3rdparty/GeographicLib/java/src/main/java/net/sf/geographiclib/PolygonArea.java b/gtsam/3rdparty/GeographicLib/java/src/main/java/net/sf/geographiclib/PolygonArea.java index 75cb09a4d..1e4ed1a1d 100644 --- a/gtsam/3rdparty/GeographicLib/java/src/main/java/net/sf/geographiclib/PolygonArea.java +++ b/gtsam/3rdparty/GeographicLib/java/src/main/java/net/sf/geographiclib/PolygonArea.java @@ -1,9 +1,9 @@ /** * Implementation of the net.sf.geographiclib.PolygonArea class * - * Copyright (c) Charles Karney (2013) and licensed + * Copyright (c) Charles Karney (2013-2017) and licensed * under the MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ package net.sf.geographiclib; @@ -15,17 +15,15 @@ package net.sf.geographiclib; *

    *

    * This class lets you add vertices one at a time to the polygon. The area - * and perimeter are accumulated in two times the standard floating point + * and perimeter are accumulated at two times the standard floating point * precision to guard against the loss of accuracy with many-sided polygons. * At any point you can ask for the perimeter and area so far. There's an * option to treat the points as defining a polyline instead of a polygon; in @@ -75,12 +73,23 @@ public class PolygonArea { // Compute lon12 the same way as Geodesic.Inverse. lon1 = GeoMath.AngNormalize(lon1); lon2 = GeoMath.AngNormalize(lon2); - double lon12 = GeoMath.AngDiff(lon1, lon2); + double lon12 = GeoMath.AngDiff(lon1, lon2).first; int cross = - lon1 < 0 && lon2 >= 0 && lon12 > 0 ? 1 : - (lon2 < 0 && lon1 >= 0 && lon12 < 0 ? -1 : 0); + lon1 <= 0 && lon2 > 0 && lon12 > 0 ? 1 : + (lon2 <= 0 && lon1 > 0 && lon12 < 0 ? -1 : 0); return cross; } + // an alternate version of transit to deal with longitudes in the direct + // problem. + private static int transitdirect(double lon1, double lon2) { + // We want to compute exactly + // int(floor(lon2 / 360)) - int(floor(lon1 / 360)) + // Since we only need the parity of the result we can use std::remquo but + // this is buggy with g++ 4.8.3 and requires C++11. So instead we do + lon1 = lon1 % 720.0; lon2 = lon2 % 720.0; + return ( ((lon2 >= 0 && lon2 < 360) || lon2 < -360 ? 0 : 1) - + ((lon1 >= 0 && lon1 < 360) || lon1 < -360 ? 0 : 1) ); + } /** * Constructor for PolygonArea. @@ -95,7 +104,8 @@ public class PolygonArea { _polyline = polyline; _mask = GeodesicMask.LATITUDE | GeodesicMask.LONGITUDE | GeodesicMask.DISTANCE | - (_polyline ? GeodesicMask.NONE : GeodesicMask.AREA); + (_polyline ? GeodesicMask.NONE : + GeodesicMask.AREA | GeodesicMask.LONG_UNROLL); _perimetersum = new Accumulator(0); if (!_polyline) _areasum = new Accumulator(0); @@ -119,8 +129,7 @@ public class PolygonArea { * @param lat the latitude of the point (degrees). * @param lon the latitude of the point (degrees). *

    - * lat should be in the range [−90°, 90°] and lon - * should be in the range [−540°, 540°). + * lat should be in the range [−90°, 90°]. **********************************************************************/ public void AddPoint(double lat, double lon) { lon = GeoMath.AngNormalize(lon); @@ -145,9 +154,8 @@ public class PolygonArea { * @param azi azimuth at current point (degrees). * @param s distance from current point to next point (meters). *

    - * azi should be in the range [−540°, 540°). This does - * nothing if no points have been added yet. Use PolygonArea.CurrentPoint to - * determine the position of the new vertex. + * This does nothing if no points have been added yet. Use + * PolygonArea.CurrentPoint to determine the position of the new vertex. **********************************************************************/ public void AddEdge(double azi, double s) { if (_num > 0) { // Do nothing if _num is zero @@ -155,7 +163,7 @@ public class PolygonArea { _perimetersum.Add(g.s12); if (!_polyline) { _areasum.Add(g.S12); - _crossings += transit(_lon1, g.lon2); + _crossings += transitdirect(_lon1, g.lon2); } _lat1 = g.lat2; _lon1 = g.lon2; ++_num; @@ -187,6 +195,8 @@ public class PolygonArea { * of the polygon or the length of the polyline (meters), and area * is the area of the polygon (meters2) or Double.NaN of * polyline is true in the constructor. + *

    + * More points can be added to the polygon after this call. **********************************************************************/ public PolygonResult Compute(boolean reverse, boolean sign) { if (_num < 2) @@ -216,7 +226,8 @@ public class PolygonArea { else if (tempsum.Sum() < 0) tempsum.Add(+_area0); } - return new PolygonResult(_num, _perimetersum.Sum(g.s12), 0 + tempsum.Sum()); + return + new PolygonResult(_num, _perimetersum.Sum(g.s12), 0 + tempsum.Sum()); } /** @@ -240,8 +251,7 @@ public class PolygonArea { * is the area of the polygon (meters2) or Double.NaN of * polyline is true in the constructor. *

    - * lat should be in the range [−90°, 90°] and lon - * should be in the range [−540°, 540°). + * lat should be in the range [−90°, 90°]. **********************************************************************/ public PolygonResult TestPoint(double lat, double lon, boolean reverse, boolean sign) { @@ -309,8 +319,6 @@ public class PolygonArea { * of the polygon or the length of the polyline (meters), and area * is the area of the polygon (meters2) or Double.NaN of * polyline is true in the constructor. - *

    - * azi should be in the range [−540°, 540°). **********************************************************************/ public PolygonResult TestEdge(double azi, double s, boolean reverse, boolean sign) { @@ -329,7 +337,7 @@ public class PolygonArea { GeodesicData g = _earth.Direct(_lat1, _lon1, azi, false, s, _mask); tempsum += g.S12; - crossings += transit(_lon1, g.lon2); + crossings += transitdirect(_lon1, g.lon2); g = _earth.Inverse(g.lat2, g.lon2, _lat0, _lon0, _mask); perimeter += g.s12; tempsum += g.S12; @@ -377,7 +385,7 @@ public class PolygonArea { * @return Pair(lat, lon), the current latitude and longitude. *

    * If no points have been added, then Double.NaN is returned. Otherwise, - * lon will be in the range [−180°, 180°). + * lon will be in the range [−180°, 180°]. **********************************************************************/ public Pair CurrentPoint() { return new Pair(_lat1, _lon1); } } diff --git a/gtsam/3rdparty/GeographicLib/java/src/main/java/net/sf/geographiclib/PolygonResult.java b/gtsam/3rdparty/GeographicLib/java/src/main/java/net/sf/geographiclib/PolygonResult.java index fdbb7ef1a..54057a4f3 100644 --- a/gtsam/3rdparty/GeographicLib/java/src/main/java/net/sf/geographiclib/PolygonResult.java +++ b/gtsam/3rdparty/GeographicLib/java/src/main/java/net/sf/geographiclib/PolygonResult.java @@ -3,7 +3,7 @@ * * Copyright (c) Charles Karney (2013) and licensed * under the MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ **********************************************************************/ package net.sf.geographiclib; diff --git a/gtsam/3rdparty/GeographicLib/java/src/main/java/net/sf/geographiclib/package-info.java b/gtsam/3rdparty/GeographicLib/java/src/main/java/net/sf/geographiclib/package-info.java index 6bceb8f69..19ce8b9f2 100644 --- a/gtsam/3rdparty/GeographicLib/java/src/main/java/net/sf/geographiclib/package-info.java +++ b/gtsam/3rdparty/GeographicLib/java/src/main/java/net/sf/geographiclib/package-info.java @@ -1,37 +1,62 @@ /** *

    Geodesic routines from GeographicLib implemented in Java

    * @author Charles F. F. Karney (charles@karney.com) - * @version 1.31 + * @version 1.49 + * + *

    + * The documentation for other versions is available at + * https://geographiclib.sourceforge.io/m.nn/java for versions numbers + * m.nn ≥ 1.31. + *

    + * Licensed under the + * MIT/X11 License; see + * + * LICENSE.txt. * *

    Abstract

    *

    - * This is a Java implementation of the geodesic algorithms from GeographicLib. This is a - * self-contained library which makes it easy to do geodesic computations - * for an ellipsoid of revolution in a Java program. It requires Java - * version 1.1 or later. + * GeographicLib-Java is a Java implementation of the geodesic algorithms from + * GeographicLib. This is a + * self-contained library which makes it easy to do geodesic computations for + * an ellipsoid of revolution in a Java program. It requires Java version 1.2 + * or later. + * + *

    Downloading

    *

    - *

    Downloading the source

    - *

    - * The Java library is part of GeographicLib which available for download at + * Download either the source or the pre-built package as follows: + * + *

    Obtaining the source

    + * GeographicLib-Java is part of GeographicLib which available for download at * *

    * as either a compressed tar file (tar.gz) or a zip file. After unpacking - * the source, the Java library can be found in GeographicLib-1.31/java. (This + * the source, the Java library can be found in GeographicLib-1.49/java. (This * library is completely independent from the rest of GeodegraphicLib.) The * library consists of the files in the src/main/java/net/sf/geographiclib * subdirectory. - *

    + * + *

    The pre-built package

    + * GeographicLib-Java is available as a pre-built package on Maven Central + * (thanks to Chris Bennight for help on this deployment). So, if you use + * maven to build your code, you just + * need to include the dependency
    {@code
    + *   
    + *     net.sf.geographiclib
    + *     GeographicLib-Java
    + *     1.49
    + *    }
    + * in your {@code pom.xml}. + * *

    Sample programs

    *

    - * Also included are 3 small test programs + * Included with the source are 3 small test programs *

      *
    • * {@code direct/src/main/java/Direct.java} is a simple command line utility @@ -40,13 +65,11 @@ * {@code inverse/src/main/java/Inverse.java} is a simple command line * utility for solving the inverse geodesic problem; *
    • - * {@code planimter/src/main/java/Planimeter.java} is a simple command line + * {@code planimeter/src/main/java/Planimeter.java} is a simple command line * utility for computing the area of a geodesic polygon given its vertices. *
    *

    - * Here, for example, is {@code Inverse.java} - *

    - * {@code
    + * Here, for example, is {@code Inverse.java} 
    {@code
      * // Solve the inverse geodesic problem.
      *
      * // This program reads in lines with lat1, lon1, lat2, lon2 and prints
    @@ -69,17 +92,25 @@
      *     catch (Exception e) {}
      *   }
      * }}
    + * *

    Compiling and running a sample program

    + *

    * Three difference ways of compiling and running {@code Inverse.java} are * given. These differ in the degree to which they utilize * maven to manage your Java code and * its dependencies. (Thanks to Skip Breidbach for supplying the maven * support.) + * *

    Without using maven

    * Compile and run as follows
      * cd inverse/src/main/java
      * javac -cp .:../../../../src/main/java Inverse.java
      * echo -30 0 29.5 179.5 | java -cp .:../../../../src/main/java Inverse 
    + * On Windows, change this to
    + * cd inverse\src\main\java
    + * javac -cp .;../../../../src/main/java Inverse.java
    + * echo -30 0 29.5 179.5 | java -cp .;../../../../src/main/java Inverse 
    + * *

    Using maven to package GeographicLib

    * Use maven to create a jar file by * running (in the main java directory)
    @@ -88,21 +119,22 @@
      * some additional packages to your local repository.)  Then compile and run
      * Inverse.java with 
      * cd inverse/src/main/java
    - * javac -cp .:../../../../target/GeographicLib-1.31.jar Inverse.java
    + * javac -cp .:../../../../target/GeographicLib-Java-1.49.jar Inverse.java
      * echo -30 0 29.5 179.5 |
    - *   java -cp .:../../../../target/GeographicLib-1.31.jar Inverse 
    + * java -cp .:../../../../target/GeographicLib-Java-1.49.jar Inverse
    + * *

    Using maven to build and run {@code Inverse.java}

    - * Use maven to install GeographicLib by - * running (in the main java directory)
    + * The sample code includes a {@code pom.xml} which specifies
    + * GeographicLib-Jave as a dependency.  You can build and install this
    + * dependency by running (in the main java directory) 
      * mvn install 
    - * (Your first run of maven may take a long time, because it needs to download - * some additional packages to your local repository.) Then compile and run - * Inverse.java using {@code inverse/pom.xml} with
    + * Alternatively, you can let maven download it from Maven Central.  You can
    + * compile and run Inverse.java with 
      * cd inverse
      * mvn compile
      * echo -30 0 29.5 179.5 | mvn -q exec:java 
    + * *

    Using the library

    - *

    *

      *
    • * Put
      @@ -139,44 +171,177 @@
        *   net.sf.geographiclib.PolygonResult}).
        * 
    *

    - * The documentation is generated using javadoc when {@code mvn package} is run - * (the top of the documentation tree is {@code target/apidocs/index.html}). - * This is also available on the web at - * - * http://geographiclib.sf.net/html/C/index.html. - *

    + * The documentation is generated using javadoc when + * {@code mvn package -P release} is run (the top of the documentation tree is + * {@code target/apidocs/index.html}). This is also available on the web at + * + * https://geographiclib.sourceforge.io/html/java/index.html. + * *

    External links

    - *

    *

    + * + *

    Change log

    + *
      + *
    • + * Version 1.49 + * (released 2017-10-05) + *
        + *
      • + * Fix code formatting and add two tests. + *
      + *
    • + * Version 1.48 + * (released 2017-04-09) + *
        + *
      • + * Change default range for longitude and azimuth to + * (−180°, 180°] (instead of [−180°, 180°)). + *
      + *
    • + * Version 1.47 + * (released 2017-02-15) + *
        + *
      • + * Improve accuracy of area calculation (fixing a flaw introduced in + * version 1.46). + *
      + *
    • + * Version 1.46 + * (released 2016-02-15) + *
        + *
      • + * Fix bug where the wrong longitude was being returned with direct geodesic + * calculation with a negative distance when starting point was at a pole + * (this bug was introduced in version 1.44). + *
      • + * Add Geodesic.DirectLine, Geodesic.ArcDirectLine, Geodesic.GenDirectLine, + * Geodesic.InverseLine, GeodesicLine.SetDistance, GeodesicLine.SetArc, + * GeodesicLine.GenSetDistance, GeodesicLine.Distance, GeodesicLine.Arc, + * GeodesicLine.GenDistance. + *
      • + * More accurate inverse solution when longitude difference is close to + * 180°. + *
      • + * GeoMath.AngDiff now returns a Pair. + *
      + *
    • + * Version 1.45 + * (released 2015-09-30) + *
        + *
      • + * The solution of the inverse problem now correctly returns NaNs if + * one of the latitudes is a NaN. + *
      • + * Add implementation of the ellipsoidal + * {@link net.sf.geographiclib.Gnomonic} (courtesy of Sebastian Mattheis). + *
      • + * Math.toRadians and Math.toDegrees are used instead of GeoMath.degree + * (which is now removed). This requires Java 1.2 or later (released + * 1998-12). + *
      + *
    • + * Version 1.44 + * (released 2015-08-14) + *
        + *
      • + * Improve accuracy of calculations by evaluating trigonometric + * functions more carefully and replacing the series for the reduced + * length with one with a smaller truncation error. + *
      • + * The allowed ranges for longitudes and azimuths is now unlimited; + * it used to be [−540°, 540°). + *
      • + * Enforce the restriction of latitude to [−90°, 90°] by + * returning NaNs if the latitude is outside this range. + *
      • + * Geodesic.Inverse sets s12 to zero for coincident points at pole + * (instead of returning a tiny quantity). + *
      • + * Geodesic.Inverse pays attentions to the GeodesicMask.LONG_UNROLL bit in + * outmask. + *
      *
    **********************************************************************/ package net.sf.geographiclib; diff --git a/gtsam/3rdparty/GeographicLib/java/src/test/java/net/sf/geographiclib/GeodesicTest.java b/gtsam/3rdparty/GeographicLib/java/src/test/java/net/sf/geographiclib/GeodesicTest.java new file mode 100644 index 000000000..6d9e29392 --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/java/src/test/java/net/sf/geographiclib/GeodesicTest.java @@ -0,0 +1,649 @@ +package net.sf.geographiclib.test; + +import static org.junit.Assert.assertEquals; +import static org.junit.Assert.assertTrue; +import org.junit.Test; +import net.sf.geographiclib.*; + +public class GeodesicTest { + + private static boolean isNaN(double x) { return x != x; } + private static final PolygonArea polygon = + new PolygonArea(Geodesic.WGS84, false); + private static final PolygonArea polyline = + new PolygonArea(Geodesic.WGS84, true); + + private static PolygonResult Planimeter(double points[][]) { + polygon.Clear(); + for (int i = 0; i < points.length; ++i) { + polygon.AddPoint(points[i][0], points[i][1]); + } + return polygon.Compute(false, true); + } + + private static PolygonResult PolyLength(double points[][]) { + polyline.Clear(); + for (int i = 0; i < points.length; ++i) { + polyline.AddPoint(points[i][0], points[i][1]); + } + return polyline.Compute(false, true); + } + + private static final double testcases[][] = { + {35.60777, -139.44815, 111.098748429560326, + -11.17491, -69.95921, 129.289270889708762, + 8935244.5604818305, 80.50729714281974, 6273170.2055303837, + 0.16606318447386067, 0.16479116945612937, 12841384694976.432}, + {55.52454, 106.05087, 22.020059880982801, + 77.03196, 197.18234, 109.112041110671519, + 4105086.1713924406, 36.892740690445894, 3828869.3344387607, + 0.80076349608092607, 0.80101006984201008, 61674961290615.615}, + {-21.97856, 142.59065, -32.44456876433189, + 41.84138, 98.56635, -41.84359951440466, + 8394328.894657671, 75.62930491011522, 6161154.5773110616, + 0.24816339233950381, 0.24930251203627892, -6637997720646.717}, + {-66.99028, 112.2363, 173.73491240878403, + -12.70631, 285.90344, 2.512956620913668, + 11150344.2312080241, 100.278634181155759, 6289939.5670446687, + -0.17199490274700385, -0.17722569526345708, -121287239862139.744}, + {-17.42761, 173.34268, -159.033557661192928, + -15.84784, 5.93557, -20.787484651536988, + 16076603.1631180673, 144.640108810286253, 3732902.1583877189, + -0.81273638700070476, -0.81299800519154474, 97825992354058.708}, + {32.84994, 48.28919, 150.492927788121982, + -56.28556, 202.29132, 48.113449399816759, + 16727068.9438164461, 150.565799985466607, 3147838.1910180939, + -0.87334918086923126, -0.86505036767110637, -72445258525585.010}, + {6.96833, 52.74123, 92.581585386317712, + -7.39675, 206.17291, 90.721692165923907, + 17102477.2496958388, 154.147366239113561, 2772035.6169917581, + -0.89991282520302447, -0.89986892177110739, -1311796973197.995}, + {-50.56724, -16.30485, -105.439679907590164, + -33.56571, -94.97412, -47.348547835650331, + 6455670.5118668696, 58.083719495371259, 5409150.7979815838, + 0.53053508035997263, 0.52988722644436602, 41071447902810.047}, + {-58.93002, -8.90775, 140.965397902500679, + -8.91104, 133.13503, 19.255429433416599, + 11756066.0219864627, 105.755691241406877, 6151101.2270708536, + -0.26548622269867183, -0.27068483874510741, -86143460552774.735}, + {-68.82867, -74.28391, 93.774347763114881, + -50.63005, -8.36685, 34.65564085411343, + 3956936.926063544, 35.572254987389284, 3708890.9544062657, + 0.81443963736383502, 0.81420859815358342, -41845309450093.787}, + {-10.62672, -32.0898, -86.426713286747751, + 5.883, -134.31681, -80.473780971034875, + 11470869.3864563009, 103.387395634504061, 6184411.6622659713, + -0.23138683500430237, -0.23155097622286792, 4198803992123.548}, + {-21.76221, 166.90563, 29.319421206936428, + 48.72884, 213.97627, 43.508671946410168, + 9098627.3986554915, 81.963476716121964, 6299240.9166992283, + 0.13965943368590333, 0.14152969707656796, 10024709850277.476}, + {-19.79938, -174.47484, 71.167275780171533, + -11.99349, -154.35109, 65.589099775199228, + 2319004.8601169389, 20.896611684802389, 2267960.8703918325, + 0.93427001867125849, 0.93424887135032789, -3935477535005.785}, + {-11.95887, -116.94513, 92.712619830452549, + 4.57352, 7.16501, 78.64960934409585, + 13834722.5801401374, 124.688684161089762, 5228093.177931598, + -0.56879356755666463, -0.56918731952397221, -9919582785894.853}, + {-87.85331, 85.66836, -65.120313040242748, + 66.48646, 16.09921, -4.888658719272296, + 17286615.3147144645, 155.58592449699137, 2635887.4729110181, + -0.90697975771398578, -0.91095608883042767, 42667211366919.534}, + {1.74708, 128.32011, -101.584843631173858, + -11.16617, 11.87109, -86.325793296437476, + 12942901.1241347408, 116.650512484301857, 5682744.8413270572, + -0.44857868222697644, -0.44824490340007729, 10763055294345.653}, + {-25.72959, -144.90758, -153.647468693117198, + -57.70581, -269.17879, -48.343983158876487, + 9413446.7452453107, 84.664533838404295, 6356176.6898881281, + 0.09492245755254703, 0.09737058264766572, 74515122850712.444}, + {-41.22777, 122.32875, 14.285113402275739, + -7.57291, 130.37946, 10.805303085187369, + 3812686.035106021, 34.34330804743883, 3588703.8812128856, + 0.82605222593217889, 0.82572158200920196, -2456961531057.857}, + {11.01307, 138.25278, 79.43682622782374, + 6.62726, 247.05981, 103.708090215522657, + 11911190.819018408, 107.341669954114577, 6070904.722786735, + -0.29767608923657404, -0.29785143390252321, 17121631423099.696}, + {-29.47124, 95.14681, -163.779130441688382, + -27.46601, -69.15955, -15.909335945554969, + 13487015.8381145492, 121.294026715742277, 5481428.9945736388, + -0.51527225545373252, -0.51556587964721788, 104679964020340.318}}; + + @Test + public void InverseCheck() { + for (int i = 0; i < testcases.length; ++i) { + double + lat1 = testcases[i][0], lon1 = testcases[i][1], azi1 = testcases[i][2], + lat2 = testcases[i][3], lon2 = testcases[i][4], azi2 = testcases[i][5], + s12 = testcases[i][6], a12 = testcases[i][7], m12 = testcases[i][8], + M12 = testcases[i][9], M21 = testcases[i][10], S12 = testcases[i][11]; + GeodesicData inv = Geodesic.WGS84.Inverse(lat1, lon1, lat2, lon2, + GeodesicMask.ALL | + GeodesicMask.LONG_UNROLL); + assertEquals(lon2, inv.lon2, 1e-13); + assertEquals(azi1, inv.azi1, 1e-13); + assertEquals(azi2, inv.azi2, 1e-13); + assertEquals(s12, inv.s12, 1e-8); + assertEquals(a12, inv.a12, 1e-13); + assertEquals(m12, inv.m12, 1e-8); + assertEquals(M12, inv.M12, 1e-15); + assertEquals(M21, inv.M21, 1e-15); + assertEquals(S12, inv.S12, 0.1); + } + } + + @Test + public void DirectCheck() { + for (int i = 0; i < testcases.length; ++i) { + double + lat1 = testcases[i][0], lon1 = testcases[i][1], azi1 = testcases[i][2], + lat2 = testcases[i][3], lon2 = testcases[i][4], azi2 = testcases[i][5], + s12 = testcases[i][6], a12 = testcases[i][7], m12 = testcases[i][8], + M12 = testcases[i][9], M21 = testcases[i][10], S12 = testcases[i][11]; + GeodesicData dir = Geodesic.WGS84.Direct(lat1, lon1, azi1, s12, + GeodesicMask.ALL | + GeodesicMask.LONG_UNROLL); + assertEquals(lat2, dir.lat2, 1e-13); + assertEquals(lon2, dir.lon2, 1e-13); + assertEquals(azi2, dir.azi2, 1e-13); + assertEquals(a12, dir.a12, 1e-13); + assertEquals(m12, dir.m12, 1e-8); + assertEquals(M12, dir.M12, 1e-15); + assertEquals(M21, dir.M21, 1e-15); + assertEquals(S12, dir.S12, 0.1); + } + } + + @Test + public void ArcDirectCheck() { + for (int i = 0; i < testcases.length; ++i) { + double + lat1 = testcases[i][0], lon1 = testcases[i][1], azi1 = testcases[i][2], + lat2 = testcases[i][3], lon2 = testcases[i][4], azi2 = testcases[i][5], + s12 = testcases[i][6], a12 = testcases[i][7], m12 = testcases[i][8], + M12 = testcases[i][9], M21 = testcases[i][10], S12 = testcases[i][11]; + GeodesicData dir = Geodesic.WGS84.ArcDirect(lat1, lon1, azi1, a12, + GeodesicMask.ALL | + GeodesicMask.LONG_UNROLL); + assertEquals(lat2, dir.lat2, 1e-13); + assertEquals(lon2, dir.lon2, 1e-13); + assertEquals(azi2, dir.azi2, 1e-13); + assertEquals(s12, dir.s12, 1e-8); + assertEquals(m12, dir.m12, 1e-8); + assertEquals(M12, dir.M12, 1e-15); + assertEquals(M21, dir.M21, 1e-15); + assertEquals(S12, dir.S12, 0.1); + } + } + + @Test + public void GeodSolve0() { + GeodesicData inv = Geodesic.WGS84.Inverse(40.6, -73.8, + 49.01666667, 2.55); + assertEquals(inv.azi1, 53.47022, 0.5e-5); + assertEquals(inv.azi2, 111.59367, 0.5e-5); + assertEquals(inv.s12, 5853226, 0.5); + } + + @Test + public void GeodSolve1() { + GeodesicData dir = Geodesic.WGS84.Direct(40.63972222, -73.77888889, + 53.5, 5850e3); + assertEquals(dir.lat2, 49.01467, 0.5e-5); + assertEquals(dir.lon2, 2.56106, 0.5e-5); + assertEquals(dir.azi2, 111.62947, 0.5e-5); + } + + @Test + public void GeodSolve2() { + // Check fix for antipodal prolate bug found 2010-09-04 + Geodesic geod = new Geodesic(6.4e6, -1/150.0); + GeodesicData inv = geod.Inverse(0.07476, 0, -0.07476, 180); + assertEquals(inv.azi1, 90.00078, 0.5e-5); + assertEquals(inv.azi2, 90.00078, 0.5e-5); + assertEquals(inv.s12, 20106193, 0.5); + inv = geod.Inverse(0.1, 0, -0.1, 180); + assertEquals(inv.azi1, 90.00105, 0.5e-5); + assertEquals(inv.azi2, 90.00105, 0.5e-5); + assertEquals(inv.s12, 20106193, 0.5); + } + + @Test + public void GeodSolve4() { + // Check fix for short line bug found 2010-05-21 + GeodesicData inv = Geodesic.WGS84.Inverse(36.493349428792, 0, + 36.49334942879201, .0000008); + assertEquals(inv.s12, 0.072, 0.5e-3); + } + + @Test + public void GeodSolve5() { + // Check fix for point2=pole bug found 2010-05-03 + GeodesicData dir = Geodesic.WGS84.Direct(0.01777745589997, 30, 0, 10e6); + assertEquals(dir.lat2, 90, 0.5e-5); + if (dir.lon2 < 0) { + assertEquals(dir.lon2, -150, 0.5e-5); + assertEquals(Math.abs(dir.azi2), 180, 0.5e-5); + } else { + assertEquals(dir.lon2, 30, 0.5e-5); + assertEquals(dir.azi2, 0, 0.5e-5); + } + } + + @Test + public void GeodSolve6() { + // Check fix for volatile sbet12a bug found 2011-06-25 (gcc 4.4.4 + // x86 -O3). Found again on 2012-03-27 with tdm-mingw32 (g++ 4.6.1). + GeodesicData inv = + Geodesic.WGS84.Inverse(88.202499451857, 0, + -88.202499451857, 179.981022032992859592); + assertEquals(inv.s12, 20003898.214, 0.5e-3); + inv = Geodesic.WGS84.Inverse(89.262080389218, 0, + -89.262080389218, 179.992207982775375662); + assertEquals(inv.s12, 20003925.854, 0.5e-3); + inv = Geodesic.WGS84.Inverse(89.333123580033, 0, -89.333123580032997687, + 179.99295812360148422); + assertEquals(inv.s12, 20003926.881, 0.5e-3); + } + + @Test + public void GeodSolve9() { + // Check fix for volatile x bug found 2011-06-25 (gcc 4.4.4 x86 -O3) + GeodesicData inv = + Geodesic.WGS84.Inverse(56.320923501171, 0, + -56.320923501171, 179.664747671772880215); + assertEquals(inv.s12, 19993558.287, 0.5e-3); + } + + @Test + public void GeodSolve10() { + // Check fix for adjust tol1_ bug found 2011-06-25 (Visual Studio + // 10 rel + debug) + GeodesicData inv = + Geodesic.WGS84.Inverse(52.784459512564, 0, + -52.784459512563990912, 179.634407464943777557); + assertEquals(inv.s12, 19991596.095, 0.5e-3); + } + + @Test + public void GeodSolve11() { + // Check fix for bet2 = -bet1 bug found 2011-06-25 (Visual Studio + // 10 rel + debug) + GeodesicData inv = + Geodesic.WGS84.Inverse(48.522876735459, 0, + -48.52287673545898293, 179.599720456223079643); + assertEquals(inv.s12, 19989144.774, 0.5e-3); + } + + @Test + public void GeodSolve12() { + // Check fix for inverse geodesics on extreme prolate/oblate + // ellipsoids Reported 2012-08-29 Stefan Guenther + // ; fixed 2012-10-07 + Geodesic geod = new Geodesic(89.8, -1.83); + GeodesicData inv = geod.Inverse(0, 0, -10, 160); + assertEquals(inv.azi1, 120.27, 1e-2); + assertEquals(inv.azi2, 105.15, 1e-2); + assertEquals(inv.s12, 266.7, 1e-1); + } + + @Test + public void GeodSolve14() { + // Check fix for inverse ignoring lon12 = nan + GeodesicData inv = Geodesic.WGS84.Inverse(0, 0, 1, Double.NaN); + assertTrue(isNaN(inv.azi1)); + assertTrue(isNaN(inv.azi2)); + assertTrue(isNaN(inv.s12)); + } + + @Test + public void GeodSolve15() { + // Initial implementation of Math::eatanhe was wrong for e^2 < 0. This + // checks that this is fixed. + Geodesic geod = new Geodesic(6.4e6, -1/150.0); + GeodesicData dir = geod.Direct(1, 2, 3, 4, GeodesicMask.AREA); + assertEquals(dir.S12, 23700, 0.5); + } + + @Test + public void GeodSolve17() { + // Check fix for LONG_UNROLL bug found on 2015-05-07 + GeodesicData dir = + Geodesic.WGS84.Direct(40, -75, -10, 2e7, + GeodesicMask.STANDARD | GeodesicMask.LONG_UNROLL); + assertEquals(dir.lat2, -39, 1); + assertEquals(dir.lon2, -254, 1); + assertEquals(dir.azi2, -170, 1); + GeodesicLine line = Geodesic.WGS84.Line(40, -75, -10); + dir = line.Position(2e7, GeodesicMask.STANDARD | GeodesicMask.LONG_UNROLL); + assertEquals(dir.lat2, -39, 1); + assertEquals(dir.lon2, -254, 1); + assertEquals(dir.azi2, -170, 1); + dir = Geodesic.WGS84.Direct(40, -75, -10, 2e7); + assertEquals(dir.lat2, -39, 1); + assertEquals(dir.lon2, 105, 1); + assertEquals(dir.azi2, -170, 1); + dir = line.Position(2e7); + assertEquals(dir.lat2, -39, 1); + assertEquals(dir.lon2, 105, 1); + assertEquals(dir.azi2, -170, 1); + } + + @Test + public void GeodSolve26() { + // Check 0/0 problem with area calculation on sphere 2015-09-08 + Geodesic geod = new Geodesic(6.4e6, 0); + GeodesicData inv = geod.Inverse(1, 2, 3, 4, GeodesicMask.AREA); + assertEquals(inv.S12, 49911046115.0, 0.5); + } + + @Test + public void GeodSolve28() { + // Check for bad placement of assignment of r.a12 with |f| > 0.01 (bug in + // Java implementation fixed on 2015-05-19). + Geodesic geod = new Geodesic(6.4e6, 0.1); + GeodesicData dir = geod.Direct(1, 2, 10, 5e6); + assertEquals(dir.a12, 48.55570690, 0.5e-8); + } + + @Test + public void GeodSolve29() { + // Check longitude unrolling with inverse calculation 2015-09-16 + GeodesicData dir = Geodesic.WGS84.Inverse(0, 539, 0, 181); + assertEquals(dir.lon1, 179, 1e-10); + assertEquals(dir.lon2, -179, 1e-10); + assertEquals(dir.s12, 222639, 0.5); + dir = Geodesic.WGS84.Inverse(0, 539, 0, 181, + GeodesicMask.STANDARD | + GeodesicMask.LONG_UNROLL); + assertEquals(dir.lon1, 539, 1e-10); + assertEquals(dir.lon2, 541, 1e-10); + assertEquals(dir.s12, 222639, 0.5); + } + + @Test + public void GeodSolve33() { + // Check max(-0.0,+0.0) issues 2015-08-22 (triggered by bugs in Octave -- + // sind(-0.0) = +0.0 -- and in some version of Visual Studio -- + // fmod(-0.0, 360.0) = +0.0. + GeodesicData inv = Geodesic.WGS84.Inverse(0, 0, 0, 179); + assertEquals(inv.azi1, 90.00000, 0.5e-5); + assertEquals(inv.azi2, 90.00000, 0.5e-5); + assertEquals(inv.s12, 19926189, 0.5); + inv = Geodesic.WGS84.Inverse(0, 0, 0, 179.5); + assertEquals(inv.azi1, 55.96650, 0.5e-5); + assertEquals(inv.azi2, 124.03350, 0.5e-5); + assertEquals(inv.s12, 19980862, 0.5); + inv = Geodesic.WGS84.Inverse(0, 0, 0, 180); + assertEquals(inv.azi1, 0.00000, 0.5e-5); + assertEquals(Math.abs(inv.azi2), 180.00000, 0.5e-5); + assertEquals(inv.s12, 20003931, 0.5); + inv = Geodesic.WGS84.Inverse(0, 0, 1, 180); + assertEquals(inv.azi1, 0.00000, 0.5e-5); + assertEquals(Math.abs(inv.azi2), 180.00000, 0.5e-5); + assertEquals(inv.s12, 19893357, 0.5); + Geodesic geod = new Geodesic(6.4e6, 0); + inv = geod.Inverse(0, 0, 0, 179); + assertEquals(inv.azi1, 90.00000, 0.5e-5); + assertEquals(inv.azi2, 90.00000, 0.5e-5); + assertEquals(inv.s12, 19994492, 0.5); + inv = geod.Inverse(0, 0, 0, 180); + assertEquals(inv.azi1, 0.00000, 0.5e-5); + assertEquals(Math.abs(inv.azi2), 180.00000, 0.5e-5); + assertEquals(inv.s12, 20106193, 0.5); + inv = geod.Inverse(0, 0, 1, 180); + assertEquals(inv.azi1, 0.00000, 0.5e-5); + assertEquals(Math.abs(inv.azi2), 180.00000, 0.5e-5); + assertEquals(inv.s12, 19994492, 0.5); + geod = new Geodesic(6.4e6, -1/300.0); + inv = geod.Inverse(0, 0, 0, 179); + assertEquals(inv.azi1, 90.00000, 0.5e-5); + assertEquals(inv.azi2, 90.00000, 0.5e-5); + assertEquals(inv.s12, 19994492, 0.5); + inv = geod.Inverse(0, 0, 0, 180); + assertEquals(inv.azi1, 90.00000, 0.5e-5); + assertEquals(inv.azi2, 90.00000, 0.5e-5); + assertEquals(inv.s12, 20106193, 0.5); + inv = geod.Inverse(0, 0, 0.5, 180); + assertEquals(inv.azi1, 33.02493, 0.5e-5); + assertEquals(inv.azi2, 146.97364, 0.5e-5); + assertEquals(inv.s12, 20082617, 0.5); + inv = geod.Inverse(0, 0, 1, 180); + assertEquals(inv.azi1, 0.00000, 0.5e-5); + assertEquals(Math.abs(inv.azi2), 180.00000, 0.5e-5); + assertEquals(inv.s12, 20027270, 0.5); + } + + @Test + public void GeodSolve55() { + // Check fix for nan + point on equator or pole not returning all nans in + // Geodesic::Inverse, found 2015-09-23. + GeodesicData inv = Geodesic.WGS84.Inverse(Double.NaN, 0, 0, 90); + assertTrue(isNaN(inv.azi1)); + assertTrue(isNaN(inv.azi2)); + assertTrue(isNaN(inv.s12)); + inv = Geodesic.WGS84.Inverse(Double.NaN, 0, 90, 3); + assertTrue(isNaN(inv.azi1)); + assertTrue(isNaN(inv.azi2)); + assertTrue(isNaN(inv.s12)); + } + + @Test + public void GeodSolve59() { + // Check for points close with longitudes close to 180 deg apart. + GeodesicData inv = Geodesic.WGS84.Inverse(5, 0.00000000000001, 10, 180); + assertEquals(inv.azi1, 0.000000000000035, 1.5e-14); + assertEquals(inv.azi2, 179.99999999999996, 1.5e-14); + assertEquals(inv.s12, 18345191.174332713, 4e-9); + } + + @Test + public void GeodSolve61() { + // Make sure small negative azimuths are west-going + GeodesicData dir = + Geodesic.WGS84.Direct(45, 0, -0.000000000000000003, 1e7, + GeodesicMask.STANDARD | GeodesicMask.LONG_UNROLL); + assertEquals(dir.lat2, 45.30632, 0.5e-5); + assertEquals(dir.lon2, -180, 0.5e-5); + assertEquals(Math.abs(dir.azi2), 180, 0.5e-5); + GeodesicLine line = Geodesic.WGS84.InverseLine(45, 0, 80, + -0.000000000000000003); + dir = line.Position(1e7, GeodesicMask.STANDARD | GeodesicMask.LONG_UNROLL); + assertEquals(dir.lat2, 45.30632, 0.5e-5); + assertEquals(dir.lon2, -180, 0.5e-5); + assertEquals(Math.abs(dir.azi2), 180, 0.5e-5); + } + + @Test + public void GeodSolve65() { + // Check for bug in east-going check in GeodesicLine (needed to check for + // sign of 0) and sign error in area calculation due to a bogus override + // of the code for alp12. Found/fixed on 2015-12-19. + GeodesicLine line = Geodesic.WGS84.InverseLine(30, -0.000000000000000001, + -31, 180); + GeodesicData dir = + line.Position(1e7, GeodesicMask.ALL | GeodesicMask.LONG_UNROLL); + assertEquals(dir.lat1, 30.00000 , 0.5e-5); + assertEquals(dir.lon1, -0.00000 , 0.5e-5); + assertEquals(Math.abs(dir.azi1), 180.00000, 0.5e-5); + assertEquals(dir.lat2, -60.23169 , 0.5e-5); + assertEquals(dir.lon2, -0.00000 , 0.5e-5); + assertEquals(Math.abs(dir.azi2), 180.00000, 0.5e-5); + assertEquals(dir.s12 , 10000000 , 0.5); + assertEquals(dir.a12 , 90.06544 , 0.5e-5); + assertEquals(dir.m12 , 6363636 , 0.5); + assertEquals(dir.M12 , -0.0012834, 0.5e7); + assertEquals(dir.M21 , 0.0013749 , 0.5e-7); + assertEquals(dir.S12 , 0 , 0.5); + dir = line.Position(2e7, GeodesicMask.ALL | GeodesicMask.LONG_UNROLL); + assertEquals(dir.lat1, 30.00000 , 0.5e-5); + assertEquals(dir.lon1, -0.00000 , 0.5e-5); + assertEquals(Math.abs(dir.azi1), 180.00000, 0.5e-5); + assertEquals(dir.lat2, -30.03547 , 0.5e-5); + assertEquals(dir.lon2, -180.00000, 0.5e-5); + assertEquals(dir.azi2, -0.00000 , 0.5e-5); + assertEquals(dir.s12 , 20000000 , 0.5); + assertEquals(dir.a12 , 179.96459 , 0.5e-5); + assertEquals(dir.m12 , 54342 , 0.5); + assertEquals(dir.M12 , -1.0045592, 0.5e7); + assertEquals(dir.M21 , -0.9954339, 0.5e-7); + assertEquals(dir.S12 , 127516405431022.0, 0.5); + } + + @Test + public void GeodSolve69() { + // Check for InverseLine if line is slightly west of S and that s13 is + // correctly set. + GeodesicLine line = + Geodesic.WGS84.InverseLine(-5, -0.000000000000002, -10, 180); + GeodesicData dir = + line.Position(2e7, GeodesicMask.STANDARD | GeodesicMask.LONG_UNROLL); + assertEquals(dir.lat2, 4.96445 , 0.5e-5); + assertEquals(dir.lon2, -180.00000, 0.5e-5); + assertEquals(dir.azi2, -0.00000 , 0.5e-5); + dir = line.Position(0.5 * line.Distance(), + GeodesicMask.STANDARD | GeodesicMask.LONG_UNROLL); + assertEquals(dir.lat2, -87.52461 , 0.5e-5); + assertEquals(dir.lon2, -0.00000 , 0.5e-5); + assertEquals(dir.azi2, -180.00000, 0.5e-5); + } + + @Test + public void GeodSolve71() { + // Check that DirectLine sets s13. + GeodesicLine line = Geodesic.WGS84.DirectLine(1, 2, 45, 1e7); + GeodesicData dir = + line.Position(0.5 * line.Distance(), + GeodesicMask.STANDARD | GeodesicMask.LONG_UNROLL); + assertEquals(dir.lat2, 30.92625, 0.5e-5); + assertEquals(dir.lon2, 37.54640, 0.5e-5); + assertEquals(dir.azi2, 55.43104, 0.5e-5); + } + + @Test + public void GeodSolve73() { + // Check for backwards from the pole bug reported by Anon on 2016-02-13. + // This only affected the Java implementation. It was introduced in Java + // version 1.44 and fixed in 1.46-SNAPSHOT on 2016-01-17. + GeodesicData dir = Geodesic.WGS84.Direct(90, 10, 180, -1e6); + assertEquals(dir.lat2, 81.04623, 0.5e-5); + assertEquals(dir.lon2, -170, 0.5e-5); + assertEquals(dir.azi2, 0, 0.5e-5); + } + + @Test + public void GeodSolve74() { + // Check fix for inaccurate areas, bug introduced in v1.46, fixed + // 2015-10-16. + GeodesicData inv = Geodesic.WGS84.Inverse(54.1589, 15.3872, + 54.1591, 15.3877, + GeodesicMask.ALL); + assertEquals(inv.azi1, 55.723110355, 5e-9); + assertEquals(inv.azi2, 55.723515675, 5e-9); + assertEquals(inv.s12, 39.527686385, 5e-9); + assertEquals(inv.a12, 0.000355495, 5e-9); + assertEquals(inv.m12, 39.527686385, 5e-9); + assertEquals(inv.M12, 0.999999995, 5e-9); + assertEquals(inv.M21, 0.999999995, 5e-9); + assertEquals(inv.S12, 286698586.30197, 5e-4); + } + + @Test + public void GeodSolve76() { + // The distance from Wellington and Salamanca (a classic failure of + // Vincenty) + GeodesicData inv = Geodesic.WGS84.Inverse(-(41+19/60.0), 174+49/60.0, + 40+58/60.0, -(5+30/60.0)); + assertEquals(inv.azi1, 160.39137649664, 0.5e-11); + assertEquals(inv.azi2, 19.50042925176, 0.5e-11); + assertEquals(inv.s12, 19960543.857179, 0.5e-6); + } + + @Test + public void GeodSolve78() { + // An example where the NGS calculator fails to converge */ + GeodesicData inv = Geodesic.WGS84.Inverse(27.2, 0.0, -27.1, 179.5); + assertEquals(inv.azi1, 45.82468716758, 0.5e-11); + assertEquals(inv.azi2, 134.22776532670, 0.5e-11); + assertEquals(inv.s12, 19974354.765767, 0.5e-6); + } + + @Test + public void Planimeter0() { + // Check fix for pole-encircling bug found 2011-03-16 + double pa[][] = {{89, 0}, {89, 90}, {89, 180}, {89, 270}}; + PolygonResult a = Planimeter(pa); + assertEquals(a.perimeter, 631819.8745, 1e-4); + assertEquals(a.area, 24952305678.0, 1); + + double pb[][] = {{-89, 0}, {-89, 90}, {-89, 180}, {-89, 270}}; + a = Planimeter(pb); + assertEquals(a.perimeter, 631819.8745, 1e-4); + assertEquals(a.area, -24952305678.0, 1); + + double pc[][] = {{0, -1}, {-1, 0}, {0, 1}, {1, 0}}; + a = Planimeter(pc); + assertEquals(a.perimeter, 627598.2731, 1e-4); + assertEquals(a.area, 24619419146.0, 1); + + double pd[][] = {{90, 0}, {0, 0}, {0, 90}}; + a = Planimeter(pd); + assertEquals(a.perimeter, 30022685, 1); + assertEquals(a.area, 63758202715511.0, 1); + a = PolyLength(pd); + assertEquals(a.perimeter, 20020719, 1); + assertTrue(isNaN(a.area)); + } + + @Test + public void Planimeter5() { + // Check fix for Planimeter pole crossing bug found 2011-06-24 + double points[][] = {{89, 0.1}, {89, 90.1}, {89, -179.9}}; + PolygonResult a = Planimeter(points); + assertEquals(a.perimeter, 539297, 1); + assertEquals(a.area, 12476152838.5, 1); + } + + @Test + public void Planimeter6() { + // Check fix for Planimeter lon12 rounding bug found 2012-12-03 + double pa[][] = {{9, -0.00000000000001}, {9, 180}, {9, 0}}; + PolygonResult a = Planimeter(pa); + assertEquals(a.perimeter, 36026861, 1); + assertEquals(a.area, 0, 1); + double pb[][] = {{9, 0.00000000000001}, {9, 0}, {9, 180}}; + a = Planimeter(pb); + assertEquals(a.perimeter, 36026861, 1); + assertEquals(a.area, 0, 1); + double pc[][] = {{9, 0.00000000000001}, {9, 180}, {9, 0}}; + a = Planimeter(pc); + assertEquals(a.perimeter, 36026861, 1); + assertEquals(a.area, 0, 1); + double pd[][] = {{9, -0.00000000000001}, {9, 0}, {9, 180}}; + a = Planimeter(pd); + assertEquals(a.perimeter, 36026861, 1); + assertEquals(a.area, 0, 1); + } + + @Test + public void Planimeter12() { + // Area of arctic circle (not really -- adjunct to rhumb-area test) + double points[][] = {{66.562222222, 0}, {66.562222222, 180}}; + PolygonResult a = Planimeter(points); + assertEquals(a.perimeter, 10465729, 1); + assertEquals(a.area, 0, 1); + } + + @Test + public void Planimeter13() { + // Check encircling pole twice + double points[][] = {{89,-360}, {89,-240}, {89,-120}, + {89,0}, {89,120}, {89,240}}; + PolygonResult a = Planimeter(points); + assertEquals(a.perimeter, 1160741, 1); + assertEquals(a.area, 32415230256.0, 1); + } + +} diff --git a/gtsam/3rdparty/GeographicLib/js/CMakeLists.txt b/gtsam/3rdparty/GeographicLib/js/CMakeLists.txt new file mode 100644 index 000000000..30b0293fc --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/js/CMakeLists.txt @@ -0,0 +1,134 @@ +# This list governs the order in which the JavaScript sources are +# concatenated. This shouldn't be changed. +set (JS_MODULES Math Geodesic GeodesicLine PolygonArea DMS) + +# Combine JavaScript into a single file if necessary +set (JSSCRIPTS) +set (JS_BUILD 0) +set (JS_BUILD_MIN 0) +set (JS_TARGET "${CMAKE_CURRENT_BINARY_DIR}/geographiclib.js") +set (JS_TARGET_MIN "${CMAKE_CURRENT_BINARY_DIR}/geographiclib.min.js") +set (JS_TARGETS ${JS_TARGET} ${JS_TARGET_MIN}) +set (FILE_INVENTORY "") +foreach (_F ${JS_MODULES}) + set (_S "src/${_F}.js") + set (FILE_INVENTORY "${FILE_INVENTORY} ${_F}.js") + list (APPEND JSSCRIPTS ${_S}) + if ("${CMAKE_CURRENT_SOURCE_DIR}/_S" IS_NEWER_THAN ${JS_TARGET}) + set (JS_BUILD 1) + endif () + if ("${CMAKE_CURRENT_SOURCE_DIR}/_S" IS_NEWER_THAN ${JS_TARGET_MIN}) + set (JS_BUILD_MIN 1) + endif () +endforeach () + +if (JS_BUILD) + file (STRINGS "src/Math.js" _S REGEX version_string) + string (REGEX REPLACE ".*\"(.*)\".*" "\\1" JS_VERSION "${_S}") + file (REMOVE ${JS_TARGET}) + file (READ "HEADER.js" _S) + string (CONFIGURE ${_S} _S @ONLY) + file (APPEND ${JS_TARGET} "${_S}") + file (APPEND ${JS_TARGET} "\n(function(cb) {\n") + foreach (_F ${JSSCRIPTS}) + get_filename_component (_N ${_F} NAME) + file (READ "${_F}" _S) + # Normalize the line endings. + string (REGEX REPLACE "\r" "" _S "${_S}") + file (APPEND ${JS_TARGET} "\n/**************** ${_N} ****************/\n") + file (APPEND ${JS_TARGET} "${_S}") + endforeach () + # export GeographlicLib + file (APPEND ${JS_TARGET} " +cb(GeographicLib); + +})(function(geo) { + if (typeof module === 'object' && module.exports) { + /******** support loading with node's require ********/ + module.exports = geo; + } else if (typeof define === 'function' && define.amd) { + /******** support loading with AMD ********/ + define('geographiclib', [], function() { return geo; }); + } else { + /******** otherwise just pollute our global namespace ********/ + window.GeographicLib = geo; + } +}); +") +endif () + +if (JS_BUILD_MIN) + file (STRINGS "src/Math.js" _S REGEX version_string) + string (REGEX REPLACE ".*\"(.*)\".*" "\\1" JS_VERSION "${_S}") + file (REMOVE ${JS_TARGET_MIN}) + file (READ "HEADER.js" _S) + string (CONFIGURE ${_S} _S @ONLY) + file (APPEND ${JS_TARGET_MIN} "${_S}") + file (APPEND ${JS_TARGET_MIN} "(function(cb){\n") + foreach (_F ${JSSCRIPTS}) + get_filename_component (_N ${_F} NAME) + file (READ "${_F}" _S) + # Normalize the line endings. + string (REGEX REPLACE "\r" "\n" _S "${_S}") + # This matches /*...*/ style comments, where ... is any number of + # \*[^/] and [^*]. This has the defect that the it won't detect, + # e.g., **/ as the end of the comment. + string (REGEX REPLACE "/\\*(\\*[^/]|[^*])*\\*/" "" _S "${_S}") + string (REGEX REPLACE "//[^\n]*\n" "\n" _S "${_S}") + string (REGEX REPLACE "[ \t]+" " " _S "${_S}") + string (REGEX REPLACE "([^\"A-Za-z0-9_]) " "\\1" _S "${_S}") + string (REGEX REPLACE " ([^\\[\"A-Za-z0-9_])" "\\1" _S "${_S}") + string (REGEX REPLACE "\n " "\n" _S "${_S}") + string (REGEX REPLACE " \n" "\n" _S "${_S}") + string (REGEX REPLACE "^\n" "" _S "${_S}") + string (REGEX REPLACE "\n+" "\n" _S "${_S}") + file (APPEND ${JS_TARGET_MIN} "// ${_N}\n${_S}") + endforeach () + # export GeographlicLib + file (APPEND ${JS_TARGET_MIN} + "cb(GeographicLib); +})(function(geo){ +if(typeof module==='object'&&module.exports){ +module.exports=geo; +}else if(typeof define==='function'&&define.amd){ +define('geographiclib',[],function(){return geo;}); +}else{ +window.GeographicLib=geo; +} +}); +") +endif () + +# "make javascript" will reconfigure cmake if necessary, since +# geographiclib.js and geographiclib.min.js are created during +# configuration. +add_custom_command (OUTPUT ${JS_TARGETS} + DEPENDS ${JSSCRIPTS} HEADER.js + COMMAND ${CMAKE_COMMAND} ARGS "." + WORKING_DIRECTORY ${PROJECT_BINARY_DIR}) + +file (GLOB SAMPLES samples/*.html) +file (COPY ${SAMPLES} DESTINATION .) + +add_custom_target (javascript ALL DEPENDS ${JS_TARGETS}) + +# Copy files so that publishing nodejs package can be done with: +# npm publish ${CMAKE_CURRENT_BINARY_DIR}/geographiclib +# To test, do: +# cd ${CMAKE_CURRENT_BINARY_DIR}/geographiclib && npm test +file (COPY ../LICENSE.txt package.json README.md ${JS_TARGETS} + DESTINATION geographiclib) +file (COPY ${JSSCRIPTS} DESTINATION geographiclib/src) +file (COPY test/geodesictest.js DESTINATION geographiclib/test) + +if (COMMON_INSTALL_PATH) + set (INSTALL_JS_DIR "lib${LIB_SUFFIX}/node_modules/geographiclib") +else () + set (INSTALL_JS_DIR "node_modules/geographiclib") +endif () + +# Install the JavaScript files +install (FILES ../LICENSE.txt package.json README.md ${JS_TARGETS} + DESTINATION ${INSTALL_JS_DIR}) +install (FILES ${JSSCRIPTS} DESTINATION ${INSTALL_JS_DIR}/src) +install (FILES test/geodesictest.js DESTINATION ${INSTALL_JS_DIR}/test) diff --git a/gtsam/3rdparty/GeographicLib/js/GeographicLib.md b/gtsam/3rdparty/GeographicLib/js/GeographicLib.md new file mode 100644 index 000000000..455aa3479 --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/js/GeographicLib.md @@ -0,0 +1,135 @@ +## Geodesic routines from GeographicLib + +This documentation applies to version 1.49. + +The documentation for other versions is available +at https://geographiclib.sourceforge.io/m.nn/js for versions +numbers m.nn ≥ 1.45. + +Licensed under the MIT/X11 License; see +[LICENSE.txt](https://geographiclib.sourceforge.io/html/LICENSE.txt). + +### Installation + +This library is a JavaScript implementation of the geodesic routines +from [GeographicLib](https://geographiclib.sourceforge.io). This solves the +direct and inverse geodesic problems for an ellipsoid of revolution. + +The library can be used in [node](https://nodejs.org) by first +installing the +[geographiclib node package](https://www.npmjs.com/package/geographiclib) +with [npm](https://www.npmjs.com) +```bash +$ npm install geographiclib +$ node +> var GeographicLib = require("geographiclib"); +``` +The npm package includes a test suite. Run this by +```bash +$ cd node_modules/geograliblib +$ npm test +``` + +Alternatively, you can use it in client-side JavaScript, by including in +your HTML page +```html + +``` +Both of these prescriptions define a {@link GeographicLib} namespace. + +### Examples + +Now geodesic calculations can be carried out, for example, +```javascript +var geod = GeographicLib.Geodesic.WGS84, r; + +// Find the distance from Wellington, NZ (41.32S, 174.81E) to +// Salamanca, Spain (40.96N, 5.50W)... +r = geod.Inverse(-41.32, 174.81, 40.96, -5.50); +console.log("The distance is " + r.s12.toFixed(3) + " m."); +// This prints "The distance is 19959679.267 m." + +// Find the point 20000 km SW of Perth, Australia (32.06S, 115.74E)... +r = geod.Direct(-32.06, 115.74, 225, 20000e3); +console.log("The position is (" + + r.lat2.toFixed(8) + ", " + r.lon2.toFixed(8) + ")."); +// This prints "The position is (32.11195529, -63.95925278)." +``` +Two examples of this library in use are +* [A geodesic calculator](https://geographiclib.sourceforge.io/scripts/geod-calc.html) +* [Displaying geodesics on Google + Maps](https://geographiclib.sourceforge.io/scripts/geod-google.html) + +### More information +* {@tutorial 1-geodesics} +* {@tutorial 2-interface} +* {@tutorial 3-examples} + +### Implementations in various languages +* {@link https://sourceforge.net/p/geographiclib/code/ci/release/tree/ + git repository} +* C++ (complete library): + {@link https://geographiclib.sourceforge.io/html/index.html + documentation}, + {@link https://sourceforge.net/projects/geographiclib/files/distrib + download}; +* C (geodesic routines): + {@link https://geographiclib.sourceforge.io/html/C/index.html + documentation}, also included with recent versions of + {@link https://github.com/OSGeo/proj.4/wiki + proj.4}; +* Fortran (geodesic routines): + {@link https://geographiclib.sourceforge.io/html/Fortran/index.html + documentation}; +* Java (geodesic routines): + {@link http://repo1.maven.org/maven2/net/sf/geographiclib/GeographicLib-Java/ + Maven Central package}, + {@link https://geographiclib.sourceforge.io/html/java/index.html + documentation}; +* JavaScript (geodesic routines): + {@link https://www.npmjs.com/package/geographiclib + npm package}, + {@link https://geographiclib.sourceforge.io/html/js/index.html + documentation}; +* Python (geodesic routines): + {@link http://pypi.python.org/pypi/geographiclib + PyPI package}, + {@link https://geographiclib.sourceforge.io/html/python/index.html + documentation}; +* Matlab/Octave (geodesic and some other routines): + {@link http://www.mathworks.com/matlabcentral/fileexchange/50605 + Matlab Central package}, + {@link http://www.mathworks.com/matlabcentral/fileexchange/50605/content/Contents.m + documentation}; +* C# (.NET wrapper for complete C++ library): + {@link https://geographiclib.sourceforge.io/html/NET/index.html + documentation}. + +### Change log + +* Version 1.49 (released 2017-10-05) + * Use explicit test for nonzero real numbers. + +* Version 1.48 (released 2017-04-09) + * Change default range for longitude and azimuth to + (−180°, 180°] (instead of [−180°, 180°)). + +* Version 1.47 (released 2017-02-15) + * Improve accuracy of area calculation (fixing a flaw introduced in + version 1.46). + +* Version 1.46 (released 2016-02-15) + * Fix bugs in PolygonArea.TestEdge (problem found by threepointone). + * Add Geodesic.DirectLine, Geodesic.ArcDirectLine, + Geodesic.GenDirectLine, Geodesic.InverseLine, + GeodesicLine.SetDistance, GeodesicLine.SetArc, + GeodesicLine.GenSetDistance, GeodesicLine.s13, GeodesicLine.a13. + * More accurate inverse solution when longitude difference is close to + 180°. + +### Authors + +* algorithms + js code: Charles Karney (charles@karney.com) +* node.js port: Yurij Mikhalevich (0@39.yt) diff --git a/gtsam/3rdparty/GeographicLib/js/HEADER.js b/gtsam/3rdparty/GeographicLib/js/HEADER.js new file mode 100644 index 000000000..880dfebbd --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/js/HEADER.js @@ -0,0 +1,22 @@ +/* + * Geodesic routines from GeographicLib translated to JavaScript. See + * https://geographiclib.sourceforge.io/html/js/ + * + * The algorithms are derived in + * + * Charles F. F. Karney, + * Algorithms for geodesics, J. Geodesy 87, 43-55 (2013), + * https://doi.org/10.1007/s00190-012-0578-z + * Addenda: https://geographiclib.sourceforge.io/geod-addenda.html + * + * This file is the concatenation and compression of the JavaScript files in + * doc/scripts/GeographicLib in the source tree for GeographicLib. + * + * Copyright (c) Charles Karney (2011-2015) and licensed + * under the MIT/X11 License. For more information, see + * https://geographiclib.sourceforge.io/ + * + * Version: @JS_VERSION@ + * File inventory: + * @FILE_INVENTORY@ + */ diff --git a/gtsam/3rdparty/GeographicLib/js/Makefile.am b/gtsam/3rdparty/GeographicLib/js/Makefile.am new file mode 100644 index 000000000..188a34aa4 --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/js/Makefile.am @@ -0,0 +1,44 @@ +EXTRAFILES = $(srcdir)/HEADER.js + +SAMPLES = \ + geod-calc.html \ + geod-google.html \ + geod-google-instructions.html + +# The order here is significant +JSSCRIPTS = \ + $(srcdir)/src/Math.js \ + $(srcdir)/src/Geodesic.js \ + $(srcdir)/src/GeodesicLine.js \ + $(srcdir)/src/PolygonArea.js \ + $(srcdir)/src/DMS.js +TESTSCRIPTS = $(srcdir)/test/geodesictest.js + +all: geographiclib.js geographiclib.min.js $(SAMPLES) + +geod-calc.html: samples/geod-calc.html + cp $^ $@ + +geod-google.html: samples/geod-google.html + cp $^ $@ + +geod-google-instructions.html: samples/geod-google-instructions.html + cp $^ $@ + +geographiclib.js: HEADER.js $(JSSCRIPTS) + $(srcdir)/js-cat.sh $^ > $@ + +geographiclib.min.js: HEADER.js $(JSSCRIPTS) + $(srcdir)/js-compress.sh $^ > $@ + +jsdir=$(DESTDIR)$(libdir)/node_modules/geographiclib + +install: all + $(INSTALL) -d $(jsdir) + $(INSTALL) -m 644 geographiclib.js geographiclib.min.js $(jsdir) + $(INSTALL) -m 644 $(top_srcdir)/LICENSE.txt $(srcdir)/README.md \ + $(srcdir)/package.json $(jsdir) + $(INSTALL) -d $(jsdir)/src + $(INSTALL) -m 644 $(JSSCRIPTS) $(jsdir)/src + $(INSTALL) -d $(jsdir)/test + $(INSTALL) -m 644 $(TESTSCRIPTS) $(jsdir)/test diff --git a/gtsam/3rdparty/GeographicLib/js/Makefile.in b/gtsam/3rdparty/GeographicLib/js/Makefile.in new file mode 100644 index 000000000..59d46e145 --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/js/Makefile.in @@ -0,0 +1,502 @@ +# Makefile.in generated by automake 1.15 from Makefile.am. +# @configure_input@ + +# Copyright (C) 1994-2014 Free Software Foundation, Inc. + +# This Makefile.in is free software; the Free Software Foundation +# gives unlimited permission to copy and/or distribute it, +# with or without modifications, as long as this notice is preserved. + +# This program is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY, to the extent permitted by law; without +# even the implied warranty of MERCHANTABILITY or FITNESS FOR A +# PARTICULAR PURPOSE. + +@SET_MAKE@ +VPATH = @srcdir@ +am__is_gnu_make = { \ + if test -z '$(MAKELEVEL)'; then \ + false; \ + elif test -n '$(MAKE_HOST)'; then \ + true; \ + elif test -n '$(MAKE_VERSION)' && test -n '$(CURDIR)'; then \ + true; \ + else \ + false; \ + fi; \ +} +am__make_running_with_option = \ + case $${target_option-} in \ + ?) ;; \ + *) echo "am__make_running_with_option: internal error: invalid" \ + "target option '$${target_option-}' specified" >&2; \ + exit 1;; \ + esac; \ + has_opt=no; \ + sane_makeflags=$$MAKEFLAGS; \ + if $(am__is_gnu_make); then \ + sane_makeflags=$$MFLAGS; \ + else \ + case $$MAKEFLAGS in \ + *\\[\ \ ]*) \ + bs=\\; \ + sane_makeflags=`printf '%s\n' "$$MAKEFLAGS" \ + | sed "s/$$bs$$bs[$$bs $$bs ]*//g"`;; \ + esac; \ + fi; \ + skip_next=no; \ + strip_trailopt () \ + { \ + flg=`printf '%s\n' "$$flg" | sed "s/$$1.*$$//"`; \ + }; \ + for flg in $$sane_makeflags; do \ + test $$skip_next = yes && { skip_next=no; continue; }; \ + case $$flg in \ + *=*|--*) continue;; \ + -*I) strip_trailopt 'I'; skip_next=yes;; \ + -*I?*) strip_trailopt 'I';; \ + -*O) strip_trailopt 'O'; skip_next=yes;; \ + -*O?*) strip_trailopt 'O';; \ + -*l) strip_trailopt 'l'; skip_next=yes;; \ + -*l?*) strip_trailopt 'l';; \ + -[dEDm]) skip_next=yes;; \ + -[JT]) skip_next=yes;; \ + esac; \ + case $$flg in \ + *$$target_option*) has_opt=yes; break;; \ + esac; \ + done; \ + test $$has_opt = yes +am__make_dryrun = (target_option=n; $(am__make_running_with_option)) +am__make_keepgoing = (target_option=k; $(am__make_running_with_option)) +pkgdatadir = $(datadir)/@PACKAGE@ +pkgincludedir = $(includedir)/@PACKAGE@ +pkglibdir = $(libdir)/@PACKAGE@ +pkglibexecdir = $(libexecdir)/@PACKAGE@ +am__cd = CDPATH="$${ZSH_VERSION+.}$(PATH_SEPARATOR)" && cd +install_sh_DATA = $(install_sh) -c -m 644 +install_sh_PROGRAM = $(install_sh) -c +install_sh_SCRIPT = $(install_sh) -c +INSTALL_HEADER = $(INSTALL_DATA) +transform = $(program_transform_name) +NORMAL_INSTALL = : +PRE_INSTALL = : +POST_INSTALL = : +NORMAL_UNINSTALL = : +PRE_UNINSTALL = : +POST_UNINSTALL = : +build_triplet = @build@ +host_triplet = @host@ +target_triplet = @target@ +subdir = js +ACLOCAL_M4 = $(top_srcdir)/aclocal.m4 +am__aclocal_m4_deps = $(top_srcdir)/m4/libtool.m4 \ + $(top_srcdir)/m4/ltoptions.m4 $(top_srcdir)/m4/ltsugar.m4 \ + $(top_srcdir)/m4/ltversion.m4 $(top_srcdir)/m4/lt~obsolete.m4 \ + $(top_srcdir)/m4/pkg.m4 $(top_srcdir)/configure.ac +am__configure_deps = $(am__aclocal_m4_deps) $(CONFIGURE_DEPENDENCIES) \ + $(ACLOCAL_M4) +DIST_COMMON = $(srcdir)/Makefile.am $(am__DIST_COMMON) +mkinstalldirs = $(install_sh) -d +CONFIG_HEADER = $(top_builddir)/include/GeographicLib/Config-ac.h +CONFIG_CLEAN_FILES = +CONFIG_CLEAN_VPATH_FILES = +AM_V_P = $(am__v_P_@AM_V@) +am__v_P_ = $(am__v_P_@AM_DEFAULT_V@) +am__v_P_0 = false +am__v_P_1 = : +AM_V_GEN = $(am__v_GEN_@AM_V@) +am__v_GEN_ = $(am__v_GEN_@AM_DEFAULT_V@) +am__v_GEN_0 = @echo " GEN " $@; +am__v_GEN_1 = +AM_V_at = $(am__v_at_@AM_V@) +am__v_at_ = $(am__v_at_@AM_DEFAULT_V@) +am__v_at_0 = @ +am__v_at_1 = +SOURCES = +DIST_SOURCES = +am__can_run_installinfo = \ + case $$AM_UPDATE_INFO_DIR in \ + n|no|NO) false;; \ + *) (install-info --version) >/dev/null 2>&1;; \ + esac +am__tagged_files = $(HEADERS) $(SOURCES) $(TAGS_FILES) $(LISP) +am__DIST_COMMON = $(srcdir)/Makefile.in +DISTFILES = $(DIST_COMMON) $(DIST_SOURCES) $(TEXINFOS) $(EXTRA_DIST) +ACLOCAL = @ACLOCAL@ +AMTAR = @AMTAR@ +AM_DEFAULT_VERBOSITY = @AM_DEFAULT_VERBOSITY@ +AR = @AR@ +AUTOCONF = @AUTOCONF@ +AUTOHEADER = @AUTOHEADER@ +AUTOMAKE = @AUTOMAKE@ +AWK = @AWK@ +CC = @CC@ +CCDEPMODE = @CCDEPMODE@ +CFLAGS = @CFLAGS@ +COL = @COL@ +CPP = @CPP@ +CPPFLAGS = @CPPFLAGS@ +CXX = @CXX@ +CXXCPP = @CXXCPP@ +CXXDEPMODE = @CXXDEPMODE@ +CXXFLAGS = @CXXFLAGS@ +CYGPATH_W = @CYGPATH_W@ +DEFS = @DEFS@ +DEPDIR = @DEPDIR@ +DLLTOOL = @DLLTOOL@ +DOXYGEN = @DOXYGEN@ +DSYMUTIL = @DSYMUTIL@ +DUMPBIN = @DUMPBIN@ +ECHO_C = @ECHO_C@ +ECHO_N = @ECHO_N@ +ECHO_T = @ECHO_T@ +EGREP = @EGREP@ +EXEEXT = @EXEEXT@ +FGREP = @FGREP@ +GEOGRAPHICLIB_VERSION_MAJOR = @GEOGRAPHICLIB_VERSION_MAJOR@ +GEOGRAPHICLIB_VERSION_MINOR = @GEOGRAPHICLIB_VERSION_MINOR@ +GEOGRAPHICLIB_VERSION_PATCH = @GEOGRAPHICLIB_VERSION_PATCH@ +GREP = @GREP@ +INSTALL = @INSTALL@ +INSTALL_DATA = @INSTALL_DATA@ +INSTALL_PROGRAM = @INSTALL_PROGRAM@ +INSTALL_SCRIPT = @INSTALL_SCRIPT@ +INSTALL_STRIP_PROGRAM = @INSTALL_STRIP_PROGRAM@ +LD = @LD@ +LDFLAGS = @LDFLAGS@ +LIBOBJS = @LIBOBJS@ +LIBS = @LIBS@ +LIBTOOL = @LIBTOOL@ +LIPO = @LIPO@ +LN_S = @LN_S@ +LTLIBOBJS = @LTLIBOBJS@ +LT_AGE = @LT_AGE@ +LT_CURRENT = @LT_CURRENT@ +LT_REVISION = @LT_REVISION@ +LT_SYS_LIBRARY_PATH = @LT_SYS_LIBRARY_PATH@ +MAINT = @MAINT@ +MAKEINFO = @MAKEINFO@ +MANIFEST_TOOL = @MANIFEST_TOOL@ +MKDIR_P = @MKDIR_P@ +NM = @NM@ +NMEDIT = @NMEDIT@ +OBJDUMP = @OBJDUMP@ +OBJEXT = @OBJEXT@ +OTOOL = @OTOOL@ +OTOOL64 = @OTOOL64@ +PACKAGE = @PACKAGE@ +PACKAGE_BUGREPORT = @PACKAGE_BUGREPORT@ +PACKAGE_NAME = @PACKAGE_NAME@ +PACKAGE_STRING = @PACKAGE_STRING@ +PACKAGE_TARNAME = @PACKAGE_TARNAME@ +PACKAGE_URL = @PACKAGE_URL@ +PACKAGE_VERSION = @PACKAGE_VERSION@ +PATH_SEPARATOR = @PATH_SEPARATOR@ +PKG_CONFIG = @PKG_CONFIG@ +PKG_CONFIG_LIBDIR = @PKG_CONFIG_LIBDIR@ +PKG_CONFIG_PATH = @PKG_CONFIG_PATH@ +POD2HTML = @POD2HTML@ +POD2MAN = @POD2MAN@ +RANLIB = @RANLIB@ +SED = @SED@ +SET_MAKE = @SET_MAKE@ +SHELL = @SHELL@ +STRIP = @STRIP@ +VERSION = @VERSION@ +abs_builddir = @abs_builddir@ +abs_srcdir = @abs_srcdir@ +abs_top_builddir = @abs_top_builddir@ +abs_top_srcdir = @abs_top_srcdir@ +ac_ct_AR = @ac_ct_AR@ +ac_ct_CC = @ac_ct_CC@ +ac_ct_CXX = @ac_ct_CXX@ +ac_ct_DUMPBIN = @ac_ct_DUMPBIN@ +am__include = @am__include@ +am__leading_dot = @am__leading_dot@ +am__quote = @am__quote@ +am__tar = @am__tar@ +am__untar = @am__untar@ +bindir = @bindir@ +build = @build@ +build_alias = @build_alias@ +build_cpu = @build_cpu@ +build_os = @build_os@ +build_vendor = @build_vendor@ +builddir = @builddir@ +datadir = @datadir@ +datarootdir = @datarootdir@ +docdir = @docdir@ +dvidir = @dvidir@ +exec_prefix = @exec_prefix@ +host = @host@ +host_alias = @host_alias@ +host_cpu = @host_cpu@ +host_os = @host_os@ +host_vendor = @host_vendor@ +htmldir = @htmldir@ +includedir = @includedir@ +infodir = @infodir@ +install_sh = @install_sh@ +libdir = @libdir@ +libexecdir = @libexecdir@ +localedir = @localedir@ +localstatedir = @localstatedir@ +mandir = @mandir@ +mkdir_p = @mkdir_p@ +oldincludedir = @oldincludedir@ +pdfdir = @pdfdir@ +pkgconfigdir = @pkgconfigdir@ +prefix = @prefix@ +program_transform_name = @program_transform_name@ +psdir = @psdir@ +sbindir = @sbindir@ +sharedstatedir = @sharedstatedir@ +srcdir = @srcdir@ +sysconfdir = @sysconfdir@ +target = @target@ +target_alias = @target_alias@ +target_cpu = @target_cpu@ +target_os = @target_os@ +target_vendor = @target_vendor@ +top_build_prefix = @top_build_prefix@ +top_builddir = @top_builddir@ +top_srcdir = @top_srcdir@ +EXTRAFILES = $(srcdir)/HEADER.js +SAMPLES = \ + geod-calc.html \ + geod-google.html \ + geod-google-instructions.html + + +# The order here is significant +JSSCRIPTS = \ + $(srcdir)/src/Math.js \ + $(srcdir)/src/Geodesic.js \ + $(srcdir)/src/GeodesicLine.js \ + $(srcdir)/src/PolygonArea.js \ + $(srcdir)/src/DMS.js + +TESTSCRIPTS = $(srcdir)/test/geodesictest.js +jsdir = $(DESTDIR)$(libdir)/node_modules/geographiclib +all: all-am + +.SUFFIXES: +$(srcdir)/Makefile.in: @MAINTAINER_MODE_TRUE@ $(srcdir)/Makefile.am $(am__configure_deps) + @for dep in $?; do \ + case '$(am__configure_deps)' in \ + *$$dep*) \ + ( cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh ) \ + && { if test -f $@; then exit 0; else break; fi; }; \ + exit 1;; \ + esac; \ + done; \ + echo ' cd $(top_srcdir) && $(AUTOMAKE) --gnu js/Makefile'; \ + $(am__cd) $(top_srcdir) && \ + $(AUTOMAKE) --gnu js/Makefile +Makefile: $(srcdir)/Makefile.in $(top_builddir)/config.status + @case '$?' in \ + *config.status*) \ + cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh;; \ + *) \ + echo ' cd $(top_builddir) && $(SHELL) ./config.status $(subdir)/$@ $(am__depfiles_maybe)'; \ + cd $(top_builddir) && $(SHELL) ./config.status $(subdir)/$@ $(am__depfiles_maybe);; \ + esac; + +$(top_builddir)/config.status: $(top_srcdir)/configure $(CONFIG_STATUS_DEPENDENCIES) + cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh + +$(top_srcdir)/configure: @MAINTAINER_MODE_TRUE@ $(am__configure_deps) + cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh +$(ACLOCAL_M4): @MAINTAINER_MODE_TRUE@ $(am__aclocal_m4_deps) + cd $(top_builddir) && $(MAKE) $(AM_MAKEFLAGS) am--refresh +$(am__aclocal_m4_deps): + +mostlyclean-libtool: + -rm -f *.lo + +clean-libtool: + -rm -rf .libs _libs +tags TAGS: + +ctags CTAGS: + +cscope cscopelist: + + +distdir: $(DISTFILES) + @srcdirstrip=`echo "$(srcdir)" | sed 's/[].[^$$\\*]/\\\\&/g'`; \ + topsrcdirstrip=`echo "$(top_srcdir)" | sed 's/[].[^$$\\*]/\\\\&/g'`; \ + list='$(DISTFILES)'; \ + dist_files=`for file in $$list; do echo $$file; done | \ + sed -e "s|^$$srcdirstrip/||;t" \ + -e "s|^$$topsrcdirstrip/|$(top_builddir)/|;t"`; \ + case $$dist_files in \ + */*) $(MKDIR_P) `echo "$$dist_files" | \ + sed '/\//!d;s|^|$(distdir)/|;s,/[^/]*$$,,' | \ + sort -u` ;; \ + esac; \ + for file in $$dist_files; do \ + if test -f $$file || test -d $$file; then d=.; else d=$(srcdir); fi; \ + if test -d $$d/$$file; then \ + dir=`echo "/$$file" | sed -e 's,/[^/]*$$,,'`; \ + if test -d "$(distdir)/$$file"; then \ + find "$(distdir)/$$file" -type d ! -perm -700 -exec chmod u+rwx {} \;; \ + fi; \ + if test -d $(srcdir)/$$file && test $$d != $(srcdir); then \ + cp -fpR $(srcdir)/$$file "$(distdir)$$dir" || exit 1; \ + find "$(distdir)/$$file" -type d ! -perm -700 -exec chmod u+rwx {} \;; \ + fi; \ + cp -fpR $$d/$$file "$(distdir)$$dir" || exit 1; \ + else \ + test -f "$(distdir)/$$file" \ + || cp -p $$d/$$file "$(distdir)/$$file" \ + || exit 1; \ + fi; \ + done +check-am: all-am +check: check-am +all-am: Makefile +installdirs: +install-exec: install-exec-am +install-data: install-data-am +uninstall: uninstall-am + +install-am: all-am + @$(MAKE) $(AM_MAKEFLAGS) install-exec-am install-data-am + +installcheck: installcheck-am +install-strip: + if test -z '$(STRIP)'; then \ + $(MAKE) $(AM_MAKEFLAGS) INSTALL_PROGRAM="$(INSTALL_STRIP_PROGRAM)" \ + install_sh_PROGRAM="$(INSTALL_STRIP_PROGRAM)" INSTALL_STRIP_FLAG=-s \ + install; \ + else \ + $(MAKE) $(AM_MAKEFLAGS) INSTALL_PROGRAM="$(INSTALL_STRIP_PROGRAM)" \ + install_sh_PROGRAM="$(INSTALL_STRIP_PROGRAM)" INSTALL_STRIP_FLAG=-s \ + "INSTALL_PROGRAM_ENV=STRIPPROG='$(STRIP)'" install; \ + fi +mostlyclean-generic: + +clean-generic: + +distclean-generic: + -test -z "$(CONFIG_CLEAN_FILES)" || rm -f $(CONFIG_CLEAN_FILES) + -test . = "$(srcdir)" || test -z "$(CONFIG_CLEAN_VPATH_FILES)" || rm -f $(CONFIG_CLEAN_VPATH_FILES) + +maintainer-clean-generic: + @echo "This command is intended for maintainers to use" + @echo "it deletes files that may require special tools to rebuild." +clean: clean-am + +clean-am: clean-generic clean-libtool mostlyclean-am + +distclean: distclean-am + -rm -f Makefile +distclean-am: clean-am distclean-generic + +dvi: dvi-am + +dvi-am: + +html: html-am + +html-am: + +info: info-am + +info-am: + +install-data-am: + +install-dvi: install-dvi-am + +install-dvi-am: + +install-exec-am: + +install-html: install-html-am + +install-html-am: + +install-info: install-info-am + +install-info-am: + +install-man: + +install-pdf: install-pdf-am + +install-pdf-am: + +install-ps: install-ps-am + +install-ps-am: + +installcheck-am: + +maintainer-clean: maintainer-clean-am + -rm -f Makefile +maintainer-clean-am: distclean-am maintainer-clean-generic + +mostlyclean: mostlyclean-am + +mostlyclean-am: mostlyclean-generic mostlyclean-libtool + +pdf: pdf-am + +pdf-am: + +ps: ps-am + +ps-am: + +uninstall-am: + +.MAKE: install-am install-strip + +.PHONY: all all-am check check-am clean clean-generic clean-libtool \ + cscopelist-am ctags-am distclean distclean-generic \ + distclean-libtool distdir dvi dvi-am html html-am info info-am \ + install install-am install-data install-data-am install-dvi \ + install-dvi-am install-exec install-exec-am install-html \ + install-html-am install-info install-info-am install-man \ + install-pdf install-pdf-am install-ps install-ps-am \ + install-strip installcheck installcheck-am installdirs \ + maintainer-clean maintainer-clean-generic mostlyclean \ + mostlyclean-generic mostlyclean-libtool pdf pdf-am ps ps-am \ + tags-am uninstall uninstall-am + +.PRECIOUS: Makefile + + +all: geographiclib.js geographiclib.min.js $(SAMPLES) + +geod-calc.html: samples/geod-calc.html + cp $^ $@ + +geod-google.html: samples/geod-google.html + cp $^ $@ + +geod-google-instructions.html: samples/geod-google-instructions.html + cp $^ $@ + +geographiclib.js: HEADER.js $(JSSCRIPTS) + $(srcdir)/js-cat.sh $^ > $@ + +geographiclib.min.js: HEADER.js $(JSSCRIPTS) + $(srcdir)/js-compress.sh $^ > $@ + +install: all + $(INSTALL) -d $(jsdir) + $(INSTALL) -m 644 geographiclib.js geographiclib.min.js $(jsdir) + $(INSTALL) -m 644 $(top_srcdir)/LICENSE.txt $(srcdir)/README.md \ + $(srcdir)/package.json $(jsdir) + $(INSTALL) -d $(jsdir)/src + $(INSTALL) -m 644 $(JSSCRIPTS) $(jsdir)/src + $(INSTALL) -d $(jsdir)/test + $(INSTALL) -m 644 $(TESTSCRIPTS) $(jsdir)/test + +# Tell versions [3.59,3.63) of GNU make to not export all variables. +# Otherwise a system limit (for SysV at least) may be exceeded. +.NOEXPORT: diff --git a/gtsam/3rdparty/GeographicLib/js/Makefile.mk b/gtsam/3rdparty/GeographicLib/js/Makefile.mk new file mode 100644 index 000000000..36da9ca2b --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/js/Makefile.mk @@ -0,0 +1,36 @@ +# The order here is significant +JS_MODULES=Math Geodesic GeodesicLine PolygonArea DMS +JSSCRIPTS = $(patsubst %,src/%.js,$(JS_MODULES)) +TESTSCRIPTS = $(wildcard test/*.js) + +SAMPLESIN = $(wildcard samples/geod-*.html) +SAMPLES = $(patsubst samples/%,%,$(SAMPLESIN)) + +all: geographiclib.js geographiclib.min.js $(SAMPLES) + +%.html: samples/%.html + cp $^ $@ + +geographiclib.js: HEADER.js $(JSSCRIPTS) + ./js-cat.sh $^ > $@ + +geographiclib.min.js: HEADER.js $(JSSCRIPTS) + ./js-compress.sh $^ > $@ + +clean: + rm -f geographiclib.js geographiclib.min.js *.html + +PREFIX = /usr/local +DEST = $(PREFIX)/lib/node_modules/geographiclib +INSTALL = install -b + +install: all + test -d $(DEST) || mkdir -p $(DEST) + $(INSTALL) -m 644 geographiclib.js geographiclib.min.js $(DEST)/ + $(INSTALL) -m 644 ../LICENSE.txt README.md package.json $(DEST)/ + test -d $(DEST)/src || mkdir -p $(DEST)/src + $(INSTALL) -m 644 $(JSSCRIPTS) $(DEST)/src/ + test -d $(DEST)/test || mkdir -p $(DEST)/test + $(INSTALL) -m 644 $(TESTSCRIPTS) $(DEST)/test/ + +.PHONY: install clean diff --git a/gtsam/3rdparty/GeographicLib/js/README.md b/gtsam/3rdparty/GeographicLib/js/README.md new file mode 100644 index 000000000..4dbc5fa80 --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/js/README.md @@ -0,0 +1,50 @@ +# Geodesic routines from GeographicLib + +This library is a JavaScript implementation of the geodesic routines +from [GeographicLib](https://geographiclib.sourceforge.io). This solves the +direct and inverse geodesic problems for an ellipsoid of revolution. + +Licensed under the MIT/X11 License; see +[LICENSE.txt](https://geographiclib.sourceforge.io/html/LICENSE.txt). + +## Installation + +```bash +$ npm install geographiclib +``` + +## Usage + +In [node](https://nodejs.org), do +```javascript +var GeographicLib = require("geographiclib"); +``` + +## Documentation + +Full documentation is provided at +[https://geographiclib.sourceforge.io/1.49/js/](https://geographiclib.sourceforge.io/1.49/js/). + +## Examples + +```javascript +var GeographicLib = require("geographiclib"), + geod = GeographicLib.Geodesic.WGS84, r; + +// Find the distance from Wellington, NZ (41.32S, 174.81E) to +// Salamanca, Spain (40.96N, 5.50W)... +r = geod.Inverse(-41.32, 174.81, 40.96, -5.50); +console.log("The distance is " + r.s12.toFixed(3) + " m."); +// This prints "The distance is 19959679.267 m." + +// Find the point 20000 km SW of Perth, Australia (32.06S, 115.74E)... +r = geod.Direct(-32.06, 115.74, 225, 20000e3); +console.log("The position is (" + + r.lat2.toFixed(8) + ", " + r.lon2.toFixed(8) + ")."); +// This prints "The position is (32.11195529, -63.95925278)." +``` + +## Authors + +* algorithms + js code: Charles Karney (charles@karney.com) +* node.js port: Yurij Mikhalevich (0@39.yt) diff --git a/gtsam/3rdparty/GeographicLib/js/conf.json b/gtsam/3rdparty/GeographicLib/js/conf.json new file mode 100644 index 000000000..d1d32d91e --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/js/conf.json @@ -0,0 +1,17 @@ +{ + "tags": { + "allowUnknownTags": true + }, + "source": { + "includePattern": ".+\\.js(doc)?$", + "excludePattern": "(^|\\/|\\\\)_" + }, + "plugins": [ "plugins/markdown" ], + "templates": { + "cleverLinks": false, + "monospaceLinks": false, + "default": { + "outputSourceFiles": true + } + } +} diff --git a/gtsam/3rdparty/GeographicLib/js/doc/1-geodesics.md b/gtsam/3rdparty/GeographicLib/js/doc/1-geodesics.md new file mode 100644 index 000000000..dec41d0b3 --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/js/doc/1-geodesics.md @@ -0,0 +1,172 @@ +Jump to +* [Introduction](#intro) +* [Additional properties](#additional) +* [Multiple shortest geodesics](#multiple) +* [Background](#background) +* [References](#references) + +### Introduction + +Consider a ellipsoid of revolution with equatorial radius *a*, polar +semi-axis *b*, and flattening *f* = (*a* − *b*)/*a* . Points on +the surface of the ellipsoid are characterized by their latitude φ +and longitude λ. (Note that latitude here means the +*geographical latitude*, the angle between the normal to the ellipsoid +and the equatorial plane). + +The shortest path between two points on the ellipsoid at +(φ1, λ1) and (φ2, +λ2) is called the geodesic. Its length is +*s*12 and the geodesic from point 1 to point 2 has forward +azimuths α1 and α2 at the two end +points. In this figure, we have λ12 = +λ2 − λ1. +
    + +
    +A geodesic can be extended indefinitely by requiring that any +sufficiently small segment is a shortest path; geodesics are also the +straightest curves on the surface. + +Traditionally two geodesic problems are considered: +* the direct problem — given φ1, + λ1, α1, *s*12, + determine φ2, λ2, and + α2; this is solved by + {@link module:GeographicLib/Geodesic.Geodesic#Direct Geodesic.Direct}. + +* the inverse problem — given φ1, + λ1, φ2, λ2, + determine *s*12, α1, and + α2; this is solved by + {@link module:GeographicLib/Geodesic.Geodesic#Inverse Geodesic.Inverse}. + +### Additional properties + +The routines also calculate several other quantities of interest +* *S*12 is the area between the geodesic from point 1 to + point 2 and the equator; i.e., it is the area, measured + counter-clockwise, of the quadrilateral with corners + (φ11), (0,λ1), + (0,λ2), and + (φ22). It is given in + meters2. +* *m*12, the reduced length of the geodesic is defined such + that if the initial azimuth is perturbed by *d*α1 + (radians) then the second point is displaced by *m*12 + *d*α1 in the direction perpendicular to the + geodesic. *m*12 is given in meters. On a curved surface + the reduced length obeys a symmetry relation, *m*12 + + *m*21 = 0. On a flat surface, we have *m*12 = + *s*12. +* *M*12 and *M*21 are geodesic scales. If two + geodesics are parallel at point 1 and separated by a small distance + *dt*, then they are separated by a distance *M*12 *dt* at + point 2. *M*21 is defined similarly (with the geodesics + being parallel to one another at point 2). *M*12 and + *M*21 are dimensionless quantities. On a flat surface, + we have *M*12 = *M*21 = 1. +* σ12 is the arc length on the auxiliary sphere. + This is a construct for converting the problem to one in spherical + trigonometry. The spherical arc length from one equator crossing to + the next is always 180°. + +If points 1, 2, and 3 lie on a single geodesic, then the following +addition rules hold: +* *s*13 = *s*12 + *s*23 +* σ13 = σ12 + σ23 +* *S*13 = *S*12 + *S*23 +* *m*13 = *m*12*M*23 + + *m*23*M*21 +* *M*13 = *M*12*M*23 − + (1 − *M*12*M*21) + *m*23/*m*12 +* *M*31 = *M*32*M*21 − + (1 − *M*23*M*32) + *m*12/*m*23 + +### Multiple shortest geodesics + +The shortest distance found by solving the inverse problem is +(obviously) uniquely defined. However, in a few special cases there are +multiple azimuths which yield the same shortest distance. Here is a +catalog of those cases: +* φ1 = −φ2 (with neither point at + a pole). If α1 = α2, the geodesic + is unique. Otherwise there are two geodesics and the second one is + obtained by setting [α12] ← + [α21], + [*M*12,*M*21] ← + [*M*21,*M*12], *S*12 ← + −*S*12. (This occurs when the longitude difference + is near ±180° for oblate ellipsoids.) +* λ2 = λ1 ± 180° (with + neither point at a pole). If α1 = 0° or + ±180°, the geodesic is unique. Otherwise there are two + geodesics and the second one is obtained by setting + [α12] ← + [−α1,−α2], + *S*12 ← −*S*12. (This occurs when + φ2 is near −φ1 for prolate + ellipsoids.) +* Points 1 and 2 at opposite poles. There are infinitely many + geodesics which can be generated by setting + [α12] ← + [α12] + + [δ,−δ], for arbitrary δ. (For spheres, this + prescription applies when points 1 and 2 are antipodal.) +* *s*12 = 0 (coincident points). There are infinitely many + geodesics which can be generated by setting + [α12] ← + [α12] + [δ,δ], for + arbitrary δ. + +### Background + +The algorithms implemented by this package are given in Karney (2013) +and are based on Bessel (1825) and Helmert (1880); the algorithm for +areas is based on Danielsen (1989). These improve on the work of +Vincenty (1975) in the following respects: +* The results are accurate to round-off for terrestrial ellipsoids (the + error in the distance is less then 15 nanometers, compared to 0.1 mm + for Vincenty). +* The solution of the inverse problem is always found. (Vincenty's + method fails to converge for nearly antipodal points.) +* The routines calculate differential and integral properties of a + geodesic. This allows, for example, the area of a geodesic polygon to + be computed. + +### References + +* F. W. Bessel, + {@link https://arxiv.org/abs/0908.1824 The calculation of longitude and + latitude from geodesic measurements (1825)}, + Astron. Nachr. **331**(8), 852–861 (2010), + translated by C. F. F. Karney and R. E. Deakin. +* F. R. Helmert, + {@link https://doi.org/10.5281/zenodo.32050 + Mathematical and Physical Theories of Higher Geodesy, Vol 1}, + (Teubner, Leipzig, 1880), Chaps. 5–7. +* T. Vincenty, + {@link http://www.ngs.noaa.gov/PUBS_LIB/inverse.pdf + Direct and inverse solutions of geodesics on the ellipsoid with + application of nested equations}, + Survey Review **23**(176), 88–93 (1975). +* J. Danielsen, + {@link https://doi.org/10.1179/003962689791474267 The area under + the geodesic}, Survey Review **30**(232), 61–66 (1989). +* C. F. F. Karney, + {@link https://doi.org/10.1007/s00190-012-0578-z + Algorithms for geodesics}, J. Geodesy **87**(1) 43–55 (2013); + {@link https://geographiclib.sourceforge.io/geod-addenda.html addenda}. +* C. F. F. Karney, + {@https://arxiv.org/abs/1102.1215v1 + Geodesics on an ellipsoid of revolution}, + Feb. 2011; + {@link https://geographiclib.sourceforge.io/geod-addenda.html#geod-errata + errata}. +* {@link https://geographiclib.sourceforge.io/geodesic-papers/biblio.html + A geodesic bibliography}. +* The wikipedia page, + {@link https://en.wikipedia.org/wiki/Geodesics_on_an_ellipsoid + Geodesics on an ellipsoid}. diff --git a/gtsam/3rdparty/GeographicLib/js/doc/2-interface.md b/gtsam/3rdparty/GeographicLib/js/doc/2-interface.md new file mode 100644 index 000000000..e0a009dbf --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/js/doc/2-interface.md @@ -0,0 +1,117 @@ +Jump to +* [The units](#units) +* [The results](#results) +* [The *outmask* and *caps* parameters](#outmask) +* [Restrictions on the parameters](#restrict) + +### The units + +All angles (latitude, longitude, azimuth, arc length) are measured in +degrees with latitudes increasing northwards, longitudes increasing +eastwards, and azimuths measured clockwise from north. For a point at a +pole, the azimuth is defined by keeping the longitude fixed, writing +φ = ±(90° − ε), and taking the limit +ε → 0+. + +### The results + +The results returned by +{@link module:GeographicLib/Geodesic.Geodesic#Inverse Geodesic.Direct}, +{@link module:GeographicLib/Geodesic.Geodesic#Inverse Geodesic.Inverse}, +{@link module:GeographicLib/GeodesicLine.GeodesicLine#Position +GeodesicLine.Position}, etc., return an object with +(some) of the following 12 fields set: +* *lat1* = φ1, latitude of point 1 (degrees) +* *lon1* = λ1, longitude of point 1 (degrees) +* *azi1* = α1, azimuth of line at point 1 (degrees) +* *lat2* = φ2, latitude of point 2 (degrees) +* *lon2* = λ2, longitude of point 2 (degrees) +* *azi2* = α2, (forward) azimuth of line at point 2 (degrees) +* *s12* = *s*12, distance from 1 to 2 (meters) +* *a12* = σ12, arc length on auxiliary sphere from 1 to 2 + (degrees) +* *m12* = *m*12, reduced length of geodesic (meters) +* *M12* = *M*12, geodesic scale at 2 relative to 1 (dimensionless) +* *M21* = *M*21, geodesic scale at 1 relative to 2 (dimensionless) +* *S12* = *S*12, area between geodesic and equator + (meters2) + +The input parameters together with *a12* are always included in the +object. Azimuths are reduced to the range [−180°, 180°]. +See {@tutorial 1-geodesics} for the definitions of these quantities. + +### The *outmask* and *caps* parameters + +By default, the geodesic routines return the 7 basic quantities: *lat1*, +*lon1*, *azi1*, *lat2*, *lon2*, *azi2*, *s12*, together with the arc +length *a12*. The optional output mask parameter, *outmask*, can be +used to tailor which quantities to calculate. In addition, when a +{@link module:GeographicLib/GeodesicLine.GeodesicLine GeodesicLine} is +constructed it can be provided with the optional capabilities parameter, +*caps*, which specifies what quantities can be returned from the +resulting object. + +Both *outmask* and *caps* are obtained by or'ing together the following +values +* Geodesic.NONE, no capabilities, no output; +* Geodesic.ARC, compute arc length, *a12*; this is always implicitly set; +* Geodesic.LATITUDE, compute latitude, *lat2*; +* Geodesic.LONGITUDE, compute longitude, *lon2*; +* Geodesic.AZIMUTH, compute azimuths, *azi1* and *azi2*; +* Geodesic.DISTANCE, compute distance, *s12*; +* Geodesic.STANDARD, all of the above; +* Geodesic.DISTANCE_IN, allow *s12* to be used as input in the direct problem; +* Geodesic.REDUCEDLENGTH, compute reduced length, *m12*; +* Geodesic.GEODESICSCALE, compute geodesic scales, *M12* and *M21*; +* Geodesic.AREA, compute area, *S12*; +* Geodesic.ALL, all of the above; +* Geodesic.LONG_UNROLL, unroll longitudes. + +Geodesic.DISTANCE_IN is a capability provided to the +{@link module:GeographicLib/GeodesicLine.GeodesicLine GeodesicLine} +constructor. It allows the position on the line to specified in terms +of distance. (Without this, the position can only be specified in terms +of the arc length.) This only makes sense in the *caps* parameter. + +Geodesic.LONG_UNROLL controls the treatment of longitude. If it is not +set then the *lon1* and *lon2* fields are both reduced to the range +[−180°, 180°]. If it is set, then *lon1* is as given in +the function call and (*lon2* − *lon1*) determines how many times +and in what sense the geodesic has encircled the ellipsoid. This only +makes sense in the *outmask* parameter. + +Note that *a12* is always included in the result. + +### Restrictions on the parameters + +* Latitudes must lie in [−90°, 90°]. Latitudes outside + this range are replaced by NaNs. +* The distance *s12* is unrestricted. This allows geodesics to wrap + around the ellipsoid. Such geodesics are no longer shortest paths. + However they retain the property that they are the straightest curves + on the surface. +* Similarly, the spherical arc length *a12* is unrestricted. +* Longitudes and azimuths are unrestricted; internally these are exactly + reduced to the range [−180°, 180°]; but see also the + LONG_UNROLL bit. +* The equatorial radius *a* and the polar semi-axis *b* must both be + positive and finite (this implies that −∞ < *f* < 1). +* The flattening *f* should satisfy *f* ∈ [−1/50,1/50] in + order to retain full accuracy. This condition holds for most + applications in geodesy. + +Reasonably accurate results can be obtained for −0.2 ≤ *f* ≤ +0.2. Here is a table of the approximate maximum error (expressed as a +distance) for an ellipsoid with the same equatorial radius as the WGS84 +ellipsoid and different values of the flattening. + + | abs(f) | error + |:-------|------: + | 0.003 | 15 nm + | 0.01 | 25 nm + | 0.02 | 30 nm + | 0.05 | 10 μm + | 0.1 | 1.5 mm + | 0.2 | 300 mm + +Here 1 nm = 1 nanometer = 10−9 m (*not* 1 nautical mile!) diff --git a/gtsam/3rdparty/GeographicLib/js/doc/3-examples.md b/gtsam/3rdparty/GeographicLib/js/doc/3-examples.md new file mode 100644 index 000000000..4aa286332 --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/js/doc/3-examples.md @@ -0,0 +1,276 @@ +Jump to +* [GeographicLib namespace](#namespace) +* [Specifying the ellipsoid](#ellipsoid) +* [Basic geodesic calculations](#basic) +* [Computing waypoints](#waypoints) +* [Measuring areas](#area) +* [Degrees, minutes, seconds conversion](#dms) + +### GeographicLib namespace + +This capabilities of this package are all exposed through the +{@link GeographicLib} namespace. This is can brought into scope in +various ways. + +#### Using node after installing the package with npm + +If [npm](https://www.npmjs.com) has been used to install geographiclib +via one of +```bash +$ npm install geographiclib +$ npm install --global geographiclib +``` +then in [node](https://nodejs.org), you can do +```javascript +var GeographicLib = require("geographiclib"); +``` + +#### Using node with a free-standing geographiclib.js + +If you have geographiclib.js (version 1.45 or later) in your current +directory, then [node](https://nodejs.org) can access it with +```javascript +var GeographicLib = require("./geographiclib"); +``` +A similar prescription works if geographiclib.js is installed elsewhere +in your filesystem, replacing "./" above with the correct directory. +Note that the directory must begin with "./", "../", or "/". + +#### HTML with your own version of geographiclib.min.js + +Load geographiclib.min.js with +```html + +``` +This ".min.js" version has been "minified" by removing comments and +redundant white space; this is appropriate for web applications. + +#### HTML downloading geographiclib.min.js from SourceForge + +Load geographiclib.min.js with +```html + +``` +This uses the latest version. If you want use a specific version, load +with, for example, +```html + +``` +Browse +[https://geographiclib.sourceforge.io/scripts](https://geographiclib.sourceforge.io/scripts) +to see what versions are available. + +#### Loading geographiclib.min.js with AMD + +This uses [require.js](http://requirejs.org/) (which you can download +[here](http://requirejs.org/docs/download.html)) to load geographiclib +(version 1.45 or later) asynchronously. Your web page includes +```html + + +``` +where main.js contains, for example, +```javascript +require.config({ + paths: { + geographiclib: "./geographiclib.min" + } +}); + +define(["geographiclib"], function(GeographicLib) { + // do something with GeographicLib here. +}); +``` + +### Specifying the ellipsoid + +Once {@link GeographicLib} has been brought into scope, the ellipsoid is +defined via the {@link module:GeographicLib/Geodesic.Geodesic Geodesic} +constructor using the equatorial radius *a* in meters and the flattening +*f*, for example +```javascipt +var geod = new GeographicLib.Geodesic.Geodesic(6378137, 1/298.257223563); +``` +These are the parameters for the WGS84 ellipsoid and this comes predefined +by the package as +```javascipt +var geod = GeographicLib.Geodesic.WGS84; +``` +Note that you can set *f* = 0 to give a sphere (on which geodesics are +great circles) and *f* < 0 to give a prolate ellipsoid. + +The rest of the examples on this page assume the following assignments +```javascript +var GeographicLib = require("geographiclib"); +var Geodesic = GeographicLib.Geodesic, + DMS = GeographicLib.DMS, + geod = Geodesic.WGS84; +``` +with the understanding that the first line should be replaced with the +appropriate construction needed to bring the +[GeographicLib namespace](#namespace) into scope. + +### Basic geodesic calculations + +The distance from Wellington, NZ (41.32S, 174.81E) to Salamanca, Spain +(40.96N, 5.50W) using +{@link module:GeographicLib/Geodesic.Geodesic#Inverse +Geodesic.Inverse}: +```javascript +var r = geod.Inverse(-41.32, 174.81, 40.96, -5.50); +console.log("The distance is " + r.s12.toFixed(3) + " m."); +``` +→`The distance is 19959679.267 m.` + +The point the point 20000 km SW of Perth, Australia (32.06S, 115.74E) using +{@link module:GeographicLib/Geodesic.Geodesic#Direct +Geodesic.Direct}: +```javascript +var r = geod.Direct(-32.06, 115.74, 225, 20000e3); +console.log("The position is (" + + r.lat2.toFixed(8) + ", " + r.lon2.toFixed(8) + ")."); +``` +→`The position is (32.11195529, -63.95925278).` + +The area between the geodesic from JFK Airport (40.6N, 73.8W) to LHR +Airport (51.6N, 0.5W) and the equator. This is an example of setting +the *outmask* parameter, see {@tutorial 2-interface}, "The *outmask* and +*caps* parameters". +```javascript +var r = geod.Inverse(40.6, -73.8, 51.6, -0.5, Geodesic.AREA); +console.log("The area is " + r.S12.toFixed(1) + " m^2"); +``` +→`The area is 40041368848742.5 m^2` + +### Computing waypoints + +Consider the geodesic between Beijing Airport (40.1N, 116.6E) and San +Fransisco Airport (37.6N, 122.4W). Compute waypoints and azimuths at +intervals of 1000 km using +{@link module:GeographicLib/Geodesic.Geodesic#InverseLine +Geodesic.InverseLine} and +{@link module:GeographicLib/GeodesicLine.GeodesicLine#Position +GeodesicLine.Position}: +```javascript +var l = geod.InverseLine(40.1, 116.6, 37.6, -122.4), + n = Math.ceil(l.s13 / ds), + i, s; +console.log("distance latitude longitude azimuth"); +for (i = 0; i <= n; ++i) { + s = Math.min(ds * i, l.s13); + r = l.Position(s, Geodesic.STANDARD | Geodesic.LONG_UNROLL); + console.log(r.s12.toFixed(0) + " " + r.lat2.toFixed(5) + " " + + r.lon2.toFixed(5) + " " + r.azi2.toFixed(5)); +} +``` +gives +```text +distance latitude longitude azimuth +0 40.10000 116.60000 42.91642 +1000000 46.37321 125.44903 48.99365 +2000000 51.78786 136.40751 57.29433 +3000000 55.92437 149.93825 68.24573 +4000000 58.27452 165.90776 81.68242 +5000000 58.43499 183.03167 96.29014 +6000000 56.37430 199.26948 109.99924 +7000000 52.45769 213.17327 121.33210 +8000000 47.19436 224.47209 129.98619 +9000000 41.02145 233.58294 136.34359 +9513998 37.60000 237.60000 138.89027 +``` +The inclusion of Geodesic.LONG_UNROLL in the call to +{@link module:GeographicLib/GeodesicLine.GeodesicLine#Position +GeodesicLine.Position} ensures that the longitude does not jump on +crossing the international dateline. + +If the purpose of computing the waypoints is to plot a smooth geodesic, +then it's not important that they be exactly equally spaced. In this +case, it's faster to parameterize the line in terms of the spherical arc +length with +{@link module:GeographicLib/GeodesicLine.GeodesicLine#ArcPosition +GeodesicLine.ArcPosition} instead of the distance. Here the spacing is +about 1° of arc which means that the distance between the waypoints +will be about 60 NM. +```javascript +var l = geod.InverseLine(40.1, 116.6, 37.6, -122.4, + Geodesic.LATITUDE | Geodesic.LONGITUDE), + da = 1, n = Math.ceil(l.a13 / da), + i, a; +da = l.a13 / n; +console.log("latitude longitude"); +for (i = 0; i <= n; ++i) { + a = da * i; + r = l.ArcPosition(a, Geodesic.LATITUDE | + Geodesic.LONGITUDE | Geodesic.LONG_UNROLL); + console.log(r.lat2.toFixed(5) + " " + r.lon2.toFixed(5)); +} +``` +gives +```text +latitude longitude +40.10000 116.60000 +40.82573 117.49243 +41.54435 118.40447 +42.25551 119.33686 +42.95886 120.29036 +43.65403 121.26575 +44.34062 122.26380 +... +39.82385 235.05331 +39.08884 235.91990 +38.34746 236.76857 +37.60000 237.60000 +``` +The variation in the distance between these waypoints is on the order of +1/*f*. + +### Measuring areas + +Measure the area of Antarctica using +{@link module:GeographicLib/Geodesic.Geodesic#Polygon +Geodesic.Polygon} and the +{@link module:GeographicLib/PolygonArea.PolygonArea +PolygonArea} class: +```javascript +var p = geod.Polygon(false), i, + antarctica = [ + [-63.1, -58], [-72.9, -74], [-71.9,-102], [-74.9,-102], [-74.3,-131], + [-77.5,-163], [-77.4, 163], [-71.7, 172], [-65.9, 140], [-65.7, 113], + [-66.6, 88], [-66.9, 59], [-69.8, 25], [-70.0, -4], [-71.0, -14], + [-77.3, -33], [-77.9, -46], [-74.7, -61] + ]; +for (i = 0; i < antarctica.length; ++i) + p.AddPoint(antarctica[i][0], antarctica[i][1]); +p = p.Compute(false, true); +console.log("Perimeter/area of Antarctica are " + + p.perimeter.toFixed(3) + " m / " + + p.area.toFixed(1) + " m^2."); +``` +→`Perimeter/area of Antarctica are 16831067.893 m / 13662703680020.1 m^2.` + +If the points of the polygon are being selected interactively, then +{@link module:GeographicLib/PolygonArea.PolygonArea#TestPoint +PolygonArea.TestPoint} can be used to report the area and perimeter for +a polygon with a tentative final vertex which tracks the mouse pointer. + +### Degrees, minutes, seconds conversion + +Compute the azimuth for geodesic from JFK (73.8W, 40.6N) to Paris CDG +(49°01'N, 2°33'E) using the {@link module:GeographicLib/DMS DMS} module: +```javascript +var c = "73.8W 40.6N 49°01'N 2°33'E".split(" "), + p1 = DMS.DecodeLatLon(c[0], c[1]), + p2 = DMS.DecodeLatLon(c[2], c[3]), + r = geod.Inverse(p1.lat, p1.lon, p2.lat, p2.lon); +console.log("Start = (" + + DMS.Encode(r.lat1, DMS.MINUTE, 0, DMS.LATITUDE) + ", " + + DMS.Encode(r.lon1, DMS.MINUTE, 0, DMS.LONGITUDE) + + "), azimuth = " + + DMS.Encode(r.azi1, DMS.MINUTE, 1, DMS.AZIMUTH)); +``` +→`Start = (40°36'N, 073°48'W), azimuth = 053°28.2'` diff --git a/gtsam/3rdparty/GeographicLib/js/doc/tutorials.json b/gtsam/3rdparty/GeographicLib/js/doc/tutorials.json new file mode 100644 index 000000000..0b6257f52 --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/js/doc/tutorials.json @@ -0,0 +1,11 @@ + { + "1-geodesics": { + "title": "General information on geodesics" + }, + "2-interface": { + "title": "The library interface" + }, + "3-examples": { + "title": "Examples of use" + } + } diff --git a/gtsam/3rdparty/GeographicLib/js/js-cat.sh b/gtsam/3rdparty/GeographicLib/js/js-cat.sh new file mode 100755 index 000000000..272149989 --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/js/js-cat.sh @@ -0,0 +1,37 @@ +#! /bin/sh -e +# Concatenate JavaScript files +HEADER=$1 +shift +JS_VERSION=`grep -h "version_string = " "$@" | cut -f2 -d'"'` +FILE_INVENTORY= +for f; do + FILE_INVENTORY="$FILE_INVENTORY `basename $f`" +done +sed -e "s/@JS_VERSION@/$JS_VERSION/" -e "s/@FILE_INVENTORY@/$FILE_INVENTORY/" \ + $HEADER +cat <", + "contributors": [ + "Yurij Mikhalevich <0@39.yt>" + ], + "license": "MIT", + "bugs": { + "url": "https://sourceforge.net/p/geographiclib/discussion/", + "email": "charles@karney.com" + } +} diff --git a/gtsam/3rdparty/GeographicLib/js/samples/geod-calc.html b/gtsam/3rdparty/GeographicLib/js/samples/geod-calc.html new file mode 100644 index 000000000..ee454da36 --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/js/samples/geod-calc.html @@ -0,0 +1,593 @@ + + + + Geodesic calculations for an ellipsoid done right + + + + + + + + + +
    +

    Geodesic calculations for an ellipsoid done right

    +
    +

    + This page illustrates the geodesic routines available in + JavaScript package + + geographiclib, the geodesic routines in GeographicLib + ( + documentation). + The algorithms are considerably more accurate than Vincenty's + method, and offer more functionality (an inverse method which + never fails to converge, differential properties of the geodesic, + and the area under a geodesic). The algorithms are derived in +

    + Charles F. F. Karney,
    + + Algorithms for geodesics,
    + J. Geodesy 87(1), 43–55 (Jan. 2013);
    + DOI: + + 10.1007/s00190-012-0578-z + (pdf); + addenda: + + geod-addenda.html. +
    + This page just provides a basic interface. Enter latitudes, + longitudes, and azimuths as degrees and distances as meters using + spaces or commas as separators. (Angles may be entered as decimal + degrees or as degrees, minutes, and seconds, e.g. -20.51125, + 20°30′40.5″S, S20d30'40.5", or + -20:30:40.5.) The results are accurate to about + 15 nanometers (or 0.1 m2 per vertex for + areas). A slicker page where the geodesics are incorporated into + Google Maps is given here. Basic + online tools which provide similar capabilities are + + GeodSolve + and + + Planimeter; + these call a C++ backend. This page uses version + + of the geodesic code. +

    + Jump to: +

    +

    +
    +
    +

    Inverse problem

    +

    + Find the shortest path between two points on the earth. The + path is characterized by its length s12 and its azimuth + at the two ends azi1 and azi2. See + + GeodSolve(1) + for the definition of the + quantities a12, m12, M12, M21, + and S12. The sample calculation finds the shortest path + between Wellington, New Zealand, and Salamanca, Spain. To + perform the calculation, press the “COMPUTE” button. +

    +

    Enter “lat1 lon1 lat2 lon2”:

    +

    input: + +

    +

    + Output format:    +
    + Output precision:   +

    +

    + +

    +

    + status: + +

    +

    + lat1 lon1 azi1: + +

    +

    + lat2 lon2 azi2: + +

    +

    + s12: + +

    +

    + a12: + +

    +

    + m12: + +

    +

    + M12 M21: + +

    +

    + S12: + +

    +
    +
    +
    +

    Direct problem

    +

    + Find the destination traveling a given distance along a geodesic + with a given azimuth at the starting point. The destination is + characterized by its position lat2, lon2 and its azimuth + at the destination azi2. See + + GeodSolve(1) + for the definition of the + quantities a12, m12, M12, M21, + and S12. The sample calculation shows the result of + travelling 10000 km NE from JFK airport. To perform the + calculation, press the “COMPUTE” button. +

    +

    Enter “lat1 lon1 azi1 s12”:

    +

    input: + +

    +

    + Output format:    +
    + Output precision:   +

    +

    + +

    +

    + status: + +

    +

    + lat1 lon1 azi1: + +

    +

    + lat2 lon2 azi2: + +

    +

    + s12: + +

    +

    + a12: + +

    +

    + m12: + +

    +

    + M12 M21: + +

    +

    + S12: + +

    +
    +
    +
    +

    Geodesic path

    +

    + Find intermediate points along a geodesic. In addition to + specifying the endpoints, give ds12, the maximum distance + between the intermediate points and maxk, the maximum + number of intervals the geodesic is broken into. The output + gives a sequence of positions lat, lon together with the + corresponding azimuths azi. The sample shows the path + from JFK to Singapore's Changi Airport at about 1000 km + intervals. (In this example, the path taken by Google Earth + deviates from the shortest path by about 2.9 km.) To perform + the calculation, press the “COMPUTE” button. +

    +

    Enter “lat1 lon1 lat2 lon2 ds12 maxk”:

    +

    input: + +

    +

    + Output format:    +
    + Output precision:   +

    +

    + +

    +

    + status: + +

    +

    + points (lat lon azi):
    + +

    + +
    +
    +

    Polygon area

    +

    + Find the perimeter and area of a polygon whose sides are + geodesics. The polygon must be simple (i.e., must not intersect + itself). (There's no need to ensure that the polygon is + closed.) Counter-clockwise traversal of the polygon results in + a positive area. The polygon can encircle one or both poles. + The sample gives the approximate perimeter (in m) and area (in + m2) of Antarctica. (For this example, Google Earth + Pro returns an area which is 30 times too large! However this + is a little unfair, since Google Earth has no concept of + polygons which encircle a pole.) If the polyline option + is selected then just the length of the line joining the points + is returned. To perform the calculation, press the + “COMPUTE” button. +

    +

    Enter points, one per line, as “lat lon”:

    +

    points (lat lon):
    + +

    +

    + Treat points as:    + +

    +

    + +

    +

    + status: + +

    +

    + number perimeter area: + +

    + +
    +
    Charles Karney + <charles@karney.com> + (2015-08-12)
    +
    + + Geographiclib Sourceforge + + diff --git a/gtsam/3rdparty/GeographicLib/js/samples/geod-google-instructions.html b/gtsam/3rdparty/GeographicLib/js/samples/geod-google-instructions.html new file mode 100644 index 000000000..10c29d206 --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/js/samples/geod-google-instructions.html @@ -0,0 +1,127 @@ + + + + + Geodesic lines, circles, envelopes in Google Maps (instructions) + + + + + + + +

    + Geodesic lines, circles, envelopes in Google Maps (instructions) +

    +

    + The page allows you to draw + accurate ellipsoidal geodesics on Google Maps. You can specify the + geodesic in one of two forms: +

      +
    • + The direct problem: specify a starting point, an + azimuth and a distance as lat1 lon1 azi1 s12 as degrees + and meters. +
    • + The inverse problem: specify the two end points + as lat1 lon1 lat2 lon2 as degrees; this finds the + shortest path between the two points. +
    + (Angles may be entered as decimal degrees or as degrees, minutes, + and seconds, e.g. -20.51125, 20°30′40.5″S, + S20d30'40.5", or -20:30:40.5.) Click on the + corresponding "compute" button. The display then shows +
      +
    • The requested geodesic as a blue + line; the WGS84 ellipsoid model is used. +
    • The geodesic circle as a green + curve; this shows the locus of points a + distance s12 from lat1, lon1. +
    • The geodesic envelopes as red + curves; all the geodesics emanating from lat1, + lon1 are tangent to the envelopes (providing they are + extended far enough). The number of solutions to the inverse + problem changes depending on whether lat2, lon2 lies + inside the envelopes. For example, there are four (resp. two) + approximately hemispheroidal geodesics if this point lies + inside (resp. outside) the inner envelope (only one of which + is a shortest path). +
    +

    +

    + The sample data has lat1, lon1 in Wellington, New + Zealand, lat2, lon2 in Salamanca, Spain, and s12 + about 1.5 times the earth's circumference. Try clicking on the + "compute" button next to the "Direct:" input box when the page + first loads. You can navigate around the map using the normal + Google Map controls. +

    +

    + The precision of output for the geodesic is 0.1" or 1 m. + A text-only geodesic calculator based + on the same JavaScript library is also available; this calculator + solves the inverse and direct geodesic problems, computes + intermediate points on a geodesic, and finds the area of a + geodesic polygon; it allows you to specify the precision of the + output and choose between decimal degrees and degrees, minutes, + and seconds. Basic online tools which provide similar capabilities + are + + GeodSolve + and + + Planimeter; + these call a C++ backend. +

    +

    + The JavaScript code for computing the geodesic lines, circles, and + envelopes available in the JavaScript package + + geographiclib, the geodesic routines in GeographicLib + ( + documentation). The algorithms are derived in +

    + Charles F. F. Karney,
    + + Algorithms for geodesics,
    + J. Geodesy 87(1), 43–55 (Jan. 2013);
    + DOI: + + 10.1007/s00190-012-0578-z + (pdf);
    + addenda: + + geod-addenda.html. +
    + In putting together this Google Maps demonstration, I started with + the sample code + + geometry-headings. +

    +
    +
    Charles Karney + <charles@karney.com> + (2011-08-02)
    +
    + + Geographiclib Sourceforge + + diff --git a/gtsam/3rdparty/GeographicLib/js/samples/geod-google.html b/gtsam/3rdparty/GeographicLib/js/samples/geod-google.html new file mode 100644 index 000000000..c62295652 --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/js/samples/geod-google.html @@ -0,0 +1,340 @@ + + + + + Geodesic lines, circles, envelopes in Google Maps + + + + + + + + + + + + +
    +
    +
    +

    +  Direct:   + + +

    +

    +  Inverse: + + +

    +

    +  lat1 lon1 azi1: +

    +

    +  lat2 lon2 azi2: +

    +

    +  s12: +    status: +    + INSTRUCTIONS + (v) +

    +
    + + diff --git a/gtsam/3rdparty/GeographicLib/js/src/DMS.js b/gtsam/3rdparty/GeographicLib/js/src/DMS.js new file mode 100644 index 000000000..e5fbf6e3a --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/js/src/DMS.js @@ -0,0 +1,477 @@ +/* + * DMS.js + * Transcription of DMS.[ch]pp into JavaScript. + * + * See the documentation for the C++ class. The conversion is a literal + * conversion from C++. + * + * Copyright (c) Charles Karney (2011-2017) and licensed + * under the MIT/X11 License. For more information, see + * https://geographiclib.sourceforge.io/ + */ + +GeographicLib.DMS = {}; + +(function( + /** + * @exports GeographicLib/DMS + * @description Decode/Encode angles expressed as degrees, minutes, and + * seconds. This module defines several constants: + * - hemisphere indicator (returned by + * {@link module:GeographicLib/DMS.Decode Decode}) and a formatting + * indicator (used by + * {@link module:GeographicLib/DMS.Encode Encode}) + * - NONE = 0, no designator and format as plain angle; + * - LATITUDE = 1, a N/S designator and format as latitude; + * - LONGITUDE = 2, an E/W designator and format as longitude; + * - AZIMUTH = 3, format as azimuth; + * - the specification of the trailing component in + * {@link module:GeographicLib/DMS.Encode Encode} + * - DEGREE; + * - MINUTE; + * - SECOND. + */ + d) { + + var lookup, zerofill, internalDecode, numMatch, + hemispheres_ = "SNWE", + signs_ = "-+", + digits_ = "0123456789", + dmsindicators_ = "D'\":", + // dmsindicatorsu_ = "\u00b0\u2032\u2033"; // Unicode variants + dmsindicatorsu_ = "\u00b0'\"", // Use degree symbol + components_ = ["degrees", "minutes", "seconds"]; + lookup = function(s, c) { + return s.indexOf(c.toUpperCase()); + }; + zerofill = function(s, n) { + return String("0000").substr(0, Math.max(0, Math.min(4, n-s.length))) + + s; + }; + d.NONE = 0; + d.LATITUDE = 1; + d.LONGITUDE = 2; + d.AZIMUTH = 3; + d.DEGREE = 0; + d.MINUTE = 1; + d.SECOND = 2; + + /** + * @summary Decode a DMS string. + * @description The interpretation of the string is given in the + * documentation of the corresponding function, Decode(string&, flag&) + * in the {@link + * https://geographiclib.sourceforge.io/html/classGeographicLib_1_1DMS.html + * C++ DMS class} + * @param {string} dms the string. + * @returns {object} r where r.val is the decoded value (degrees) and r.ind + * is a hemisphere designator, one of NONE, LATITUDE, LONGITUDE. + * @throws an error if the string is illegal. + */ + d.Decode = function(dms) { + var dmsa = dms, end, + v = 0, i = 0, mi, pi, vals, + ind1 = d.NONE, ind2, p, pa, pb; + dmsa = dmsa.replace(/\u00b0/g, 'd') + .replace(/\u00ba/g, 'd') + .replace(/\u2070/g, 'd') + .replace(/\u02da/g, 'd') + .replace(/\u2032/g, '\'') + .replace(/\u00b4/g, '\'') + .replace(/\u2019/g, '\'') + .replace(/\u2033/g, '"') + .replace(/\u201d/g, '"') + .replace(/\u2212/g, '-') + .replace(/''/g, '"') + .trim(); + end = dmsa.length; + // p is pointer to the next piece that needs decoding + for (p = 0; p < end; p = pb, ++i) { + pa = p; + // Skip over initial hemisphere letter (for i == 0) + if (i === 0 && lookup(hemispheres_, dmsa.charAt(pa)) >= 0) + ++pa; + // Skip over initial sign (checking for it if i == 0) + if (i > 0 || (pa < end && lookup(signs_, dmsa.charAt(pa)) >= 0)) + ++pa; + // Find next sign + mi = dmsa.substr(pa, end - pa).indexOf('-'); + pi = dmsa.substr(pa, end - pa).indexOf('+'); + if (mi < 0) mi = end; else mi += pa; + if (pi < 0) pi = end; else pi += pa; + pb = Math.min(mi, pi); + vals = internalDecode(dmsa.substr(p, pb - p)); + v += vals.val; ind2 = vals.ind; + if (ind1 === d.NONE) + ind1 = ind2; + else if (!(ind2 === d.NONE || ind1 === ind2)) + throw new Error("Incompatible hemisphere specifies in " + + dmsa.substr(0, pb)); + } + if (i === 0) + throw new Error("Empty or incomplete DMS string " + dmsa); + return {val: v, ind: ind1}; + }; + + internalDecode = function(dmsa) { + var vals = {}, errormsg = "", + sign, beg, end, ind1, k, + ipieces, fpieces, npiece, + icurrent, fcurrent, ncurrent, p, + pointseen, + digcount, intcount, + x; + do { // Executed once (provides the ability to break) + sign = 1; + beg = 0; end = dmsa.length; + ind1 = d.NONE; + k = -1; + if (end > beg && (k = lookup(hemispheres_, dmsa.charAt(beg))) >= 0) { + ind1 = (k & 2) ? d.LONGITUDE : d.LATITUDE; + sign = (k & 1) ? 1 : -1; + ++beg; + } + if (end > beg && + (k = lookup(hemispheres_, dmsa.charAt(end-1))) >= 0) { + if (k >= 0) { + if (ind1 !== d.NONE) { + if (dmsa.charAt(beg - 1).toUpperCase() === + dmsa.charAt(end - 1).toUpperCase()) + errormsg = "Repeated hemisphere indicators " + + dmsa.charAt(beg - 1) + " in " + + dmsa.substr(beg - 1, end - beg + 1); + else + errormsg = "Contradictory hemisphere indicators " + + dmsa.charAt(beg - 1) + " and " + dmsa.charAt(end - 1) + " in " + + dmsa.substr(beg - 1, end - beg + 1); + break; + } + ind1 = (k & 2) ? d.LONGITUDE : d.LATITUDE; + sign = (k & 1) ? 1 : -1; + --end; + } + } + if (end > beg && (k = lookup(signs_, dmsa.charAt(beg))) >= 0) { + if (k >= 0) { + sign *= k ? 1 : -1; + ++beg; + } + } + if (end === beg) { + errormsg = "Empty or incomplete DMS string " + dmsa; + break; + } + ipieces = [0, 0, 0]; + fpieces = [0, 0, 0]; + npiece = 0; + icurrent = 0; + fcurrent = 0; + ncurrent = 0; + p = beg; + pointseen = false; + digcount = 0; + intcount = 0; + while (p < end) { + x = dmsa.charAt(p++); + if ((k = lookup(digits_, x)) >= 0) { + ++ncurrent; + if (digcount > 0) { + ++digcount; // Count of decimal digits + } else { + icurrent = 10 * icurrent + k; + ++intcount; + } + } else if (x === '.') { + if (pointseen) { + errormsg = "Multiple decimal points in " + + dmsa.substr(beg, end - beg); + break; + } + pointseen = true; + digcount = 1; + } else if ((k = lookup(dmsindicators_, x)) >= 0) { + if (k >= 3) { + if (p === end) { + errormsg = "Illegal for colon to appear at the end of " + + dmsa.substr(beg, end - beg); + break; + } + k = npiece; + } + if (k === npiece - 1) { + errormsg = "Repeated " + components_[k] + + " component in " + dmsa.substr(beg, end - beg); + break; + } else if (k < npiece) { + errormsg = components_[k] + " component follows " + + components_[npiece - 1] + " component in " + + dmsa.substr(beg, end - beg); + break; + } + if (ncurrent === 0) { + errormsg = "Missing numbers in " + components_[k] + + " component of " + dmsa.substr(beg, end - beg); + break; + } + if (digcount > 0) { + fcurrent = parseFloat(dmsa.substr(p - intcount - digcount - 1, + intcount + digcount)); + icurrent = 0; + } + ipieces[k] = icurrent; + fpieces[k] = icurrent + fcurrent; + if (p < end) { + npiece = k + 1; + icurrent = fcurrent = 0; + ncurrent = digcount = intcount = 0; + } + } else if (lookup(signs_, x) >= 0) { + errormsg = "Internal sign in DMS string " + + dmsa.substr(beg, end - beg); + break; + } else { + errormsg = "Illegal character " + x + " in DMS string " + + dmsa.substr(beg, end - beg); + break; + } + } + if (errormsg.length) + break; + if (lookup(dmsindicators_, dmsa.charAt(p - 1)) < 0) { + if (npiece >= 3) { + errormsg = "Extra text following seconds in DMS string " + + dmsa.substr(beg, end - beg); + break; + } + if (ncurrent === 0) { + errormsg = "Missing numbers in trailing component of " + + dmsa.substr(beg, end - beg); + break; + } + if (digcount > 0) { + fcurrent = parseFloat(dmsa.substr(p - intcount - digcount, + intcount + digcount)); + icurrent = 0; + } + ipieces[npiece] = icurrent; + fpieces[npiece] = icurrent + fcurrent; + } + if (pointseen && digcount === 0) { + errormsg = "Decimal point in non-terminal component of " + + dmsa.substr(beg, end - beg); + break; + } + // Note that we accept 59.999999... even though it rounds to 60. + if (ipieces[1] >= 60 || fpieces[1] > 60) { + errormsg = "Minutes " + fpieces[1] + " not in range [0,60)"; + break; + } + if (ipieces[2] >= 60 || fpieces[2] > 60) { + errormsg = "Seconds " + fpieces[2] + " not in range [0,60)"; + break; + } + vals.ind = ind1; + // Assume check on range of result is made by calling routine (which + // might be able to offer a better diagnostic). + vals.val = sign * + ( fpieces[2] ? (60*(60*fpieces[0] + fpieces[1]) + fpieces[2]) / 3600 : + ( fpieces[1] ? (60*fpieces[0] + fpieces[1]) / 60 : fpieces[0] ) ); + return vals; + } while (false); + vals.val = numMatch(dmsa); + if (vals.val === 0) + throw new Error(errormsg); + else + vals.ind = d.NONE; + return vals; + }; + + numMatch = function(s) { + var t, sign, p0, p1; + if (s.length < 3) + return 0; + t = s.toUpperCase().replace(/0+$/, ""); + sign = t.charAt(0) === '-' ? -1 : 1; + p0 = t.charAt(0) === '-' || t.charAt(0) === '+' ? 1 : 0; + p1 = t.length - 1; + if (p1 + 1 < p0 + 3) + return 0; + // Strip off sign and trailing 0s + t = t.substr(p0, p1 + 1 - p0); // Length at least 3 + if (t === "NAN" || t === "1.#QNAN" || t === "1.#SNAN" || t === "1.#IND" || + t === "1.#R") + return Number.NaN; + else if (t === "INF" || t === "1.#INF") + return sign * Number.POSITIVE_INFINITY; + return 0; + }; + + /** + * @summary Decode two DMS strings interpreting them as a latitude/longitude + * pair. + * @param {string} stra the first string. + * @param {string} strb the first string. + * @param {bool} [longfirst = false] if true assume then longitude is given + * first (in the absense of any hemisphere indicators). + * @returns {object} r where r.lat is the decoded latitude and r.lon is the + * decoded longitude (both in degrees). + * @throws an error if the strings are illegal. + */ + d.DecodeLatLon = function(stra, strb, longfirst) { + var vals = {}, + valsa = d.Decode(stra), + valsb = d.Decode(strb), + a = valsa.val, ia = valsa.ind, + b = valsb.val, ib = valsb.ind, + lat, lon; + if (!longfirst) longfirst = false; + if (ia === d.NONE && ib === d.NONE) { + // Default to lat, long unless longfirst + ia = longfirst ? d.LONGITUDE : d.LATITUDE; + ib = longfirst ? d.LATITUDE : d.LONGITUDE; + } else if (ia === d.NONE) + ia = d.LATITUDE + d.LONGITUDE - ib; + else if (ib === d.NONE) + ib = d.LATITUDE + d.LONGITUDE - ia; + if (ia === ib) + throw new Error("Both " + stra + " and " + strb + " interpreted as " + + (ia === d.LATITUDE ? "latitudes" : "longitudes")); + lat = ia === d.LATITUDE ? a : b; + lon = ia === d.LATITUDE ? b : a; + if (Math.abs(lat) > 90) + throw new Error("Latitude " + lat + " not in [-90,90]"); + vals.lat = lat; + vals.lon = lon; + return vals; + }; + + /** + * @summary Decode a DMS string interpreting it as an arc length. + * @param {string} angstr the string (this must not include a hemisphere + * indicator). + * @returns {number} the arc length (degrees). + * @throws an error if the string is illegal. + */ + d.DecodeAngle = function(angstr) { + var vals = d.Decode(angstr), + ang = vals.val, ind = vals.ind; + if (ind !== d.NONE) + throw new Error("Arc angle " + angstr + + " includes a hemisphere N/E/W/S"); + return ang; + }; + + /** + * @summary Decode a DMS string interpreting it as an azimuth. + * @param {string} azistr the string (this may include an E/W hemisphere + * indicator). + * @returns {number} the azimuth (degrees). + * @throws an error if the string is illegal. + */ + d.DecodeAzimuth = function(azistr) { + var vals = d.Decode(azistr), + azi = vals.val, ind = vals.ind; + if (ind === d.LATITUDE) + throw new Error("Azimuth " + azistr + " has a latitude hemisphere N/S"); + return azi; + }; + + /** + * @summary Convert angle (in degrees) into a DMS string (using °, ', + * and "). + * @param {number} angle input angle (degrees). + * @param {number} trailing one of DEGREE, MINUTE, or SECOND to indicate + * the trailing component of the string (this component is given as a + * decimal number if necessary). + * @param {number} prec the number of digits after the decimal point for + * the trailing component. + * @param {number} [ind = NONE] a formatting indicator, one of NONE, + * LATITUDE, LONGITUDE, AZIMUTH. + * @returns {string} the resulting string formatted as follows: + * * NONE, signed result no leading zeros on degrees except in the units + * place, e.g., -8°03'. + * * LATITUDE, trailing N or S hemisphere designator, no sign, pad + * degrees to 2 digits, e.g., 08°03'S. + * * LONGITUDE, trailing E or W hemisphere designator, no sign, pad + * degrees to 3 digits, e.g., 008°03'W. + * * AZIMUTH, convert to the range [0, 360°), no sign, pad degrees to + * 3 digits, e.g., 351°57'. + */ + d.Encode = function(angle, trailing, prec, ind) { + // Assume check on range of input angle has been made by calling + // routine (which might be able to offer a better diagnostic). + var scale = 1, i, sign, + idegree, fdegree, f, pieces, ip, fp, s; + if (!ind) ind = d.NONE; + if (!isFinite(angle)) + return angle < 0 ? String("-inf") : + (angle > 0 ? String("inf") : String("nan")); + + // 15 - 2 * trailing = ceiling(log10(2^53/90/60^trailing)). + // This suffices to give full real precision for numbers in [-90,90] + prec = Math.min(15 - 2 * trailing, prec); + for (i = 0; i < trailing; ++i) + scale *= 60; + for (i = 0; i < prec; ++i) + scale *= 10; + if (ind === d.AZIMUTH) + angle -= Math.floor(angle/360) * 360; + sign = angle < 0 ? -1 : 1; + angle *= sign; + + // Break off integer part to preserve precision in manipulation of + // fractional part. + idegree = Math.floor(angle); + fdegree = (angle - idegree) * scale + 0.5; + f = Math.floor(fdegree); + // Implement the "round ties to even" rule + fdegree = (f === fdegree && (f & 1) === 1) ? f - 1 : f; + fdegree /= scale; + + fdegree = Math.floor((angle - idegree) * scale + 0.5) / scale; + if (fdegree >= 1) { + idegree += 1; + fdegree -= 1; + } + pieces = [fdegree, 0, 0]; + for (i = 1; i <= trailing; ++i) { + ip = Math.floor(pieces[i - 1]); + fp = pieces[i - 1] - ip; + pieces[i] = fp * 60; + pieces[i - 1] = ip; + } + pieces[0] += idegree; + s = ""; + if (ind === d.NONE && sign < 0) + s += '-'; + switch (trailing) { + case d.DEGREE: + s += zerofill(pieces[0].toFixed(prec), + ind === d.NONE ? 0 : + 1 + Math.min(ind, 2) + prec + (prec ? 1 : 0)) + + dmsindicatorsu_.charAt(0); + break; + default: + s += zerofill(pieces[0].toFixed(0), + ind === d.NONE ? 0 : 1 + Math.min(ind, 2)) + + dmsindicatorsu_.charAt(0); + switch (trailing) { + case d.MINUTE: + s += zerofill(pieces[1].toFixed(prec), 2 + prec + (prec ? 1 : 0)) + + dmsindicatorsu_.charAt(1); + break; + case d.SECOND: + s += zerofill(pieces[1].toFixed(0), 2) + dmsindicatorsu_.charAt(1); + s += zerofill(pieces[2].toFixed(prec), 2 + prec + (prec ? 1 : 0)) + + dmsindicatorsu_.charAt(2); + break; + default: + break; + } + } + if (ind !== d.NONE && ind !== d.AZIMUTH) + s += hemispheres_.charAt((ind === d.LATITUDE ? 0 : 2) + + (sign < 0 ? 0 : 1)); + return s; + }; +})(GeographicLib.DMS); diff --git a/gtsam/3rdparty/GeographicLib/js/src/Geodesic.js b/gtsam/3rdparty/GeographicLib/js/src/Geodesic.js new file mode 100644 index 000000000..974d1d471 --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/js/src/Geodesic.js @@ -0,0 +1,1393 @@ +/* + * Geodesic.js + * Transcription of Geodesic.[ch]pp into JavaScript. + * + * See the documentation for the C++ class. The conversion is a literal + * conversion from C++. + * + * The algorithms are derived in + * + * Charles F. F. Karney, + * Algorithms for geodesics, J. Geodesy 87, 43-55 (2013); + * https://doi.org/10.1007/s00190-012-0578-z + * Addenda: https://geographiclib.sourceforge.io/geod-addenda.html + * + * Copyright (c) Charles Karney (2011-2017) and licensed + * under the MIT/X11 License. For more information, see + * https://geographiclib.sourceforge.io/ + */ + +// Load AFTER Math.js + +GeographicLib.Geodesic = {}; +GeographicLib.GeodesicLine = {}; +GeographicLib.PolygonArea = {}; + +(function( + /** + * @exports GeographicLib/Geodesic + * @description Solve geodesic problems via the + * {@link module:GeographicLib/Geodesic.Geodesic Geodesic} class. + */ + g, l, p, m, c) { + + var GEOGRAPHICLIB_GEODESIC_ORDER = 6, + nA1_ = GEOGRAPHICLIB_GEODESIC_ORDER, + nA2_ = GEOGRAPHICLIB_GEODESIC_ORDER, + nA3_ = GEOGRAPHICLIB_GEODESIC_ORDER, + nA3x_ = nA3_, + nC3x_, nC4x_, + maxit1_ = 20, + maxit2_ = maxit1_ + m.digits + 10, + tol0_ = m.epsilon, + tol1_ = 200 * tol0_, + tol2_ = Math.sqrt(tol0_), + tolb_ = tol0_ * tol1_, + xthresh_ = 1000 * tol2_, + CAP_NONE = 0, + CAP_ALL = 0x1F, + CAP_MASK = CAP_ALL, + OUT_ALL = 0x7F80, + astroid, + A1m1f_coeff, C1f_coeff, C1pf_coeff, + A2m1f_coeff, C2f_coeff, + A3_coeff, C3_coeff, C4_coeff; + + g.tiny_ = Math.sqrt(Number.MIN_VALUE); + g.nC1_ = GEOGRAPHICLIB_GEODESIC_ORDER; + g.nC1p_ = GEOGRAPHICLIB_GEODESIC_ORDER; + g.nC2_ = GEOGRAPHICLIB_GEODESIC_ORDER; + g.nC3_ = GEOGRAPHICLIB_GEODESIC_ORDER; + g.nC4_ = GEOGRAPHICLIB_GEODESIC_ORDER; + nC3x_ = (g.nC3_ * (g.nC3_ - 1)) / 2; + nC4x_ = (g.nC4_ * (g.nC4_ + 1)) / 2; + g.CAP_C1 = 1<<0; + g.CAP_C1p = 1<<1; + g.CAP_C2 = 1<<2; + g.CAP_C3 = 1<<3; + g.CAP_C4 = 1<<4; + + g.NONE = 0; + g.ARC = 1<<6; + g.LATITUDE = 1<<7 | CAP_NONE; + g.LONGITUDE = 1<<8 | g.CAP_C3; + g.AZIMUTH = 1<<9 | CAP_NONE; + g.DISTANCE = 1<<10 | g.CAP_C1; + g.STANDARD = g.LATITUDE | g.LONGITUDE | g.AZIMUTH | g.DISTANCE; + g.DISTANCE_IN = 1<<11 | g.CAP_C1 | g.CAP_C1p; + g.REDUCEDLENGTH = 1<<12 | g.CAP_C1 | g.CAP_C2; + g.GEODESICSCALE = 1<<13 | g.CAP_C1 | g.CAP_C2; + g.AREA = 1<<14 | g.CAP_C4; + g.ALL = OUT_ALL| CAP_ALL; + g.LONG_UNROLL = 1<<15; + g.OUT_MASK = OUT_ALL| g.LONG_UNROLL; + + g.SinCosSeries = function(sinp, sinx, cosx, c) { + // Evaluate + // y = sinp ? sum(c[i] * sin( 2*i * x), i, 1, n) : + // sum(c[i] * cos((2*i+1) * x), i, 0, n-1) + // using Clenshaw summation. N.B. c[0] is unused for sin series + // Approx operation count = (n + 5) mult and (2 * n + 2) add + var k = c.length, // Point to one beyond last element + n = k - (sinp ? 1 : 0), + ar = 2 * (cosx - sinx) * (cosx + sinx), // 2 * cos(2 * x) + y0 = n & 1 ? c[--k] : 0, y1 = 0; // accumulators for sum + // Now n is even + n = Math.floor(n/2); + while (n--) { + // Unroll loop x 2, so accumulators return to their original role + y1 = ar * y0 - y1 + c[--k]; + y0 = ar * y1 - y0 + c[--k]; + } + return (sinp ? 2 * sinx * cosx * y0 : // sin(2 * x) * y0 + cosx * (y0 - y1)); // cos(x) * (y0 - y1) + }; + + astroid = function(x, y) { + // Solve k^4+2*k^3-(x^2+y^2-1)*k^2-2*y^2*k-y^2 = 0 for positive + // root k. This solution is adapted from Geocentric::Reverse. + var k, + p = m.sq(x), + q = m.sq(y), + r = (p + q - 1) / 6, + S, r2, r3, disc, u, T3, T, ang, v, uv, w; + if ( !(q === 0 && r <= 0) ) { + // Avoid possible division by zero when r = 0 by multiplying + // equations for s and t by r^3 and r, resp. + S = p * q / 4; // S = r^3 * s + r2 = m.sq(r); + r3 = r * r2; + // The discriminant of the quadratic equation for T3. This is + // zero on the evolute curve p^(1/3)+q^(1/3) = 1 + disc = S * (S + 2 * r3); + u = r; + if (disc >= 0) { + T3 = S + r3; + // Pick the sign on the sqrt to maximize abs(T3). This + // minimizes loss of precision due to cancellation. The + // result is unchanged because of the way the T is used + // in definition of u. + T3 += T3 < 0 ? -Math.sqrt(disc) : Math.sqrt(disc); // T3 = (r * t)^3 + // N.B. cbrt always returns the real root. cbrt(-8) = -2. + T = m.cbrt(T3); // T = r * t + // T can be zero; but then r2 / T -> 0. + u += T + (T !== 0 ? r2 / T : 0); + } else { + // T is complex, but the way u is defined the result is real. + ang = Math.atan2(Math.sqrt(-disc), -(S + r3)); + // There are three possible cube roots. We choose the + // root which avoids cancellation. Note that disc < 0 + // implies that r < 0. + u += 2 * r * Math.cos(ang / 3); + } + v = Math.sqrt(m.sq(u) + q); // guaranteed positive + // Avoid loss of accuracy when u < 0. + uv = u < 0 ? q / (v - u) : u + v; // u+v, guaranteed positive + w = (uv - q) / (2 * v); // positive? + // Rearrange expression for k to avoid loss of accuracy due to + // subtraction. Division by 0 not possible because uv > 0, w >= 0. + k = uv / (Math.sqrt(uv + m.sq(w)) + w); // guaranteed positive + } else { // q == 0 && r <= 0 + // y = 0 with |x| <= 1. Handle this case directly. + // for y small, positive root is k = abs(y)/sqrt(1-x^2) + k = 0; + } + return k; + }; + + A1m1f_coeff = [ + // (1-eps)*A1-1, polynomial in eps2 of order 3 + +1, 4, 64, 0, 256 + ]; + + // The scale factor A1-1 = mean value of (d/dsigma)I1 - 1 + g.A1m1f = function(eps) { + var p = Math.floor(nA1_/2), + t = m.polyval(p, A1m1f_coeff, 0, m.sq(eps)) / A1m1f_coeff[p + 1]; + return (t + eps) / (1 - eps); + }; + + C1f_coeff = [ + // C1[1]/eps^1, polynomial in eps2 of order 2 + -1, 6, -16, 32, + // C1[2]/eps^2, polynomial in eps2 of order 2 + -9, 64, -128, 2048, + // C1[3]/eps^3, polynomial in eps2 of order 1 + +9, -16, 768, + // C1[4]/eps^4, polynomial in eps2 of order 1 + +3, -5, 512, + // C1[5]/eps^5, polynomial in eps2 of order 0 + -7, 1280, + // C1[6]/eps^6, polynomial in eps2 of order 0 + -7, 2048 + ]; + + // The coefficients C1[l] in the Fourier expansion of B1 + g.C1f = function(eps, c) { + var eps2 = m.sq(eps), + d = eps, + o = 0, + l, p; + for (l = 1; l <= g.nC1_; ++l) { // l is index of C1p[l] + p = Math.floor((g.nC1_ - l) / 2); // order of polynomial in eps^2 + c[l] = d * m.polyval(p, C1f_coeff, o, eps2) / C1f_coeff[o + p + 1]; + o += p + 2; + d *= eps; + } + }; + + C1pf_coeff = [ + // C1p[1]/eps^1, polynomial in eps2 of order 2 + +205, -432, 768, 1536, + // C1p[2]/eps^2, polynomial in eps2 of order 2 + +4005, -4736, 3840, 12288, + // C1p[3]/eps^3, polynomial in eps2 of order 1 + -225, 116, 384, + // C1p[4]/eps^4, polynomial in eps2 of order 1 + -7173, 2695, 7680, + // C1p[5]/eps^5, polynomial in eps2 of order 0 + +3467, 7680, + // C1p[6]/eps^6, polynomial in eps2 of order 0 + +38081, 61440 + ]; + + // The coefficients C1p[l] in the Fourier expansion of B1p + g.C1pf = function(eps, c) { + var eps2 = m.sq(eps), + d = eps, + o = 0, + l, p; + for (l = 1; l <= g.nC1p_; ++l) { // l is index of C1p[l] + p = Math.floor((g.nC1p_ - l) / 2); // order of polynomial in eps^2 + c[l] = d * m.polyval(p, C1pf_coeff, o, eps2) / C1pf_coeff[o + p + 1]; + o += p + 2; + d *= eps; + } + }; + + A2m1f_coeff = [ + // (eps+1)*A2-1, polynomial in eps2 of order 3 + -11, -28, -192, 0, 256 + ]; + + // The scale factor A2-1 = mean value of (d/dsigma)I2 - 1 + g.A2m1f = function(eps) { + var p = Math.floor(nA2_/2), + t = m.polyval(p, A2m1f_coeff, 0, m.sq(eps)) / A2m1f_coeff[p + 1]; + return (t - eps) / (1 + eps); + }; + + C2f_coeff = [ + // C2[1]/eps^1, polynomial in eps2 of order 2 + +1, 2, 16, 32, + // C2[2]/eps^2, polynomial in eps2 of order 2 + +35, 64, 384, 2048, + // C2[3]/eps^3, polynomial in eps2 of order 1 + +15, 80, 768, + // C2[4]/eps^4, polynomial in eps2 of order 1 + +7, 35, 512, + // C2[5]/eps^5, polynomial in eps2 of order 0 + +63, 1280, + // C2[6]/eps^6, polynomial in eps2 of order 0 + +77, 2048 + ]; + + // The coefficients C2[l] in the Fourier expansion of B2 + g.C2f = function(eps, c) { + var eps2 = m.sq(eps), + d = eps, + o = 0, + l, p; + for (l = 1; l <= g.nC2_; ++l) { // l is index of C2[l] + p = Math.floor((g.nC2_ - l) / 2); // order of polynomial in eps^2 + c[l] = d * m.polyval(p, C2f_coeff, o, eps2) / C2f_coeff[o + p + 1]; + o += p + 2; + d *= eps; + } + }; + + /** + * @class + * @property {number} a the equatorial radius (meters). + * @property {number} f the flattening. + * @summary Initialize a Geodesic object for a specific ellipsoid. + * @classdesc Performs geodesic calculations on an ellipsoid of revolution. + * The routines for solving the direct and inverse problems return an + * object with some of the following fields set: lat1, lon1, azi1, lat2, + * lon2, azi2, s12, a12, m12, M12, M21, S12. See {@tutorial 2-interface}, + * "The results". + * @example + * var GeographicLib = require("geographiclib"), + * geod = GeographicLib.Geodesic.WGS84; + * var inv = geod.Inverse(1,2,3,4); + * console.log("lat1 = " + inv.lat1 + ", lon1 = " + inv.lon1 + + * ", lat2 = " + inv.lat2 + ", lon2 = " + inv.lon2 + + * ",\nazi1 = " + inv.azi1 + ", azi2 = " + inv.azi2 + + * ", s12 = " + inv.s12); + * @param {number} a the equatorial radius of the ellipsoid (meters). + * @param {number} f the flattening of the ellipsoid. Setting f = 0 gives + * a sphere (on which geodesics are great circles). Negative f gives a + * prolate ellipsoid. + * @throws an error if the parameters are illegal. + */ + g.Geodesic = function(a, f) { + this.a = a; + this.f = f; + this._f1 = 1 - this.f; + this._e2 = this.f * (2 - this.f); + this._ep2 = this._e2 / m.sq(this._f1); // e2 / (1 - e2) + this._n = this.f / ( 2 - this.f); + this._b = this.a * this._f1; + // authalic radius squared + this._c2 = (m.sq(this.a) + m.sq(this._b) * + (this._e2 === 0 ? 1 : + (this._e2 > 0 ? m.atanh(Math.sqrt(this._e2)) : + Math.atan(Math.sqrt(-this._e2))) / + Math.sqrt(Math.abs(this._e2))))/2; + // The sig12 threshold for "really short". Using the auxiliary sphere + // solution with dnm computed at (bet1 + bet2) / 2, the relative error in + // the azimuth consistency check is sig12^2 * abs(f) * min(1, 1-f/2) / 2. + // (Error measured for 1/100 < b/a < 100 and abs(f) >= 1/1000. For a given + // f and sig12, the max error occurs for lines near the pole. If the old + // rule for computing dnm = (dn1 + dn2)/2 is used, then the error increases + // by a factor of 2.) Setting this equal to epsilon gives sig12 = etol2. + // Here 0.1 is a safety factor (error decreased by 100) and max(0.001, + // abs(f)) stops etol2 getting too large in the nearly spherical case. + this._etol2 = 0.1 * tol2_ / + Math.sqrt( Math.max(0.001, Math.abs(this.f)) * + Math.min(1.0, 1 - this.f/2) / 2 ); + if (!(isFinite(this.a) && this.a > 0)) + throw new Error("Equatorial radius is not positive"); + if (!(isFinite(this._b) && this._b > 0)) + throw new Error("Polar semi-axis is not positive"); + this._A3x = new Array(nA3x_); + this._C3x = new Array(nC3x_); + this._C4x = new Array(nC4x_); + this.A3coeff(); + this.C3coeff(); + this.C4coeff(); + }; + + A3_coeff = [ + // A3, coeff of eps^5, polynomial in n of order 0 + -3, 128, + // A3, coeff of eps^4, polynomial in n of order 1 + -2, -3, 64, + // A3, coeff of eps^3, polynomial in n of order 2 + -1, -3, -1, 16, + // A3, coeff of eps^2, polynomial in n of order 2 + +3, -1, -2, 8, + // A3, coeff of eps^1, polynomial in n of order 1 + +1, -1, 2, + // A3, coeff of eps^0, polynomial in n of order 0 + +1, 1 + ]; + + // The scale factor A3 = mean value of (d/dsigma)I3 + g.Geodesic.prototype.A3coeff = function() { + var o = 0, k = 0, + j, p; + for (j = nA3_ - 1; j >= 0; --j) { // coeff of eps^j + p = Math.min(nA3_ - j - 1, j); // order of polynomial in n + this._A3x[k++] = m.polyval(p, A3_coeff, o, this._n) / + A3_coeff[o + p + 1]; + o += p + 2; + } + }; + + C3_coeff = [ + // C3[1], coeff of eps^5, polynomial in n of order 0 + +3, 128, + // C3[1], coeff of eps^4, polynomial in n of order 1 + +2, 5, 128, + // C3[1], coeff of eps^3, polynomial in n of order 2 + -1, 3, 3, 64, + // C3[1], coeff of eps^2, polynomial in n of order 2 + -1, 0, 1, 8, + // C3[1], coeff of eps^1, polynomial in n of order 1 + -1, 1, 4, + // C3[2], coeff of eps^5, polynomial in n of order 0 + +5, 256, + // C3[2], coeff of eps^4, polynomial in n of order 1 + +1, 3, 128, + // C3[2], coeff of eps^3, polynomial in n of order 2 + -3, -2, 3, 64, + // C3[2], coeff of eps^2, polynomial in n of order 2 + +1, -3, 2, 32, + // C3[3], coeff of eps^5, polynomial in n of order 0 + +7, 512, + // C3[3], coeff of eps^4, polynomial in n of order 1 + -10, 9, 384, + // C3[3], coeff of eps^3, polynomial in n of order 2 + +5, -9, 5, 192, + // C3[4], coeff of eps^5, polynomial in n of order 0 + +7, 512, + // C3[4], coeff of eps^4, polynomial in n of order 1 + -14, 7, 512, + // C3[5], coeff of eps^5, polynomial in n of order 0 + +21, 2560 + ]; + + // The coefficients C3[l] in the Fourier expansion of B3 + g.Geodesic.prototype.C3coeff = function() { + var o = 0, k = 0, + l, j, p; + for (l = 1; l < g.nC3_; ++l) { // l is index of C3[l] + for (j = g.nC3_ - 1; j >= l; --j) { // coeff of eps^j + p = Math.min(g.nC3_ - j - 1, j); // order of polynomial in n + this._C3x[k++] = m.polyval(p, C3_coeff, o, this._n) / + C3_coeff[o + p + 1]; + o += p + 2; + } + } + }; + + C4_coeff = [ + // C4[0], coeff of eps^5, polynomial in n of order 0 + +97, 15015, + // C4[0], coeff of eps^4, polynomial in n of order 1 + +1088, 156, 45045, + // C4[0], coeff of eps^3, polynomial in n of order 2 + -224, -4784, 1573, 45045, + // C4[0], coeff of eps^2, polynomial in n of order 3 + -10656, 14144, -4576, -858, 45045, + // C4[0], coeff of eps^1, polynomial in n of order 4 + +64, 624, -4576, 6864, -3003, 15015, + // C4[0], coeff of eps^0, polynomial in n of order 5 + +100, 208, 572, 3432, -12012, 30030, 45045, + // C4[1], coeff of eps^5, polynomial in n of order 0 + +1, 9009, + // C4[1], coeff of eps^4, polynomial in n of order 1 + -2944, 468, 135135, + // C4[1], coeff of eps^3, polynomial in n of order 2 + +5792, 1040, -1287, 135135, + // C4[1], coeff of eps^2, polynomial in n of order 3 + +5952, -11648, 9152, -2574, 135135, + // C4[1], coeff of eps^1, polynomial in n of order 4 + -64, -624, 4576, -6864, 3003, 135135, + // C4[2], coeff of eps^5, polynomial in n of order 0 + +8, 10725, + // C4[2], coeff of eps^4, polynomial in n of order 1 + +1856, -936, 225225, + // C4[2], coeff of eps^3, polynomial in n of order 2 + -8448, 4992, -1144, 225225, + // C4[2], coeff of eps^2, polynomial in n of order 3 + -1440, 4160, -4576, 1716, 225225, + // C4[3], coeff of eps^5, polynomial in n of order 0 + -136, 63063, + // C4[3], coeff of eps^4, polynomial in n of order 1 + +1024, -208, 105105, + // C4[3], coeff of eps^3, polynomial in n of order 2 + +3584, -3328, 1144, 315315, + // C4[4], coeff of eps^5, polynomial in n of order 0 + -128, 135135, + // C4[4], coeff of eps^4, polynomial in n of order 1 + -2560, 832, 405405, + // C4[5], coeff of eps^5, polynomial in n of order 0 + +128, 99099 + ]; + + g.Geodesic.prototype.C4coeff = function() { + var o = 0, k = 0, + l, j, p; + for (l = 0; l < g.nC4_; ++l) { // l is index of C4[l] + for (j = g.nC4_ - 1; j >= l; --j) { // coeff of eps^j + p = g.nC4_ - j - 1; // order of polynomial in n + this._C4x[k++] = m.polyval(p, C4_coeff, o, this._n) / + C4_coeff[o + p + 1]; + o += p + 2; + } + } + }; + + g.Geodesic.prototype.A3f = function(eps) { + // Evaluate A3 + return m.polyval(nA3x_ - 1, this._A3x, 0, eps); + }; + + g.Geodesic.prototype.C3f = function(eps, c) { + // Evaluate C3 coeffs + // Elements c[1] thru c[nC3_ - 1] are set + var mult = 1, + o = 0, + l, p; + for (l = 1; l < g.nC3_; ++l) { // l is index of C3[l] + p = g.nC3_ - l - 1; // order of polynomial in eps + mult *= eps; + c[l] = mult * m.polyval(p, this._C3x, o, eps); + o += p + 1; + } + }; + + g.Geodesic.prototype.C4f = function(eps, c) { + // Evaluate C4 coeffs + // Elements c[0] thru c[g.nC4_ - 1] are set + var mult = 1, + o = 0, + l, p; + for (l = 0; l < g.nC4_; ++l) { // l is index of C4[l] + p = g.nC4_ - l - 1; // order of polynomial in eps + c[l] = mult * m.polyval(p, this._C4x, o, eps); + o += p + 1; + mult *= eps; + } + }; + + // return s12b, m12b, m0, M12, M21 + g.Geodesic.prototype.Lengths = function(eps, sig12, + ssig1, csig1, dn1, ssig2, csig2, dn2, + cbet1, cbet2, outmask, + C1a, C2a) { + // Return m12b = (reduced length)/_b; also calculate s12b = + // distance/_b, and m0 = coefficient of secular term in + // expression for reduced length. + outmask &= g.OUT_MASK; + var vals = {}, + m0x = 0, J12 = 0, A1 = 0, A2 = 0, + B1, B2, l, csig12, t; + if (outmask & (g.DISTANCE | g.REDUCEDLENGTH | g.GEODESICSCALE)) { + A1 = g.A1m1f(eps); + g.C1f(eps, C1a); + if (outmask & (g.REDUCEDLENGTH | g.GEODESICSCALE)) { + A2 = g.A2m1f(eps); + g.C2f(eps, C2a); + m0x = A1 - A2; + A2 = 1 + A2; + } + A1 = 1 + A1; + } + if (outmask & g.DISTANCE) { + B1 = g.SinCosSeries(true, ssig2, csig2, C1a) - + g.SinCosSeries(true, ssig1, csig1, C1a); + // Missing a factor of _b + vals.s12b = A1 * (sig12 + B1); + if (outmask & (g.REDUCEDLENGTH | g.GEODESICSCALE)) { + B2 = g.SinCosSeries(true, ssig2, csig2, C2a) - + g.SinCosSeries(true, ssig1, csig1, C2a); + J12 = m0x * sig12 + (A1 * B1 - A2 * B2); + } + } else if (outmask & (g.REDUCEDLENGTH | g.GEODESICSCALE)) { + // Assume here that nC1_ >= nC2_ + for (l = 1; l <= g.nC2_; ++l) + C2a[l] = A1 * C1a[l] - A2 * C2a[l]; + J12 = m0x * sig12 + (g.SinCosSeries(true, ssig2, csig2, C2a) - + g.SinCosSeries(true, ssig1, csig1, C2a)); + } + if (outmask & g.REDUCEDLENGTH) { + vals.m0 = m0x; + // Missing a factor of _b. + // Add parens around (csig1 * ssig2) and (ssig1 * csig2) to ensure + // accurate cancellation in the case of coincident points. + vals.m12b = dn2 * (csig1 * ssig2) - dn1 * (ssig1 * csig2) - + csig1 * csig2 * J12; + } + if (outmask & g.GEODESICSCALE) { + csig12 = csig1 * csig2 + ssig1 * ssig2; + t = this._ep2 * (cbet1 - cbet2) * (cbet1 + cbet2) / (dn1 + dn2); + vals.M12 = csig12 + (t * ssig2 - csig2 * J12) * ssig1 / dn1; + vals.M21 = csig12 - (t * ssig1 - csig1 * J12) * ssig2 / dn2; + } + return vals; + }; + + // return sig12, salp1, calp1, salp2, calp2, dnm + g.Geodesic.prototype.InverseStart = function(sbet1, cbet1, dn1, + sbet2, cbet2, dn2, + lam12, slam12, clam12, + C1a, C2a) { + // Return a starting point for Newton's method in salp1 and calp1 + // (function value is -1). If Newton's method doesn't need to be + // used, return also salp2 and calp2 and function value is sig12. + // salp2, calp2 only updated if return val >= 0. + var vals = {}, + // bet12 = bet2 - bet1 in [0, pi); bet12a = bet2 + bet1 in (-pi, 0] + sbet12 = sbet2 * cbet1 - cbet2 * sbet1, + cbet12 = cbet2 * cbet1 + sbet2 * sbet1, + sbet12a, shortline, omg12, sbetm2, somg12, comg12, t, ssig12, csig12, + x, y, lamscale, betscale, k2, eps, cbet12a, bet12a, m12b, m0, nvals, + k, omg12a, lam12x; + vals.sig12 = -1; // Return value + // Volatile declaration needed to fix inverse cases + // 88.202499451857 0 -88.202499451857 179.981022032992859592 + // 89.262080389218 0 -89.262080389218 179.992207982775375662 + // 89.333123580033 0 -89.333123580032997687 179.99295812360148422 + // which otherwise fail with g++ 4.4.4 x86 -O3 + sbet12a = sbet2 * cbet1; + sbet12a += cbet2 * sbet1; + + shortline = cbet12 >= 0 && sbet12 < 0.5 && cbet2 * lam12 < 0.5; + if (shortline) { + sbetm2 = m.sq(sbet1 + sbet2); + // sin((bet1+bet2)/2)^2 + // = (sbet1 + sbet2)^2 / ((sbet1 + sbet2)^2 + (cbet1 + cbet2)^2) + sbetm2 /= sbetm2 + m.sq(cbet1 + cbet2); + vals.dnm = Math.sqrt(1 + this._ep2 * sbetm2); + omg12 = lam12 / (this._f1 * vals.dnm); + somg12 = Math.sin(omg12); comg12 = Math.cos(omg12); + } else { + somg12 = slam12; comg12 = clam12; + } + + vals.salp1 = cbet2 * somg12; + vals.calp1 = comg12 >= 0 ? + sbet12 + cbet2 * sbet1 * m.sq(somg12) / (1 + comg12) : + sbet12a - cbet2 * sbet1 * m.sq(somg12) / (1 - comg12); + + ssig12 = m.hypot(vals.salp1, vals.calp1); + csig12 = sbet1 * sbet2 + cbet1 * cbet2 * comg12; + if (shortline && ssig12 < this._etol2) { + // really short lines + vals.salp2 = cbet1 * somg12; + vals.calp2 = sbet12 - cbet1 * sbet2 * + (comg12 >= 0 ? m.sq(somg12) / (1 + comg12) : 1 - comg12); + // norm(vals.salp2, vals.calp2); + t = m.hypot(vals.salp2, vals.calp2); vals.salp2 /= t; vals.calp2 /= t; + // Set return value + vals.sig12 = Math.atan2(ssig12, csig12); + } else if (Math.abs(this._n) > 0.1 || // Skip astroid calc if too eccentric + csig12 >= 0 || + ssig12 >= 6 * Math.abs(this._n) * Math.PI * m.sq(cbet1)) { + // Nothing to do, zeroth order spherical approximation is OK + } else { + // Scale lam12 and bet2 to x, y coordinate system where antipodal + // point is at origin and singular point is at y = 0, x = -1. + lam12x = Math.atan2(-slam12, -clam12); // lam12 - pi + if (this.f >= 0) { // In fact f == 0 does not get here + // x = dlong, y = dlat + k2 = m.sq(sbet1) * this._ep2; + eps = k2 / (2 * (1 + Math.sqrt(1 + k2)) + k2); + lamscale = this.f * cbet1 * this.A3f(eps) * Math.PI; + betscale = lamscale * cbet1; + + x = lam12x / lamscale; + y = sbet12a / betscale; + } else { // f < 0 + // x = dlat, y = dlong + cbet12a = cbet2 * cbet1 - sbet2 * sbet1; + bet12a = Math.atan2(sbet12a, cbet12a); + // In the case of lon12 = 180, this repeats a calculation made + // in Inverse. + nvals = this.Lengths(this._n, Math.PI + bet12a, + sbet1, -cbet1, dn1, sbet2, cbet2, dn2, + cbet1, cbet2, g.REDUCEDLENGTH, C1a, C2a); + m12b = nvals.m12b; m0 = nvals.m0; + x = -1 + m12b / (cbet1 * cbet2 * m0 * Math.PI); + betscale = x < -0.01 ? sbet12a / x : + -this.f * m.sq(cbet1) * Math.PI; + lamscale = betscale / cbet1; + y = lam12 / lamscale; + } + + if (y > -tol1_ && x > -1 - xthresh_) { + // strip near cut + if (this.f >= 0) { + vals.salp1 = Math.min(1, -x); + vals.calp1 = -Math.sqrt(1 - m.sq(vals.salp1)); + } else { + vals.calp1 = Math.max(x > -tol1_ ? 0 : -1, x); + vals.salp1 = Math.sqrt(1 - m.sq(vals.calp1)); + } + } else { + // Estimate alp1, by solving the astroid problem. + // + // Could estimate alpha1 = theta + pi/2, directly, i.e., + // calp1 = y/k; salp1 = -x/(1+k); for f >= 0 + // calp1 = x/(1+k); salp1 = -y/k; for f < 0 (need to check) + // + // However, it's better to estimate omg12 from astroid and use + // spherical formula to compute alp1. This reduces the mean number of + // Newton iterations for astroid cases from 2.24 (min 0, max 6) to 2.12 + // (min 0 max 5). The changes in the number of iterations are as + // follows: + // + // change percent + // 1 5 + // 0 78 + // -1 16 + // -2 0.6 + // -3 0.04 + // -4 0.002 + // + // The histogram of iterations is (m = number of iterations estimating + // alp1 directly, n = number of iterations estimating via omg12, total + // number of trials = 148605): + // + // iter m n + // 0 148 186 + // 1 13046 13845 + // 2 93315 102225 + // 3 36189 32341 + // 4 5396 7 + // 5 455 1 + // 6 56 0 + // + // Because omg12 is near pi, estimate work with omg12a = pi - omg12 + k = astroid(x, y); + omg12a = lamscale * ( this.f >= 0 ? -x * k/(1 + k) : -y * (1 + k)/k ); + somg12 = Math.sin(omg12a); comg12 = -Math.cos(omg12a); + // Update spherical estimate of alp1 using omg12 instead of + // lam12 + vals.salp1 = cbet2 * somg12; + vals.calp1 = sbet12a - + cbet2 * sbet1 * m.sq(somg12) / (1 - comg12); + } + } + // Sanity check on starting guess. Backwards check allows NaN through. + if (!(vals.salp1 <= 0.0)) { + // norm(vals.salp1, vals.calp1); + t = m.hypot(vals.salp1, vals.calp1); vals.salp1 /= t; vals.calp1 /= t; + } else { + vals.salp1 = 1; vals.calp1 = 0; + } + return vals; + }; + + // return lam12, salp2, calp2, sig12, ssig1, csig1, ssig2, csig2, eps, + // domg12, dlam12, + g.Geodesic.prototype.Lambda12 = function(sbet1, cbet1, dn1, + sbet2, cbet2, dn2, + salp1, calp1, slam120, clam120, + diffp, C1a, C2a, C3a) { + var vals = {}, + t, salp0, calp0, + somg1, comg1, somg2, comg2, somg12, comg12, B312, eta, k2, nvals; + if (sbet1 === 0 && calp1 === 0) + // Break degeneracy of equatorial line. This case has already been + // handled. + calp1 = -g.tiny_; + + // sin(alp1) * cos(bet1) = sin(alp0) + salp0 = salp1 * cbet1; + calp0 = m.hypot(calp1, salp1 * sbet1); // calp0 > 0 + + // tan(bet1) = tan(sig1) * cos(alp1) + // tan(omg1) = sin(alp0) * tan(sig1) = tan(omg1)=tan(alp1)*sin(bet1) + vals.ssig1 = sbet1; somg1 = salp0 * sbet1; + vals.csig1 = comg1 = calp1 * cbet1; + // norm(vals.ssig1, vals.csig1); + t = m.hypot(vals.ssig1, vals.csig1); vals.ssig1 /= t; vals.csig1 /= t; + // norm(somg1, comg1); -- don't need to normalize! + + // Enforce symmetries in the case abs(bet2) = -bet1. Need to be careful + // about this case, since this can yield singularities in the Newton + // iteration. + // sin(alp2) * cos(bet2) = sin(alp0) + vals.salp2 = cbet2 !== cbet1 ? salp0 / cbet2 : salp1; + // calp2 = sqrt(1 - sq(salp2)) + // = sqrt(sq(calp0) - sq(sbet2)) / cbet2 + // and subst for calp0 and rearrange to give (choose positive sqrt + // to give alp2 in [0, pi/2]). + vals.calp2 = cbet2 !== cbet1 || Math.abs(sbet2) !== -sbet1 ? + Math.sqrt(m.sq(calp1 * cbet1) + (cbet1 < -sbet1 ? + (cbet2 - cbet1) * (cbet1 + cbet2) : + (sbet1 - sbet2) * (sbet1 + sbet2))) / + cbet2 : Math.abs(calp1); + // tan(bet2) = tan(sig2) * cos(alp2) + // tan(omg2) = sin(alp0) * tan(sig2). + vals.ssig2 = sbet2; somg2 = salp0 * sbet2; + vals.csig2 = comg2 = vals.calp2 * cbet2; + // norm(vals.ssig2, vals.csig2); + t = m.hypot(vals.ssig2, vals.csig2); vals.ssig2 /= t; vals.csig2 /= t; + // norm(somg2, comg2); -- don't need to normalize! + + // sig12 = sig2 - sig1, limit to [0, pi] + vals.sig12 = Math.atan2(Math.max(0, vals.csig1 * vals.ssig2 - + vals.ssig1 * vals.csig2), + vals.csig1 * vals.csig2 + + vals.ssig1 * vals.ssig2); + + // omg12 = omg2 - omg1, limit to [0, pi] + somg12 = Math.max(0, comg1 * somg2 - somg1 * comg2); + comg12 = comg1 * comg2 + somg1 * somg2; + // eta = omg12 - lam120 + eta = Math.atan2(somg12 * clam120 - comg12 * slam120, + comg12 * clam120 + somg12 * slam120); + k2 = m.sq(calp0) * this._ep2; + vals.eps = k2 / (2 * (1 + Math.sqrt(1 + k2)) + k2); + this.C3f(vals.eps, C3a); + B312 = (g.SinCosSeries(true, vals.ssig2, vals.csig2, C3a) - + g.SinCosSeries(true, vals.ssig1, vals.csig1, C3a)); + vals.domg12 = -this.f * this.A3f(vals.eps) * salp0 * (vals.sig12 + B312); + vals.lam12 = eta + vals.domg12; + if (diffp) { + if (vals.calp2 === 0) + vals.dlam12 = -2 * this._f1 * dn1 / sbet1; + else { + nvals = this.Lengths(vals.eps, vals.sig12, + vals.ssig1, vals.csig1, dn1, + vals.ssig2, vals.csig2, dn2, + cbet1, cbet2, g.REDUCEDLENGTH, C1a, C2a); + vals.dlam12 = nvals.m12b; + vals.dlam12 *= this._f1 / (vals.calp2 * cbet2); + } + } + return vals; + }; + + /** + * @summary Solve the inverse geodesic problem. + * @param {number} lat1 the latitude of the first point in degrees. + * @param {number} lon1 the longitude of the first point in degrees. + * @param {number} lat2 the latitude of the second point in degrees. + * @param {number} lon2 the longitude of the second point in degrees. + * @param {bitmask} [outmask = STANDARD] which results to include. + * @returns {object} the requested results + * @description The lat1, lon1, lat2, lon2, and a12 fields of the result are + * always set. For details on the outmask parameter, see {@tutorial + * 2-interface}, "The outmask and caps parameters". + */ + g.Geodesic.prototype.Inverse = function(lat1, lon1, lat2, lon2, outmask) { + var r, vals; + if (!outmask) outmask = g.STANDARD; + if (outmask === g.LONG_UNROLL) outmask |= g.STANDARD; + outmask &= g.OUT_MASK; + r = this.InverseInt(lat1, lon1, lat2, lon2, outmask); + vals = r.vals; + if (outmask & g.AZIMUTH) { + vals.azi1 = m.atan2d(r.salp1, r.calp1); + vals.azi2 = m.atan2d(r.salp2, r.calp2); + } + return vals; + }; + + g.Geodesic.prototype.InverseInt = function(lat1, lon1, lat2, lon2, outmask) { + var vals = {}, + lon12, lon12s, lonsign, t, swapp, latsign, + sbet1, cbet1, sbet2, cbet2, s12x, m12x, + dn1, dn2, lam12, slam12, clam12, + sig12, calp1, salp1, calp2, salp2, C1a, C2a, C3a, meridian, nvals, + ssig1, csig1, ssig2, csig2, eps, omg12, dnm, + numit, salp1a, calp1a, salp1b, calp1b, + tripn, tripb, v, dv, dalp1, sdalp1, cdalp1, nsalp1, + lengthmask, salp0, calp0, alp12, k2, A4, C4a, B41, B42, + somg12, comg12, domg12, dbet1, dbet2, salp12, calp12, sdomg12, cdomg12; + // Compute longitude difference (AngDiff does this carefully). Result is + // in [-180, 180] but -180 is only for west-going geodesics. 180 is for + // east-going and meridional geodesics. + vals.lat1 = lat1 = m.LatFix(lat1); vals.lat2 = lat2 = m.LatFix(lat2); + // If really close to the equator, treat as on equator. + lat1 = m.AngRound(lat1); + lat2 = m.AngRound(lat2); + lon12 = m.AngDiff(lon1, lon2); lon12s = lon12.t; lon12 = lon12.s; + if (outmask & g.LONG_UNROLL) { + vals.lon1 = lon1; vals.lon2 = (lon1 + lon12) + lon12s; + } else { + vals.lon1 = m.AngNormalize(lon1); vals.lon2 = m.AngNormalize(lon2); + } + // Make longitude difference positive. + lonsign = lon12 >= 0 ? 1 : -1; + // If very close to being on the same half-meridian, then make it so. + lon12 = lonsign * m.AngRound(lon12); + lon12s = m.AngRound((180 - lon12) - lonsign * lon12s); + lam12 = lon12 * m.degree; + t = m.sincosd(lon12 > 90 ? lon12s : lon12); + slam12 = t.s; clam12 = (lon12 > 90 ? -1 : 1) * t.c; + + // Swap points so that point with higher (abs) latitude is point 1 + // If one latitude is a nan, then it becomes lat1. + swapp = Math.abs(lat1) < Math.abs(lat2) ? -1 : 1; + if (swapp < 0) { + lonsign *= -1; + t = lat1; + lat1 = lat2; + lat2 = t; + // swap(lat1, lat2); + } + // Make lat1 <= 0 + latsign = lat1 < 0 ? 1 : -1; + lat1 *= latsign; + lat2 *= latsign; + // Now we have + // + // 0 <= lon12 <= 180 + // -90 <= lat1 <= 0 + // lat1 <= lat2 <= -lat1 + // + // longsign, swapp, latsign register the transformation to bring the + // coordinates to this canonical form. In all cases, 1 means no change was + // made. We make these transformations so that there are few cases to + // check, e.g., on verifying quadrants in atan2. In addition, this + // enforces some symmetries in the results returned. + + t = m.sincosd(lat1); sbet1 = this._f1 * t.s; cbet1 = t.c; + // norm(sbet1, cbet1); + t = m.hypot(sbet1, cbet1); sbet1 /= t; cbet1 /= t; + // Ensure cbet1 = +epsilon at poles + cbet1 = Math.max(g.tiny_, cbet1); + + t = m.sincosd(lat2); sbet2 = this._f1 * t.s; cbet2 = t.c; + // norm(sbet2, cbet2); + t = m.hypot(sbet2, cbet2); sbet2 /= t; cbet2 /= t; + // Ensure cbet2 = +epsilon at poles + cbet2 = Math.max(g.tiny_, cbet2); + + // If cbet1 < -sbet1, then cbet2 - cbet1 is a sensitive measure of the + // |bet1| - |bet2|. Alternatively (cbet1 >= -sbet1), abs(sbet2) + sbet1 is + // a better measure. This logic is used in assigning calp2 in Lambda12. + // Sometimes these quantities vanish and in that case we force bet2 = +/- + // bet1 exactly. An example where is is necessary is the inverse problem + // 48.522876735459 0 -48.52287673545898293 179.599720456223079643 + // which failed with Visual Studio 10 (Release and Debug) + + if (cbet1 < -sbet1) { + if (cbet2 === cbet1) + sbet2 = sbet2 < 0 ? sbet1 : -sbet1; + } else { + if (Math.abs(sbet2) === -sbet1) + cbet2 = cbet1; + } + + dn1 = Math.sqrt(1 + this._ep2 * m.sq(sbet1)); + dn2 = Math.sqrt(1 + this._ep2 * m.sq(sbet2)); + + // index zero elements of these arrays are unused + C1a = new Array(g.nC1_ + 1); + C2a = new Array(g.nC2_ + 1); + C3a = new Array(g.nC3_); + + meridian = lat1 === -90 || slam12 === 0; + if (meridian) { + + // Endpoints are on a single full meridian, so the geodesic might + // lie on a meridian. + + calp1 = clam12; salp1 = slam12; // Head to the target longitude + calp2 = 1; salp2 = 0; // At the target we're heading north + + // tan(bet) = tan(sig) * cos(alp) + ssig1 = sbet1; csig1 = calp1 * cbet1; + ssig2 = sbet2; csig2 = calp2 * cbet2; + + // sig12 = sig2 - sig1 + sig12 = Math.atan2(Math.max(0, csig1 * ssig2 - ssig1 * csig2), + csig1 * csig2 + ssig1 * ssig2); + nvals = this.Lengths(this._n, sig12, + ssig1, csig1, dn1, ssig2, csig2, dn2, cbet1, cbet2, + outmask | g.DISTANCE | g.REDUCEDLENGTH, + C1a, C2a); + s12x = nvals.s12b; + m12x = nvals.m12b; + // Ignore m0 + if (outmask & g.GEODESICSCALE) { + vals.M12 = nvals.M12; + vals.M21 = nvals.M21; + } + // Add the check for sig12 since zero length geodesics might yield + // m12 < 0. Test case was + // + // echo 20.001 0 20.001 0 | GeodSolve -i + // + // In fact, we will have sig12 > pi/2 for meridional geodesic + // which is not a shortest path. + if (sig12 < 1 || m12x >= 0) { + // Need at least 2, to handle 90 0 90 180 + if (sig12 < 3 * g.tiny_) + sig12 = m12x = s12x = 0; + m12x *= this._b; + s12x *= this._b; + vals.a12 = sig12 / m.degree; + } else + // m12 < 0, i.e., prolate and too close to anti-podal + meridian = false; + } + + somg12 = 2; + if (!meridian && + sbet1 === 0 && // and sbet2 == 0 + (this.f <= 0 || lon12s >= this.f * 180)) { + + // Geodesic runs along equator + calp1 = calp2 = 0; salp1 = salp2 = 1; + s12x = this.a * lam12; + sig12 = omg12 = lam12 / this._f1; + m12x = this._b * Math.sin(sig12); + if (outmask & g.GEODESICSCALE) + vals.M12 = vals.M21 = Math.cos(sig12); + vals.a12 = lon12 / this._f1; + + } else if (!meridian) { + + // Now point1 and point2 belong within a hemisphere bounded by a + // meridian and geodesic is neither meridional or equatorial. + + // Figure a starting point for Newton's method + nvals = this.InverseStart(sbet1, cbet1, dn1, sbet2, cbet2, dn2, + lam12, slam12, clam12, C1a, C2a); + sig12 = nvals.sig12; + salp1 = nvals.salp1; + calp1 = nvals.calp1; + + if (sig12 >= 0) { + salp2 = nvals.salp2; + calp2 = nvals.calp2; + // Short lines (InverseStart sets salp2, calp2, dnm) + + dnm = nvals.dnm; + s12x = sig12 * this._b * dnm; + m12x = m.sq(dnm) * this._b * Math.sin(sig12 / dnm); + if (outmask & g.GEODESICSCALE) + vals.M12 = vals.M21 = Math.cos(sig12 / dnm); + vals.a12 = sig12 / m.degree; + omg12 = lam12 / (this._f1 * dnm); + } else { + + // Newton's method. This is a straightforward solution of f(alp1) = + // lambda12(alp1) - lam12 = 0 with one wrinkle. f(alp) has exactly one + // root in the interval (0, pi) and its derivative is positive at the + // root. Thus f(alp) is positive for alp > alp1 and negative for alp < + // alp1. During the course of the iteration, a range (alp1a, alp1b) is + // maintained which brackets the root and with each evaluation of + // f(alp) the range is shrunk if possible. Newton's method is + // restarted whenever the derivative of f is negative (because the new + // value of alp1 is then further from the solution) or if the new + // estimate of alp1 lies outside (0,pi); in this case, the new starting + // guess is taken to be (alp1a + alp1b) / 2. + numit = 0; + // Bracketing range + salp1a = g.tiny_; calp1a = 1; salp1b = g.tiny_; calp1b = -1; + for (tripn = false, tripb = false; numit < maxit2_; ++numit) { + // the WGS84 test set: mean = 1.47, sd = 1.25, max = 16 + // WGS84 and random input: mean = 2.85, sd = 0.60 + nvals = this.Lambda12(sbet1, cbet1, dn1, sbet2, cbet2, dn2, + salp1, calp1, slam12, clam12, numit < maxit1_, + C1a, C2a, C3a); + v = nvals.lam12; + salp2 = nvals.salp2; + calp2 = nvals.calp2; + sig12 = nvals.sig12; + ssig1 = nvals.ssig1; + csig1 = nvals.csig1; + ssig2 = nvals.ssig2; + csig2 = nvals.csig2; + eps = nvals.eps; + domg12 = nvals.domg12; + dv = nvals.dlam12; + + // 2 * tol0 is approximately 1 ulp for a number in [0, pi]. + // Reversed test to allow escape with NaNs + if (tripb || !(Math.abs(v) >= (tripn ? 8 : 1) * tol0_)) + break; + // Update bracketing values + if (v > 0 && (numit < maxit1_ || calp1/salp1 > calp1b/salp1b)) { + salp1b = salp1; calp1b = calp1; + } else if (v < 0 && + (numit < maxit1_ || calp1/salp1 < calp1a/salp1a)) { + salp1a = salp1; calp1a = calp1; + } + if (numit < maxit1_ && dv > 0) { + dalp1 = -v/dv; + sdalp1 = Math.sin(dalp1); cdalp1 = Math.cos(dalp1); + nsalp1 = salp1 * cdalp1 + calp1 * sdalp1; + if (nsalp1 > 0 && Math.abs(dalp1) < Math.PI) { + calp1 = calp1 * cdalp1 - salp1 * sdalp1; + salp1 = nsalp1; + // norm(salp1, calp1); + t = m.hypot(salp1, calp1); salp1 /= t; calp1 /= t; + // In some regimes we don't get quadratic convergence because + // slope -> 0. So use convergence conditions based on epsilon + // instead of sqrt(epsilon). + tripn = Math.abs(v) <= 16 * tol0_; + continue; + } + } + // Either dv was not positive or updated value was outside legal + // range. Use the midpoint of the bracket as the next estimate. + // This mechanism is not needed for the WGS84 ellipsoid, but it does + // catch problems with more eccentric ellipsoids. Its efficacy is + // such for the WGS84 test set with the starting guess set to alp1 = + // 90deg: + // the WGS84 test set: mean = 5.21, sd = 3.93, max = 24 + // WGS84 and random input: mean = 4.74, sd = 0.99 + salp1 = (salp1a + salp1b)/2; + calp1 = (calp1a + calp1b)/2; + // norm(salp1, calp1); + t = m.hypot(salp1, calp1); salp1 /= t; calp1 /= t; + tripn = false; + tripb = (Math.abs(salp1a - salp1) + (calp1a - calp1) < tolb_ || + Math.abs(salp1 - salp1b) + (calp1 - calp1b) < tolb_); + } + lengthmask = outmask | + (outmask & (g.REDUCEDLENGTH | g.GEODESICSCALE) ? + g.DISTANCE : g.NONE); + nvals = this.Lengths(eps, sig12, + ssig1, csig1, dn1, ssig2, csig2, dn2, + cbet1, cbet2, + lengthmask, C1a, C2a); + s12x = nvals.s12b; + m12x = nvals.m12b; + // Ignore m0 + if (outmask & g.GEODESICSCALE) { + vals.M12 = nvals.M12; + vals.M21 = nvals.M21; + } + m12x *= this._b; + s12x *= this._b; + vals.a12 = sig12 / m.degree; + if (outmask & g.AREA) { + // omg12 = lam12 - domg12 + sdomg12 = Math.sin(domg12); cdomg12 = Math.cos(domg12); + somg12 = slam12 * cdomg12 - clam12 * sdomg12; + comg12 = clam12 * cdomg12 + slam12 * sdomg12; + } + } + } + + if (outmask & g.DISTANCE) + vals.s12 = 0 + s12x; // Convert -0 to 0 + + if (outmask & g.REDUCEDLENGTH) + vals.m12 = 0 + m12x; // Convert -0 to 0 + + if (outmask & g.AREA) { + // From Lambda12: sin(alp1) * cos(bet1) = sin(alp0) + salp0 = salp1 * cbet1; + calp0 = m.hypot(calp1, salp1 * sbet1); // calp0 > 0 + if (calp0 !== 0 && salp0 !== 0) { + // From Lambda12: tan(bet) = tan(sig) * cos(alp) + ssig1 = sbet1; csig1 = calp1 * cbet1; + ssig2 = sbet2; csig2 = calp2 * cbet2; + k2 = m.sq(calp0) * this._ep2; + eps = k2 / (2 * (1 + Math.sqrt(1 + k2)) + k2); + // Multiplier = a^2 * e^2 * cos(alpha0) * sin(alpha0). + A4 = m.sq(this.a) * calp0 * salp0 * this._e2; + // norm(ssig1, csig1); + t = m.hypot(ssig1, csig1); ssig1 /= t; csig1 /= t; + // norm(ssig2, csig2); + t = m.hypot(ssig2, csig2); ssig2 /= t; csig2 /= t; + C4a = new Array(g.nC4_); + this.C4f(eps, C4a); + B41 = g.SinCosSeries(false, ssig1, csig1, C4a); + B42 = g.SinCosSeries(false, ssig2, csig2, C4a); + vals.S12 = A4 * (B42 - B41); + } else + // Avoid problems with indeterminate sig1, sig2 on equator + vals.S12 = 0; + if (!meridian && somg12 > 1) { + somg12 = Math.sin(omg12); comg12 = Math.cos(omg12); + } + if (!meridian && + comg12 > -0.7071 && // Long difference not too big + sbet2 - sbet1 < 1.75) { // Lat difference not too big + // Use tan(Gamma/2) = tan(omg12/2) + // * (tan(bet1/2)+tan(bet2/2))/(1+tan(bet1/2)*tan(bet2/2)) + // with tan(x/2) = sin(x)/(1+cos(x)) + domg12 = 1 + comg12; dbet1 = 1 + cbet1; dbet2 = 1 + cbet2; + alp12 = 2 * Math.atan2( somg12 * (sbet1*dbet2 + sbet2*dbet1), + domg12 * (sbet1*sbet2 + dbet1*dbet2) ); + } else { + // alp12 = alp2 - alp1, used in atan2 so no need to normalize + salp12 = salp2 * calp1 - calp2 * salp1; + calp12 = calp2 * calp1 + salp2 * salp1; + // The right thing appears to happen if alp1 = +/-180 and alp2 = 0, viz + // salp12 = -0 and alp12 = -180. However this depends on the sign + // being attached to 0 correctly. The following ensures the correct + // behavior. + if (salp12 === 0 && calp12 < 0) { + salp12 = g.tiny_ * calp1; + calp12 = -1; + } + alp12 = Math.atan2(salp12, calp12); + } + vals.S12 += this._c2 * alp12; + vals.S12 *= swapp * lonsign * latsign; + // Convert -0 to 0 + vals.S12 += 0; + } + + // Convert calp, salp to azimuth accounting for lonsign, swapp, latsign. + if (swapp < 0) { + t = salp1; + salp1 = salp2; + salp2 = t; + // swap(salp1, salp2); + t = calp1; + calp1 = calp2; + calp2 = t; + // swap(calp1, calp2); + if (outmask & g.GEODESICSCALE) { + t = vals.M12; + vals.M12 = vals.M21; + vals.M21 = t; + // swap(vals.M12, vals.M21); + } + } + + salp1 *= swapp * lonsign; calp1 *= swapp * latsign; + salp2 *= swapp * lonsign; calp2 *= swapp * latsign; + + return {vals: vals, + salp1: salp1, calp1: calp1, + salp2: salp2, calp2: calp2}; + }; + + /** + * @summary Solve the general direct geodesic problem. + * @param {number} lat1 the latitude of the first point in degrees. + * @param {number} lon1 the longitude of the first point in degrees. + * @param {number} azi1 the azimuth at the first point in degrees. + * @param {bool} arcmode is the next parameter an arc length? + * @param {number} s12_a12 the (arcmode ? arc length : distance) from the + * first point to the second in (arcmode ? degrees : meters). + * @param {bitmask} [outmask = STANDARD] which results to include. + * @returns {object} the requested results. + * @description The lat1, lon1, azi1, and a12 fields of the result are always + * set; s12 is included if arcmode is false. For details on the outmask + * parameter, see {@tutorial 2-interface}, "The outmask and caps + * parameters". + */ + g.Geodesic.prototype.GenDirect = function(lat1, lon1, azi1, + arcmode, s12_a12, outmask) { + var line; + if (!outmask) outmask = g.STANDARD; + else if (outmask === g.LONG_UNROLL) outmask |= g.STANDARD; + // Automatically supply DISTANCE_IN if necessary + if (!arcmode) outmask |= g.DISTANCE_IN; + line = new l.GeodesicLine(this, lat1, lon1, azi1, outmask); + return line.GenPosition(arcmode, s12_a12, outmask); + }; + + /** + * @summary Solve the direct geodesic problem. + * @param {number} lat1 the latitude of the first point in degrees. + * @param {number} lon1 the longitude of the first point in degrees. + * @param {number} azi1 the azimuth at the first point in degrees. + * @param {number} s12 the distance from the first point to the second in + * meters. + * @param {bitmask} [outmask = STANDARD] which results to include. + * @returns {object} the requested results. + * @description The lat1, lon1, azi1, s12, and a12 fields of the result are + * always set. For details on the outmask parameter, see {@tutorial + * 2-interface}, "The outmask and caps parameters". + */ + g.Geodesic.prototype.Direct = function(lat1, lon1, azi1, s12, outmask) { + return this.GenDirect(lat1, lon1, azi1, false, s12, outmask); + }; + + /** + * @summary Solve the direct geodesic problem with arc length. + * @param {number} lat1 the latitude of the first point in degrees. + * @param {number} lon1 the longitude of the first point in degrees. + * @param {number} azi1 the azimuth at the first point in degrees. + * @param {number} a12 the arc length from the first point to the second in + * degrees. + * @param {bitmask} [outmask = STANDARD] which results to include. + * @returns {object} the requested results. + * @description The lat1, lon1, azi1, and a12 fields of the result are + * always set. For details on the outmask parameter, see {@tutorial + * 2-interface}, "The outmask and caps parameters". + */ + g.Geodesic.prototype.ArcDirect = function(lat1, lon1, azi1, a12, outmask) { + return this.GenDirect(lat1, lon1, azi1, true, a12, outmask); + }; + + /** + * @summary Create a {@link module:GeographicLib/GeodesicLine.GeodesicLine + * GeodesicLine} object. + * @param {number} lat1 the latitude of the first point in degrees. + * @param {number} lon1 the longitude of the first point in degrees. + * @param {number} azi1 the azimuth at the first point in degrees. + * degrees. + * @param {bitmask} [caps = STANDARD | DISTANCE_IN] which capabilities to + * include. + * @returns {object} the + * {@link module:GeographicLib/GeodesicLine.GeodesicLine + * GeodesicLine} object + * @description For details on the caps parameter, see {@tutorial + * 2-interface}, "The outmask and caps parameters". + */ + g.Geodesic.prototype.Line = function(lat1, lon1, azi1, caps) { + return new l.GeodesicLine(this, lat1, lon1, azi1, caps); + }; + + /** + * @summary Define a {@link module:GeographicLib/GeodesicLine.GeodesicLine + * GeodesicLine} in terms of the direct geodesic problem specified in terms + * of distance. + * @param {number} lat1 the latitude of the first point in degrees. + * @param {number} lon1 the longitude of the first point in degrees. + * @param {number} azi1 the azimuth at the first point in degrees. + * degrees. + * @param {number} s12 the distance between point 1 and point 2 (meters); it + * can be negative. + * @param {bitmask} [caps = STANDARD | DISTANCE_IN] which capabilities to + * include. + * @returns {object} the + * {@link module:GeographicLib/GeodesicLine.GeodesicLine + * GeodesicLine} object + * @description This function sets point 3 of the GeodesicLine to correspond + * to point 2 of the direct geodesic problem. For details on the caps + * parameter, see {@tutorial 2-interface}, "The outmask and caps + * parameters". + */ + g.Geodesic.prototype.DirectLine = function(lat1, lon1, azi1, s12, caps) { + return this.GenDirectLine(lat1, lon1, azi1, false, s12, caps); + }; + + /** + * @summary Define a {@link module:GeographicLib/GeodesicLine.GeodesicLine + * GeodesicLine} in terms of the direct geodesic problem specified in terms + * of arc length. + * @param {number} lat1 the latitude of the first point in degrees. + * @param {number} lon1 the longitude of the first point in degrees. + * @param {number} azi1 the azimuth at the first point in degrees. + * degrees. + * @param {number} a12 the arc length between point 1 and point 2 (degrees); + * it can be negative. + * @param {bitmask} [caps = STANDARD | DISTANCE_IN] which capabilities to + * include. + * @returns {object} the + * {@link module:GeographicLib/GeodesicLine.GeodesicLine + * GeodesicLine} object + * @description This function sets point 3 of the GeodesicLine to correspond + * to point 2 of the direct geodesic problem. For details on the caps + * parameter, see {@tutorial 2-interface}, "The outmask and caps + * parameters". + */ + g.Geodesic.prototype.ArcDirectLine = function(lat1, lon1, azi1, a12, caps) { + return this.GenDirectLine(lat1, lon1, azi1, true, a12, caps); + }; + + /** + * @summary Define a {@link module:GeographicLib/GeodesicLine.GeodesicLine + * GeodesicLine} in terms of the direct geodesic problem specified in terms + * of either distance or arc length. + * @param {number} lat1 the latitude of the first point in degrees. + * @param {number} lon1 the longitude of the first point in degrees. + * @param {number} azi1 the azimuth at the first point in degrees. + * degrees. + * @param {bool} arcmode boolean flag determining the meaning of the + * s12_a12. + * @param {number} s12_a12 if arcmode is false, this is the distance between + * point 1 and point 2 (meters); otherwise it is the arc length between + * point 1 and point 2 (degrees); it can be negative. + * @param {bitmask} [caps = STANDARD | DISTANCE_IN] which capabilities to + * include. + * @returns {object} the + * {@link module:GeographicLib/GeodesicLine.GeodesicLine + * GeodesicLine} object + * @description This function sets point 3 of the GeodesicLine to correspond + * to point 2 of the direct geodesic problem. For details on the caps + * parameter, see {@tutorial 2-interface}, "The outmask and caps + * parameters". + */ + g.Geodesic.prototype.GenDirectLine = function(lat1, lon1, azi1, + arcmode, s12_a12, caps) { + var t; + if (!caps) caps = g.STANDARD | g.DISTANCE_IN; + // Automatically supply DISTANCE_IN if necessary + if (!arcmode) caps |= g.DISTANCE_IN; + t = new l.GeodesicLine(this, lat1, lon1, azi1, caps); + t.GenSetDistance(arcmode, s12_a12); + return t; + }; + + /** + * @summary Define a {@link module:GeographicLib/GeodesicLine.GeodesicLine + * GeodesicLine} in terms of the inverse geodesic problem. + * @param {number} lat1 the latitude of the first point in degrees. + * @param {number} lon1 the longitude of the first point in degrees. + * @param {number} lat2 the latitude of the second point in degrees. + * @param {number} lon2 the longitude of the second point in degrees. + * @param {bitmask} [caps = STANDARD | DISTANCE_IN] which capabilities to + * include. + * @returns {object} the + * {@link module:GeographicLib/GeodesicLine.GeodesicLine + * GeodesicLine} object + * @description This function sets point 3 of the GeodesicLine to correspond + * to point 2 of the inverse geodesic problem. For details on the caps + * parameter, see {@tutorial 2-interface}, "The outmask and caps + * parameters". + */ + g.Geodesic.prototype.InverseLine = function(lat1, lon1, lat2, lon2, caps) { + var r, t, azi1; + if (!caps) caps = g.STANDARD | g.DISTANCE_IN; + r = this.InverseInt(lat1, lon1, lat2, lon2, g.ARC); + azi1 = m.atan2d(r.salp1, r.calp1); + // Ensure that a12 can be converted to a distance + if (caps & (g.OUT_MASK & g.DISTANCE_IN)) caps |= g.DISTANCE; + t = new l.GeodesicLine(this, lat1, lon1, azi1, caps, r.salp1, r.calp1); + t.SetArc(r.vals.a12); + return t; + }; + + /** + * @summary Create a {@link module:GeographicLib/PolygonArea.PolygonArea + * PolygonArea} object. + * @param {bool} [polyline = false] if true the new PolygonArea object + * describes a polyline instead of a polygon. + * @returns {object} the + * {@link module:GeographicLib/PolygonArea.PolygonArea + * PolygonArea} object + */ + g.Geodesic.prototype.Polygon = function(polyline) { + return new p.PolygonArea(this, polyline); + }; + + /** + * @summary a {@link module:GeographicLib/Geodesic.Geodesic Geodesic} object + * initialized for the WGS84 ellipsoid. + * @constant {object} + */ + g.WGS84 = new g.Geodesic(c.WGS84.a, c.WGS84.f); +})(GeographicLib.Geodesic, GeographicLib.GeodesicLine, + GeographicLib.PolygonArea, GeographicLib.Math, GeographicLib.Constants); diff --git a/gtsam/3rdparty/GeographicLib/js/src/GeodesicLine.js b/gtsam/3rdparty/GeographicLib/js/src/GeodesicLine.js new file mode 100644 index 000000000..3f29dead3 --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/js/src/GeodesicLine.js @@ -0,0 +1,415 @@ +/* + * GeodesicLine.js + * Transcription of GeodesicLine.[ch]pp into JavaScript. + * + * See the documentation for the C++ class. The conversion is a literal + * conversion from C++. + * + * The algorithms are derived in + * + * Charles F. F. Karney, + * Algorithms for geodesics, J. Geodesy 87, 43-55 (2013); + * https://doi.org/10.1007/s00190-012-0578-z + * Addenda: https://geographiclib.sourceforge.io/geod-addenda.html + * + * Copyright (c) Charles Karney (2011-2016) and licensed + * under the MIT/X11 License. For more information, see + * https://geographiclib.sourceforge.io/ + */ + +// Load AFTER GeographicLib/Math.js, GeographicLib/Geodesic.js + +(function( + g, + /** + * @exports GeographicLib/GeodesicLine + * @description Solve geodesic problems on a single geodesic line via the + * {@link module:GeographicLib/GeodesicLine.GeodesicLine GeodesicLine} + * class. + */ + l, m) { + + /** + * @class + * @property {number} a the equatorial radius (meters). + * @property {number} f the flattening. + * @property {number} lat1 the initial latitude (degrees). + * @property {number} lon1 the initial longitude (degrees). + * @property {number} azi1 the initial azimuth (degrees). + * @property {number} salp1 the sine of the azimuth at the first point. + * @property {number} calp1 the cosine the azimuth at the first point. + * @property {number} s13 the distance to point 3 (meters). + * @property {number} a13 the arc length to point 3 (degrees). + * @property {bitmask} caps the capabilities of the object. + * @summary Initialize a GeodesicLine object. For details on the caps + * parameter, see {@tutorial 2-interface}, "The outmask and caps + * parameters". + * @classdesc Performs geodesic calculations along a given geodesic line. + * This object is usually instantiated by + * {@link module:GeographicLib/Geodesic.Geodesic#Line Geodesic.Line}. + * The methods + * {@link module:GeographicLib/Geodesic.Geodesic#DirectLine + * Geodesic.DirectLine} and + * {@link module:GeographicLib/Geodesic.Geodesic#InverseLine + * Geodesic.InverseLine} set in addition the position of a reference point + * 3. + * @param {object} geod a {@link module:GeographicLib/Geodesic.Geodesic + * Geodesic} object. + * @param {number} lat1 the latitude of the first point in degrees. + * @param {number} lon1 the longitude of the first point in degrees. + * @param {number} azi1 the azimuth at the first point in degrees. + * @param {bitmask} [caps = STANDARD | DISTANCE_IN] which capabilities to + * include; LATITUDE | AZIMUTH are always included. + */ + l.GeodesicLine = function(geod, lat1, lon1, azi1, caps, salp1, calp1) { + var t, cbet1, sbet1, eps, s, c; + if (!caps) caps = g.STANDARD | g.DISTANCE_IN; + + this.a = geod.a; + this.f = geod.f; + this._b = geod._b; + this._c2 = geod._c2; + this._f1 = geod._f1; + this.caps = caps | g.LATITUDE | g.AZIMUTH | g.LONG_UNROLL; + + this.lat1 = m.LatFix(lat1); + this.lon1 = lon1; + if (typeof salp1 === 'undefined' || typeof calp1 === 'undefined') { + this.azi1 = m.AngNormalize(azi1); + t = m.sincosd(m.AngRound(this.azi1)); this.salp1 = t.s; this.calp1 = t.c; + } else { + this.azi1 = azi1; this.salp1 = salp1; this.calp1 = calp1; + } + t = m.sincosd(m.AngRound(this.lat1)); sbet1 = this._f1 * t.s; cbet1 = t.c; + // norm(sbet1, cbet1); + t = m.hypot(sbet1, cbet1); sbet1 /= t; cbet1 /= t; + // Ensure cbet1 = +epsilon at poles + cbet1 = Math.max(g.tiny_, cbet1); + this._dn1 = Math.sqrt(1 + geod._ep2 * m.sq(sbet1)); + + // Evaluate alp0 from sin(alp1) * cos(bet1) = sin(alp0), + this._salp0 = this.salp1 * cbet1; // alp0 in [0, pi/2 - |bet1|] + // Alt: calp0 = hypot(sbet1, calp1 * cbet1). The following + // is slightly better (consider the case salp1 = 0). + this._calp0 = m.hypot(this.calp1, this.salp1 * sbet1); + // Evaluate sig with tan(bet1) = tan(sig1) * cos(alp1). + // sig = 0 is nearest northward crossing of equator. + // With bet1 = 0, alp1 = pi/2, we have sig1 = 0 (equatorial line). + // With bet1 = pi/2, alp1 = -pi, sig1 = pi/2 + // With bet1 = -pi/2, alp1 = 0 , sig1 = -pi/2 + // Evaluate omg1 with tan(omg1) = sin(alp0) * tan(sig1). + // With alp0 in (0, pi/2], quadrants for sig and omg coincide. + // No atan2(0,0) ambiguity at poles since cbet1 = +epsilon. + // With alp0 = 0, omg1 = 0 for alp1 = 0, omg1 = pi for alp1 = pi. + this._ssig1 = sbet1; this._somg1 = this._salp0 * sbet1; + this._csig1 = this._comg1 = + sbet1 !== 0 || this.calp1 !== 0 ? cbet1 * this.calp1 : 1; + // norm(this._ssig1, this._csig1); // sig1 in (-pi, pi] + t = m.hypot(this._ssig1, this._csig1); + this._ssig1 /= t; this._csig1 /= t; + // norm(this._somg1, this._comg1); -- don't need to normalize! + + this._k2 = m.sq(this._calp0) * geod._ep2; + eps = this._k2 / (2 * (1 + Math.sqrt(1 + this._k2)) + this._k2); + + if (this.caps & g.CAP_C1) { + this._A1m1 = g.A1m1f(eps); + this._C1a = new Array(g.nC1_ + 1); + g.C1f(eps, this._C1a); + this._B11 = g.SinCosSeries(true, this._ssig1, this._csig1, this._C1a); + s = Math.sin(this._B11); c = Math.cos(this._B11); + // tau1 = sig1 + B11 + this._stau1 = this._ssig1 * c + this._csig1 * s; + this._ctau1 = this._csig1 * c - this._ssig1 * s; + // Not necessary because C1pa reverts C1a + // _B11 = -SinCosSeries(true, _stau1, _ctau1, _C1pa); + } + + if (this.caps & g.CAP_C1p) { + this._C1pa = new Array(g.nC1p_ + 1); + g.C1pf(eps, this._C1pa); + } + + if (this.caps & g.CAP_C2) { + this._A2m1 = g.A2m1f(eps); + this._C2a = new Array(g.nC2_ + 1); + g.C2f(eps, this._C2a); + this._B21 = g.SinCosSeries(true, this._ssig1, this._csig1, this._C2a); + } + + if (this.caps & g.CAP_C3) { + this._C3a = new Array(g.nC3_); + geod.C3f(eps, this._C3a); + this._A3c = -this.f * this._salp0 * geod.A3f(eps); + this._B31 = g.SinCosSeries(true, this._ssig1, this._csig1, this._C3a); + } + + if (this.caps & g.CAP_C4) { + this._C4a = new Array(g.nC4_); // all the elements of _C4a are used + geod.C4f(eps, this._C4a); + // Multiplier = a^2 * e^2 * cos(alpha0) * sin(alpha0) + this._A4 = m.sq(this.a) * this._calp0 * this._salp0 * geod._e2; + this._B41 = g.SinCosSeries(false, this._ssig1, this._csig1, this._C4a); + } + + this.a13 = this.s13 = Number.NaN; + }; + + /** + * @summary Find the position on the line (general case). + * @param {bool} arcmode is the next parameter an arc length? + * @param {number} s12_a12 the (arcmode ? arc length : distance) from the + * first point to the second in (arcmode ? degrees : meters). + * @param {bitmask} [outmask = STANDARD] which results to include; this is + * subject to the capabilities of the object. + * @returns {object} the requested results. + * @description The lat1, lon1, azi1, and a12 fields of the result are + * always set; s12 is included if arcmode is false. For details on the + * outmask parameter, see {@tutorial 2-interface}, "The outmask and caps + * parameters". + */ + l.GeodesicLine.prototype.GenPosition = function(arcmode, s12_a12, + outmask) { + var vals = {}, + sig12, ssig12, csig12, B12, AB1, ssig2, csig2, tau12, s, c, serr, + omg12, lam12, lon12, E, sbet2, cbet2, somg2, comg2, salp2, calp2, dn2, + B22, AB2, J12, t, B42, salp12, calp12; + if (!outmask) outmask = g.STANDARD; + else if (outmask === g.LONG_UNROLL) outmask |= g.STANDARD; + outmask &= this.caps & g.OUT_MASK; + vals.lat1 = this.lat1; vals.azi1 = this.azi1; + vals.lon1 = outmask & g.LONG_UNROLL ? + this.lon1 : m.AngNormalize(this.lon1); + if (arcmode) + vals.a12 = s12_a12; + else + vals.s12 = s12_a12; + if (!( arcmode || (this.caps & g.DISTANCE_IN & g.OUT_MASK) )) { + // Uninitialized or impossible distance calculation requested + vals.a12 = Number.NaN; + return vals; + } + + // Avoid warning about uninitialized B12. + B12 = 0; AB1 = 0; + if (arcmode) { + // Interpret s12_a12 as spherical arc length + sig12 = s12_a12 * m.degree; + t = m.sincosd(s12_a12); ssig12 = t.s; csig12 = t.c; + } else { + // Interpret s12_a12 as distance + tau12 = s12_a12 / (this._b * (1 + this._A1m1)); + s = Math.sin(tau12); + c = Math.cos(tau12); + // tau2 = tau1 + tau12 + B12 = -g.SinCosSeries(true, + this._stau1 * c + this._ctau1 * s, + this._ctau1 * c - this._stau1 * s, + this._C1pa); + sig12 = tau12 - (B12 - this._B11); + ssig12 = Math.sin(sig12); csig12 = Math.cos(sig12); + if (Math.abs(this.f) > 0.01) { + // Reverted distance series is inaccurate for |f| > 1/100, so correct + // sig12 with 1 Newton iteration. The following table shows the + // approximate maximum error for a = WGS_a() and various f relative to + // GeodesicExact. + // erri = the error in the inverse solution (nm) + // errd = the error in the direct solution (series only) (nm) + // errda = the error in the direct solution + // (series + 1 Newton) (nm) + // + // f erri errd errda + // -1/5 12e6 1.2e9 69e6 + // -1/10 123e3 12e6 765e3 + // -1/20 1110 108e3 7155 + // -1/50 18.63 200.9 27.12 + // -1/100 18.63 23.78 23.37 + // -1/150 18.63 21.05 20.26 + // 1/150 22.35 24.73 25.83 + // 1/100 22.35 25.03 25.31 + // 1/50 29.80 231.9 30.44 + // 1/20 5376 146e3 10e3 + // 1/10 829e3 22e6 1.5e6 + // 1/5 157e6 3.8e9 280e6 + ssig2 = this._ssig1 * csig12 + this._csig1 * ssig12; + csig2 = this._csig1 * csig12 - this._ssig1 * ssig12; + B12 = g.SinCosSeries(true, ssig2, csig2, this._C1a); + serr = (1 + this._A1m1) * (sig12 + (B12 - this._B11)) - + s12_a12 / this._b; + sig12 = sig12 - serr / Math.sqrt(1 + this._k2 * m.sq(ssig2)); + ssig12 = Math.sin(sig12); csig12 = Math.cos(sig12); + // Update B12 below + } + } + + // sig2 = sig1 + sig12 + ssig2 = this._ssig1 * csig12 + this._csig1 * ssig12; + csig2 = this._csig1 * csig12 - this._ssig1 * ssig12; + dn2 = Math.sqrt(1 + this._k2 * m.sq(ssig2)); + if (outmask & (g.DISTANCE | g.REDUCEDLENGTH | g.GEODESICSCALE)) { + if (arcmode || Math.abs(this.f) > 0.01) + B12 = g.SinCosSeries(true, ssig2, csig2, this._C1a); + AB1 = (1 + this._A1m1) * (B12 - this._B11); + } + // sin(bet2) = cos(alp0) * sin(sig2) + sbet2 = this._calp0 * ssig2; + // Alt: cbet2 = hypot(csig2, salp0 * ssig2); + cbet2 = m.hypot(this._salp0, this._calp0 * csig2); + if (cbet2 === 0) + // I.e., salp0 = 0, csig2 = 0. Break the degeneracy in this case + cbet2 = csig2 = g.tiny_; + // tan(alp0) = cos(sig2)*tan(alp2) + salp2 = this._salp0; calp2 = this._calp0 * csig2; // No need to normalize + + if (arcmode && (outmask & g.DISTANCE)) + vals.s12 = this._b * ((1 + this._A1m1) * sig12 + AB1); + + if (outmask & g.LONGITUDE) { + // tan(omg2) = sin(alp0) * tan(sig2) + somg2 = this._salp0 * ssig2; comg2 = csig2; // No need to normalize + E = m.copysign(1, this._salp0); + // omg12 = omg2 - omg1 + omg12 = outmask & g.LONG_UNROLL ? + E * (sig12 - + (Math.atan2(ssig2, csig2) - + Math.atan2(this._ssig1, this._csig1)) + + (Math.atan2(E * somg2, comg2) - + Math.atan2(E * this._somg1, this._comg1))) : + Math.atan2(somg2 * this._comg1 - comg2 * this._somg1, + comg2 * this._comg1 + somg2 * this._somg1); + lam12 = omg12 + this._A3c * + ( sig12 + (g.SinCosSeries(true, ssig2, csig2, this._C3a) - + this._B31)); + lon12 = lam12 / m.degree; + vals.lon2 = outmask & g.LONG_UNROLL ? this.lon1 + lon12 : + m.AngNormalize(m.AngNormalize(this.lon1) + m.AngNormalize(lon12)); + } + + if (outmask & g.LATITUDE) + vals.lat2 = m.atan2d(sbet2, this._f1 * cbet2); + + if (outmask & g.AZIMUTH) + vals.azi2 = m.atan2d(salp2, calp2); + + if (outmask & (g.REDUCEDLENGTH | g.GEODESICSCALE)) { + B22 = g.SinCosSeries(true, ssig2, csig2, this._C2a); + AB2 = (1 + this._A2m1) * (B22 - this._B21); + J12 = (this._A1m1 - this._A2m1) * sig12 + (AB1 - AB2); + if (outmask & g.REDUCEDLENGTH) + // Add parens around (_csig1 * ssig2) and (_ssig1 * csig2) to ensure + // accurate cancellation in the case of coincident points. + vals.m12 = this._b * (( dn2 * (this._csig1 * ssig2) - + this._dn1 * (this._ssig1 * csig2)) - + this._csig1 * csig2 * J12); + if (outmask & g.GEODESICSCALE) { + t = this._k2 * (ssig2 - this._ssig1) * (ssig2 + this._ssig1) / + (this._dn1 + dn2); + vals.M12 = csig12 + + (t * ssig2 - csig2 * J12) * this._ssig1 / this._dn1; + vals.M21 = csig12 - + (t * this._ssig1 - this._csig1 * J12) * ssig2 / dn2; + } + } + + if (outmask & g.AREA) { + B42 = g.SinCosSeries(false, ssig2, csig2, this._C4a); + if (this._calp0 === 0 || this._salp0 === 0) { + // alp12 = alp2 - alp1, used in atan2 so no need to normalize + salp12 = salp2 * this.calp1 - calp2 * this.salp1; + calp12 = calp2 * this.calp1 + salp2 * this.salp1; + } else { + // tan(alp) = tan(alp0) * sec(sig) + // tan(alp2-alp1) = (tan(alp2) -tan(alp1)) / (tan(alp2)*tan(alp1)+1) + // = calp0 * salp0 * (csig1-csig2) / (salp0^2 + calp0^2 * csig1*csig2) + // If csig12 > 0, write + // csig1 - csig2 = ssig12 * (csig1 * ssig12 / (1 + csig12) + ssig1) + // else + // csig1 - csig2 = csig1 * (1 - csig12) + ssig12 * ssig1 + // No need to normalize + salp12 = this._calp0 * this._salp0 * + (csig12 <= 0 ? this._csig1 * (1 - csig12) + ssig12 * this._ssig1 : + ssig12 * (this._csig1 * ssig12 / (1 + csig12) + this._ssig1)); + calp12 = m.sq(this._salp0) + m.sq(this._calp0) * this._csig1 * csig2; + } + vals.S12 = this._c2 * Math.atan2(salp12, calp12) + + this._A4 * (B42 - this._B41); + } + + if (!arcmode) + vals.a12 = sig12 / m.degree; + return vals; + }; + + /** + * @summary Find the position on the line given s12. + * @param {number} s12 the distance from the first point to the second in + * meters. + * @param {bitmask} [outmask = STANDARD] which results to include; this is + * subject to the capabilities of the object. + * @returns {object} the requested results. + * @description The lat1, lon1, azi1, s12, and a12 fields of the result are + * always set; s12 is included if arcmode is false. For details on the + * outmask parameter, see {@tutorial 2-interface}, "The outmask and caps + * parameters". + */ + l.GeodesicLine.prototype.Position = function(s12, outmask) { + return this.GenPosition(false, s12, outmask); + }; + + /** + * @summary Find the position on the line given a12. + * @param {number} a12 the arc length from the first point to the second in + * degrees. + * @param {bitmask} [outmask = STANDARD] which results to include; this is + * subject to the capabilities of the object. + * @returns {object} the requested results. + * @description The lat1, lon1, azi1, and a12 fields of the result are + * always set. For details on the outmask parameter, see {@tutorial + * 2-interface}, "The outmask and caps parameters". + */ + l.GeodesicLine.prototype.ArcPosition = function(a12, outmask) { + return this.GenPosition(true, a12, outmask); + }; + + /** + * @summary Specify position of point 3 in terms of either distance or arc + * length. + * @param {bool} arcmode boolean flag determining the meaning of the second + * parameter; if arcmode is false, then the GeodesicLine object must have + * been constructed with caps |= DISTANCE_IN. + * @param {number} s13_a13 if arcmode is false, this is the distance from + * point 1 to point 3 (meters); otherwise it is the arc length from + * point 1 to point 3 (degrees); it can be negative. + **********************************************************************/ + l.GeodesicLine.prototype.GenSetDistance = function(arcmode, s13_a13) { + if (arcmode) + this.SetArc(s13_a13); + else + this.SetDistance(s13_a13); + }; + + /** + * @summary Specify position of point 3 in terms distance. + * @param {number} s13 the distance from point 1 to point 3 (meters); it + * can be negative. + **********************************************************************/ + l.GeodesicLine.prototype.SetDistance = function(s13) { + var r; + this.s13 = s13; + r = this.GenPosition(false, this.s13, g.ARC); + this.a13 = 0 + r.a12; // the 0+ converts undefined into NaN + }; + + /** + * @summary Specify position of point 3 in terms of arc length. + * @param {number} a13 the arc length from point 1 to point 3 (degrees); + * it can be negative. + **********************************************************************/ + l.GeodesicLine.prototype.SetArc = function(a13) { + var r; + this.a13 = a13; + r = this.GenPosition(true, this.a13, g.DISTANCE); + this.s13 = 0 + r.s12; // the 0+ converts undefined into NaN + }; + +})(GeographicLib.Geodesic, GeographicLib.GeodesicLine, GeographicLib.Math); diff --git a/gtsam/3rdparty/GeographicLib/js/src/Math.js b/gtsam/3rdparty/GeographicLib/js/src/Math.js new file mode 100644 index 000000000..dee30d737 --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/js/src/Math.js @@ -0,0 +1,428 @@ +/* + * Math.js + * Transcription of Math.hpp, Constants.hpp, and Accumulator.hpp into + * JavaScript. + * + * Copyright (c) Charles Karney (2011-2017) and licensed + * under the MIT/X11 License. For more information, see + * https://geographiclib.sourceforge.io/ + */ + +/** + * @namespace GeographicLib + * @description The parent namespace for the following modules: + * - {@link module:GeographicLib/Geodesic GeographicLib/Geodesic} The main + * engine for solving geodesic problems via the + * {@link module:GeographicLib/Geodesic.Geodesic Geodesic} class. + * - {@link module:GeographicLib/GeodesicLine GeographicLib/GeodesicLine} + * computes points along a single geodesic line via the + * {@link module:GeographicLib/GeodesicLine.GeodesicLine GeodesicLine} + * class. + * - {@link module:GeographicLib/PolygonArea GeographicLib/PolygonArea} + * computes the area of a geodesic polygon via the + * {@link module:GeographicLib/PolygonArea.PolygonArea PolygonArea} + * class. + * - {@link module:GeographicLib/DMS GeographicLib/DMS} handles the decoding + * and encoding of angles in degree, minutes, and seconds, via static + * functions in this module. + * - {@link module:GeographicLib/Constants GeographicLib/Constants} defines + * constants specifying the version numbers and the parameters for the WGS84 + * ellipsoid. + * + * The following modules are used internally by the package: + * - {@link module:GeographicLib/Math GeographicLib/Math} defines various + * mathematical functions. + * - {@link module:GeographicLib/Accumulator GeographicLib/Accumulator} + * interally used by + * {@link module:GeographicLib/PolygonArea.PolygonArea PolygonArea} (via the + * {@link module:GeographicLib/Accumulator.Accumulator Accumulator} class) + * for summing the contributions to the area of a polygon. + */ +"use strict"; +var GeographicLib = {}; +GeographicLib.Constants = {}; +GeographicLib.Math = {}; +GeographicLib.Accumulator = {}; + +(function( + /** + * @exports GeographicLib/Constants + * @description Define constants defining the version and WGS84 parameters. + */ + c) { + + /** + * @constant + * @summary WGS84 parameters. + * @property {number} a the equatorial radius (meters). + * @property {number} f the flattening. + */ + c.WGS84 = { a: 6378137, f: 1/298.257223563 }; + /** + * @constant + * @summary an array of version numbers. + * @property {number} major the major version number. + * @property {number} minor the minor version number. + * @property {number} patch the patch number. + */ + c.version = { major: 1, minor: 49, patch: 0 }; + /** + * @constant + * @summary version string + */ + c.version_string = "1.49"; +})(GeographicLib.Constants); + +(function( + /** + * @exports GeographicLib/Math + * @description Some useful mathematical constants and functions (mainly for + * internal use). + */ + m) { + + /** + * @summary The number of digits of precision in floating-point numbers. + * @constant {number} + */ + m.digits = 53; + /** + * @summary The machine epsilon. + * @constant {number} + */ + m.epsilon = Math.pow(0.5, m.digits - 1); + /** + * @summary The factor to convert degrees to radians. + * @constant {number} + */ + m.degree = Math.PI/180; + + /** + * @summary Square a number. + * @param {number} x the number. + * @returns {number} the square. + */ + m.sq = function(x) { return x * x; }; + + /** + * @summary The hypotenuse function. + * @param {number} x the first side. + * @param {number} y the second side. + * @returns {number} the hypotenuse. + */ + m.hypot = function(x, y) { + var a, b; + x = Math.abs(x); + y = Math.abs(y); + a = Math.max(x, y); b = Math.min(x, y) / (a ? a : 1); + return a * Math.sqrt(1 + b * b); + }; + + /** + * @summary Cube root function. + * @param {number} x the argument. + * @returns {number} the real cube root. + */ + m.cbrt = function(x) { + var y = Math.pow(Math.abs(x), 1/3); + return x < 0 ? -y : y; + }; + + /** + * @summary The log1p function. + * @param {number} x the argument. + * @returns {number} log(1 + x). + */ + m.log1p = function(x) { + var y = 1 + x, + z = y - 1; + // Here's the explanation for this magic: y = 1 + z, exactly, and z + // approx x, thus log(y)/z (which is nearly constant near z = 0) returns + // a good approximation to the true log(1 + x)/x. The multiplication x * + // (log(y)/z) introduces little additional error. + return z === 0 ? x : x * Math.log(y) / z; + }; + + /** + * @summary Inverse hyperbolic tangent. + * @param {number} x the argument. + * @returns {number} tanh−1 x. + */ + m.atanh = function(x) { + var y = Math.abs(x); // Enforce odd parity + y = m.log1p(2 * y/(1 - y))/2; + return x < 0 ? -y : y; + }; + + /** + * @summary Copy the sign. + * @param {number} x gives the magitude of the result. + * @param {number} y gives the sign of the result. + * @returns {number} value with the magnitude of x and with the sign of y. + */ + m.copysign = function(x, y) { + return Math.abs(x) * (y < 0 || (y === 0 && 1/y < 0) ? -1 : 1); + }; + + /** + * @summary An error-free sum. + * @param {number} u + * @param {number} v + * @returns {object} sum with sum.s = round(u + v) and sum.t is u + v − + * round(u + v) + */ + m.sum = function(u, v) { + var s = u + v, + up = s - v, + vpp = s - up, + t; + up -= u; + vpp -= v; + t = -(up + vpp); + // u + v = s + t + // = round(u + v) + t + return {s: s, t: t}; + }; + + /** + * @summary Evaluate a polynomial. + * @param {integer} N the order of the polynomial. + * @param {array} p the coefficient array (of size N + 1) (leading + * order coefficient first) + * @param {number} x the variable. + * @returns {number} the value of the polynomial. + */ + m.polyval = function(N, p, s, x) { + var y = N < 0 ? 0 : p[s++]; + while (--N >= 0) y = y * x + p[s++]; + return y; + }; + + /** + * @summary Coarsen a value close to zero. + * @param {number} x + * @returns {number} the coarsened value. + */ + m.AngRound = function(x) { + // The makes the smallest gap in x = 1/16 - nextafter(1/16, 0) = 1/2^57 for + // reals = 0.7 pm on the earth if x is an angle in degrees. (This is about + // 1000 times more resolution than we get with angles around 90 degrees.) + // We use this to avoid having to deal with near singular cases when x is + // non-zero but tiny (e.g., 1.0e-200). This converts -0 to +0; however + // tiny negative numbers get converted to -0. + if (x === 0) return x; + var z = 1/16, + y = Math.abs(x); + // The compiler mustn't "simplify" z - (z - y) to y + y = y < z ? z - (z - y) : y; + return x < 0 ? -y : y; + }; + + /** + * @summary Normalize an angle. + * @param {number} x the angle in degrees. + * @returns {number} the angle reduced to the range (−180°, + * 180°]. + */ + m.AngNormalize = function(x) { + // Place angle in [-180, 180). + x = x % 360; + return x <= -180 ? x + 360 : (x <= 180 ? x : x - 360); + }; + + /** + * @summary Normalize a latitude. + * @param {number} x the angle in degrees. + * @returns {number} x if it is in the range [−90°, 90°], + * otherwise return NaN. + */ + m.LatFix = function(x) { + // Replace angle with NaN if outside [-90, 90]. + return Math.abs(x) > 90 ? Number.NaN : x; + }; + + /** + * @summary The exact difference of two angles reduced to (−180°, + * 180°] + * @param {number} x the first angle in degrees. + * @param {number} y the second angle in degrees. + * @return {object} diff the exact difference, y − x. + * + * This computes z = y − x exactly, reduced to (−180°, + * 180°]; and then sets diff.s = d = round(z) and diff.t = e = z − + * round(z). If d = −180, then e > 0; If d = 180, then e ≤ 0. + */ + m.AngDiff = function(x, y) { + // Compute y - x and reduce to [-180,180] accurately. + var r = m.sum(m.AngNormalize(-x), m.AngNormalize(y)), + d = m.AngNormalize(r.s), + t = r.t; + return m.sum(d === 180 && t > 0 ? -180 : d, t); + }; + + /** + * @summary Evaluate the sine and cosine function with the argument in + * degrees + * @param {number} x in degrees. + * @returns {object} r with r.s = sin(x) and r.c = cos(x). + */ + m.sincosd = function(x) { + // In order to minimize round-off errors, this function exactly reduces + // the argument to the range [-45, 45] before converting it to radians. + var r, q, s, c, sinx, cosx; + r = x % 360; + q = Math.floor(r / 90 + 0.5); + r -= 90 * q; + // now abs(r) <= 45 + r *= this.degree; + // Possibly could call the gnu extension sincos + s = Math.sin(r); c = Math.cos(r); + switch (q & 3) { + case 0: sinx = s; cosx = c; break; + case 1: sinx = c; cosx = -s; break; + case 2: sinx = -s; cosx = -c; break; + default: sinx = -c; cosx = s; break; // case 3 + } + if (x !== 0) { sinx += 0; cosx += 0; } + return {s: sinx, c: cosx}; + }; + + /** + * @summary Evaluate the atan2 function with the result in degrees + * @param {number} y + * @param {number} x + * @returns atan2(y, x) in degrees, in the range (−180° + * 180°]. + */ + m.atan2d = function(y, x) { + // In order to minimize round-off errors, this function rearranges the + // arguments so that result of atan2 is in the range [-pi/4, pi/4] before + // converting it to degrees and mapping the result to the correct + // quadrant. + var q = 0, t, ang; + if (Math.abs(y) > Math.abs(x)) { t = x; x = y; y = t; q = 2; } + if (x < 0) { x = -x; ++q; } + // here x >= 0 and x >= abs(y), so angle is in [-pi/4, pi/4] + ang = Math.atan2(y, x) / this.degree; + switch (q) { + // Note that atan2d(-0.0, 1.0) will return -0. However, we expect that + // atan2d will not be called with y = -0. If need be, include + // + // case 0: ang = 0 + ang; break; + // + // and handle mpfr as in AngRound. + case 1: ang = (y >= 0 ? 180 : -180) - ang; break; + case 2: ang = 90 - ang; break; + case 3: ang = -90 + ang; break; + } + return ang; + }; +})(GeographicLib.Math); + +(function( + /** + * @exports GeographicLib/Accumulator + * @description Accurate summation via the + * {@link module:GeographicLib/Accumulator.Accumulator Accumulator} class + * (mainly for internal use). + */ + a, m) { + + /** + * @class + * @summary Accurate summation of many numbers. + * @classdesc This allows many numbers to be added together with twice the + * normal precision. In the documentation of the member functions, sum + * stands for the value currently held in the accumulator. + * @param {number | Accumulator} [y = 0] set sum = y. + */ + a.Accumulator = function(y) { + this.Set(y); + }; + + /** + * @summary Set the accumulator to a number. + * @param {number | Accumulator} [y = 0] set sum = y. + */ + a.Accumulator.prototype.Set = function(y) { + if (!y) y = 0; + if (y.constructor === a.Accumulator) { + this._s = y._s; + this._t = y._t; + } else { + this._s = y; + this._t = 0; + } + }; + + /** + * @summary Add a number to the accumulator. + * @param {number} [y = 0] set sum += y. + */ + a.Accumulator.prototype.Add = function(y) { + // Here's Shewchuk's solution... + // Accumulate starting at least significant end + var u = m.sum(y, this._t), + v = m.sum(u.s, this._s); + u = u.t; + this._s = v.s; + this._t = v.t; + // Start is _s, _t decreasing and non-adjacent. Sum is now (s + t + u) + // exactly with s, t, u non-adjacent and in decreasing order (except + // for possible zeros). The following code tries to normalize the + // result. Ideally, we want _s = round(s+t+u) and _u = round(s+t+u - + // _s). The follow does an approximate job (and maintains the + // decreasing non-adjacent property). Here are two "failures" using + // 3-bit floats: + // + // Case 1: _s is not equal to round(s+t+u) -- off by 1 ulp + // [12, -1] - 8 -> [4, 0, -1] -> [4, -1] = 3 should be [3, 0] = 3 + // + // Case 2: _s+_t is not as close to s+t+u as it shold be + // [64, 5] + 4 -> [64, 8, 1] -> [64, 8] = 72 (off by 1) + // should be [80, -7] = 73 (exact) + // + // "Fixing" these problems is probably not worth the expense. The + // representation inevitably leads to small errors in the accumulated + // values. The additional errors illustrated here amount to 1 ulp of + // the less significant word during each addition to the Accumulator + // and an additional possible error of 1 ulp in the reported sum. + // + // Incidentally, the "ideal" representation described above is not + // canonical, because _s = round(_s + _t) may not be true. For + // example, with 3-bit floats: + // + // [128, 16] + 1 -> [160, -16] -- 160 = round(145). + // But [160, 0] - 16 -> [128, 16] -- 128 = round(144). + // + if (this._s === 0) // This implies t == 0, + this._s = u; // so result is u + else + this._t += u; // otherwise just accumulate u to t. + }; + + /** + * @summary Return the result of adding a number to sum (but + * don't change sum). + * @param {number} [y = 0] the number to be added to the sum. + * @return sum + y. + */ + a.Accumulator.prototype.Sum = function(y) { + var b; + if (!y) + return this._s; + else { + b = new a.Accumulator(this); + b.Add(y); + return b._s; + } + }; + + /** + * @summary Set sum = −sum. + */ + a.Accumulator.prototype.Negate = function() { + this._s *= -1; + this._t *= -1; + }; +})(GeographicLib.Accumulator, GeographicLib.Math); diff --git a/gtsam/3rdparty/GeographicLib/js/src/PolygonArea.js b/gtsam/3rdparty/GeographicLib/js/src/PolygonArea.js new file mode 100644 index 000000000..abd340a90 --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/js/src/PolygonArea.js @@ -0,0 +1,321 @@ +/* + * PolygonArea.js + * Transcription of PolygonArea.[ch]pp into JavaScript. + * + * See the documentation for the C++ class. The conversion is a literal + * conversion from C++. + * + * The algorithms are derived in + * + * Charles F. F. Karney, + * Algorithms for geodesics, J. Geodesy 87, 43-55 (2013); + * https://doi.org/10.1007/s00190-012-0578-z + * Addenda: https://geographiclib.sourceforge.io/geod-addenda.html + * + * Copyright (c) Charles Karney (2011-2017) and licensed + * under the MIT/X11 License. For more information, see + * https://geographiclib.sourceforge.io/ + */ + +// Load AFTER GeographicLib/Math.js and GeographicLib/Geodesic.js + +(function( + /** + * @exports GeographicLib/PolygonArea + * @description Compute the area of geodesic polygons via the + * {@link module:GeographicLib/PolygonArea.PolygonArea PolygonArea} + * class. + */ + p, g, m, a) { + + var transit, transitdirect; + transit = function(lon1, lon2) { + // Return 1 or -1 if crossing prime meridian in east or west direction. + // Otherwise return zero. + var lon12, cross; + // Compute lon12 the same way as Geodesic::Inverse. + lon1 = m.AngNormalize(lon1); + lon2 = m.AngNormalize(lon2); + lon12 = m.AngDiff(lon1, lon2).s; + cross = lon1 <= 0 && lon2 > 0 && lon12 > 0 ? 1 : + (lon2 <= 0 && lon1 > 0 && lon12 < 0 ? -1 : 0); + return cross; + }; + + // an alternate version of transit to deal with longitudes in the direct + // problem. + transitdirect = function(lon1, lon2) { + // We want to compute exactly + // int(floor(lon2 / 360)) - int(floor(lon1 / 360)) + // Since we only need the parity of the result we can use std::remquo but + // this is buggy with g++ 4.8.3 and requires C++11. So instead we do + lon1 = lon1 % 720.0; lon2 = lon2 % 720.0; + return ( ((lon2 >= 0 && lon2 < 360) || lon2 < -360 ? 0 : 1) - + ((lon1 >= 0 && lon1 < 360) || lon1 < -360 ? 0 : 1) ); + }; + + /** + * @class + * @property {number} a the equatorial radius (meters). + * @property {number} f the flattening. + * @property {bool} polyline whether the PolygonArea object describes a + * polyline or a polygon. + * @property {number} num the number of vertices so far. + * @property {number} lat the current latitude (degrees). + * @property {number} lon the current longitude (degrees). + * @summary Initialize a PolygonArea object. + * @classdesc Computes the area and perimeter of a geodesic polygon. + * This object is usually instantiated by + * {@link module:GeographicLib/Geodesic.Geodesic#Polygon Geodesic.Polygon}. + * @param {object} geod a {@link module:GeographicLib/Geodesic.Geodesic + * Geodesic} object. + * @param {bool} [polyline = false] if true the new PolygonArea object + * describes a polyline instead of a polygon. + */ + p.PolygonArea = function(geod, polyline) { + this._geod = geod; + this.a = this._geod.a; + this.f = this._geod.f; + this._area0 = 4 * Math.PI * geod._c2; + this.polyline = !polyline ? false : polyline; + this._mask = g.LATITUDE | g.LONGITUDE | g.DISTANCE | + (this.polyline ? g.NONE : g.AREA | g.LONG_UNROLL); + if (!this.polyline) + this._areasum = new a.Accumulator(0); + this._perimetersum = new a.Accumulator(0); + this.Clear(); + }; + + /** + * @summary Clear the PolygonArea object, setting the number of vertices to + * 0. + */ + p.PolygonArea.prototype.Clear = function() { + this.num = 0; + this._crossings = 0; + if (!this.polyline) + this._areasum.Set(0); + this._perimetersum.Set(0); + this._lat0 = this._lon0 = this.lat = this.lon = Number.NaN; + }; + + /** + * @summary Add the next vertex to the polygon. + * @param {number} lat the latitude of the point (degrees). + * @param {number} lon the longitude of the point (degrees). + * @description This adds an edge from the current vertex to the new vertex. + */ + p.PolygonArea.prototype.AddPoint = function(lat, lon) { + var t; + if (this.num === 0) { + this._lat0 = this.lat = lat; + this._lon0 = this.lon = lon; + } else { + t = this._geod.Inverse(this.lat, this.lon, lat, lon, this._mask); + this._perimetersum.Add(t.s12); + if (!this.polyline) { + this._areasum.Add(t.S12); + this._crossings += transit(this.lon, lon); + } + this.lat = lat; + this.lon = lon; + } + ++this.num; + }; + + /** + * @summary Add the next edge to the polygon. + * @param {number} azi the azimuth at the current the point (degrees). + * @param {number} s the length of the edge (meters). + * @description This specifies the new vertex in terms of the edge from the + * current vertex. + */ + p.PolygonArea.prototype.AddEdge = function(azi, s) { + var t; + if (this.num) { + t = this._geod.Direct(this.lat, this.lon, azi, s, this._mask); + this._perimetersum.Add(s); + if (!this.polyline) { + this._areasum.Add(t.S12); + this._crossings += transitdirect(this.lon, t.lon2); + } + this.lat = t.lat2; + this.lon = t.lon2; + } + ++this.num; + }; + + /** + * @summary Compute the perimeter and area of the polygon. + * @param {bool} reverse if true then clockwise (instead of + * counter-clockwise) traversal counts as a positive area. + * @param {bool} sign if true then return a signed result for the area if the + * polygon is traversed in the "wrong" direction instead of returning the + * area for the rest of the earth. + * @returns {object} r where r.number is the number of vertices, r.perimeter + * is the perimeter (meters), and r.area (only returned if polyline is + * false) is the area (meters2). + * @description If the object is a polygon (and not a polygon), the perimeter + * includes the length of a final edge connecting the current point to the + * initial point. If the object is a polyline, then area is nan. More + * points can be added to the polygon after this call. + */ + p.PolygonArea.prototype.Compute = function(reverse, sign) { + var vals = {number: this.num}, t, tempsum, crossings; + if (this.num < 2) { + vals.perimeter = 0; + if (!this.polyline) + vals.area = 0; + return vals; + } + if (this.polyline) { + vals.perimeter = this._perimetersum.Sum(); + return vals; + } + t = this._geod.Inverse(this.lat, this.lon, this._lat0, this._lon0, + this._mask); + vals.perimeter = this._perimetersum.Sum(t.s12); + tempsum = new a.Accumulator(this._areasum); + tempsum.Add(t.S12); + crossings = this._crossings + transit(this.lon, this._lon0); + if (crossings & 1) + tempsum.Add( (tempsum.Sum() < 0 ? 1 : -1) * this._area0/2 ); + // area is with the clockwise sense. If !reverse convert to + // counter-clockwise convention. + if (!reverse) + tempsum.Negate(); + // If sign put area in (-area0/2, area0/2], else put area in [0, area0) + if (sign) { + if (tempsum.Sum() > this._area0/2) + tempsum.Add( -this._area0 ); + else if (tempsum.Sum() <= -this._area0/2) + tempsum.Add( +this._area0 ); + } else { + if (tempsum.Sum() >= this._area0) + tempsum.Add( -this._area0 ); + else if (tempsum < 0) + tempsum.Add( -this._area0 ); + } + vals.area = tempsum.Sum(); + return vals; + }; + + /** + * @summary Compute the perimeter and area of the polygon with a tentative + * new vertex. + * @param {number} lat the latitude of the point (degrees). + * @param {number} lon the longitude of the point (degrees). + * @param {bool} reverse if true then clockwise (instead of + * counter-clockwise) traversal counts as a positive area. + * @param {bool} sign if true then return a signed result for the area if the + * polygon is traversed in the "wrong" direction instead of returning the + * @returns {object} r where r.number is the number of vertices, r.perimeter + * is the perimeter (meters), and r.area (only returned if polyline is + * false) is the area (meters2). + * @description A new vertex is *not* added to the polygon. + */ + p.PolygonArea.prototype.TestPoint = function(lat, lon, reverse, sign) { + var vals = {number: this.num + 1}, t, tempsum, crossings, i; + if (this.num === 0) { + vals.perimeter = 0; + if (!this.polyline) + vals.area = 0; + return vals; + } + vals.perimeter = this._perimetersum.Sum(); + tempsum = this.polyline ? 0 : this._areasum.Sum(); + crossings = this._crossings; + for (i = 0; i < (this.polyline ? 1 : 2); ++i) { + t = this._geod.Inverse( + i === 0 ? this.lat : lat, i === 0 ? this.lon : lon, + i !== 0 ? this._lat0 : lat, i !== 0 ? this._lon0 : lon, + this._mask); + vals.perimeter += t.s12; + if (!this.polyline) { + tempsum += t.S12; + crossings += transit(i === 0 ? this.lon : lon, + i !== 0 ? this._lon0 : lon); + } + } + + if (this.polyline) + return vals; + + if (crossings & 1) + tempsum += (tempsum < 0 ? 1 : -1) * this._area0/2; + // area is with the clockwise sense. If !reverse convert to + // counter-clockwise convention. + if (!reverse) + tempsum *= -1; + // If sign put area in (-area0/2, area0/2], else put area in [0, area0) + if (sign) { + if (tempsum > this._area0/2) + tempsum -= this._area0; + else if (tempsum <= -this._area0/2) + tempsum += this._area0; + } else { + if (tempsum >= this._area0) + tempsum -= this._area0; + else if (tempsum < 0) + tempsum += this._area0; + } + vals.area = tempsum; + return vals; + }; + + /** + * @summary Compute the perimeter and area of the polygon with a tentative + * new edge. + * @param {number} azi the azimuth of the edge (degrees). + * @param {number} s the length of the edge (meters). + * @param {bool} reverse if true then clockwise (instead of + * counter-clockwise) traversal counts as a positive area. + * @param {bool} sign if true then return a signed result for the area if the + * polygon is traversed in the "wrong" direction instead of returning the + * @returns {object} r where r.number is the number of vertices, r.perimeter + * is the perimeter (meters), and r.area (only returned if polyline is + * false) is the area (meters2). + * @description A new vertex is *not* added to the polygon. + */ + p.PolygonArea.prototype.TestEdge = function(azi, s, reverse, sign) { + var vals = {number: this.num ? this.num + 1 : 0}, t, tempsum, crossings; + if (this.num === 0) + return vals; + vals.perimeter = this._perimetersum.Sum() + s; + if (this.polyline) + return vals; + + tempsum = this._areasum.Sum(); + crossings = this._crossings; + t = this._geod.Direct(this.lat, this.lon, azi, s, this._mask); + tempsum += t.S12; + crossings += transitdirect(this.lon, t.lon2); + t = this._geod.Inverse(t.lat2, t.lon2, this._lat0, this._lon0, this._mask); + vals.perimeter += t.s12; + tempsum += t.S12; + crossings += transit(t.lon2, this._lon0); + + if (crossings & 1) + tempsum += (tempsum < 0 ? 1 : -1) * this._area0/2; + // area is with the clockwise sense. If !reverse convert to + // counter-clockwise convention. + if (!reverse) + tempsum *= -1; + // If sign put area in (-area0/2, area0/2], else put area in [0, area0) + if (sign) { + if (tempsum > this._area0/2) + tempsum -= this._area0; + else if (tempsum <= -this._area0/2) + tempsum += this._area0; + } else { + if (tempsum >= this._area0) + tempsum -= this._area0; + else if (tempsum < 0) + tempsum += this._area0; + } + vals.area = tempsum; + return vals; + }; + +})(GeographicLib.PolygonArea, GeographicLib.Geodesic, + GeographicLib.Math, GeographicLib.Accumulator); diff --git a/gtsam/3rdparty/GeographicLib/js/test/geodesictest.js b/gtsam/3rdparty/GeographicLib/js/test/geodesictest.js new file mode 100644 index 000000000..72c25aee4 --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/js/test/geodesictest.js @@ -0,0 +1,654 @@ +"use strict"; + +var assert = require("assert"), + G = require("../geographiclib"), + g = G.Geodesic, + d = G.DMS, + testcases = [ + [35.60777, -139.44815, 111.098748429560326, + -11.17491, -69.95921, 129.289270889708762, + 8935244.5604818305, 80.50729714281974, 6273170.2055303837, + 0.16606318447386067, 0.16479116945612937, 12841384694976.432], + [55.52454, 106.05087, 22.020059880982801, + 77.03196, 197.18234, 109.112041110671519, + 4105086.1713924406, 36.892740690445894, 3828869.3344387607, + 0.80076349608092607, 0.80101006984201008, 61674961290615.615], + [-21.97856, 142.59065, -32.44456876433189, + 41.84138, 98.56635, -41.84359951440466, + 8394328.894657671, 75.62930491011522, 6161154.5773110616, + 0.24816339233950381, 0.24930251203627892, -6637997720646.717], + [-66.99028, 112.2363, 173.73491240878403, + -12.70631, 285.90344, 2.512956620913668, + 11150344.2312080241, 100.278634181155759, 6289939.5670446687, + -0.17199490274700385, -0.17722569526345708, -121287239862139.744], + [-17.42761, 173.34268, -159.033557661192928, + -15.84784, 5.93557, -20.787484651536988, + 16076603.1631180673, 144.640108810286253, 3732902.1583877189, + -0.81273638700070476, -0.81299800519154474, 97825992354058.708], + [32.84994, 48.28919, 150.492927788121982, + -56.28556, 202.29132, 48.113449399816759, + 16727068.9438164461, 150.565799985466607, 3147838.1910180939, + -0.87334918086923126, -0.86505036767110637, -72445258525585.010], + [6.96833, 52.74123, 92.581585386317712, + -7.39675, 206.17291, 90.721692165923907, + 17102477.2496958388, 154.147366239113561, 2772035.6169917581, + -0.89991282520302447, -0.89986892177110739, -1311796973197.995], + [-50.56724, -16.30485, -105.439679907590164, + -33.56571, -94.97412, -47.348547835650331, + 6455670.5118668696, 58.083719495371259, 5409150.7979815838, + 0.53053508035997263, 0.52988722644436602, 41071447902810.047], + [-58.93002, -8.90775, 140.965397902500679, + -8.91104, 133.13503, 19.255429433416599, + 11756066.0219864627, 105.755691241406877, 6151101.2270708536, + -0.26548622269867183, -0.27068483874510741, -86143460552774.735], + [-68.82867, -74.28391, 93.774347763114881, + -50.63005, -8.36685, 34.65564085411343, + 3956936.926063544, 35.572254987389284, 3708890.9544062657, + 0.81443963736383502, 0.81420859815358342, -41845309450093.787], + [-10.62672, -32.0898, -86.426713286747751, + 5.883, -134.31681, -80.473780971034875, + 11470869.3864563009, 103.387395634504061, 6184411.6622659713, + -0.23138683500430237, -0.23155097622286792, 4198803992123.548], + [-21.76221, 166.90563, 29.319421206936428, + 48.72884, 213.97627, 43.508671946410168, + 9098627.3986554915, 81.963476716121964, 6299240.9166992283, + 0.13965943368590333, 0.14152969707656796, 10024709850277.476], + [-19.79938, -174.47484, 71.167275780171533, + -11.99349, -154.35109, 65.589099775199228, + 2319004.8601169389, 20.896611684802389, 2267960.8703918325, + 0.93427001867125849, 0.93424887135032789, -3935477535005.785], + [-11.95887, -116.94513, 92.712619830452549, + 4.57352, 7.16501, 78.64960934409585, + 13834722.5801401374, 124.688684161089762, 5228093.177931598, + -0.56879356755666463, -0.56918731952397221, -9919582785894.853], + [-87.85331, 85.66836, -65.120313040242748, + 66.48646, 16.09921, -4.888658719272296, + 17286615.3147144645, 155.58592449699137, 2635887.4729110181, + -0.90697975771398578, -0.91095608883042767, 42667211366919.534], + [1.74708, 128.32011, -101.584843631173858, + -11.16617, 11.87109, -86.325793296437476, + 12942901.1241347408, 116.650512484301857, 5682744.8413270572, + -0.44857868222697644, -0.44824490340007729, 10763055294345.653], + [-25.72959, -144.90758, -153.647468693117198, + -57.70581, -269.17879, -48.343983158876487, + 9413446.7452453107, 84.664533838404295, 6356176.6898881281, + 0.09492245755254703, 0.09737058264766572, 74515122850712.444], + [-41.22777, 122.32875, 14.285113402275739, + -7.57291, 130.37946, 10.805303085187369, + 3812686.035106021, 34.34330804743883, 3588703.8812128856, + 0.82605222593217889, 0.82572158200920196, -2456961531057.857], + [11.01307, 138.25278, 79.43682622782374, + 6.62726, 247.05981, 103.708090215522657, + 11911190.819018408, 107.341669954114577, 6070904.722786735, + -0.29767608923657404, -0.29785143390252321, 17121631423099.696], + [-29.47124, 95.14681, -163.779130441688382, + -27.46601, -69.15955, -15.909335945554969, + 13487015.8381145492, 121.294026715742277, 5481428.9945736388, + -0.51527225545373252, -0.51556587964721788, 104679964020340.318]]; + +assert.approx = function(x, y, d) { + assert(Math.abs(x-y) <= d, x + " = " + y + " +/- " + d); +}; + +describe("GeographicLib", function() { + describe("GeodesicTest", function () { + var geod = g.WGS84, i, + check_geod_inverse, check_geod_direct, check_geod_arcdirect; + + check_geod_inverse = function(l) { + var lat1 = l[0], lon1 = l[1], azi1 = l[2], + lat2 = l[3], lon2 = l[4], azi2 = l[5], + s12 = l[6], a12 = l[7], m12 = l[8], + M12 = l[9], M21 = l[10], S12 = l[11], + inv = geod.Inverse(lat1, lon1, lat2, G.Math.AngNormalize(lon2), + g.ALL | g.LONG_UNROLL); + assert.approx(lon2, inv.lon2, 1e-13); + assert.approx(azi1, inv.azi1, 1e-13); + assert.approx(azi2, inv.azi2, 1e-13); + assert.approx(s12, inv.s12, 1e-8); + assert.approx(a12, inv.a12, 1e-13); + assert.approx(m12, inv.m12, 1e-8); + assert.approx(M12, inv.M12, 1e-15); + assert.approx(M21, inv.M21, 1e-15); + assert.approx(S12, inv.S12, 0.1); + }; + + check_geod_direct = function(l) { + var lat1 = l[0], lon1 = l[1], azi1 = l[2], + lat2 = l[3], lon2 = l[4], azi2 = l[5], + s12 = l[6], a12 = l[7], m12 = l[8], + M12 = l[9], M21 = l[10], S12 = l[11], + dir = geod.Direct(lat1, lon1, azi1, s12, g.ALL | g.LONG_UNROLL); + assert.approx(lat2, dir.lat2, 1e-13); + assert.approx(lon2, dir.lon2, 1e-13); + assert.approx(azi2, dir.azi2, 1e-13); + assert.approx(a12, dir.a12, 1e-13); + assert.approx(m12, dir.m12, 1e-8); + assert.approx(M12, dir.M12, 1e-15); + assert.approx(M21, dir.M21, 1e-15); + assert.approx(S12, dir.S12, 0.1); + }; + + check_geod_arcdirect = function(l) { + var lat1 = l[0], lon1 = l[1], azi1 = l[2], + lat2 = l[3], lon2 = l[4], azi2 = l[5], + s12 = l[6], a12 = l[7], m12 = l[8], + M12 = l[9], M21 = l[10], S12 = l[11], + dir = geod.ArcDirect(lat1, lon1, azi1, a12, g.ALL | g.LONG_UNROLL); + assert.approx(lat2, dir.lat2, 1e-13); + assert.approx(lon2, dir.lon2, 1e-13); + assert.approx(azi2, dir.azi2, 1e-13); + assert.approx(s12, dir.s12, 1e-8); + assert.approx(m12, dir.m12, 1e-8); + assert.approx(M12, dir.M12, 1e-15); + assert.approx(M21, dir.M21, 1e-15); + assert.approx(S12, dir.S12, 0.1); + }; + + it("check inverse", function () { + for (i = 0; i < testcases.length; ++i) { + check_geod_inverse(testcases[i]); + } + }); + + it("check direct", function () { + for (i = 0; i < testcases.length; ++i) { + check_geod_direct(testcases[i]); + } + }); + + it("check arcdirect", function () { + for (i = 0; i < testcases.length; ++i) { + check_geod_arcdirect(testcases[i]); + } + }); + + }); + + describe("DMSTest", function () { + it("check decode", function () { + assert.deepEqual(d.Decode("E7:33:36"), d.Decode("-7.56W")); + }); + }); + + describe("GeodesicSolve", function () { + it("GeodSolve0", function () { + var geod = g.WGS84, + inv = geod.Inverse(40.6, -73.8, 49.01666667, 2.55); + assert.approx(inv.azi1, 53.47022, 0.5e-5); + assert.approx(inv.azi2, 111.59367, 0.5e-5); + assert.approx(inv.s12, 5853226, 0.5); + }); + + it("GeodSolve1", function() { + var geod = g.WGS84, + dir = geod.Direct(40.63972222, -73.77888889, 53.5, 5850e3); + assert.approx(dir.lat2, 49.01467, 0.5e-5); + assert.approx(dir.lon2, 2.56106, 0.5e-5); + assert.approx(dir.azi2, 111.62947, 0.5e-5); + }); + + it("GeodSolve2", function() { + // Check fix for antipodal prolate bug found 2010-09-04 + var geod = new g.Geodesic(6.4e6, -1/150.0), + inv = geod.Inverse(0.07476, 0, -0.07476, 180); + assert.approx(inv.azi1, 90.00078, 0.5e-5); + assert.approx(inv.azi2, 90.00078, 0.5e-5); + assert.approx(inv.s12, 20106193, 0.5); + inv = geod.Inverse(0.1, 0, -0.1, 180); + assert.approx(inv.azi1, 90.00105, 0.5e-5); + assert.approx(inv.azi2, 90.00105, 0.5e-5); + assert.approx(inv.s12, 20106193, 0.5); + }); + + it("GeodSolve4", function() { + // Check fix for short line bug found 2010-05-21 + var geod = g.WGS84, + inv = geod.Inverse(36.493349428792, 0, 36.49334942879201, 0.0000008); + assert.approx(inv.s12, 0.072, 0.5e-3); + }); + + it("GeodSolve5", function() { + // Check fix for point2=pole bug found 2010-05-03 + var geod = g.WGS84, + dir = geod.Direct(0.01777745589997, 30, 0, 10e6); + assert.approx(dir.lat2, 90, 0.5e-5); + if (dir.lon2 < 0) { + assert.approx(dir.lon2, -150, 0.5e-5); + assert.approx(Math.abs(dir.azi2), 180, 0.5e-5); + } else { + assert.approx(dir.lon2, 30, 0.5e-5); + assert.approx(dir.azi2, 0, 0.5e-5); + } + }); + + it("GeodSolve6", function() { + // Check fix for volatile sbet12a bug found 2011-06-25 (gcc 4.4.4 + // x86 -O3). Found again on 2012-03-27 with tdm-mingw32 (g++ 4.6.1). + var geod = g.WGS84, + inv = geod.Inverse(88.202499451857, 0, + -88.202499451857, 179.981022032992859592); + assert.approx(inv.s12, 20003898.214, 0.5e-3); + inv = geod.Inverse(89.262080389218, 0, + -89.262080389218, 179.992207982775375662); + assert.approx(inv.s12, 20003925.854, 0.5e-3); + inv = geod.Inverse(89.333123580033, 0, + -89.333123580032997687, 179.99295812360148422); + assert.approx(inv.s12, 20003926.881, 0.5e-3); + }); + + it("GeodSolve9", function() { + // Check fix for volatile x bug found 2011-06-25 (gcc 4.4.4 x86 -O3) + var geod = g.WGS84, + inv = geod.Inverse(56.320923501171, 0, + -56.320923501171, 179.664747671772880215); + assert.approx(inv.s12, 19993558.287, 0.5e-3); + }); + + it("GeodSolve10", function() { + // Check fix for adjust tol1_ bug found 2011-06-25 (Visual Studio + // 10 rel + debug) + var geod = g.WGS84, + inv = geod.Inverse(52.784459512564, 0, + -52.784459512563990912, 179.634407464943777557); + assert.approx(inv.s12, 19991596.095, 0.5e-3); + }); + + it("GeodSolve11", function() { + // Check fix for bet2 = -bet1 bug found 2011-06-25 (Visual Studio + // 10 rel + debug) + var geod = g.WGS84, + inv = geod.Inverse(48.522876735459, 0, + -48.52287673545898293, 179.599720456223079643); + assert.approx(inv.s12, 19989144.774, 0.5e-3); + }); + + it("GeodSolve12", function() { + // Check fix for inverse geodesics on extreme prolate/oblate + // ellipsoids Reported 2012-08-29 Stefan Guenther + // ; fixed 2012-10-07 + var geod = new g.Geodesic(89.8, -1.83), + inv = geod.Inverse(0, 0, -10, 160); + assert.approx(inv.azi1, 120.27, 1e-2); + assert.approx(inv.azi2, 105.15, 1e-2); + assert.approx(inv.s12, 266.7, 1e-1); + }); + + it("GeodSolve14", function() { + // Check fix for inverse ignoring lon12 = nan + var geod = g.WGS84, + inv = geod.Inverse(0, 0, 1, NaN); + assert(isNaN(inv.azi1)); + assert(isNaN(inv.azi2)); + assert(isNaN(inv.s12)); + }); + + it("GeodSolve15", function() { + // Initial implementation of Math::eatanhe was wrong for e^2 < 0. This + // checks that this is fixed. + var geod = new g.Geodesic(6.4e6, -1/150.0), + dir = geod.Direct(1, 2, 3, 4, g.AREA); + assert.approx(dir.S12, 23700, 0.5); + }); + + it("GeodSolve17", function() { + // Check fix for LONG_UNROLL bug found on 2015-05-07 + var geod = g.WGS84, + dir = geod.Direct(40, -75, -10, 2e7, g.LONG_UNROLL), + line; + assert.approx(dir.lat2, -39, 1); + assert.approx(dir.lon2, -254, 1); + assert.approx(dir.azi2, -170, 1); + line = geod.Line(40, -75, -10); + dir = line.Position(2e7, g.LONG_UNROLL); + assert.approx(dir.lat2, -39, 1); + assert.approx(dir.lon2, -254, 1); + assert.approx(dir.azi2, -170, 1); + dir = geod.Direct(40, -75, -10, 2e7); + assert.approx(dir.lat2, -39, 1); + assert.approx(dir.lon2, 105, 1); + assert.approx(dir.azi2, -170, 1); + dir = line.Position(2e7); + assert.approx(dir.lat2, -39, 1); + assert.approx(dir.lon2, 105, 1); + assert.approx(dir.azi2, -170, 1); + }); + + it("GeodSolve26", function() { + // Check 0/0 problem with area calculation on sphere 2015-09-08 + var geod = new g.Geodesic(6.4e6, 0), + inv = geod.Inverse(1, 2, 3, 4, g.AREA); + assert.approx(inv.S12, 49911046115.0, 0.5); + }); + + it("GeodSolve28", function() { + // Check for bad placement of assignment of r.a12 with |f| > 0.01 (bug in + // Java implementation fixed on 2015-05-19). + var geod = new g.Geodesic(6.4e6, 0.1), + dir = geod.Direct(1, 2, 10, 5e6); + assert.approx(dir.a12, 48.55570690, 0.5e-8); + }); + + it("GeodSolve29", function() { + // Check longitude unrolling with inverse calculation 2015-09-16 + var geod = g.WGS84, + dir = geod.Inverse(0, 539, 0, 181); + assert.approx(dir.lon1, 179, 1e-10); + assert.approx(dir.lon2, -179, 1e-10); + assert.approx(dir.s12, 222639, 0.5); + dir = geod.Inverse(0, 539, 0, 181, g.LONG_UNROLL); + assert.approx(dir.lon1, 539, 1e-10); + assert.approx(dir.lon2, 541, 1e-10); + assert.approx(dir.s12, 222639, 0.5); + }); + + it("GeodSolve33", function() { + // Check max(-0.0,+0.0) issues 2015-08-22 (triggered by bugs in Octave -- + // sind(-0.0) = +0.0 -- and in some version of Visual Studio -- + // fmod(-0.0, 360.0) = +0.0. + var geod = g.WGS84, + inv = geod.Inverse(0, 0, 0, 179); + assert.approx(inv.azi1, 90.00000, 0.5e-5); + assert.approx(inv.azi2, 90.00000, 0.5e-5); + assert.approx(inv.s12, 19926189, 0.5); + inv = geod.Inverse(0, 0, 0, 179.5); + assert.approx(inv.azi1, 55.96650, 0.5e-5); + assert.approx(inv.azi2, 124.03350, 0.5e-5); + assert.approx(inv.s12, 19980862, 0.5); + inv = geod.Inverse(0, 0, 0, 180); + assert.approx(inv.azi1, 0.00000, 0.5e-5); + assert.approx(Math.abs(inv.azi2), 180.00000, 0.5e-5); + assert.approx(inv.s12, 20003931, 0.5); + inv = geod.Inverse(0, 0, 1, 180); + assert.approx(inv.azi1, 0.00000, 0.5e-5); + assert.approx(Math.abs(inv.azi2), 180.00000, 0.5e-5); + assert.approx(inv.s12, 19893357, 0.5); + geod = new g.Geodesic(6.4e6, 0); + inv = geod.Inverse(0, 0, 0, 179); + assert.approx(inv.azi1, 90.00000, 0.5e-5); + assert.approx(inv.azi2, 90.00000, 0.5e-5); + assert.approx(inv.s12, 19994492, 0.5); + inv = geod.Inverse(0, 0, 0, 180); + assert.approx(inv.azi1, 0.00000, 0.5e-5); + assert.approx(Math.abs(inv.azi2), 180.00000, 0.5e-5); + assert.approx(inv.s12, 20106193, 0.5); + inv = geod.Inverse(0, 0, 1, 180); + assert.approx(inv.azi1, 0.00000, 0.5e-5); + assert.approx(Math.abs(inv.azi2), 180.00000, 0.5e-5); + assert.approx(inv.s12, 19994492, 0.5); + geod = new g.Geodesic(6.4e6, -1/300.0); + inv = geod.Inverse(0, 0, 0, 179); + assert.approx(inv.azi1, 90.00000, 0.5e-5); + assert.approx(inv.azi2, 90.00000, 0.5e-5); + assert.approx(inv.s12, 19994492, 0.5); + inv = geod.Inverse(0, 0, 0, 180); + assert.approx(inv.azi1, 90.00000, 0.5e-5); + assert.approx(inv.azi2, 90.00000, 0.5e-5); + assert.approx(inv.s12, 20106193, 0.5); + inv = geod.Inverse(0, 0, 0.5, 180); + assert.approx(inv.azi1, 33.02493, 0.5e-5); + assert.approx(inv.azi2, 146.97364, 0.5e-5); + assert.approx(inv.s12, 20082617, 0.5); + inv = geod.Inverse(0, 0, 1, 180); + assert.approx(inv.azi1, 0.00000, 0.5e-5); + assert.approx(Math.abs(inv.azi2), 180.00000, 0.5e-5); + assert.approx(inv.s12, 20027270, 0.5); + }); + + it("GeodSolve55", function() { + // Check fix for nan + point on equator or pole not returning all nans in + // Geodesic::Inverse, found 2015-09-23. + var geod = g.WGS84, + inv = geod.Inverse(NaN, 0, 0, 90); + assert(isNaN(inv.azi1)); + assert(isNaN(inv.azi2)); + assert(isNaN(inv.s12)); + inv = geod.Inverse(NaN, 0, 90, 9); + assert(isNaN(inv.azi1)); + assert(isNaN(inv.azi2)); + assert(isNaN(inv.s12)); + }); + + it("GeodSolve59", function() { + // Check for points close with longitudes close to 180 deg apart. + var geod = g.WGS84, + inv = geod.Inverse(5, 0.00000000000001, 10, 180); + assert.approx(inv.azi1, 0.000000000000035, 1.5e-14); + assert.approx(inv.azi2, 179.99999999999996, 1.5e-14); + assert.approx(inv.s12, 18345191.174332713, 4e-9); + }); + + it("GeodSolve61", function() { + // Make sure small negative azimuths are west-going + var geod = g.WGS84, + dir = geod.Direct(45, 0, -0.000000000000000003, 1e7, + g.LONG_UNROLL), + line; + assert.approx(dir.lat2, 45.30632, 0.5e-5); + assert.approx(dir.lon2, -180, 0.5e-5); + assert.approx(Math.abs(dir.azi2), 180, 0.5e-5); + line = geod.InverseLine(45, 0, 80, -0.000000000000000003); + dir = line.Position(1e7, g.LONG_UNROLL); + assert.approx(dir.lat2, 45.30632, 0.5e-5); + assert.approx(dir.lon2, -180, 0.5e-5); + assert.approx(Math.abs(dir.azi2), 180, 0.5e-5); + }); + + it("GeodSolve65", function() { + // Check for bug in east-going check in GeodesicLine (needed to check for + // sign of 0) and sign error in area calculation due to a bogus override + // of the code for alp12. Found/fixed on 2015-12-19. + var geod = g.WGS84, + line = geod.InverseLine(30, -0.000000000000000001, -31, 180, + g.ALL), + dir = line.Position(1e7, g.ALL | g.LONG_UNROLL); + assert.approx(dir.lat1, 30.00000 , 0.5e-5); + assert.approx(dir.lon1, -0.00000 , 0.5e-5); + assert.approx(Math.abs(dir.azi1), 180.00000, 0.5e-5); + assert.approx(dir.lat2, -60.23169 , 0.5e-5); + assert.approx(dir.lon2, -0.00000 , 0.5e-5); + assert.approx(Math.abs(dir.azi2), 180.00000, 0.5e-5); + assert.approx(dir.s12 , 10000000 , 0.5); + assert.approx(dir.a12 , 90.06544 , 0.5e-5); + assert.approx(dir.m12 , 6363636 , 0.5); + assert.approx(dir.M12 , -0.0012834, 0.5e7); + assert.approx(dir.M21 , 0.0013749 , 0.5e-7); + assert.approx(dir.S12 , 0 , 0.5); + dir = line.Position(2e7, g.ALL | g.LONG_UNROLL); + assert.approx(dir.lat1, 30.00000 , 0.5e-5); + assert.approx(dir.lon1, -0.00000 , 0.5e-5); + assert.approx(Math.abs(dir.azi1), 180.00000, 0.5e-5); + assert.approx(dir.lat2, -30.03547 , 0.5e-5); + assert.approx(dir.lon2, -180.00000, 0.5e-5); + assert.approx(dir.azi2, -0.00000 , 0.5e-5); + assert.approx(dir.s12 , 20000000 , 0.5); + assert.approx(dir.a12 , 179.96459 , 0.5e-5); + assert.approx(dir.m12 , 54342 , 0.5); + assert.approx(dir.M12 , -1.0045592, 0.5e7); + assert.approx(dir.M21 , -0.9954339, 0.5e-7); + assert.approx(dir.S12 , 127516405431022.0, 0.5); + }); + + it("GeodSolve69", function() { + // Check for InverseLine if line is slightly west of S and that s13 is + // correctly set. + var geod = g.WGS84, + line = geod.InverseLine(-5, -0.000000000000002, -10, 180), + dir = line.Position(2e7, g.LONG_UNROLL); + assert.approx(dir.lat2, 4.96445 , 0.5e-5); + assert.approx(dir.lon2, -180.00000, 0.5e-5); + assert.approx(dir.azi2, -0.00000 , 0.5e-5); + dir = line.Position(0.5 * line.s13, g.LONG_UNROLL); + assert.approx(dir.lat2, -87.52461 , 0.5e-5); + assert.approx(dir.lon2, -0.00000 , 0.5e-5); + assert.approx(dir.azi2, -180.00000, 0.5e-5); + }); + + it("GeodSolve71", function() { + // Check that DirectLine sets s13. + var geod = g.WGS84, + line = geod.DirectLine(1, 2, 45, 1e7), + dir = line.Position(0.5 * line.s13, g.LONG_UNROLL); + assert.approx(dir.lat2, 30.92625, 0.5e-5); + assert.approx(dir.lon2, 37.54640, 0.5e-5); + assert.approx(dir.azi2, 55.43104, 0.5e-5); + }); + + it("GeodSolve73", function() { + // Check for backwards from the pole bug reported by Anon on 2016-02-13. + // This only affected the Java implementation. It was introduced in Java + // version 1.44 and fixed in 1.46-SNAPSHOT on 2016-01-17. + var geod = g.WGS84, + dir = geod.Direct(90, 10, 180, -1e6); + assert.approx(dir.lat2, 81.04623, 0.5e-5); + assert.approx(dir.lon2, -170, 0.5e-5); + assert.approx(dir.azi2, 0, 0.5e-5); + }); + + it("GeodSolve74", function() { + // Check fix for inaccurate areas, bug introduced in v1.46, fixed + // 2015-10-16. + var geod = g.WGS84, + inv = geod.Inverse(54.1589, 15.3872, 54.1591, 15.3877, g.ALL); + assert.approx(inv.azi1, 55.723110355, 5e-9); + assert.approx(inv.azi2, 55.723515675, 5e-9); + assert.approx(inv.s12, 39.527686385, 5e-9); + assert.approx(inv.a12, 0.000355495, 5e-9); + assert.approx(inv.m12, 39.527686385, 5e-9); + assert.approx(inv.M12, 0.999999995, 5e-9); + assert.approx(inv.M21, 0.999999995, 5e-9); + assert.approx(inv.S12, 286698586.30197, 5e-4); + }); + + it("GeodSolve76", function() { + // The distance from Wellington and Salamanca (a classic failure of + // Vincenty) + var geod = g.WGS84, + inv = geod.Inverse(-(41+19/60.0), 174+49/60.0, + 40+58/60.0, -(5+30/60.0)); + assert.approx(inv.azi1, 160.39137649664, 0.5e-11); + assert.approx(inv.azi2, 19.50042925176, 0.5e-11); + assert.approx(inv.s12, 19960543.857179, 0.5e-6); + }); + + it("GeodSolve78", function() { + // An example where the NGS calculator fails to converge + var geod = g.WGS84, + inv = geod.Inverse(27.2, 0.0, -27.1, 179.5); + assert.approx(inv.azi1, 45.82468716758, 0.5e-11); + assert.approx(inv.azi2, 134.22776532670, 0.5e-11); + assert.approx(inv.s12, 19974354.765767, 0.5e-6); + }); + + }); + + describe("Planimeter", function () { + + var geod = g.WGS84, + polygon = geod.Polygon(false), + polyline = geod.Polygon(true), + Planimeter, PolyLength; + + Planimeter = function(points) { + var i; + polygon.Clear(); + for (i = 0; i < points.length; ++i) { + polygon.AddPoint(points[i][0], points[i][1]); + } + return polygon.Compute(false, true); + }; + + PolyLength = function(points) { + var i; + polyline.Clear(); + for (i = 0; i < points.length; ++i) { + polyline.AddPoint(points[i][0], points[i][1]); + } + return polyline.Compute(false, true); + }; + + it("Planimeter0", function() { + // Check fix for pole-encircling bug found 2011-03-16 + var points, a; + points = [[89, 0], [89, 90], [89, 180], [89, 270]]; + a = Planimeter(points); + assert.approx(a.perimeter, 631819.8745, 1e-4); + assert.approx(a.area, 24952305678.0, 1); + + points = [[-89, 0], [-89, 90], [-89, 180], [-89, 270]]; + a = Planimeter(points); + assert.approx(a.perimeter, 631819.8745, 1e-4); + assert.approx(a.area, -24952305678.0, 1); + + points = [[0, -1], [-1, 0], [0, 1], [1, 0]]; + a = Planimeter(points); + assert.approx(a.perimeter, 627598.2731, 1e-4); + assert.approx(a.area, 24619419146.0, 1); + + points = [[90, 0], [0, 0], [0, 90]]; + a = Planimeter(points); + assert.approx(a.perimeter, 30022685, 1); + assert.approx(a.area, 63758202715511.0, 1); + a = PolyLength(points); + assert.approx(a.perimeter, 20020719, 1); + assert(isNaN(a.area)); + }); + + it("Planimeter5", function() { + // Check fix for Planimeter pole crossing bug found 2011-06-24 + var points, a; + points = [[89, 0.1], [89, 90.1], [89, -179.9]]; + a = Planimeter(points); + assert.approx(a.perimeter, 539297, 1); + assert.approx(a.area, 12476152838.5, 1); + }); + + it("Planimeter6", function() { + // Check fix for Planimeter lon12 rounding bug found 2012-12-03 + var points, a; + points = [[9, -0.00000000000001], [9, 180], [9, 0]]; + a = Planimeter(points); + assert.approx(a.perimeter, 36026861, 1); + assert.approx(a.area, 0, 1); + points = [[9, 0.00000000000001], [9, 0], [9, 180]]; + a = Planimeter(points); + assert.approx(a.perimeter, 36026861, 1); + assert.approx(a.area, 0, 1); + points = [[9, 0.00000000000001], [9, 180], [9, 0]]; + a = Planimeter(points); + assert.approx(a.perimeter, 36026861, 1); + assert.approx(a.area, 0, 1); + points = [[9, -0.00000000000001], [9, 0], [9, 180]]; + a = Planimeter(points); + assert.approx(a.perimeter, 36026861, 1); + assert.approx(a.area, 0, 1); + }); + + it("Planimeter12", function() { + // Area of arctic circle (not really -- adjunct to rhumb-area test) + var points, a; + points = [[66.562222222, 0], [66.562222222, 180]]; + a = Planimeter(points); + assert.approx(a.perimeter, 10465729, 1); + assert.approx(a.area, 0, 1); + }); + + it("Planimeter13", function() { + // Check encircling pole twice + var points, a; + points = [[89,-360], [89,-240], [89,-120], [89,0], [89,120], [89,240]]; + a = Planimeter(points); + assert.approx(a.perimeter, 1160741, 1); + assert.approx(a.area, 32415230256.0, 1); + }); + + it("check TestEdge", function() { + // Check fix of bugs found by threepointone, 2015-10-14 + polygon.Clear(); + polygon.AddPoint(33, 44); + polygon.TestEdge(90, 10e3, false, true); + polygon.AddEdge(90, 10e3, false, true); + }); + + }); +}); diff --git a/gtsam/3rdparty/GeographicLib/legacy/C/00README.txt b/gtsam/3rdparty/GeographicLib/legacy/C/00README.txt index 45027219a..2d56bc3b1 100644 --- a/gtsam/3rdparty/GeographicLib/legacy/C/00README.txt +++ b/gtsam/3rdparty/GeographicLib/legacy/C/00README.txt @@ -3,12 +3,12 @@ This is a C implementation of the geodesic algorithms described in C. F. F. Karney, Algorithms for geodesics, J. Geodesy 87, 43-55 (2013); - http://dx.doi.org/10.1007/s00190-012-0578-z - Addenda: http://geographiclib.sf.net/geod-addenda.html + https://doi.org/10.1007/s00190-012-0578-z + Addenda: https://geographiclib.sourceforge.io/geod-addenda.html For documentation, see - http://geographiclib.sourceforge.net/html/C/ + https://geographiclib.sourceforge.io/html/C/ The code in this directory is entirely self-contained. In particular, it does not depend on the C++ classes. You can compile and link the diff --git a/gtsam/3rdparty/GeographicLib/legacy/C/CMakeLists.txt b/gtsam/3rdparty/GeographicLib/legacy/C/CMakeLists.txt index 3bdf38f1f..bbf5bca7d 100644 --- a/gtsam/3rdparty/GeographicLib/legacy/C/CMakeLists.txt +++ b/gtsam/3rdparty/GeographicLib/legacy/C/CMakeLists.txt @@ -1,6 +1,6 @@ -cmake_minimum_required (VERSION 2.6) +project (GeographicLib-C C) -project (GeographicLib-legacy-C C) +cmake_minimum_required (VERSION 2.8.4) # Set a default build type for single-configuration cmake generators if # no build type is set. @@ -9,17 +9,54 @@ if (NOT CMAKE_CONFIGURATION_TYPES AND NOT CMAKE_BUILD_TYPE) endif () # Make the compiler more picky. -if (WIN32) +if (MSVC) set (CMAKE_C_FLAGS "${CMAKE_C_FLAGS} /W4") else () - set (CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wall -Wextra -pedantic -ansi") + set (CMAKE_C_FLAGS + "${CMAKE_C_FLAGS} -Wall -Wextra -Wfloat-conversion -Wno-array-bounds -pedantic") endif () -set (TOOLS direct inverse planimeter) +include (CheckCSourceCompiles) +if (MSVC) + set (CMAKE_REQUIRED_FLAGS "${CMAKE_C_FLAGS} /WX") +else () + set (CMAKE_REQUIRED_LIBRARIES m) + set (CMAKE_REQUIRED_FLAGS "${CMAKE_C_FLAGS} -Werror") +endif () +# Check whether the C99 math function: hypot, atanh, etc. are available. +check_c_source_compiles ( + "#include +int main() { + int q; + return (int)(hypot(3.0, 4.0) + atanh(0.8) + cbrt(8.0) + + remquo(100.0, 90.0, &q) + + remainder(100.0, 90.0) + copysign(1.0, -0.0)); +}\n" C99_MATH) +if (C99_MATH) + add_definitions (-DHAVE_C99_MATH=1) +else () + add_definitions (-DHAVE_C99_MATH=0) +endif () + +if (CONVERT_WARNINGS_TO_ERRORS) + if (MSVC) + set (CMAKE_C_FLAGS "${CMAKE_C_FLAGS} /WX") + else () + set (CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Werror") + endif () +endif () + +set (TOOLS direct inverse planimeter geodtest) foreach (TOOL ${TOOLS}) add_executable (${TOOL} ${TOOL}.c geodesic.c geodesic.h) - if (NOT WIN32) + if (NOT MSVC) target_link_libraries (${TOOL} m) endif () endforeach () + +# Turn on testing +enable_testing () + +# Run the test suite +add_test (NAME geodtest COMMAND geodtest) diff --git a/gtsam/3rdparty/GeographicLib/legacy/C/direct.c b/gtsam/3rdparty/GeographicLib/legacy/C/direct.c index b8c113064..9df69e8f1 100644 --- a/gtsam/3rdparty/GeographicLib/legacy/C/direct.c +++ b/gtsam/3rdparty/GeographicLib/legacy/C/direct.c @@ -24,7 +24,7 @@ int main() { struct geod_geodesic g; geod_init(&g, a, f); - while (scanf("%lf %lf %lf %lf\n", &lat1, &lon1, &azi1, &s12) == 4) { + while (scanf("%lf %lf %lf %lf", &lat1, &lon1, &azi1, &s12) == 4) { geod_direct(&g, lat1, lon1, azi1, s12, &lat2, &lon2, &azi2); printf("%.15f %.15f %.15f\n", lat2, lon2, azi2); } diff --git a/gtsam/3rdparty/GeographicLib/legacy/C/geodesic.c b/gtsam/3rdparty/GeographicLib/legacy/C/geodesic.c index f46a6ff41..84951d7fa 100644 --- a/gtsam/3rdparty/GeographicLib/legacy/C/geodesic.c +++ b/gtsam/3rdparty/GeographicLib/legacy/C/geodesic.c @@ -13,22 +13,28 @@ * C. F. F. Karney, * Algorithms for geodesics, * J. Geodesy 87, 43--55 (2013); - * http://dx.doi.org/10.1007/s00190-012-0578-z - * Addenda: http://geographiclib.sf.net/geod-addenda.html + * https://doi.org/10.1007/s00190-012-0578-z + * Addenda: https://geographiclib.sourceforge.io/geod-addenda.html * * See the comments in geodesic.h for documentation. * - * Copyright (c) Charles Karney (2012-2013) and licensed + * Copyright (c) Charles Karney (2012-2017) and licensed * under the MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ */ #include "geodesic.h" #include +#if !defined(HAVE_C99_MATH) +#define HAVE_C99_MATH 0 +#endif + #define GEOGRAPHICLIB_GEODESIC_ORDER 6 +#define nA1 GEOGRAPHICLIB_GEODESIC_ORDER #define nC1 GEOGRAPHICLIB_GEODESIC_ORDER #define nC1p GEOGRAPHICLIB_GEODESIC_ORDER +#define nA2 GEOGRAPHICLIB_GEODESIC_ORDER #define nC2 GEOGRAPHICLIB_GEODESIC_ORDER #define nA3 GEOGRAPHICLIB_GEODESIC_ORDER #define nA3x nA3 @@ -36,6 +42,7 @@ #define nC3x ((nC3 * (nC3 - 1)) / 2) #define nC4 GEOGRAPHICLIB_GEODESIC_ORDER #define nC4x ((nC4 * (nC4 + 1)) / 2) +#define nC (GEOGRAPHICLIB_GEODESIC_ORDER + 1) typedef double real; typedef int boolx; @@ -82,7 +89,10 @@ static void Init() { tolb = tol0 * tol2; xthresh = 1000 * tol2; degree = pi/180; - NaN = sqrt(-1.0); + { + real minus1 = -1; + NaN = sqrt(minus1); + } init = 1; } } @@ -99,6 +109,12 @@ enum captype { }; static real sq(real x) { return x * x; } +#if HAVE_C99_MATH +#define atanhx atanh +#define copysignx copysign +#define hypotx hypot +#define cbrtx cbrt +#else static real log1px(real x) { volatile real y = 1 + x, @@ -116,6 +132,10 @@ static real atanhx(real x) { return x < 0 ? -y : y; } +static real copysignx(real x, real y) { + return fabs(x) * (y < 0 || (y == 0 && 1/y < 0) ? -1 : 1); +} + static real hypotx(real x, real y) { return sqrt(x * x + y * y); } @@ -123,6 +143,7 @@ static real cbrtx(real x) { real y = pow(fabs(x), 1/(real)(3)); /* Return the real cube root */ return x < 0 ? -y : y; } +#endif static real sumx(real u, real v, real* t) { volatile real s = u + v; @@ -130,50 +151,118 @@ static real sumx(real u, real v, real* t) { volatile real vpp = s - up; up -= u; vpp -= v; - *t = -(up + vpp); + if (t) *t = -(up + vpp); /* error-free sum: * u + v = s + t * = round(u + v) + t */ return s; } -static real minx(real x, real y) -{ return x < y ? x : y; } +static real polyval(int N, const real p[], real x) { + real y = N < 0 ? 0 : *p++; + while (--N >= 0) y = y * x + *p++; + return y; +} -static real maxx(real x, real y) -{ return x > y ? x : y; } +/* mimic C++ std::min and std::max */ +static real minx(real a, real b) +{ return (b < a) ? b : a; } + +static real maxx(real a, real b) +{ return (a < b) ? b : a; } static void swapx(real* x, real* y) { real t = *x; *x = *y; *y = t; } -static void SinCosNorm(real* sinx, real* cosx) { +static void norm2(real* sinx, real* cosx) { real r = hypotx(*sinx, *cosx); *sinx /= r; *cosx /= r; } -static real AngNormalize(real x) -{ return x >= 180 ? x - 360 : (x < -180 ? x + 360 : x); } -static real AngNormalize2(real x) -{ return AngNormalize(fmod(x, (real)(360))); } +static real AngNormalize(real x) { +#if HAVE_C99_MATH + x = remainder(x, (real)(360)); + return x != -180 ? x : 180; +#else + x = fmod(x, (real)(360)); + return x <= -180 ? x + 360 : (x <= 180 ? x : x - 360); +#endif +} -static real AngDiff(real x, real y) { - real t, d = sumx(-x, y, &t); - if ((d - (real)(180)) + t > (real)(0)) /* y - x > 180 */ - d -= (real)(360); /* exact */ - else if ((d + (real)(180)) + t <= (real)(0)) /* y - x <= -180 */ - d += (real)(360); /* exact */ - return d + t; +static real LatFix(real x) +{ return fabs(x) > 90 ? NaN : x; } + +static real AngDiff(real x, real y, real* e) { + real t, d = AngNormalize(sumx(AngNormalize(-x), AngNormalize(y), &t)); + /* Here y - x = d + t (mod 360), exactly, where d is in (-180,180] and + * abs(t) <= eps (eps = 2^-45 for doubles). The only case where the + * addition of t takes the result outside the range (-180,180] is d = 180 + * and t > 0. The case, d = -180 + eps, t = -eps, can't happen, since + * sum would have returned the exact result in such a case (i.e., given t + * = 0). */ + return sumx(d == 180 && t > 0 ? -180 : d, t, e); } static real AngRound(real x) { const real z = 1/(real)(16); - volatile real y = fabs(x); + volatile real y; + if (x == 0) return 0; + y = fabs(x); /* The compiler mustn't "simplify" z - (z - y) to y */ y = y < z ? z - (z - y) : y; return x < 0 ? -y : y; } +static void sincosdx(real x, real* sinx, real* cosx) { + /* In order to minimize round-off errors, this function exactly reduces + * the argument to the range [-45, 45] before converting it to radians. */ + real r, s, c; int q; +#if HAVE_C99_MATH && !defined(__GNUC__) + /* Disable for gcc because of bug in glibc version < 2.22, see + * https://sourceware.org/bugzilla/show_bug.cgi?id=17569 */ + r = remquo(x, (real)(90), &q); +#else + r = fmod(x, (real)(360)); + q = (int)(floor(r / 90 + (real)(0.5))); + r -= 90 * q; +#endif + /* now abs(r) <= 45 */ + r *= degree; + /* Possibly could call the gnu extension sincos */ + s = sin(r); c = cos(r); + switch ((unsigned)q & 3U) { + case 0U: *sinx = s; *cosx = c; break; + case 1U: *sinx = c; *cosx = -s; break; + case 2U: *sinx = -s; *cosx = -c; break; + default: *sinx = -c; *cosx = s; break; /* case 3U */ + } + if (x != 0) { *sinx += (real)(0); *cosx += (real)(0); } +} + +static real atan2dx(real y, real x) { + /* In order to minimize round-off errors, this function rearranges the + * arguments so that result of atan2 is in the range [-pi/4, pi/4] before + * converting it to degrees and mapping the result to the correct + * quadrant. */ + int q = 0; real ang; + if (fabs(y) > fabs(x)) { swapx(&x, &y); q = 2; } + if (x < 0) { x = -x; ++q; } + /* here x >= 0 and x >= abs(y), so angle is in [-pi/4, pi/4] */ + ang = atan2(y, x) / degree; + switch (q) { + /* Note that atan2d(-0.0, 1.0) will return -0. However, we expect that + * atan2d will not be called with y = -0. If need be, include + * + * case 0: ang = 0 + ang; break; + */ + case 1: ang = (y >= 0 ? 180 : -180) - ang; break; + case 2: ang = 90 - ang; break; + case 3: ang = -90 + ang; break; + } + return ang; +} + static void A3coeff(struct geod_geodesic* g); static void C3coeff(struct geod_geodesic* g); static void C4coeff(struct geod_geodesic* g); @@ -186,33 +275,35 @@ static void Lengths(const struct geod_geodesic* g, real ssig2, real csig2, real dn2, real cbet1, real cbet2, real* ps12b, real* pm12b, real* pm0, - boolx scalep, real* pM12, real* pM21, - /* Scratch areas of the right size */ - real C1a[], real C2a[]); + real* pM12, real* pM21, + /* Scratch area of the right size */ + real Ca[]); static real Astroid(real x, real y); static real InverseStart(const struct geod_geodesic* g, real sbet1, real cbet1, real dn1, real sbet2, real cbet2, real dn2, - real lam12, + real lam12, real slam12, real clam12, real* psalp1, real* pcalp1, /* Only updated if return val >= 0 */ real* psalp2, real* pcalp2, /* Only updated for short lines */ real* pdnm, - /* Scratch areas of the right size */ - real C1a[], real C2a[]); + /* Scratch area of the right size */ + real Ca[]); static real Lambda12(const struct geod_geodesic* g, real sbet1, real cbet1, real dn1, real sbet2, real cbet2, real dn2, real salp1, real calp1, + real slam120, real clam120, real* psalp2, real* pcalp2, real* psig12, real* pssig1, real* pcsig1, real* pssig2, real* pcsig2, - real* peps, real* pdomg12, + real* peps, + real* pgomg12, boolx diffp, real* pdlam12, - /* Scratch areas of the right size */ - real C1a[], real C2a[], real C3a[]); + /* Scratch area of the right size */ + real Ca[]); static real A3f(const struct geod_geodesic* g, real eps); static void C3f(const struct geod_geodesic* g, real eps, real c[]); static void C4f(const struct geod_geodesic* g, real eps, real c[]); @@ -222,6 +313,7 @@ static void C1pf(real eps, real c[]); static real A2m1f(real eps); static void C2f(real eps, real c[]); static int transit(real lon1, real lon2); +static int transitdirect(real lon1, real lon2); static void accini(real s[]); static void acccopy(const real s[], real t[]); static void accadd(real s[], real y); @@ -231,7 +323,7 @@ static void accneg(real s[]); void geod_init(struct geod_geodesic* g, real a, real f) { if (!init) Init(); g->a = a; - g->f = f <= 1 ? f : 1/f; + g->f = f; g->f1 = 1 - g->f; g->e2 = g->f * (2 - g->f); g->ep2 = g->e2 / sq(g->f1); /* e2 / (1 - e2) */ @@ -258,10 +350,12 @@ void geod_init(struct geod_geodesic* g, real a, real f) { C4coeff(g); } -void geod_lineinit(struct geod_geodesicline* l, - const struct geod_geodesic* g, - real lat1, real lon1, real azi1, unsigned caps) { - real alp1, cbet1, sbet1, phi, eps; +static void geod_lineinit_int(struct geod_geodesicline* l, + const struct geod_geodesic* g, + real lat1, real lon1, + real azi1, real salp1, real calp1, + unsigned caps) { + real cbet1, sbet1, eps; l->a = g->a; l->f = g->f; l->b = g->b; @@ -269,25 +363,18 @@ void geod_lineinit(struct geod_geodesicline* l, l->f1 = g->f1; /* If caps is 0 assume the standard direct calculation */ l->caps = (caps ? caps : GEOD_DISTANCE_IN | GEOD_LONGITUDE) | - GEOD_LATITUDE | GEOD_AZIMUTH; /* Always allow latitude and azimuth */ + /* always allow latitude and azimuth and unrolling of longitude */ + GEOD_LATITUDE | GEOD_AZIMUTH | GEOD_LONG_UNROLL; - /* Guard against underflow in salp0 */ - azi1 = AngRound(AngNormalize(azi1)); - lon1 = AngNormalize(lon1); - l->lat1 = lat1; + l->lat1 = LatFix(lat1); l->lon1 = lon1; l->azi1 = azi1; - /* alp1 is in [0, pi] */ - alp1 = azi1 * degree; - /* Enforce sin(pi) == 0 and cos(pi/2) == 0. Better to face the ensuing - * problems directly than to skirt them. */ - l->salp1 = azi1 == -180 ? 0 : sin(alp1); - l->calp1 = fabs(azi1) == 90 ? 0 : cos(alp1); - phi = lat1 * degree; + l->salp1 = salp1; + l->calp1 = calp1; + + sincosdx(AngRound(l->lat1), &sbet1, &cbet1); sbet1 *= l->f1; /* Ensure cbet1 = +epsilon at poles */ - sbet1 = l->f1 * sin(phi); - cbet1 = fabs(lat1) == 90 ? tiny : cos(phi); - SinCosNorm(&sbet1, &cbet1); + norm2(&sbet1, &cbet1); cbet1 = maxx(tiny, cbet1); l->dn1 = sqrt(1 + g->ep2 * sq(sbet1)); /* Evaluate alp0 from sin(alp1) * cos(bet1) = sin(alp0), */ @@ -306,8 +393,8 @@ void geod_lineinit(struct geod_geodesicline* l, * With alp0 = 0, omg1 = 0 for alp1 = 0, omg1 = pi for alp1 = pi. */ l->ssig1 = sbet1; l->somg1 = l->salp0 * sbet1; l->csig1 = l->comg1 = sbet1 != 0 || l->calp1 != 0 ? cbet1 * l->calp1 : 1; - SinCosNorm(&l->ssig1, &l->csig1); /* sig1 in (-pi, pi] */ - /* SinCosNorm(somg1, comg1); -- don't need to normalize! */ + norm2(&l->ssig1, &l->csig1); /* sig1 in (-pi, pi] */ + /* norm2(somg1, comg1); -- don't need to normalize! */ l->k2 = sq(l->calp0) * g->ep2; eps = l->k2 / (2 * (1 + sqrt(1 + l->k2)) + l->k2); @@ -346,10 +433,38 @@ void geod_lineinit(struct geod_geodesicline* l, l->A4 = sq(l->a) * l->calp0 * l->salp0 * g->e2; l->B41 = SinCosSeries(FALSE, l->ssig1, l->csig1, l->C4a, nC4); } + + l->a13 = l->s13 = NaN; +} + +void geod_lineinit(struct geod_geodesicline* l, + const struct geod_geodesic* g, + real lat1, real lon1, real azi1, unsigned caps) { + real salp1, calp1; + azi1 = AngNormalize(azi1); + /* Guard against underflow in salp0 */ + sincosdx(AngRound(azi1), &salp1, &calp1); + geod_lineinit_int(l, g, lat1, lon1, azi1, salp1, calp1, caps); +} + +void geod_gendirectline(struct geod_geodesicline* l, + const struct geod_geodesic* g, + real lat1, real lon1, real azi1, + unsigned flags, real a12_s12, + unsigned caps) { + geod_lineinit(l, g, lat1, lon1, azi1, caps); + geod_gensetdistance(l, flags, a12_s12); +} + +void geod_directline(struct geod_geodesicline* l, + const struct geod_geodesic* g, + real lat1, real lon1, real azi1, + real s12, unsigned caps) { + geod_gendirectline(l, g, lat1, lon1, azi1, GEOD_NOFLAGS, s12, caps); } real geod_genposition(const struct geod_geodesicline* l, - boolx arcmode, real s12_a12, + unsigned flags, real s12_a12, real* plat2, real* plon2, real* pazi2, real* ps12, real* pm12, real* pM12, real* pM21, @@ -371,18 +486,14 @@ real geod_genposition(const struct geod_geodesicline* l, outmask &= l->caps & OUT_ALL; if (!( TRUE /*Init()*/ && - (arcmode || (l->caps & GEOD_DISTANCE_IN & OUT_ALL)) )) + (flags & GEOD_ARCMODE || (l->caps & (GEOD_DISTANCE_IN & OUT_ALL))) )) /* Uninitialized or impossible distance calculation requested */ return NaN; - if (arcmode) { - real s12a; + if (flags & GEOD_ARCMODE) { /* Interpret s12_a12 as spherical arc length */ sig12 = s12_a12 * degree; - s12a = fabs(s12_a12); - s12a -= 180 * floor(s12a / 180); - ssig12 = s12a == 0 ? 0 : sin(sig12); - csig12 = s12a == 90 ? 0 : cos(sig12); + sincosdx(s12_a12, &ssig12, &csig12); } else { /* Interpret s12_a12 as distance */ real @@ -418,10 +529,9 @@ real geod_genposition(const struct geod_geodesicline* l, * 1/20 5376 146e3 10e3 * 1/10 829e3 22e6 1.5e6 * 1/5 157e6 3.8e9 280e6 */ - real - ssig2 = l->ssig1 * csig12 + l->csig1 * ssig12, - csig2 = l->csig1 * csig12 - l->ssig1 * ssig12, - serr; + real serr; + ssig2 = l->ssig1 * csig12 + l->csig1 * ssig12; + csig2 = l->csig1 * csig12 - l->ssig1 * ssig12; B12 = SinCosSeries(TRUE, ssig2, csig2, l->C1a, nC1); serr = (1 + l->A1m1) * (sig12 + (B12 - l->B11)) - s12_a12 / l->b; sig12 = sig12 - serr / sqrt(1 + l->k2 * sq(ssig2)); @@ -435,7 +545,7 @@ real geod_genposition(const struct geod_geodesicline* l, csig2 = l->csig1 * csig12 - l->ssig1 * ssig12; dn2 = sqrt(1 + l->k2 * sq(ssig2)); if (outmask & (GEOD_DISTANCE | GEOD_REDUCEDLENGTH | GEOD_GEODESICSCALE)) { - if (arcmode || fabs(l->f) > 0.01) + if (flags & GEOD_ARCMODE || fabs(l->f) > 0.01) B12 = SinCosSeries(TRUE, ssig2, csig2, l->C1a, nC1); AB1 = (1 + l->A1m1) * (B12 - l->B11); } @@ -446,34 +556,38 @@ real geod_genposition(const struct geod_geodesicline* l, if (cbet2 == 0) /* I.e., salp0 = 0, csig2 = 0. Break the degeneracy in this case */ cbet2 = csig2 = tiny; - /* tan(omg2) = sin(alp0) * tan(sig2) */ - somg2 = l->salp0 * ssig2; comg2 = csig2; /* No need to normalize */ /* tan(alp0) = cos(sig2)*tan(alp2) */ salp2 = l->salp0; calp2 = l->calp0 * csig2; /* No need to normalize */ - /* omg12 = omg2 - omg1 */ - omg12 = atan2(somg2 * l->comg1 - comg2 * l->somg1, - comg2 * l->comg1 + somg2 * l->somg1); if (outmask & GEOD_DISTANCE) - s12 = arcmode ? l->b * ((1 + l->A1m1) * sig12 + AB1) : s12_a12; + s12 = flags & GEOD_ARCMODE ? + l->b * ((1 + l->A1m1) * sig12 + AB1) : + s12_a12; if (outmask & GEOD_LONGITUDE) { + real E = copysignx(1, l->salp0); /* east or west going? */ + /* tan(omg2) = sin(alp0) * tan(sig2) */ + somg2 = l->salp0 * ssig2; comg2 = csig2; /* No need to normalize */ + /* omg12 = omg2 - omg1 */ + omg12 = flags & GEOD_LONG_UNROLL + ? E * (sig12 + - (atan2( ssig2, csig2) - atan2( l->ssig1, l->csig1)) + + (atan2(E * somg2, comg2) - atan2(E * l->somg1, l->comg1))) + : atan2(somg2 * l->comg1 - comg2 * l->somg1, + comg2 * l->comg1 + somg2 * l->somg1); lam12 = omg12 + l->A3c * ( sig12 + (SinCosSeries(TRUE, ssig2, csig2, l->C3a, nC3-1) - l->B31)); lon12 = lam12 / degree; - /* Use AngNormalize2 because longitude might have wrapped multiple - * times. */ - lon12 = AngNormalize2(lon12); - lon2 = AngNormalize(l->lon1 + lon12); + lon2 = flags & GEOD_LONG_UNROLL ? l->lon1 + lon12 : + AngNormalize(AngNormalize(l->lon1) + AngNormalize(lon12)); } if (outmask & GEOD_LATITUDE) - lat2 = atan2(sbet2, l->f1 * cbet2) / degree; + lat2 = atan2dx(sbet2, l->f1 * cbet2); if (outmask & GEOD_AZIMUTH) - /* minus signs give range [-180, 180). 0- converts -0 to +0. */ - azi2 = 0 - atan2(-salp2, calp2) / degree; + azi2 = atan2dx(salp2, calp2); if (outmask & (GEOD_REDUCEDLENGTH | GEOD_GEODESICSCALE)) { real @@ -486,7 +600,8 @@ real geod_genposition(const struct geod_geodesicline* l, m12 = l->b * ((dn2 * (l->csig1 * ssig2) - l->dn1 * (l->ssig1 * csig2)) - l->csig1 * csig2 * J12); if (outmask & GEOD_GEODESICSCALE) { - real t = l->k2 * (ssig2 - l->ssig1) * (ssig2 + l->ssig1) / (l->dn1 + dn2); + real t = l->k2 * (ssig2 - l->ssig1) * (ssig2 + l->ssig1) / + (l->dn1 + dn2); M12 = csig12 + (t * ssig2 - csig2 * J12) * l->ssig1 / l->dn1; M21 = csig12 - (t * l->ssig1 - l->csig1 * J12) * ssig2 / dn2; } @@ -497,17 +612,9 @@ real geod_genposition(const struct geod_geodesicline* l, B42 = SinCosSeries(FALSE, ssig2, csig2, l->C4a, nC4); real salp12, calp12; if (l->calp0 == 0 || l->salp0 == 0) { - /* alp12 = alp2 - alp1, used in atan2 so no need to normalized */ + /* alp12 = alp2 - alp1, used in atan2 so no need to normalize */ salp12 = salp2 * l->calp1 - calp2 * l->salp1; calp12 = calp2 * l->calp1 + salp2 * l->salp1; - /* The right thing appears to happen if alp1 = +/-180 and alp2 = 0, viz - * salp12 = -0 and alp12 = -180. However this depends on the sign being - * attached to 0 correctly. The following ensures the correct - * behavior. */ - if (salp12 == 0 && calp12 < 0) { - salp12 = tiny * l->calp1; - calp12 = -1; - } } else { /* tan(alp) = tan(alp0) * sec(sig) * tan(alp2-alp1) = (tan(alp2) -tan(alp1)) / (tan(alp2)*tan(alp1)+1) @@ -542,7 +649,24 @@ real geod_genposition(const struct geod_geodesicline* l, if (outmask & GEOD_AREA) *pS12 = S12; - return arcmode ? s12_a12 : sig12 / degree; + return flags & GEOD_ARCMODE ? s12_a12 : sig12 / degree; +} + +void geod_setdistance(struct geod_geodesicline* l, real s13) { + l->s13 = s13; + l->a13 = geod_genposition(l, GEOD_NOFLAGS, l->s13, 0, 0, 0, 0, 0, 0, 0, 0); +} + +static void geod_setarc(struct geod_geodesicline* l, real a13) { + l->a13 = a13; l->s13 = NaN; + geod_genposition(l, GEOD_ARCMODE, l->a13, 0, 0, 0, &l->s13, 0, 0, 0, 0); +} + +void geod_gensetdistance(struct geod_geodesicline* l, + unsigned flags, real s13_a13) { + flags & GEOD_ARCMODE ? + geod_setarc(l, s13_a13) : + geod_setdistance(l, s13_a13); } void geod_position(const struct geod_geodesicline* l, real s12, @@ -552,7 +676,7 @@ void geod_position(const struct geod_geodesicline* l, real s12, real geod_gendirect(const struct geod_geodesic* g, real lat1, real lon1, real azi1, - boolx arcmode, real s12_a12, + unsigned flags, real s12_a12, real* plat2, real* plon2, real* pazi2, real* ps12, real* pm12, real* pM12, real* pM21, real* pS12) { @@ -568,8 +692,9 @@ real geod_gendirect(const struct geod_geodesic* g, geod_lineinit(&l, g, lat1, lon1, azi1, /* Automatically supply GEOD_DISTANCE_IN if necessary */ - outmask | (arcmode ? GEOD_NONE : GEOD_DISTANCE_IN)); - return geod_genposition(&l, arcmode, s12_a12, + outmask | + (flags & GEOD_ARCMODE ? GEOD_NONE : GEOD_DISTANCE_IN)); + return geod_genposition(&l, flags, s12_a12, plat2, plon2, pazi2, ps12, pm12, pM12, pM21, pS12); } @@ -577,28 +702,30 @@ void geod_direct(const struct geod_geodesic* g, real lat1, real lon1, real azi1, real s12, real* plat2, real* plon2, real* pazi2) { - geod_gendirect(g, lat1, lon1, azi1, FALSE, s12, plat2, plon2, pazi2, + geod_gendirect(g, lat1, lon1, azi1, GEOD_NOFLAGS, s12, plat2, plon2, pazi2, 0, 0, 0, 0, 0); } -real geod_geninverse(const struct geod_geodesic* g, - real lat1, real lon1, real lat2, real lon2, - real* ps12, real* pazi1, real* pazi2, - real* pm12, real* pM12, real* pM21, real* pS12) { - real s12 = 0, azi1 = 0, azi2 = 0, m12 = 0, M12 = 0, M21 = 0, S12 = 0; - real lon12; +static real geod_geninverse_int(const struct geod_geodesic* g, + real lat1, real lon1, real lat2, real lon2, + real* ps12, + real* psalp1, real* pcalp1, + real* psalp2, real* pcalp2, + real* pm12, real* pM12, real* pM21, + real* pS12) { + real s12 = 0, m12 = 0, M12 = 0, M21 = 0, S12 = 0; + real lon12, lon12s; int latsign, lonsign, swapp; - real phi, sbet1, cbet1, sbet2, cbet2, s12x = 0, m12x = 0; + real sbet1, cbet1, sbet2, cbet2, s12x = 0, m12x = 0; real dn1, dn2, lam12, slam12, clam12; real a12 = 0, sig12, calp1 = 0, salp1 = 0, calp2 = 0, salp2 = 0; - /* index zero elements of these arrays are unused */ - real C1a[nC1 + 1], C2a[nC2 + 1], C3a[nC3]; + real Ca[nC]; boolx meridian; - real omg12 = 0; + /* somg12 > 1 marks that it needs to be calculated */ + real omg12 = 0, somg12 = 2, comg12 = 0; unsigned outmask = (ps12 ? GEOD_DISTANCE : 0U) | - (pazi1 || pazi2 ? GEOD_AZIMUTH : 0U) | (pm12 ? GEOD_REDUCEDLENGTH : 0U) | (pM12 || pM21 ? GEOD_GEODESICSCALE : 0U) | (pS12 ? GEOD_AREA : 0U); @@ -607,17 +734,25 @@ real geod_geninverse(const struct geod_geodesic* g, /* Compute longitude difference (AngDiff does this carefully). Result is * in [-180, 180] but -180 is only for west-going geodesics. 180 is for * east-going and meridional geodesics. */ - lon12 = AngDiff(AngNormalize(lon1), AngNormalize(lon2)); - /* If very close to being on the same half-meridian, then make it so. */ - lon12 = AngRound(lon12); + lon12 = AngDiff(lon1, lon2, &lon12s); /* Make longitude difference positive. */ lonsign = lon12 >= 0 ? 1 : -1; - lon12 *= lonsign; + /* If very close to being on the same half-meridian, then make it so. */ + lon12 = lonsign * AngRound(lon12); + lon12s = AngRound((180 - lon12) - lonsign * lon12s); + lam12 = lon12 * degree; + if (lon12 > 90) { + sincosdx(lon12s, &slam12, &clam12); + clam12 = -clam12; + } else + sincosdx(lon12, &slam12, &clam12); + /* If really close to the equator, treat as on equator. */ - lat1 = AngRound(lat1); - lat2 = AngRound(lat2); - /* Swap points so that point with higher (abs) latitude is point 1 */ - swapp = fabs(lat1) >= fabs(lat2) ? 1 : -1; + lat1 = AngRound(LatFix(lat1)); + lat2 = AngRound(LatFix(lat2)); + /* Swap points so that point with higher (abs) latitude is point 1 + * If one latitude is a nan, then it becomes lat1. */ + swapp = fabs(lat1) < fabs(lat2) ? -1 : 1; if (swapp < 0) { lonsign *= -1; swapx(&lat1, &lat2); @@ -638,17 +773,13 @@ real geod_geninverse(const struct geod_geodesic* g, * check, e.g., on verifying quadrants in atan2. In addition, this * enforces some symmetries in the results returned. */ - phi = lat1 * degree; + sincosdx(lat1, &sbet1, &cbet1); sbet1 *= g->f1; /* Ensure cbet1 = +epsilon at poles */ - sbet1 = g->f1 * sin(phi); - cbet1 = lat1 == -90 ? tiny : cos(phi); - SinCosNorm(&sbet1, &cbet1); + norm2(&sbet1, &cbet1); cbet1 = maxx(tiny, cbet1); - phi = lat2 * degree; + sincosdx(lat2, &sbet2, &cbet2); sbet2 *= g->f1; /* Ensure cbet2 = +epsilon at poles */ - sbet2 = g->f1 * sin(phi); - cbet2 = fabs(lat2) == 90 ? tiny : cos(phi); - SinCosNorm(&sbet2, &cbet2); + norm2(&sbet2, &cbet2); cbet2 = maxx(tiny, cbet2); /* If cbet1 < -sbet1, then cbet2 - cbet1 is a sensitive measure of the * |bet1| - |bet2|. Alternatively (cbet1 >= -sbet1), abs(sbet2) + sbet1 is @@ -669,10 +800,6 @@ real geod_geninverse(const struct geod_geodesic* g, dn1 = sqrt(1 + g->ep2 * sq(sbet1)); dn2 = sqrt(1 + g->ep2 * sq(sbet2)); - lam12 = lon12 * degree; - slam12 = lon12 == 180 ? 0 : sin(lam12); - clam12 = cos(lam12); /* lon12 == 90 isn't interesting */ - meridian = lat1 == -90 || slam12 == 0; if (meridian) { @@ -689,14 +816,13 @@ real geod_geninverse(const struct geod_geodesic* g, ssig2 = sbet2; csig2 = calp2 * cbet2; /* sig12 = sig2 - sig1 */ - sig12 = atan2(maxx(csig1 * ssig2 - ssig1 * csig2, (real)(0)), - csig1 * csig2 + ssig1 * ssig2); - { - real dummy; - Lengths(g, g->n, sig12, ssig1, csig1, dn1, ssig2, csig2, dn2, - cbet1, cbet2, &s12x, &m12x, &dummy, - (outmask & GEOD_GEODESICSCALE) != 0U, &M12, &M21, C1a, C2a); - } + sig12 = atan2(maxx((real)(0), csig1 * ssig2 - ssig1 * csig2), + csig1 * csig2 + ssig1 * ssig2); + Lengths(g, g->n, sig12, ssig1, csig1, dn1, ssig2, csig2, dn2, + cbet1, cbet2, &s12x, &m12x, 0, + outmask & GEOD_GEODESICSCALE ? &M12 : 0, + outmask & GEOD_GEODESICSCALE ? &M21 : 0, + Ca); /* Add the check for sig12 since zero length geodesics might yield m12 < * 0. Test case was * @@ -705,6 +831,9 @@ real geod_geninverse(const struct geod_geodesic* g, * In fact, we will have sig12 > pi/2 for meridional geodesic which is * not a shortest path. */ if (sig12 < 1 || m12x >= 0) { + /* Need at least 2, to handle 90 0 90 180 */ + if (sig12 < 3 * tiny) + sig12 = m12x = s12x = 0; m12x *= g->b; s12x *= g->b; a12 = sig12 / degree; @@ -716,7 +845,7 @@ real geod_geninverse(const struct geod_geodesic* g, if (!meridian && sbet1 == 0 && /* and sbet2 == 0 */ /* Mimic the way Lambda12 works with calp1 = 0 */ - (g->f <= 0 || lam12 <= pi - g->f * pi)) { + (g->f <= 0 || lon12s >= g->f * 180)) { /* Geodesic runs along equator */ calp1 = calp2 = 0; salp1 = salp2 = 1; @@ -735,9 +864,9 @@ real geod_geninverse(const struct geod_geodesic* g, /* Figure a starting point for Newton's method */ real dnm = 0; sig12 = InverseStart(g, sbet1, cbet1, dn1, sbet2, cbet2, dn2, - lam12, + lam12, slam12, clam12, &salp1, &calp1, &salp2, &calp2, &dnm, - C1a, C2a); + Ca); if (sig12 >= 0) { /* Short lines (InverseStart sets salp2, calp2, dnm) */ @@ -760,7 +889,7 @@ real geod_geninverse(const struct geod_geodesic* g, * value of alp1 is then further from the solution) or if the new * estimate of alp1 lies outside (0,pi); in this case, the new starting * guess is taken to be (alp1a + alp1b) / 2. */ - real ssig1 = 0, csig1 = 0, ssig2 = 0, csig2 = 0, eps = 0; + real ssig1 = 0, csig1 = 0, ssig2 = 0, csig2 = 0, eps = 0, domg12 = 0; unsigned numit = 0; /* Bracketing range */ real salp1a = tiny, calp1a = 1, salp1b = tiny, calp1b = -1; @@ -768,14 +897,14 @@ real geod_geninverse(const struct geod_geodesic* g, for (tripn = FALSE, tripb = FALSE; numit < maxit2; ++numit) { /* the WGS84 test set: mean = 1.47, sd = 1.25, max = 16 * WGS84 and random input: mean = 2.85, sd = 0.60 */ - real dv, - v = (Lambda12(g, sbet1, cbet1, dn1, sbet2, cbet2, dn2, salp1, calp1, + real dv = 0, + v = Lambda12(g, sbet1, cbet1, dn1, sbet2, cbet2, dn2, salp1, calp1, + slam12, clam12, &salp2, &calp2, &sig12, &ssig1, &csig1, &ssig2, &csig2, - &eps, &omg12, numit < maxit1, &dv, C1a, C2a, C3a) - - lam12); + &eps, &domg12, numit < maxit1, &dv, Ca); /* 2 * tol0 is approximately 1 ulp for a number in [0, pi]. */ /* Reversed test to allow escape with NaNs */ - if (tripb || !(fabs(v) >= (tripn ? 8 : 2) * tol0)) break; + if (tripb || !(fabs(v) >= (tripn ? 8 : 1) * tol0)) break; /* Update bracketing values */ if (v > 0 && (numit > maxit1 || calp1/salp1 > calp1b/salp1b)) { salp1b = salp1; calp1b = calp1; } @@ -790,7 +919,7 @@ real geod_geninverse(const struct geod_geodesic* g, if (nsalp1 > 0 && fabs(dalp1) < pi) { calp1 = calp1 * cdalp1 - salp1 * sdalp1; salp1 = nsalp1; - SinCosNorm(&salp1, &calp1); + norm2(&salp1, &calp1); /* In some regimes we don't get quadratic convergence because * slope -> 0. So use convergence conditions based on epsilon * instead of sqrt(epsilon). */ @@ -798,7 +927,7 @@ real geod_geninverse(const struct geod_geodesic* g, continue; } } - /* Either dv was not postive or updated value was outside legal + /* Either dv was not positive or updated value was outside legal * range. Use the midpoint of the bracket as the next estimate. * This mechanism is not needed for the WGS84 ellipsoid, but it does * catch problems with more eccentric ellipsoids. Its efficacy is @@ -808,21 +937,24 @@ real geod_geninverse(const struct geod_geodesic* g, * WGS84 and random input: mean = 4.74, sd = 0.99 */ salp1 = (salp1a + salp1b)/2; calp1 = (calp1a + calp1b)/2; - SinCosNorm(&salp1, &calp1); + norm2(&salp1, &calp1); tripn = FALSE; tripb = (fabs(salp1a - salp1) + (calp1a - calp1) < tolb || fabs(salp1 - salp1b) + (calp1 - calp1b) < tolb); } - { - real dummy; - Lengths(g, eps, sig12, ssig1, csig1, dn1, ssig2, csig2, dn2, - cbet1, cbet2, &s12x, &m12x, &dummy, - (outmask & GEOD_GEODESICSCALE) != 0U, &M12, &M21, C1a, C2a); - } + Lengths(g, eps, sig12, ssig1, csig1, dn1, ssig2, csig2, dn2, + cbet1, cbet2, &s12x, &m12x, 0, + outmask & GEOD_GEODESICSCALE ? &M12 : 0, + outmask & GEOD_GEODESICSCALE ? &M21 : 0, Ca); m12x *= g->b; s12x *= g->b; a12 = sig12 / degree; - omg12 = lam12 - omg12; + if (outmask & GEOD_AREA) { + /* omg12 = lam12 - domg12 */ + real sdomg12 = sin(domg12), cdomg12 = cos(domg12); + somg12 = slam12 * cdomg12 - clam12 * sdomg12; + comg12 = clam12 * cdomg12 + slam12 * sdomg12; + } } } @@ -847,27 +979,30 @@ real geod_geninverse(const struct geod_geodesic* g, eps = k2 / (2 * (1 + sqrt(1 + k2)) + k2), /* Multiplier = a^2 * e^2 * cos(alpha0) * sin(alpha0). */ A4 = sq(g->a) * calp0 * salp0 * g->e2; - real C4a[nC4]; real B41, B42; - SinCosNorm(&ssig1, &csig1); - SinCosNorm(&ssig2, &csig2); - C4f(g, eps, C4a); - B41 = SinCosSeries(FALSE, ssig1, csig1, C4a, nC4); - B42 = SinCosSeries(FALSE, ssig2, csig2, C4a, nC4); + norm2(&ssig1, &csig1); + norm2(&ssig2, &csig2); + C4f(g, eps, Ca); + B41 = SinCosSeries(FALSE, ssig1, csig1, Ca, nC4); + B42 = SinCosSeries(FALSE, ssig2, csig2, Ca, nC4); S12 = A4 * (B42 - B41); } else /* Avoid problems with indeterminate sig1, sig2 on equator */ S12 = 0; + if (!meridian && somg12 > 1) { + somg12 = sin(omg12); comg12 = cos(omg12); + } + if (!meridian && - omg12 < (real)(0.75) * pi && /* Long difference too big */ - sbet2 - sbet1 < (real)(1.75)) { /* Lat difference too big */ + /* omg12 < 3/4 * pi */ + comg12 > -(real)(0.7071) && /* Long difference not too big */ + sbet2 - sbet1 < (real)(1.75)) { /* Lat difference not too big */ /* Use tan(Gamma/2) = tan(omg12/2) * * (tan(bet1/2)+tan(bet2/2))/(1+tan(bet1/2)*tan(bet2/2)) * with tan(x/2) = sin(x)/(1+cos(x)) */ real - somg12 = sin(omg12), domg12 = 1 + cos(omg12), - dbet1 = 1 + cbet1, dbet2 = 1 + cbet2; + domg12 = 1 + comg12, dbet1 = 1 + cbet1, dbet2 = 1 + cbet2; alp12 = 2 * atan2( somg12 * ( sbet1 * dbet2 + sbet2 * dbet1 ), domg12 * ( sbet1 * sbet2 + dbet1 * dbet2 ) ); } else { @@ -902,18 +1037,13 @@ real geod_geninverse(const struct geod_geodesic* g, salp1 *= swapp * lonsign; calp1 *= swapp * latsign; salp2 *= swapp * lonsign; calp2 *= swapp * latsign; - if (outmask & GEOD_AZIMUTH) { - /* minus signs give range [-180, 180). 0- converts -0 to +0. */ - azi1 = 0 - atan2(-salp1, calp1) / degree; - azi2 = 0 - atan2(-salp2, calp2) / degree; - } + if (psalp1) *psalp1 = salp1; + if (pcalp1) *pcalp1 = calp1; + if (psalp2) *psalp2 = salp2; + if (pcalp2) *pcalp2 = calp2; if (outmask & GEOD_DISTANCE) *ps12 = s12; - if (outmask & GEOD_AZIMUTH) { - if (pazi1) *pazi1 = azi1; - if (pazi2) *pazi2 = azi2; - } if (outmask & GEOD_REDUCEDLENGTH) *pm12 = m12; if (outmask & GEOD_GEODESICSCALE) { @@ -927,6 +1057,35 @@ real geod_geninverse(const struct geod_geodesic* g, return a12; } +real geod_geninverse(const struct geod_geodesic* g, + real lat1, real lon1, real lat2, real lon2, + real* ps12, real* pazi1, real* pazi2, + real* pm12, real* pM12, real* pM21, real* pS12) { + real salp1, calp1, salp2, calp2, + a12 = geod_geninverse_int(g, lat1, lon1, lat2, lon2, ps12, + &salp1, &calp1, &salp2, &calp2, + pm12, pM12, pM21, pS12); + if (pazi1) *pazi1 = atan2dx(salp1, calp1); + if (pazi2) *pazi2 = atan2dx(salp2, calp2); + return a12; +} + +void geod_inverseline(struct geod_geodesicline* l, + const struct geod_geodesic* g, + real lat1, real lon1, real lat2, real lon2, + unsigned caps) { + real salp1, calp1, + a12 = geod_geninverse_int(g, lat1, lon1, lat2, lon2, 0, + &salp1, &calp1, 0, 0, + 0, 0, 0, 0), + azi1 = atan2dx(salp1, calp1); + caps = caps ? caps : GEOD_DISTANCE_IN | GEOD_LONGITUDE; + /* Ensure that a12 can be converted to a distance */ + if (caps & (OUT_ALL & GEOD_DISTANCE_IN)) caps |= GEOD_DISTANCE; + geod_lineinit_int(l, g, lat1, lon1, azi1, salp1, calp1, caps); + geod_setarc(l, a12); +} + void geod_inverse(const struct geod_geodesic* g, real lat1, real lon1, real lat2, real lon2, real* ps12, real* pazi1, real* pazi2) { @@ -961,42 +1120,58 @@ void Lengths(const struct geod_geodesic* g, real ssig2, real csig2, real dn2, real cbet1, real cbet2, real* ps12b, real* pm12b, real* pm0, - boolx scalep, real* pM12, real* pM21, - /* Scratch areas of the right size */ - real C1a[], real C2a[]) { - real s12b = 0, m12b = 0, m0 = 0, M12 = 0, M21 = 0; - real A1m1, AB1, A2m1, AB2, J12; + real* pM12, real* pM21, + /* Scratch area of the right size */ + real Ca[]) { + real m0 = 0, J12 = 0, A1 = 0, A2 = 0; + real Cb[nC]; /* Return m12b = (reduced length)/b; also calculate s12b = distance/b, * and m0 = coefficient of secular term in expression for reduced length. */ - C1f(eps, C1a); - C2f(eps, C2a); - A1m1 = A1m1f(eps); - AB1 = (1 + A1m1) * (SinCosSeries(TRUE, ssig2, csig2, C1a, nC1) - - SinCosSeries(TRUE, ssig1, csig1, C1a, nC1)); - A2m1 = A2m1f(eps); - AB2 = (1 + A2m1) * (SinCosSeries(TRUE, ssig2, csig2, C2a, nC2) - - SinCosSeries(TRUE, ssig1, csig1, C2a, nC2)); - m0 = A1m1 - A2m1; - J12 = m0 * sig12 + (AB1 - AB2); - /* Missing a factor of b. - * Add parens around (csig1 * ssig2) and (ssig1 * csig2) to ensure accurate - * cancellation in the case of coincident points. */ - m12b = dn2 * (csig1 * ssig2) - dn1 * (ssig1 * csig2) - csig1 * csig2 * J12; - /* Missing a factor of b */ - s12b = (1 + A1m1) * sig12 + AB1; - if (scalep) { + boolx redlp = pm12b || pm0 || pM12 || pM21; + if (ps12b || redlp) { + A1 = A1m1f(eps); + C1f(eps, Ca); + if (redlp) { + A2 = A2m1f(eps); + C2f(eps, Cb); + m0 = A1 - A2; + A2 = 1 + A2; + } + A1 = 1 + A1; + } + if (ps12b) { + real B1 = SinCosSeries(TRUE, ssig2, csig2, Ca, nC1) - + SinCosSeries(TRUE, ssig1, csig1, Ca, nC1); + /* Missing a factor of b */ + *ps12b = A1 * (sig12 + B1); + if (redlp) { + real B2 = SinCosSeries(TRUE, ssig2, csig2, Cb, nC2) - + SinCosSeries(TRUE, ssig1, csig1, Cb, nC2); + J12 = m0 * sig12 + (A1 * B1 - A2 * B2); + } + } else if (redlp) { + /* Assume here that nC1 >= nC2 */ + int l; + for (l = 1; l <= nC2; ++l) + Cb[l] = A1 * Ca[l] - A2 * Cb[l]; + J12 = m0 * sig12 + (SinCosSeries(TRUE, ssig2, csig2, Cb, nC2) - + SinCosSeries(TRUE, ssig1, csig1, Cb, nC2)); + } + if (pm0) *pm0 = m0; + if (pm12b) + /* Missing a factor of b. + * Add parens around (csig1 * ssig2) and (ssig1 * csig2) to ensure + * accurate cancellation in the case of coincident points. */ + *pm12b = dn2 * (csig1 * ssig2) - dn1 * (ssig1 * csig2) - + csig1 * csig2 * J12; + if (pM12 || pM21) { real csig12 = csig1 * csig2 + ssig1 * ssig2; real t = g->ep2 * (cbet1 - cbet2) * (cbet1 + cbet2) / (dn1 + dn2); - M12 = csig12 + (t * ssig2 - csig2 * J12) * ssig1 / dn1; - M21 = csig12 - (t * ssig1 - csig1 * J12) * ssig2 / dn2; - } - *ps12b = s12b; - *pm12b = m12b; - *pm0 = m0; - if (scalep) { - *pM12 = M12; - *pM21 = M21; + if (pM12) + *pM12 = csig12 + (t * ssig2 - csig2 * J12) * ssig1 / dn1; + if (pM21) + *pM21 = csig12 - (t * ssig1 - csig1 * J12) * ssig2 / dn2; } } @@ -1015,7 +1190,7 @@ real Astroid(real x, real y) { S = p * q / 4, /* S = r^3 * s */ r2 = sq(r), r3 = r * r2, - /* The discrimant of the quadratic equation for T3. This is zero on + /* The discriminant of the quadratic equation for T3. This is zero on * the evolute curve p^(1/3)+q^(1/3) = 1 */ disc = S * (S + 2 * r3); real u = r; @@ -1055,14 +1230,14 @@ real Astroid(real x, real y) { real InverseStart(const struct geod_geodesic* g, real sbet1, real cbet1, real dn1, real sbet2, real cbet2, real dn2, - real lam12, + real lam12, real slam12, real clam12, real* psalp1, real* pcalp1, /* Only updated if return val >= 0 */ real* psalp2, real* pcalp2, /* Only updated for short lines */ real* pdnm, - /* Scratch areas of the right size */ - real C1a[], real C2a[]) { + /* Scratch area of the right size */ + real Ca[]) { real salp1 = 0, calp1 = 0, salp2 = 0, calp2 = 0, dnm = 0; /* Return a starting point for Newton's method in salp1 and calp1 (function @@ -1073,6 +1248,10 @@ real InverseStart(const struct geod_geodesic* g, /* bet12 = bet2 - bet1 in [0, pi); bet12a = bet2 + bet1 in (-pi, 0] */ sbet12 = sbet2 * cbet1 - cbet2 * sbet1, cbet12 = cbet2 * cbet1 + sbet2 * sbet1; + real sbet12a; + boolx shortline = cbet12 >= 0 && sbet12 < (real)(0.5) && + cbet2 * lam12 < (real)(0.5); + real somg12, comg12, ssig12, csig12; #if defined(__GNUC__) && __GNUC__ == 4 && \ (__GNUC_MINOR__ < 6 || defined(__MINGW32__)) /* Volatile declaration needed to fix inverse cases @@ -1081,27 +1260,25 @@ real InverseStart(const struct geod_geodesic* g, * 89.333123580033 0 -89.333123580032997687 179.99295812360148422 * which otherwise fail with g++ 4.4.4 x86 -O3 (Linux) * and g++ 4.4.0 (mingw) and g++ 4.6.1 (tdm mingw). */ - real sbet12a; { volatile real xx1 = sbet2 * cbet1; volatile real xx2 = cbet2 * sbet1; sbet12a = xx1 + xx2; } #else - real sbet12a = sbet2 * cbet1 + cbet2 * sbet1; + sbet12a = sbet2 * cbet1 + cbet2 * sbet1; #endif - boolx shortline = cbet12 >= 0 && sbet12 < (real)(0.5) && - cbet2 * lam12 < (real)(0.5); - real omg12 = lam12, somg12, comg12, ssig12, csig12; if (shortline) { - real sbetm2 = sq(sbet1 + sbet2); + real sbetm2 = sq(sbet1 + sbet2), omg12; /* sin((bet1+bet2)/2)^2 * = (sbet1 + sbet2)^2 / ((sbet1 + sbet2)^2 + (cbet1 + cbet2)^2) */ sbetm2 /= sbetm2 + sq(cbet1 + cbet2); dnm = sqrt(1 + g->ep2 * sbetm2); - omg12 /= g->f1 * dnm; + omg12 = lam12 / (g->f1 * dnm); + somg12 = sin(omg12); comg12 = cos(omg12); + } else { + somg12 = slam12; comg12 = clam12; } - somg12 = sin(omg12); comg12 = cos(omg12); salp1 = cbet2 * somg12; calp1 = comg12 >= 0 ? @@ -1116,7 +1293,7 @@ real InverseStart(const struct geod_geodesic* g, salp2 = cbet1 * somg12; calp2 = sbet12 - cbet1 * sbet2 * (comg12 >= 0 ? sq(somg12) / (1 + comg12) : 1 - comg12); - SinCosNorm(&salp2, &calp2); + norm2(&salp2, &calp2); /* Set return value */ sig12 = atan2(ssig12, csig12); } else if (fabs(g->n) > (real)(0.1) || /* No astroid calc if too eccentric */ @@ -1131,6 +1308,7 @@ real InverseStart(const struct geod_geodesic* g, * 56.320923501171 0 -56.320923501171 179.664747671772880215 * which otherwise fails with g++ 4.4.4 x86 -O3 */ volatile real x; + real lam12x = atan2(-slam12, -clam12); /* lam12 - pi */ if (g->f >= 0) { /* In fact f == 0 does not get here */ /* x = dlong, y = dlat */ { @@ -1141,25 +1319,24 @@ real InverseStart(const struct geod_geodesic* g, } betscale = lamscale * cbet1; - x = (lam12 - pi) / lamscale; + x = lam12x / lamscale; y = sbet12a / betscale; } else { /* f < 0 */ /* x = dlat, y = dlong */ real cbet12a = cbet2 * cbet1 - sbet2 * sbet1, bet12a = atan2(sbet12a, cbet12a); - real m12b, m0, dummy; + real m12b, m0; /* In the case of lon12 = 180, this repeats a calculation made in * Inverse. */ Lengths(g, g->n, pi + bet12a, sbet1, -cbet1, dn1, sbet2, cbet2, dn2, - cbet1, cbet2, &dummy, &m12b, &m0, FALSE, - &dummy, &dummy, C1a, C2a); + cbet1, cbet2, 0, &m12b, &m0, 0, 0, Ca); x = -1 + m12b / (cbet1 * cbet2 * m0 * pi); betscale = x < -(real)(0.01) ? sbet12a / x : -g->f * sq(cbet1) * pi; lamscale = betscale / cbet1; - y = (lam12 - pi) / lamscale; + y = lam12x / lamscale; } if (y > -tol1 && x > -1 - xthresh) { @@ -1214,8 +1391,9 @@ real InverseStart(const struct geod_geodesic* g, calp1 = sbet12a - cbet2 * sbet1 * sq(somg12) / (1 - comg12); } } - if (salp1 > 0) /* Sanity check on starting guess */ - SinCosNorm(&salp1, &calp1); + /* Sanity check on starting guess. Backwards check allows NaN through. */ + if (!(salp1 <= 0)) + norm2(&salp1, &calp1); else { salp1 = 1; calp1 = 0; } @@ -1235,19 +1413,22 @@ real Lambda12(const struct geod_geodesic* g, real sbet1, real cbet1, real dn1, real sbet2, real cbet2, real dn2, real salp1, real calp1, + real slam120, real clam120, real* psalp2, real* pcalp2, real* psig12, real* pssig1, real* pcsig1, real* pssig2, real* pcsig2, - real* peps, real* pdomg12, + real* peps, + real* pdomg12, boolx diffp, real* pdlam12, - /* Scratch areas of the right size */ - real C1a[], real C2a[], real C3a[]) { + /* Scratch area of the right size */ + real Ca[]) { real salp2 = 0, calp2 = 0, sig12 = 0, - ssig1 = 0, csig1 = 0, ssig2 = 0, csig2 = 0, eps = 0, domg12 = 0, dlam12 = 0; + ssig1 = 0, csig1 = 0, ssig2 = 0, csig2 = 0, eps = 0, + domg12 = 0, dlam12 = 0; real salp0, calp0; - real somg1, comg1, somg2, comg2, omg12, lam12; - real B312, h0, k2; + real somg1, comg1, somg2, comg2, somg12, comg12, lam12; + real B312, eta, k2; if (sbet1 == 0 && calp1 == 0) /* Break degeneracy of equatorial line. This case has already been @@ -1262,8 +1443,8 @@ real Lambda12(const struct geod_geodesic* g, * tan(omg1) = sin(alp0) * tan(sig1) = tan(omg1)=tan(alp1)*sin(bet1) */ ssig1 = sbet1; somg1 = salp0 * sbet1; csig1 = comg1 = calp1 * cbet1; - SinCosNorm(&ssig1, &csig1); - /* SinCosNorm(&somg1, &comg1); -- don't need to normalize! */ + norm2(&ssig1, &csig1); + /* norm2(&somg1, &comg1); -- don't need to normalize! */ /* Enforce symmetries in the case abs(bet2) = -bet1. Need to be careful * about this case, since this can yield singularities in the Newton @@ -1284,33 +1465,33 @@ real Lambda12(const struct geod_geodesic* g, * tan(omg2) = sin(alp0) * tan(sig2). */ ssig2 = sbet2; somg2 = salp0 * sbet2; csig2 = comg2 = calp2 * cbet2; - SinCosNorm(&ssig2, &csig2); - /* SinCosNorm(&somg2, &comg2); -- don't need to normalize! */ + norm2(&ssig2, &csig2); + /* norm2(&somg2, &comg2); -- don't need to normalize! */ /* sig12 = sig2 - sig1, limit to [0, pi] */ - sig12 = atan2(maxx(csig1 * ssig2 - ssig1 * csig2, (real)(0)), - csig1 * csig2 + ssig1 * ssig2); + sig12 = atan2(maxx((real)(0), csig1 * ssig2 - ssig1 * csig2), + csig1 * csig2 + ssig1 * ssig2); /* omg12 = omg2 - omg1, limit to [0, pi] */ - omg12 = atan2(maxx(comg1 * somg2 - somg1 * comg2, (real)(0)), - comg1 * comg2 + somg1 * somg2); + somg12 = maxx((real)(0), comg1 * somg2 - somg1 * comg2); + comg12 = comg1 * comg2 + somg1 * somg2; + /* eta = omg12 - lam120 */ + eta = atan2(somg12 * clam120 - comg12 * slam120, + comg12 * clam120 + somg12 * slam120); k2 = sq(calp0) * g->ep2; eps = k2 / (2 * (1 + sqrt(1 + k2)) + k2); - C3f(g, eps, C3a); - B312 = (SinCosSeries(TRUE, ssig2, csig2, C3a, nC3-1) - - SinCosSeries(TRUE, ssig1, csig1, C3a, nC3-1)); - h0 = -g->f * A3f(g, eps); - domg12 = salp0 * h0 * (sig12 + B312); - lam12 = omg12 + domg12; + C3f(g, eps, Ca); + B312 = (SinCosSeries(TRUE, ssig2, csig2, Ca, nC3-1) - + SinCosSeries(TRUE, ssig1, csig1, Ca, nC3-1)); + domg12 = -g->f * A3f(g, eps) * salp0 * (sig12 + B312); + lam12 = eta + domg12; if (diffp) { if (calp2 == 0) dlam12 = - 2 * g->f1 * dn1 / sbet1; else { - real dummy; Lengths(g, eps, sig12, ssig1, csig1, dn1, ssig2, csig2, dn2, - cbet1, cbet2, &dummy, &dlam12, &dummy, - FALSE, &dummy, &dummy, C1a, C2a); + cbet1, cbet2, 0, &dlam12, 0, 0, 0, Ca); dlam12 *= g->f1 / (calp2 * cbet2); } } @@ -1331,177 +1512,264 @@ real Lambda12(const struct geod_geodesic* g, } real A3f(const struct geod_geodesic* g, real eps) { - /* Evaluate sum(A3x[k] * eps^k, k, 0, nA3x-1) by Horner's method */ - real v = 0; - int i; - for (i = nA3x; i; ) - v = eps * v + g->A3x[--i]; - return v; + /* Evaluate A3 */ + return polyval(nA3 - 1, g->A3x, eps); } void C3f(const struct geod_geodesic* g, real eps, real c[]) { - /* Evaluate C3 coeffs by Horner's method - * Elements c[1] thru c[nC3 - 1] are set */ - int i, j, k; + /* Evaluate C3 coeffs + * Elements c[1] through c[nC3 - 1] are set */ real mult = 1; - for (j = nC3x, k = nC3 - 1; k; ) { - real t = 0; - for (i = nC3 - k; i; --i) - t = eps * t + g->C3x[--j]; - c[k--] = t; - } - - for (k = 1; k < nC3; ) { + int o = 0, l; + for (l = 1; l < nC3; ++l) { /* l is index of C3[l] */ + int m = nC3 - l - 1; /* order of polynomial in eps */ mult *= eps; - c[k++] *= mult; + c[l] = mult * polyval(m, g->C3x + o, eps); + o += m + 1; } } void C4f(const struct geod_geodesic* g, real eps, real c[]) { - /* Evaluate C4 coeffs by Horner's method - * Elements c[0] thru c[nC4 - 1] are set */ - int i, j, k; + /* Evaluate C4 coeffs + * Elements c[0] through c[nC4 - 1] are set */ real mult = 1; - for (j = nC4x, k = nC4; k; ) { - real t = 0; - for (i = nC4 - k + 1; i; --i) - t = eps * t + g->C4x[--j]; - c[--k] = t; - } - - for (k = 1; k < nC4; ) { + int o = 0, l; + for (l = 0; l < nC4; ++l) { /* l is index of C4[l] */ + int m = nC4 - l - 1; /* order of polynomial in eps */ + c[l] = mult * polyval(m, g->C4x + o, eps); + o += m + 1; mult *= eps; - c[k++] *= mult; } } -/* Generated by Maxima on 2010-09-04 10:26:17-04:00 */ - /* The scale factor A1-1 = mean value of (d/dsigma)I1 - 1 */ real A1m1f(real eps) { - real - eps2 = sq(eps), - t = eps2*(eps2*(eps2+4)+64)/256; + static const real coeff[] = { + /* (1-eps)*A1-1, polynomial in eps2 of order 3 */ + 1, 4, 64, 0, 256, + }; + int m = nA1/2; + real t = polyval(m, coeff, sq(eps)) / coeff[m + 1]; return (t + eps) / (1 - eps); } /* The coefficients C1[l] in the Fourier expansion of B1 */ void C1f(real eps, real c[]) { + static const real coeff[] = { + /* C1[1]/eps^1, polynomial in eps2 of order 2 */ + -1, 6, -16, 32, + /* C1[2]/eps^2, polynomial in eps2 of order 2 */ + -9, 64, -128, 2048, + /* C1[3]/eps^3, polynomial in eps2 of order 1 */ + 9, -16, 768, + /* C1[4]/eps^4, polynomial in eps2 of order 1 */ + 3, -5, 512, + /* C1[5]/eps^5, polynomial in eps2 of order 0 */ + -7, 1280, + /* C1[6]/eps^6, polynomial in eps2 of order 0 */ + -7, 2048, + }; real eps2 = sq(eps), d = eps; - c[1] = d*((6-eps2)*eps2-16)/32; - d *= eps; - c[2] = d*((64-9*eps2)*eps2-128)/2048; - d *= eps; - c[3] = d*(9*eps2-16)/768; - d *= eps; - c[4] = d*(3*eps2-5)/512; - d *= eps; - c[5] = -7*d/1280; - d *= eps; - c[6] = -7*d/2048; + int o = 0, l; + for (l = 1; l <= nC1; ++l) { /* l is index of C1p[l] */ + int m = (nC1 - l) / 2; /* order of polynomial in eps^2 */ + c[l] = d * polyval(m, coeff + o, eps2) / coeff[o + m + 1]; + o += m + 2; + d *= eps; + } } /* The coefficients C1p[l] in the Fourier expansion of B1p */ void C1pf(real eps, real c[]) { + static const real coeff[] = { + /* C1p[1]/eps^1, polynomial in eps2 of order 2 */ + 205, -432, 768, 1536, + /* C1p[2]/eps^2, polynomial in eps2 of order 2 */ + 4005, -4736, 3840, 12288, + /* C1p[3]/eps^3, polynomial in eps2 of order 1 */ + -225, 116, 384, + /* C1p[4]/eps^4, polynomial in eps2 of order 1 */ + -7173, 2695, 7680, + /* C1p[5]/eps^5, polynomial in eps2 of order 0 */ + 3467, 7680, + /* C1p[6]/eps^6, polynomial in eps2 of order 0 */ + 38081, 61440, + }; real eps2 = sq(eps), d = eps; - c[1] = d*(eps2*(205*eps2-432)+768)/1536; - d *= eps; - c[2] = d*(eps2*(4005*eps2-4736)+3840)/12288; - d *= eps; - c[3] = d*(116-225*eps2)/384; - d *= eps; - c[4] = d*(2695-7173*eps2)/7680; - d *= eps; - c[5] = 3467*d/7680; - d *= eps; - c[6] = 38081*d/61440; + int o = 0, l; + for (l = 1; l <= nC1p; ++l) { /* l is index of C1p[l] */ + int m = (nC1p - l) / 2; /* order of polynomial in eps^2 */ + c[l] = d * polyval(m, coeff + o, eps2) / coeff[o + m + 1]; + o += m + 2; + d *= eps; + } } /* The scale factor A2-1 = mean value of (d/dsigma)I2 - 1 */ real A2m1f(real eps) { - real - eps2 = sq(eps), - t = eps2*(eps2*(25*eps2+36)+64)/256; - return t * (1 - eps) - eps; + static const real coeff[] = { + /* (eps+1)*A2-1, polynomial in eps2 of order 3 */ + -11, -28, -192, 0, 256, + }; + int m = nA2/2; + real t = polyval(m, coeff, sq(eps)) / coeff[m + 1]; + return (t - eps) / (1 + eps); } /* The coefficients C2[l] in the Fourier expansion of B2 */ void C2f(real eps, real c[]) { + static const real coeff[] = { + /* C2[1]/eps^1, polynomial in eps2 of order 2 */ + 1, 2, 16, 32, + /* C2[2]/eps^2, polynomial in eps2 of order 2 */ + 35, 64, 384, 2048, + /* C2[3]/eps^3, polynomial in eps2 of order 1 */ + 15, 80, 768, + /* C2[4]/eps^4, polynomial in eps2 of order 1 */ + 7, 35, 512, + /* C2[5]/eps^5, polynomial in eps2 of order 0 */ + 63, 1280, + /* C2[6]/eps^6, polynomial in eps2 of order 0 */ + 77, 2048, + }; real eps2 = sq(eps), d = eps; - c[1] = d*(eps2*(eps2+2)+16)/32; - d *= eps; - c[2] = d*(eps2*(35*eps2+64)+384)/2048; - d *= eps; - c[3] = d*(15*eps2+80)/768; - d *= eps; - c[4] = d*(7*eps2+35)/512; - d *= eps; - c[5] = 63*d/1280; - d *= eps; - c[6] = 77*d/2048; + int o = 0, l; + for (l = 1; l <= nC2; ++l) { /* l is index of C2[l] */ + int m = (nC2 - l) / 2; /* order of polynomial in eps^2 */ + c[l] = d * polyval(m, coeff + o, eps2) / coeff[o + m + 1]; + o += m + 2; + d *= eps; + } } /* The scale factor A3 = mean value of (d/dsigma)I3 */ void A3coeff(struct geod_geodesic* g) { - g->A3x[0] = 1; - g->A3x[1] = (g->n-1)/2; - g->A3x[2] = (g->n*(3*g->n-1)-2)/8; - g->A3x[3] = ((-g->n-3)*g->n-1)/16; - g->A3x[4] = (-2*g->n-3)/64; - g->A3x[5] = -3/(real)(128); + static const real coeff[] = { + /* A3, coeff of eps^5, polynomial in n of order 0 */ + -3, 128, + /* A3, coeff of eps^4, polynomial in n of order 1 */ + -2, -3, 64, + /* A3, coeff of eps^3, polynomial in n of order 2 */ + -1, -3, -1, 16, + /* A3, coeff of eps^2, polynomial in n of order 2 */ + 3, -1, -2, 8, + /* A3, coeff of eps^1, polynomial in n of order 1 */ + 1, -1, 2, + /* A3, coeff of eps^0, polynomial in n of order 0 */ + 1, 1, + }; + int o = 0, k = 0, j; + for (j = nA3 - 1; j >= 0; --j) { /* coeff of eps^j */ + int m = nA3 - j - 1 < j ? nA3 - j - 1 : j; /* order of polynomial in n */ + g->A3x[k++] = polyval(m, coeff + o, g->n) / coeff[o + m + 1]; + o += m + 2; + } } /* The coefficients C3[l] in the Fourier expansion of B3 */ void C3coeff(struct geod_geodesic* g) { - g->C3x[0] = (1-g->n)/4; - g->C3x[1] = (1-g->n*g->n)/8; - g->C3x[2] = ((3-g->n)*g->n+3)/64; - g->C3x[3] = (2*g->n+5)/128; - g->C3x[4] = 3/(real)(128); - g->C3x[5] = ((g->n-3)*g->n+2)/32; - g->C3x[6] = ((-3*g->n-2)*g->n+3)/64; - g->C3x[7] = (g->n+3)/128; - g->C3x[8] = 5/(real)(256); - g->C3x[9] = (g->n*(5*g->n-9)+5)/192; - g->C3x[10] = (9-10*g->n)/384; - g->C3x[11] = 7/(real)(512); - g->C3x[12] = (7-14*g->n)/512; - g->C3x[13] = 7/(real)(512); - g->C3x[14] = 21/(real)(2560); + static const real coeff[] = { + /* C3[1], coeff of eps^5, polynomial in n of order 0 */ + 3, 128, + /* C3[1], coeff of eps^4, polynomial in n of order 1 */ + 2, 5, 128, + /* C3[1], coeff of eps^3, polynomial in n of order 2 */ + -1, 3, 3, 64, + /* C3[1], coeff of eps^2, polynomial in n of order 2 */ + -1, 0, 1, 8, + /* C3[1], coeff of eps^1, polynomial in n of order 1 */ + -1, 1, 4, + /* C3[2], coeff of eps^5, polynomial in n of order 0 */ + 5, 256, + /* C3[2], coeff of eps^4, polynomial in n of order 1 */ + 1, 3, 128, + /* C3[2], coeff of eps^3, polynomial in n of order 2 */ + -3, -2, 3, 64, + /* C3[2], coeff of eps^2, polynomial in n of order 2 */ + 1, -3, 2, 32, + /* C3[3], coeff of eps^5, polynomial in n of order 0 */ + 7, 512, + /* C3[3], coeff of eps^4, polynomial in n of order 1 */ + -10, 9, 384, + /* C3[3], coeff of eps^3, polynomial in n of order 2 */ + 5, -9, 5, 192, + /* C3[4], coeff of eps^5, polynomial in n of order 0 */ + 7, 512, + /* C3[4], coeff of eps^4, polynomial in n of order 1 */ + -14, 7, 512, + /* C3[5], coeff of eps^5, polynomial in n of order 0 */ + 21, 2560, + }; + int o = 0, k = 0, l, j; + for (l = 1; l < nC3; ++l) { /* l is index of C3[l] */ + for (j = nC3 - 1; j >= l; --j) { /* coeff of eps^j */ + int m = nC3 - j - 1 < j ? nC3 - j - 1 : j; /* order of polynomial in n */ + g->C3x[k++] = polyval(m, coeff + o, g->n) / coeff[o + m + 1]; + o += m + 2; + } + } } -/* Generated by Maxima on 2012-10-19 08:02:34-04:00 */ - /* The coefficients C4[l] in the Fourier expansion of I4 */ void C4coeff(struct geod_geodesic* g) { - g->C4x[0] = (g->n*(g->n*(g->n*(g->n*(100*g->n+208)+572)+3432)-12012)+30030)/ - 45045; - g->C4x[1] = (g->n*(g->n*(g->n*(64*g->n+624)-4576)+6864)-3003)/15015; - g->C4x[2] = (g->n*((14144-10656*g->n)*g->n-4576)-858)/45045; - g->C4x[3] = ((-224*g->n-4784)*g->n+1573)/45045; - g->C4x[4] = (1088*g->n+156)/45045; - g->C4x[5] = 97/(real)(15015); - g->C4x[6] = (g->n*(g->n*((-64*g->n-624)*g->n+4576)-6864)+3003)/135135; - g->C4x[7] = (g->n*(g->n*(5952*g->n-11648)+9152)-2574)/135135; - g->C4x[8] = (g->n*(5792*g->n+1040)-1287)/135135; - g->C4x[9] = (468-2944*g->n)/135135; - g->C4x[10] = 1/(real)(9009); - g->C4x[11] = (g->n*((4160-1440*g->n)*g->n-4576)+1716)/225225; - g->C4x[12] = ((4992-8448*g->n)*g->n-1144)/225225; - g->C4x[13] = (1856*g->n-936)/225225; - g->C4x[14] = 8/(real)(10725); - g->C4x[15] = (g->n*(3584*g->n-3328)+1144)/315315; - g->C4x[16] = (1024*g->n-208)/105105; - g->C4x[17] = -136/(real)(63063); - g->C4x[18] = (832-2560*g->n)/405405; - g->C4x[19] = -128/(real)(135135); - g->C4x[20] = 128/(real)(99099); + static const real coeff[] = { + /* C4[0], coeff of eps^5, polynomial in n of order 0 */ + 97, 15015, + /* C4[0], coeff of eps^4, polynomial in n of order 1 */ + 1088, 156, 45045, + /* C4[0], coeff of eps^3, polynomial in n of order 2 */ + -224, -4784, 1573, 45045, + /* C4[0], coeff of eps^2, polynomial in n of order 3 */ + -10656, 14144, -4576, -858, 45045, + /* C4[0], coeff of eps^1, polynomial in n of order 4 */ + 64, 624, -4576, 6864, -3003, 15015, + /* C4[0], coeff of eps^0, polynomial in n of order 5 */ + 100, 208, 572, 3432, -12012, 30030, 45045, + /* C4[1], coeff of eps^5, polynomial in n of order 0 */ + 1, 9009, + /* C4[1], coeff of eps^4, polynomial in n of order 1 */ + -2944, 468, 135135, + /* C4[1], coeff of eps^3, polynomial in n of order 2 */ + 5792, 1040, -1287, 135135, + /* C4[1], coeff of eps^2, polynomial in n of order 3 */ + 5952, -11648, 9152, -2574, 135135, + /* C4[1], coeff of eps^1, polynomial in n of order 4 */ + -64, -624, 4576, -6864, 3003, 135135, + /* C4[2], coeff of eps^5, polynomial in n of order 0 */ + 8, 10725, + /* C4[2], coeff of eps^4, polynomial in n of order 1 */ + 1856, -936, 225225, + /* C4[2], coeff of eps^3, polynomial in n of order 2 */ + -8448, 4992, -1144, 225225, + /* C4[2], coeff of eps^2, polynomial in n of order 3 */ + -1440, 4160, -4576, 1716, 225225, + /* C4[3], coeff of eps^5, polynomial in n of order 0 */ + -136, 63063, + /* C4[3], coeff of eps^4, polynomial in n of order 1 */ + 1024, -208, 105105, + /* C4[3], coeff of eps^3, polynomial in n of order 2 */ + 3584, -3328, 1144, 315315, + /* C4[4], coeff of eps^5, polynomial in n of order 0 */ + -128, 135135, + /* C4[4], coeff of eps^4, polynomial in n of order 1 */ + -2560, 832, 405405, + /* C4[5], coeff of eps^5, polynomial in n of order 0 */ + 128, 99099, + }; + int o = 0, k = 0, l, j; + for (l = 0; l < nC4; ++l) { /* l is index of C4[l] */ + for (j = nC4 - 1; j >= l; --j) { /* coeff of eps^j */ + int m = nC4 - j - 1; /* order of polynomial in n */ + g->C4x[k++] = polyval(m, coeff + o, g->n) / coeff[o + m + 1]; + o += m + 2; + } + } } int transit(real lon1, real lon2) { @@ -1511,9 +1779,23 @@ int transit(real lon1, real lon2) { /* Compute lon12 the same way as Geodesic::Inverse. */ lon1 = AngNormalize(lon1); lon2 = AngNormalize(lon2); - lon12 = AngDiff(lon1, lon2); - return lon1 < 0 && lon2 >= 0 && lon12 > 0 ? 1 : - (lon2 < 0 && lon1 >= 0 && lon12 < 0 ? -1 : 0); + lon12 = AngDiff(lon1, lon2, 0); + return lon1 <= 0 && lon2 > 0 && lon12 > 0 ? 1 : + (lon2 <= 0 && lon1 > 0 && lon12 < 0 ? -1 : 0); +} + +int transitdirect(real lon1, real lon2) { +#if HAVE_C99_MATH + lon1 = remainder(lon1, (real)(720)); + lon2 = remainder(lon2, (real)(720)); + return ( (lon2 >= 0 && lon2 < 360 ? 0 : 1) - + (lon1 >= 0 && lon1 < 360 ? 0 : 1) ); +#else + lon1 = fmod(lon1, (real)(720)); + lon2 = fmod(lon2, (real)(720)); + return ( ((lon2 >= 0 && lon2 < 360) || lon2 < -360 ? 0 : 1) - + ((lon1 >= 0 && lon1 < 360) || lon1 < -360 ? 0 : 1) ); +#endif } void accini(real s[]) { @@ -1550,8 +1832,12 @@ void accneg(real s[]) { } void geod_polygon_init(struct geod_polygon* p, boolx polylinep) { - p->lat0 = p->lon0 = p->lat = p->lon = NaN; p->polyline = (polylinep != 0); + geod_polygon_clear(p); +} + +void geod_polygon_clear(struct geod_polygon* p) { + p->lat0 = p->lon0 = p->lat = p->lon = NaN; accini(p->P); accini(p->A); p->num = p->crossings = 0; @@ -1565,7 +1851,7 @@ void geod_polygon_addpoint(const struct geod_geodesic* g, p->lat0 = p->lat = lat; p->lon0 = p->lon = lon; } else { - real s12, S12; + real s12, S12 = 0; /* Initialize S12 to stop Visual Studio warning */ geod_geninverse(g, p->lat, p->lon, lat, lon, &s12, 0, 0, 0, 0, 0, p->polyline ? 0 : &S12); accadd(p->P, s12); @@ -1582,14 +1868,14 @@ void geod_polygon_addedge(const struct geod_geodesic* g, struct geod_polygon* p, real azi, real s) { if (p->num) { /* Do nothing is num is zero */ - real lat, lon, S12; - geod_gendirect(g, p->lat, p->lon, azi, FALSE, s, + real lat, lon, S12 = 0; /* Initialize S12 to stop Visual Studio warning */ + geod_gendirect(g, p->lat, p->lon, azi, GEOD_LONG_UNROLL, s, &lat, &lon, 0, 0, 0, 0, 0, p->polyline ? 0 : &S12); accadd(p->P, s); if (!p->polyline) { accadd(p->A, S12); - p->crossings += transit(p->lon, lon); + p->crossings += transitdirect(p->lon, lon); } p->lat = lat; p->lon = lon; ++p->num; @@ -1657,7 +1943,7 @@ unsigned geod_polygon_testpoint(const struct geod_geodesic* g, tempsum = p->polyline ? 0 : p->A[0]; crossings = p->crossings; for (i = 0; i < (p->polyline ? 1 : 2); ++i) { - real s12, S12; + real s12, S12 = 0; /* Initialize S12 to stop Visual Studio warning */ geod_geninverse(g, i == 0 ? p->lat : lat, i == 0 ? p->lon : lon, i != 0 ? p->lat0 : lat, i != 0 ? p->lon0 : lon, @@ -1720,11 +2006,11 @@ unsigned geod_polygon_testedge(const struct geod_geodesic* g, crossings = p->crossings; { real lat, lon, s12, S12; - geod_gendirect(g, p->lat, p->lon, azi, FALSE, s, + geod_gendirect(g, p->lat, p->lon, azi, GEOD_LONG_UNROLL, s, &lat, &lon, 0, 0, 0, 0, 0, &S12); tempsum += S12; - crossings += transit(p->lon, lon); + crossings += transitdirect(p->lon, lon); geod_geninverse(g, lat, lon, p->lat0, p->lon0, &s12, 0, 0, 0, 0, 0, &S12); perimeter += s12; diff --git a/gtsam/3rdparty/GeographicLib/legacy/C/geodesic.h b/gtsam/3rdparty/GeographicLib/legacy/C/geodesic.h index 5efa63f57..ab18a01f0 100644 --- a/gtsam/3rdparty/GeographicLib/legacy/C/geodesic.h +++ b/gtsam/3rdparty/GeographicLib/legacy/C/geodesic.h @@ -1,15 +1,15 @@ /** * \file geodesic.h - * \brief Header for the geodesic routines in C + * \brief API for the geodesic routines in C * * This an implementation in C of the geodesic algorithms described in * - C. F. F. Karney, - * + * * Algorithms for geodesics, * J. Geodesy 87, 43--55 (2013); - * DOI: + * DOI: * 10.1007/s00190-012-0578-z; - * addenda: + * addenda: * geod-addenda.html. * . * The principal advantages of these algorithms over previous ones (e.g., @@ -76,44 +76,43 @@ * multiple azimuths which yield the same shortest distance. Here is a * catalog of those cases: * - \e lat1 = −\e lat2 (with neither point at a pole). If \e azi1 = \e - * azi2, the geodesic is unique. Otherwise there are two geodesics - * and the second one is obtained by setting [\e azi1, \e azi2] = [\e - * azi2, \e azi1], [\e M12, \e M21] = [\e M21, \e M12], \e S12 = - * −\e S12. (This occurs when the longitude difference is near - * ±180° for oblate ellipsoids.) - * - \e lon2 = \e lon1 ± 180° (with neither point at a pole). If - * \e azi1 = 0° or ±180°, the geodesic is unique. - * Otherwise there are two geodesics and the second one is obtained by - * setting [\e azi1, \e azi2] = [−\e azi1, −\e azi2], \e - * S12 = −\e S12. (This occurs when \e lat2 is near - * −\e lat1 for prolate ellipsoids.) - * - Points 1 and 2 at opposite poles. There are infinitely many - * geodesics which can be generated by setting [\e azi1, \e azi2] = - * [\e azi1, \e azi2] + [\e d, −\e d], for arbitrary \e d. (For - * spheres, this prescription applies when points 1 and 2 are - * antipodal.) - * - \e s12 = 0 (coincident points). There are infinitely many geodesics - * which can be generated by setting [\e azi1, \e azi2] = [\e azi1, \e - * azi2] + [\e d, \e d], for arbitrary \e d. + * azi2, the geodesic is unique. Otherwise there are two geodesics and the + * second one is obtained by setting [\e azi1, \e azi2] → [\e azi2, \e + * azi1], [\e M12, \e M21] → [\e M21, \e M12], \e S12 → −\e + * S12. (This occurs when the longitude difference is near ±180° + * for oblate ellipsoids.) + * - \e lon2 = \e lon1 ± 180° (with neither point at a pole). If \e + * azi1 = 0° or ±180°, the geodesic is unique. Otherwise + * there are two geodesics and the second one is obtained by setting [\e + * azi1, \e azi2] → [−\e azi1, −\e azi2], \e S12 → + * −\e S12. (This occurs when \e lat2 is near −\e lat1 for + * prolate ellipsoids.) + * - Points 1 and 2 at opposite poles. There are infinitely many geodesics + * which can be generated by setting [\e azi1, \e azi2] → [\e azi1, \e + * azi2] + [\e d, −\e d], for arbitrary \e d. (For spheres, this + * prescription applies when points 1 and 2 are antipodal.) + * - \e s12 = 0 (coincident points). There are infinitely many geodesics which + * can be generated by setting [\e azi1, \e azi2] → [\e azi1, \e azi2] + + * [\e d, \e d], for arbitrary \e d. * * These routines are a simple transcription of the corresponding C++ classes - * in GeographicLib. The "class - * data" is represented by the structs geod_geodesic, geod_geodesicline, + * in GeographicLib. The + * "class data" is represented by the structs geod_geodesic, geod_geodesicline, * geod_polygon and pointers to these objects are passed as initial arguments * to the member functions. Most of the internal comments have been retained. * However, in the process of transcription some documentation has been lost * and the documentation for the C++ classes, GeographicLib::Geodesic, - * GeographicLib::GeodesicLine, and GeographicLib::PolygonArea, should be + * GeographicLib::GeodesicLine, and GeographicLib::PolygonAreaT, should be * consulted. The C++ code remains the "reference implementation". Think * twice about restructuring the internals of the C code since this may make * porting fixes from the C++ code more difficult. * - * Copyright (c) Charles Karney (2012-2013) and licensed + * Copyright (c) Charles Karney (2012-2017) and licensed * under the MIT/X11 License. For more information, see - * http://geographiclib.sourceforge.net/ + * https://geographiclib.sourceforge.io/ * * This library was distributed with - * GeographicLib 1.32. + * GeographicLib 1.49. **********************************************************************/ #if !defined(GEODESIC_H) @@ -128,13 +127,36 @@ * The minor version of the geodesic library. (This tracks the version of * GeographicLib.) **********************************************************************/ -#define GEODESIC_VERSION_MINOR 32 +#define GEODESIC_VERSION_MINOR 49 /** * The patch level of the geodesic library. (This tracks the version of * GeographicLib.) **********************************************************************/ #define GEODESIC_VERSION_PATCH 0 +/** + * Pack the version components into a single integer. Users should not rely on + * this particular packing of the components of the version number; see the + * documentation for GEODESIC_VERSION, below. + **********************************************************************/ +#define GEODESIC_VERSION_NUM(a,b,c) ((((a) * 10000 + (b)) * 100) + (c)) + +/** + * The version of the geodesic library as a single integer, packed as MMmmmmpp + * where MM is the major version, mmmm is the minor version, and pp is the + * patch level. Users should not rely on this particular packing of the + * components of the version number. Instead they should use a test such as + * @code{.c} + #if GEODESIC_VERSION >= GEODESIC_VERSION_NUM(1,40,0) + ... + #endif + * @endcode + **********************************************************************/ +#define GEODESIC_VERSION \ + GEODESIC_VERSION_NUM(GEODESIC_VERSION_MAJOR, \ + GEODESIC_VERSION_MINOR, \ + GEODESIC_VERSION_PATCH) + #if defined(__cplusplus) extern "C" { #endif @@ -154,7 +176,8 @@ extern "C" { /** * The struct containing information about a single geodesic. This must be - * initialized by geod_lineinit() before use. + * initialized by geod_lineinit(), geod_directline(), geod_gendirectline(), + * or geod_inverseline() before use. **********************************************************************/ struct geod_geodesicline { double lat1; /**< the starting latitude */ @@ -162,9 +185,13 @@ extern "C" { double azi1; /**< the starting azimuth */ double a; /**< the equatorial radius */ double f; /**< the flattening */ + double salp1; /**< sine of \e azi1 */ + double calp1; /**< cosine of \e azi1 */ + double a13; /**< arc length to reference point */ + double s13; /**< distance to reference point */ /**< @cond SKIP */ double b, c2, f1, salp0, calp0, k2, - salp1, calp1, ssig1, csig1, dn1, stau1, ctau1, somg1, comg1, + ssig1, csig1, dn1, stau1, ctau1, somg1, comg1, A1m1, A2m1, A3c, B11, B21, B31, A4, B41; double C1a[6+1], C1pa[6+1], C2a[6+1], C3a[6], C4a[6]; /**< @endcond */ @@ -199,6 +226,166 @@ extern "C" { **********************************************************************/ void geod_init(struct geod_geodesic* g, double a, double f); + /** + * Solve the direct geodesic problem. + * + * @param[in] g a pointer to the geod_geodesic object specifying the + * ellipsoid. + * @param[in] lat1 latitude of point 1 (degrees). + * @param[in] lon1 longitude of point 1 (degrees). + * @param[in] azi1 azimuth at point 1 (degrees). + * @param[in] s12 distance from point 1 to point 2 (meters); it can be + * negative. + * @param[out] plat2 pointer to the latitude of point 2 (degrees). + * @param[out] plon2 pointer to the longitude of point 2 (degrees). + * @param[out] pazi2 pointer to the (forward) azimuth at point 2 (degrees). + * + * \e g must have been initialized with a call to geod_init(). \e lat1 + * should be in the range [−90°, 90°]. The values of \e lon2 + * and \e azi2 returned are in the range [−180°, 180°]. Any of + * the "return" arguments \e plat2, etc., may be replaced by 0, if you do not + * need some quantities computed. + * + * If either point is at a pole, the azimuth is defined by keeping the + * longitude fixed, writing \e lat = ±(90° − ε), and + * taking the limit ε → 0+. An arc length greater that 180° + * signifies a geodesic which is not a shortest path. (For a prolate + * ellipsoid, an additional condition is necessary for a shortest path: the + * longitudinal extent must not exceed of 180°.) + * + * Example, determine the point 10000 km NE of JFK: + @code{.c} + struct geod_geodesic g; + double lat, lon; + geod_init(&g, 6378137, 1/298.257223563); + geod_direct(&g, 40.64, -73.78, 45.0, 10e6, &lat, &lon, 0); + printf("%.5f %.5f\n", lat, lon); + @endcode + **********************************************************************/ + void geod_direct(const struct geod_geodesic* g, + double lat1, double lon1, double azi1, double s12, + double* plat2, double* plon2, double* pazi2); + + /** + * The general direct geodesic problem. + * + * @param[in] g a pointer to the geod_geodesic object specifying the + * ellipsoid. + * @param[in] lat1 latitude of point 1 (degrees). + * @param[in] lon1 longitude of point 1 (degrees). + * @param[in] azi1 azimuth at point 1 (degrees). + * @param[in] flags bitor'ed combination of geod_flags(); \e flags & + * GEOD_ARCMODE determines the meaning of \e s12_a12 and \e flags & + * GEOD_LONG_UNROLL "unrolls" \e lon2. + * @param[in] s12_a12 if \e flags & GEOD_ARCMODE is 0, this is the distance + * from point 1 to point 2 (meters); otherwise it is the arc length + * from point 1 to point 2 (degrees); it can be negative. + * @param[out] plat2 pointer to the latitude of point 2 (degrees). + * @param[out] plon2 pointer to the longitude of point 2 (degrees). + * @param[out] pazi2 pointer to the (forward) azimuth at point 2 (degrees). + * @param[out] ps12 pointer to the distance from point 1 to point 2 + * (meters). + * @param[out] pm12 pointer to the reduced length of geodesic (meters). + * @param[out] pM12 pointer to the geodesic scale of point 2 relative to + * point 1 (dimensionless). + * @param[out] pM21 pointer to the geodesic scale of point 1 relative to + * point 2 (dimensionless). + * @param[out] pS12 pointer to the area under the geodesic + * (meters2). + * @return \e a12 arc length from point 1 to point 2 (degrees). + * + * \e g must have been initialized with a call to geod_init(). \e lat1 + * should be in the range [−90°, 90°]. The function value \e + * a12 equals \e s12_a12 if \e flags & GEOD_ARCMODE. Any of the "return" + * arguments, \e plat2, etc., may be replaced by 0, if you do not need some + * quantities computed. + * + * With \e flags & GEOD_LONG_UNROLL bit set, the longitude is "unrolled" so + * that the quantity \e lon2 − \e lon1 indicates how many times and in + * what sense the geodesic encircles the ellipsoid. + **********************************************************************/ + double geod_gendirect(const struct geod_geodesic* g, + double lat1, double lon1, double azi1, + unsigned flags, double s12_a12, + double* plat2, double* plon2, double* pazi2, + double* ps12, double* pm12, double* pM12, double* pM21, + double* pS12); + + /** + * Solve the inverse geodesic problem. + * + * @param[in] g a pointer to the geod_geodesic object specifying the + * ellipsoid. + * @param[in] lat1 latitude of point 1 (degrees). + * @param[in] lon1 longitude of point 1 (degrees). + * @param[in] lat2 latitude of point 2 (degrees). + * @param[in] lon2 longitude of point 2 (degrees). + * @param[out] ps12 pointer to the distance from point 1 to point 2 + * (meters). + * @param[out] pazi1 pointer to the azimuth at point 1 (degrees). + * @param[out] pazi2 pointer to the (forward) azimuth at point 2 (degrees). + * + * \e g must have been initialized with a call to geod_init(). \e lat1 and + * \e lat2 should be in the range [−90°, 90°]. The values of + * \e azi1 and \e azi2 returned are in the range [−180°, 180°]. + * Any of the "return" arguments, \e ps12, etc., may be replaced by 0, if you + * do not need some quantities computed. + * + * If either point is at a pole, the azimuth is defined by keeping the + * longitude fixed, writing \e lat = ±(90° − ε), and + * taking the limit ε → 0+. + * + * The solution to the inverse problem is found using Newton's method. If + * this fails to converge (this is very unlikely in geodetic applications + * but does occur for very eccentric ellipsoids), then the bisection method + * is used to refine the solution. + * + * Example, determine the distance between JFK and Singapore Changi Airport: + @code{.c} + struct geod_geodesic g; + double s12; + geod_init(&g, 6378137, 1/298.257223563); + geod_inverse(&g, 40.64, -73.78, 1.36, 103.99, &s12, 0, 0); + printf("%.3f\n", s12); + @endcode + **********************************************************************/ + void geod_inverse(const struct geod_geodesic* g, + double lat1, double lon1, double lat2, double lon2, + double* ps12, double* pazi1, double* pazi2); + + /** + * The general inverse geodesic calculation. + * + * @param[in] g a pointer to the geod_geodesic object specifying the + * ellipsoid. + * @param[in] lat1 latitude of point 1 (degrees). + * @param[in] lon1 longitude of point 1 (degrees). + * @param[in] lat2 latitude of point 2 (degrees). + * @param[in] lon2 longitude of point 2 (degrees). + * @param[out] ps12 pointer to the distance from point 1 to point 2 + * (meters). + * @param[out] pazi1 pointer to the azimuth at point 1 (degrees). + * @param[out] pazi2 pointer to the (forward) azimuth at point 2 (degrees). + * @param[out] pm12 pointer to the reduced length of geodesic (meters). + * @param[out] pM12 pointer to the geodesic scale of point 2 relative to + * point 1 (dimensionless). + * @param[out] pM21 pointer to the geodesic scale of point 1 relative to + * point 2 (dimensionless). + * @param[out] pS12 pointer to the area under the geodesic + * (meters2). + * @return \e a12 arc length from point 1 to point 2 (degrees). + * + * \e g must have been initialized with a call to geod_init(). \e lat1 and + * \e lat2 should be in the range [−90°, 90°]. Any of the + * "return" arguments \e ps12, etc., may be replaced by 0, if you do not need + * some quantities computed. + **********************************************************************/ + double geod_geninverse(const struct geod_geodesic* g, + double lat1, double lon1, double lat2, double lon2, + double* ps12, double* pazi1, double* pazi2, + double* pm12, double* pM12, double* pM21, + double* pS12); + /** * Initialize a geod_geodesicline object. * @@ -214,8 +401,7 @@ extern "C" { * geod_genposition(). * * \e g must have been initialized with a call to geod_init(). \e lat1 - * should be in the range [−90°, 90°]; \e lon1 and \e azi1 - * should be in the range [−540°, 540°). + * should be in the range [−90°, 90°]. * * The geod_mask values are [see geod_mask()]: * - \e caps |= GEOD_LATITUDE for the latitude \e lat2; this is @@ -235,116 +421,117 @@ extern "C" { * A value of \e caps = 0 is treated as GEOD_LATITUDE | GEOD_LONGITUDE | * GEOD_AZIMUTH | GEOD_DISTANCE_IN (to support the solution of the "standard" * direct problem). + * + * When initialized by this function, point 3 is undefined (l->s13 = l->a13 = + * NaN). **********************************************************************/ void geod_lineinit(struct geod_geodesicline* l, const struct geod_geodesic* g, double lat1, double lon1, double azi1, unsigned caps); /** - * Solve the direct geodesic problem. + * Initialize a geod_geodesicline object in terms of the direct geodesic + * problem. * + * @param[out] l a pointer to the object to be initialized. * @param[in] g a pointer to the geod_geodesic object specifying the * ellipsoid. * @param[in] lat1 latitude of point 1 (degrees). * @param[in] lon1 longitude of point 1 (degrees). * @param[in] azi1 azimuth at point 1 (degrees). - * @param[in] s12 distance between point 1 and point 2 (meters); it can be + * @param[in] s12 distance from point 1 to point 2 (meters); it can be * negative. - * @param[out] plat2 pointer to the latitude of point 2 (degrees). - * @param[out] plon2 pointer to the longitude of point 2 (degrees). - * @param[out] pazi2 pointer to the (forward) azimuth at point 2 (degrees). + * @param[in] caps bitor'ed combination of geod_mask() values specifying the + * capabilities the geod_geodesicline object should possess, i.e., which + * quantities can be returned in calls to geod_position() and + * geod_genposition(). * - * \e g must have been initialized with a call to geod_init(). \e lat1 - * should be in the range [−90°, 90°]; \e lon1 and \e azi1 - * should be in the range [−540°, 540°). The values of \e lon2 - * and \e azi2 returned are in the range [−180°, 180°). Any of - * the "return" arguments \e plat2, etc., may be replaced by 0, if you do not - * need some quantities computed. - * - * If either point is at a pole, the azimuth is defined by keeping the - * longitude fixed, writing \e lat = ±(90° − ε), and - * taking the limit ε → 0+. An arc length greater that 180° - * signifies a geodesic which is not a shortest path. (For a prolate - * ellipsoid, an additional condition is necessary for a shortest path: the - * longitudinal extent must not exceed of 180°.) - * - * Example, determine the point 10000 km NE of JFK: - @code - struct geod_geodesic g; - double lat, lon; - geod_init(&g, 6378137, 1/298.257223563); - geod_direct(&g, 40.64, -73.78, 45.0, 10e6, &lat, &lon, 0); - printf("%.5f %.5f\n", lat, lon); - @endcode + * This function sets point 3 of the geod_geodesicline to correspond to point + * 2 of the direct geodesic problem. See geod_lineinit() for more + * information. **********************************************************************/ - void geod_direct(const struct geod_geodesic* g, - double lat1, double lon1, double azi1, double s12, - double* plat2, double* plon2, double* pazi2); + void geod_directline(struct geod_geodesicline* l, + const struct geod_geodesic* g, + double lat1, double lon1, double azi1, double s12, + unsigned caps); /** - * Solve the inverse geodesic problem. + * Initialize a geod_geodesicline object in terms of the direct geodesic + * problem spacified in terms of either distance or arc length. * + * @param[out] l a pointer to the object to be initialized. + * @param[in] g a pointer to the geod_geodesic object specifying the + * ellipsoid. + * @param[in] lat1 latitude of point 1 (degrees). + * @param[in] lon1 longitude of point 1 (degrees). + * @param[in] azi1 azimuth at point 1 (degrees). + * @param[in] flags either GEOD_NOFLAGS or GEOD_ARCMODE to determining the + * meaning of the \e s12_a12. + * @param[in] s12_a12 if \e flags = GEOD_NOFLAGS, this is the distance + * from point 1 to point 2 (meters); if \e flags = GEOD_ARCMODE, it is + * the arc length from point 1 to point 2 (degrees); it can be + * negative. + * @param[in] caps bitor'ed combination of geod_mask() values specifying the + * capabilities the geod_geodesicline object should possess, i.e., which + * quantities can be returned in calls to geod_position() and + * geod_genposition(). + * + * This function sets point 3 of the geod_geodesicline to correspond to point + * 2 of the direct geodesic problem. See geod_lineinit() for more + * information. + **********************************************************************/ + void geod_gendirectline(struct geod_geodesicline* l, + const struct geod_geodesic* g, + double lat1, double lon1, double azi1, + unsigned flags, double s12_a12, + unsigned caps); + + /** + * Initialize a geod_geodesicline object in terms of the inverse geodesic + * problem. + * + * @param[out] l a pointer to the object to be initialized. * @param[in] g a pointer to the geod_geodesic object specifying the * ellipsoid. * @param[in] lat1 latitude of point 1 (degrees). * @param[in] lon1 longitude of point 1 (degrees). * @param[in] lat2 latitude of point 2 (degrees). * @param[in] lon2 longitude of point 2 (degrees). - * @param[out] ps12 pointer to the distance between point 1 and point 2 - * (meters). - * @param[out] pazi1 pointer to the azimuth at point 1 (degrees). - * @param[out] pazi2 pointer to the (forward) azimuth at point 2 (degrees). + * @param[in] caps bitor'ed combination of geod_mask() values specifying the + * capabilities the geod_geodesicline object should possess, i.e., which + * quantities can be returned in calls to geod_position() and + * geod_genposition(). * - * \e g must have been initialized with a call to geod_init(). \e lat1 - * and \e lat2 should be in the range [−90°, 90°]; \e lon1 and - * \e lon2 should be in the range [−540°, 540°). The values of - * \e azi1 and \e azi2 returned are in the range [−180°, 180°). - * Any of the "return" arguments \e ps12, etc., may be replaced by 0, if you - * do not need some quantities computed. - * - * If either point is at a pole, the azimuth is defined by keeping the - * longitude fixed, writing \e lat = ±(90° − ε), and - * taking the limit ε → 0+. - * - * The solution to the inverse problem is found using Newton's method. If - * this fails to converge (this is very unlikely in geodetic applications - * but does occur for very eccentric ellipsoids), then the bisection method - * is used to refine the solution. - * - * Example, determine the distance between JFK and Singapore Changi Airport: - @code - struct geod_geodesic g; - double s12; - geod_init(&g, 6378137, 1/298.257223563); - geod_inverse(&g, 40.64, -73.78, 1.36, 103.99, &s12, 0, 0); - printf("%.3f\n", s12); - @endcode + * This function sets point 3 of the geod_geodesicline to correspond to point + * 2 of the inverse geodesic problem. See geod_lineinit() for more + * information. **********************************************************************/ - void geod_inverse(const struct geod_geodesic* g, - double lat1, double lon1, double lat2, double lon2, - double* ps12, double* pazi1, double* pazi2); + void geod_inverseline(struct geod_geodesicline* l, + const struct geod_geodesic* g, + double lat1, double lon1, double lat2, double lon2, + unsigned caps); /** * Compute the position along a geod_geodesicline. * * @param[in] l a pointer to the geod_geodesicline object specifying the * geodesic line. - * @param[in] s12 distance between point 1 and point 2 (meters); it can be + * @param[in] s12 distance from point 1 to point 2 (meters); it can be * negative. * @param[out] plat2 pointer to the latitude of point 2 (degrees). * @param[out] plon2 pointer to the longitude of point 2 (degrees); requires * that \e l was initialized with \e caps |= GEOD_LONGITUDE. * @param[out] pazi2 pointer to the (forward) azimuth at point 2 (degrees). * - * \e l must have been initialized with a call to geod_lineinit() with \e - * caps |= GEOD_DISTANCE_IN. The values of \e lon2 and \e azi2 returned are - * in the range [−180°, 180°). Any of the "return" arguments - * \e plat2, etc., may be replaced by 0, if you do not need some quantities - * computed. + * \e l must have been initialized with a call, e.g., to geod_lineinit(), + * with \e caps |= GEOD_DISTANCE_IN. The values of \e lon2 and \e azi2 + * returned are in the range [−180°, 180°]. Any of the + * "return" arguments \e plat2, etc., may be replaced by 0, if you do not + * need some quantities computed. * * Example, compute way points between JFK and Singapore Changi Airport * the "obvious" way using geod_direct(): - @code + @code{.c} struct geod_geodesic g; double s12, azi1, lat[101],lon[101]; int i; @@ -356,16 +543,15 @@ extern "C" { } @endcode * A faster way using geod_position(): - @code + @code{.c} struct geod_geodesic g; struct geod_geodesicline l; - double s12, azi1, lat[101],lon[101]; + double lat[101],lon[101]; int i; geod_init(&g, 6378137, 1/298.257223563); - geod_inverse(&g, 40.64, -73.78, 1.36, 103.99, &s12, &azi1, 0); - geod_lineinit(&l, &g, 40.64, -73.78, azi1, 0); - for (i = 0; i < 101; ++i) { - geod_position(&l, i * s12 * 0.01, lat + i, lon + i, 0); + geod_inverseline(&l, &g, 40.64, -73.78, 1.36, 103.99, 0); + for (i = 0; i <= 100; ++i) { + geod_position(&l, i * l.s13 * 0.01, lat + i, lon + i, 0); printf("%.5f %.5f\n", lat[i], lon[i]); } @endcode @@ -373,97 +559,24 @@ extern "C" { void geod_position(const struct geod_geodesicline* l, double s12, double* plat2, double* plon2, double* pazi2); - /** - * The general direct geodesic problem. - * - * @param[in] g a pointer to the geod_geodesic object specifying the - * ellipsoid. - * @param[in] lat1 latitude of point 1 (degrees). - * @param[in] lon1 longitude of point 1 (degrees). - * @param[in] azi1 azimuth at point 1 (degrees). - * @param[in] arcmode flag determining the meaning of the \e - * s12_a12. - * @param[in] s12_a12 if \e arcmode is 0, this is the distance between - * point 1 and point 2 (meters); otherwise it is the arc length between - * point 1 and point 2 (degrees); it can be negative. - * @param[out] plat2 pointer to the latitude of point 2 (degrees). - * @param[out] plon2 pointer to the longitude of point 2 (degrees). - * @param[out] pazi2 pointer to the (forward) azimuth at point 2 (degrees). - * @param[out] ps12 pointer to the distance between point 1 and point 2 - * (meters). - * @param[out] pm12 pointer to the reduced length of geodesic (meters). - * @param[out] pM12 pointer to the geodesic scale of point 2 relative to - * point 1 (dimensionless). - * @param[out] pM21 pointer to the geodesic scale of point 1 relative to - * point 2 (dimensionless). - * @param[out] pS12 pointer to the area under the geodesic - * (meters2). - * @return \e a12 arc length of between point 1 and point 2 (degrees). - * - * \e g must have been initialized with a call to geod_init(). \e lat1 - * should be in the range [−90°, 90°]; \e lon1 and \e azi1 - * should be in the range [−540°, 540°). The function value \e - * a12 equals \e s12_a12 is \e arcmode is non-zero. Any of the "return" - * arguments \e plat2, etc., may be replaced by 0, if you do not need some - * quantities computed. - **********************************************************************/ - double geod_gendirect(const struct geod_geodesic* g, - double lat1, double lon1, double azi1, - int arcmode, double s12_a12, - double* plat2, double* plon2, double* pazi2, - double* ps12, double* pm12, double* pM12, double* pM21, - double* pS12); - - /** - * The general inverse geodesic calculation. - * - * @param[in] g a pointer to the geod_geodesic object specifying the - * ellipsoid. - * @param[in] lat1 latitude of point 1 (degrees). - * @param[in] lon1 longitude of point 1 (degrees). - * @param[in] lat2 latitude of point 2 (degrees). - * @param[in] lon2 longitude of point 2 (degrees). - * @param[out] ps12 pointer to the distance between point 1 and point 2 - * (meters). - * @param[out] pazi1 pointer to the azimuth at point 1 (degrees). - * @param[out] pazi2 pointer to the (forward) azimuth at point 2 (degrees). - * @param[out] pm12 pointer to the reduced length of geodesic (meters). - * @param[out] pM12 pointer to the geodesic scale of point 2 relative to - * point 1 (dimensionless). - * @param[out] pM21 pointer to the geodesic scale of point 1 relative to - * point 2 (dimensionless). - * @param[out] pS12 pointer to the area under the geodesic - * (meters2). - * @return \e a12 arc length of between point 1 and point 2 (degrees). - * - * \e g must have been initialized with a call to geod_init(). \e lat1 - * and \e lat2 should be in the range [−90°, 90°]; \e lon1 and - * \e lon2 should be in the range [−540°, 540°). Any of the - * "return" arguments \e ps12, etc., may be replaced by 0, if you do not need - * some quantities computed. - **********************************************************************/ - double geod_geninverse(const struct geod_geodesic* g, - double lat1, double lon1, double lat2, double lon2, - double* ps12, double* pazi1, double* pazi2, - double* pm12, double* pM12, double* pM21, - double* pS12); - /** * The general position function. * * @param[in] l a pointer to the geod_geodesicline object specifying the * geodesic line. - * @param[in] arcmode flag determining the meaning of the second parameter; - * if arcmode is 0, then \e l must have been initialized with \e caps |= - * GEOD_DISTANCE_IN. - * @param[in] s12_a12 if \e arcmode is 0, this is the distance between - * point 1 and point 2 (meters); otherwise it is the arc length between - * point 1 and point 2 (degrees); it can be negative. + * @param[in] flags bitor'ed combination of geod_flags(); \e flags & + * GEOD_ARCMODE determines the meaning of \e s12_a12 and \e flags & + * GEOD_LONG_UNROLL "unrolls" \e lon2; if \e flags & GEOD_ARCMODE is 0, + * then \e l must have been initialized with \e caps |= GEOD_DISTANCE_IN. + * @param[in] s12_a12 if \e flags & GEOD_ARCMODE is 0, this is the + * distance from point 1 to point 2 (meters); otherwise it is the + * arc length from point 1 to point 2 (degrees); it can be + * negative. * @param[out] plat2 pointer to the latitude of point 2 (degrees). * @param[out] plon2 pointer to the longitude of point 2 (degrees); requires * that \e l was initialized with \e caps |= GEOD_LONGITUDE. * @param[out] pazi2 pointer to the (forward) azimuth at point 2 (degrees). - * @param[out] ps12 pointer to the distance between point 1 and point 2 + * @param[out] ps12 pointer to the distance from point 1 to point 2 * (meters); requires that \e l was initialized with \e caps |= * GEOD_DISTANCE. * @param[out] pm12 pointer to the reduced length of geodesic (meters); @@ -477,43 +590,76 @@ extern "C" { * @param[out] pS12 pointer to the area under the geodesic * (meters2); requires that \e l was initialized with \e caps |= * GEOD_AREA. - * @return \e a12 arc length of between point 1 and point 2 (degrees). + * @return \e a12 arc length from point 1 to point 2 (degrees). * * \e l must have been initialized with a call to geod_lineinit() with \e - * caps |= GEOD_DISTANCE_IN. The values of \e lon2 and \e azi2 returned are - * in the range [−180°, 180°). Any of the "return" arguments - * \e plat2, etc., may be replaced by 0, if you do not need some quantities - * computed. Requesting a value which \e l is not capable of computing is - * not an error; the corresponding argument will not be altered. + * caps |= GEOD_DISTANCE_IN. The value \e azi2 returned is in the range + * [−180°, 180°]. Any of the "return" arguments \e plat2, + * etc., may be replaced by 0, if you do not need some quantities + * computed. Requesting a value which \e l is not capable of computing + * is not an error; the corresponding argument will not be altered. * - * Example, compute way points between JFK and Singapore Changi Airport - * using geod_genposition(). In this example, the points are evenly space in - * arc length (and so only approximately equally space in distance). This is - * faster than using geod_position() would be appropriate if drawing the path - * on a map. - @code + * With \e flags & GEOD_LONG_UNROLL bit set, the longitude is "unrolled" so + * that the quantity \e lon2 − \e lon1 indicates how many times and in + * what sense the geodesic encircles the ellipsoid. + * + * Example, compute way points between JFK and Singapore Changi Airport using + * geod_genposition(). In this example, the points are evenly space in arc + * length (and so only approximately equally spaced in distance). This is + * faster than using geod_position() and would be appropriate if drawing the + * path on a map. + @code{.c} struct geod_geodesic g; struct geod_geodesicline l; - double a12, azi1, lat[101],lon[101]; + double lat[101], lon[101]; int i; geod_init(&g, 6378137, 1/298.257223563); - a12 = geod_geninverse(&g, 40.64, -73.78, 1.36, 103.99, - 0, &azi1, 0, 0, 0, 0, 0); - geod_lineinit(&l, &g, 40.64, -73.78, azi1, GEOD_LATITUDE | GEOD_LONGITUDE); - for (i = 0; i < 101; ++i) { - geod_genposition(&l, 1, i * a12 * 0.01, + geod_inverseline(&l, &g, 40.64, -73.78, 1.36, 103.99, + GEOD_LATITUDE | GEOD_LONGITUDE); + for (i = 0; i <= 100; ++i) { + geod_genposition(&l, GEOD_ARCMODE, i * l.a13 * 0.01, lat + i, lon + i, 0, 0, 0, 0, 0, 0); printf("%.5f %.5f\n", lat[i], lon[i]); } @endcode **********************************************************************/ double geod_genposition(const struct geod_geodesicline* l, - int arcmode, double s12_a12, + unsigned flags, double s12_a12, double* plat2, double* plon2, double* pazi2, double* ps12, double* pm12, double* pM12, double* pM21, double* pS12); + /** + * Specify position of point 3 in terms of distance. + * + * @param[inout] l a pointer to the geod_geodesicline object. + * @param[in] s13 the distance from point 1 to point 3 (meters); it + * can be negative. + * + * This is only useful if the geod_geodesicline object has been constructed + * with \e caps |= GEOD_DISTANCE_IN. + **********************************************************************/ + void geod_setdistance(struct geod_geodesicline* l, double s13); + + /** + * Specify position of point 3 in terms of either distance or arc length. + * + * @param[inout] l a pointer to the geod_geodesicline object. + * @param[in] flags either GEOD_NOFLAGS or GEOD_ARCMODE to determining the + * meaning of the \e s13_a13. + * @param[in] s13_a13 if \e flags = GEOD_NOFLAGS, this is the distance + * from point 1 to point 3 (meters); if \e flags = GEOD_ARCMODE, it is + * the arc length from point 1 to point 3 (degrees); it can be + * negative. + * + * If flags = GEOD_NOFLAGS, this calls geod_setdistance(). If flags = + * GEOD_ARCMODE, the \e s13 is only set if the geod_geodesicline object has + * been constructed with \e caps |= GEOD_DISTANCE. + **********************************************************************/ + void geod_gensetdistance(struct geod_geodesicline* l, + unsigned flags, double s13_a13); + /** * Initialize a geod_polygon object. * @@ -526,11 +672,22 @@ extern "C" { * polylinep is non-zero, then the vertices and edges define a polyline and * only the perimeter is returned by geod_polygon_compute(). * + * The area and perimeter are accumulated at two times the standard floating + * point precision to guard against the loss of accuracy with many-sided + * polygons. At any point you can ask for the perimeter and area so far. + * * An example of the use of this function is given in the documentation for * geod_polygon_compute(). **********************************************************************/ void geod_polygon_init(struct geod_polygon* p, int polylinep); + /** + * Clear the polygon, allowing a new polygon to be started. + * + * @param[in,out] p a pointer to the object to be cleared. + **********************************************************************/ + void geod_polygon_clear(struct geod_polygon* p); + /** * Add a point to the polygon or polyline. * @@ -544,8 +701,7 @@ extern "C" { * \e g and \e p must have been initialized with calls to geod_init() and * geod_polygon_init(), respectively. The same \e g must be used for all the * points and edges in a polygon. \e lat should be in the range - * [−90°, 90°] and \e lon should be in the range - * [−540°, 540°). + * [−90°, 90°]. * * An example of the use of this function is given in the documentation for * geod_polygon_compute(). @@ -566,10 +722,9 @@ extern "C" { * * \e g and \e p must have been initialized with calls to geod_init() and * geod_polygon_init(), respectively. The same \e g must be used for all the - * points and edges in a polygon. \e azi should be in the range - * [−540°, 540°). This does nothing if no points have been - * added yet. The \e lat and \e lon fields of \e p give the location of - * the new vertex. + * points and edges in a polygon. This does nothing if no points have been + * added yet. The \e lat and \e lon fields of \e p give the location of the + * new vertex. **********************************************************************/ void geod_polygon_addedge(const struct geod_geodesic* g, struct geod_polygon* p, @@ -592,14 +747,18 @@ extern "C" { * polyline (meters). * @return the number of points. * - * Only simple polygons (which are not self-intersecting) are allowed. - * There's no need to "close" the polygon by repeating the first vertex. Set - * \e pA or \e pP to zero, if you do not want the corresponding quantity - * returned. + * The area and perimeter are accumulated at two times the standard floating + * point precision to guard against the loss of accuracy with many-sided + * polygons. Only simple polygons (which are not self-intersecting) are + * allowed. There's no need to "close" the polygon by repeating the first + * vertex. Set \e pA or \e pP to zero, if you do not want the corresponding + * quantity returned. + * + * More points can be added to the polygon after this call. * * Example, compute the perimeter and area of the geodesic triangle with * vertices (0°N,0°E), (0°N,90°E), (90°N,0°E). - @code + @code{.c} double A, P; int n; struct geod_geodesic g; @@ -643,8 +802,7 @@ extern "C" { * polyline (meters). * @return the number of points. * - * \e lat should be in the range [−90°, 90°] and \e - * lon should be in the range [−540°, 540°). + * \e lat should be in the range [−90°, 90°]. **********************************************************************/ unsigned geod_polygon_testpoint(const struct geod_geodesic* g, const struct geod_polygon* p, @@ -676,8 +834,6 @@ extern "C" { * @param[out] pP pointer to the perimeter of the polygon or length of the * polyline (meters). * @return the number of points. - * - * \e azi should be in the range [−540°, 540°). **********************************************************************/ unsigned geod_polygon_testedge(const struct geod_geodesic* g, const struct geod_polygon* p, @@ -696,16 +852,15 @@ extern "C" { * @param[out] pA pointer to the area of the polygon (meters2). * @param[out] pP pointer to the perimeter of the polygon (meters). * - * \e lats should be in the range [−90°, 90°]; \e lons should - * be in the range [−540°, 540°). + * \e lats should be in the range [−90°, 90°]. * * Only simple polygons (which are not self-intersecting) are allowed. * There's no need to "close" the polygon by repeating the first vertex. The * area returned is signed with counter-clockwise traversal being treated as * positive. * - * Example, compute the area of Antarctic: - @code + * Example, compute the area of Antarctica: + @code{.c} double lats[] = {-72.9, -71.9, -74.9, -74.3, -77.5, -77.4, -71.7, -65.9, -65.7, -66.6, -66.9, -69.8, -70.0, -71.0, -77.3, -77.9, -74.7}, @@ -723,19 +878,29 @@ extern "C" { double* pA, double* pP); /** - * mask values for the the \e caps argument to geod_lineinit(). + * mask values for the \e caps argument to geod_lineinit(). **********************************************************************/ enum geod_mask { - GEOD_NONE = 0U, /**< Calculate nothing */ - GEOD_LATITUDE = 1U<<7 | 0U, /**< Calculate latitude */ - GEOD_LONGITUDE = 1U<<8 | 1U<<3, /**< Calculate longitude */ - GEOD_AZIMUTH = 1U<<9 | 0U, /**< Calculate azimuth */ - GEOD_DISTANCE = 1U<<10 | 1U<<0, /**< Calculate distance */ - GEOD_DISTANCE_IN = 1U<<11 | 1U<<0 | 1U<<1, /**< Allow distance as input */ - GEOD_REDUCEDLENGTH= 1U<<12 | 1U<<0 | 1U<<2, /**< Calculate reduced length */ - GEOD_GEODESICSCALE= 1U<<13 | 1U<<0 | 1U<<2, /**< Calculate geodesic scale */ - GEOD_AREA = 1U<<14 | 1U<<4, /**< Calculate reduced length */ - GEOD_ALL = 0x7F80U| 0x1FU /**< Calculate everything */ + GEOD_NONE = 0U, /**< Calculate nothing */ + GEOD_LATITUDE = 1U<<7 | 0U, /**< Calculate latitude */ + GEOD_LONGITUDE = 1U<<8 | 1U<<3, /**< Calculate longitude */ + GEOD_AZIMUTH = 1U<<9 | 0U, /**< Calculate azimuth */ + GEOD_DISTANCE = 1U<<10 | 1U<<0, /**< Calculate distance */ + GEOD_DISTANCE_IN = 1U<<11 | 1U<<0 | 1U<<1,/**< Allow distance as input */ + GEOD_REDUCEDLENGTH= 1U<<12 | 1U<<0 | 1U<<2,/**< Calculate reduced length */ + GEOD_GEODESICSCALE= 1U<<13 | 1U<<0 | 1U<<2,/**< Calculate geodesic scale */ + GEOD_AREA = 1U<<14 | 1U<<4, /**< Calculate reduced length */ + GEOD_ALL = 0x7F80U| 0x1FU /**< Calculate everything */ + }; + + /** + * flag values for the \e flags argument to geod_gendirect() and + * geod_genposition() + **********************************************************************/ + enum geod_flags { + GEOD_NOFLAGS = 0U, /**< No flags */ + GEOD_ARCMODE = 1U<<0, /**< Position given in terms of arc distance */ + GEOD_LONG_UNROLL = 1U<<15 /**< Unroll the longitude */ }; #if defined(__cplusplus) diff --git a/gtsam/3rdparty/GeographicLib/legacy/C/geodtest.c b/gtsam/3rdparty/GeographicLib/legacy/C/geodtest.c new file mode 100644 index 000000000..6899436c0 --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/legacy/C/geodtest.c @@ -0,0 +1,829 @@ +/** + * \file geodtest.c + * \brief Test suite for the geodesic routines in C + * + * Run these tests by configuring with cmake and running "make test". + * + * Copyright (c) Charles Karney (2015-2017) and licensed + * under the MIT/X11 License. For more information, see + * https://geographiclib.sourceforge.io/ + **********************************************************************/ + +/** @cond SKIP */ + +#include "geodesic.h" +#include +#include + +#if defined(_MSC_VER) +/* Squelch warnings about assignment within conditional expression */ +# pragma warning (disable: 4706) +#endif + +double wgs84_a = 6378137, wgs84_f = 1/298.257223563; /* WGS84 */ + +static int assertEquals(double x, double y, double d) { + if (fabs(x - y) <= d) + return 0; + printf("assertEquals fails: %.7g != %.7g +/- %.7g\n", x, y, d); + return 1; +} + +const int ncases = 20; +double testcases[20][12] = { + {35.60777, -139.44815, 111.098748429560326, + -11.17491, -69.95921, 129.289270889708762, + 8935244.5604818305, 80.50729714281974, 6273170.2055303837, + 0.16606318447386067, 0.16479116945612937, 12841384694976.432}, + {55.52454, 106.05087, 22.020059880982801, + 77.03196, 197.18234, 109.112041110671519, + 4105086.1713924406, 36.892740690445894, 3828869.3344387607, + 0.80076349608092607, 0.80101006984201008, 61674961290615.615}, + {-21.97856, 142.59065, -32.44456876433189, + 41.84138, 98.56635, -41.84359951440466, + 8394328.894657671, 75.62930491011522, 6161154.5773110616, + 0.24816339233950381, 0.24930251203627892, -6637997720646.717}, + {-66.99028, 112.2363, 173.73491240878403, + -12.70631, 285.90344, 2.512956620913668, + 11150344.2312080241, 100.278634181155759, 6289939.5670446687, + -0.17199490274700385, -0.17722569526345708, -121287239862139.744}, + {-17.42761, 173.34268, -159.033557661192928, + -15.84784, 5.93557, -20.787484651536988, + 16076603.1631180673, 144.640108810286253, 3732902.1583877189, + -0.81273638700070476, -0.81299800519154474, 97825992354058.708}, + {32.84994, 48.28919, 150.492927788121982, + -56.28556, 202.29132, 48.113449399816759, + 16727068.9438164461, 150.565799985466607, 3147838.1910180939, + -0.87334918086923126, -0.86505036767110637, -72445258525585.010}, + {6.96833, 52.74123, 92.581585386317712, + -7.39675, 206.17291, 90.721692165923907, + 17102477.2496958388, 154.147366239113561, 2772035.6169917581, + -0.89991282520302447, -0.89986892177110739, -1311796973197.995}, + {-50.56724, -16.30485, -105.439679907590164, + -33.56571, -94.97412, -47.348547835650331, + 6455670.5118668696, 58.083719495371259, 5409150.7979815838, + 0.53053508035997263, 0.52988722644436602, 41071447902810.047}, + {-58.93002, -8.90775, 140.965397902500679, + -8.91104, 133.13503, 19.255429433416599, + 11756066.0219864627, 105.755691241406877, 6151101.2270708536, + -0.26548622269867183, -0.27068483874510741, -86143460552774.735}, + {-68.82867, -74.28391, 93.774347763114881, + -50.63005, -8.36685, 34.65564085411343, + 3956936.926063544, 35.572254987389284, 3708890.9544062657, + 0.81443963736383502, 0.81420859815358342, -41845309450093.787}, + {-10.62672, -32.0898, -86.426713286747751, + 5.883, -134.31681, -80.473780971034875, + 11470869.3864563009, 103.387395634504061, 6184411.6622659713, + -0.23138683500430237, -0.23155097622286792, 4198803992123.548}, + {-21.76221, 166.90563, 29.319421206936428, + 48.72884, 213.97627, 43.508671946410168, + 9098627.3986554915, 81.963476716121964, 6299240.9166992283, + 0.13965943368590333, 0.14152969707656796, 10024709850277.476}, + {-19.79938, -174.47484, 71.167275780171533, + -11.99349, -154.35109, 65.589099775199228, + 2319004.8601169389, 20.896611684802389, 2267960.8703918325, + 0.93427001867125849, 0.93424887135032789, -3935477535005.785}, + {-11.95887, -116.94513, 92.712619830452549, + 4.57352, 7.16501, 78.64960934409585, + 13834722.5801401374, 124.688684161089762, 5228093.177931598, + -0.56879356755666463, -0.56918731952397221, -9919582785894.853}, + {-87.85331, 85.66836, -65.120313040242748, + 66.48646, 16.09921, -4.888658719272296, + 17286615.3147144645, 155.58592449699137, 2635887.4729110181, + -0.90697975771398578, -0.91095608883042767, 42667211366919.534}, + {1.74708, 128.32011, -101.584843631173858, + -11.16617, 11.87109, -86.325793296437476, + 12942901.1241347408, 116.650512484301857, 5682744.8413270572, + -0.44857868222697644, -0.44824490340007729, 10763055294345.653}, + {-25.72959, -144.90758, -153.647468693117198, + -57.70581, -269.17879, -48.343983158876487, + 9413446.7452453107, 84.664533838404295, 6356176.6898881281, + 0.09492245755254703, 0.09737058264766572, 74515122850712.444}, + {-41.22777, 122.32875, 14.285113402275739, + -7.57291, 130.37946, 10.805303085187369, + 3812686.035106021, 34.34330804743883, 3588703.8812128856, + 0.82605222593217889, 0.82572158200920196, -2456961531057.857}, + {11.01307, 138.25278, 79.43682622782374, + 6.62726, 247.05981, 103.708090215522657, + 11911190.819018408, 107.341669954114577, 6070904.722786735, + -0.29767608923657404, -0.29785143390252321, 17121631423099.696}, + {-29.47124, 95.14681, -163.779130441688382, + -27.46601, -69.15955, -15.909335945554969, + 13487015.8381145492, 121.294026715742277, 5481428.9945736388, + -0.51527225545373252, -0.51556587964721788, 104679964020340.318}}; + +static int testinverse() { + double lat1, lon1, azi1, lat2, lon2, azi2, s12, a12, m12, M12, M21, S12; + double azi1a, azi2a, s12a, a12a, m12a, M12a, M21a, S12a; + struct geod_geodesic g; + int i, result = 0; + geod_init(&g, wgs84_a, wgs84_f); + for (i = 0; i < ncases; ++i) { + lat1 = testcases[i][0]; lon1 = testcases[i][1]; azi1 = testcases[i][2]; + lat2 = testcases[i][3]; lon2 = testcases[i][4]; azi2 = testcases[i][5]; + s12 = testcases[i][6]; a12 = testcases[i][7]; m12 = testcases[i][8]; + M12 = testcases[i][9]; M21 = testcases[i][10]; S12 = testcases[i][11]; + a12a = geod_geninverse(&g, lat1, lon1, lat2, lon2, &s12a, &azi1a, &azi2a, + &m12a, &M12a, &M21a, &S12a); + result += assertEquals(azi1, azi1a, 1e-13); + result += assertEquals(azi2, azi2a, 1e-13); + result += assertEquals(s12, s12a, 1e-8); + result += assertEquals(a12, a12a, 1e-13); + result += assertEquals(m12, m12a, 1e-8); + result += assertEquals(M12, M12a, 1e-15); + result += assertEquals(M21, M21a, 1e-15); + result += assertEquals(S12, S12a, 0.1); + } + return result; +} + +static int testdirect() { + double lat1, lon1, azi1, lat2, lon2, azi2, s12, a12, m12, M12, M21, S12; + double lat2a, lon2a, azi2a, a12a, m12a, M12a, M21a, S12a; + struct geod_geodesic g; + int i, result = 0; + unsigned flags = GEOD_LONG_UNROLL; + geod_init(&g, wgs84_a, wgs84_f); + for (i = 0; i < ncases; ++i) { + lat1 = testcases[i][0]; lon1 = testcases[i][1]; azi1 = testcases[i][2]; + lat2 = testcases[i][3]; lon2 = testcases[i][4]; azi2 = testcases[i][5]; + s12 = testcases[i][6]; a12 = testcases[i][7]; m12 = testcases[i][8]; + M12 = testcases[i][9]; M21 = testcases[i][10]; S12 = testcases[i][11]; + a12a = geod_gendirect(&g, lat1, lon1, azi1, flags, s12, + &lat2a, &lon2a, &azi2a, 0, + &m12a, &M12a, &M21a, &S12a); + result += assertEquals(lat2, lat2a, 1e-13); + result += assertEquals(lon2, lon2a, 1e-13); + result += assertEquals(azi2, azi2a, 1e-13); + result += assertEquals(a12, a12a, 1e-13); + result += assertEquals(m12, m12a, 1e-8); + result += assertEquals(M12, M12a, 1e-15); + result += assertEquals(M21, M21a, 1e-15); + result += assertEquals(S12, S12a, 0.1); + } + return result; +} + +static int testarcdirect() { + double lat1, lon1, azi1, lat2, lon2, azi2, s12, a12, m12, M12, M21, S12; + double lat2a, lon2a, azi2a, s12a, m12a, M12a, M21a, S12a; + struct geod_geodesic g; + int i, result = 0; + unsigned flags = GEOD_ARCMODE | GEOD_LONG_UNROLL; + geod_init(&g, wgs84_a, wgs84_f); + for (i = 0; i < ncases; ++i) { + lat1 = testcases[i][0]; lon1 = testcases[i][1]; azi1 = testcases[i][2]; + lat2 = testcases[i][3]; lon2 = testcases[i][4]; azi2 = testcases[i][5]; + s12 = testcases[i][6]; a12 = testcases[i][7]; m12 = testcases[i][8]; + M12 = testcases[i][9]; M21 = testcases[i][10]; S12 = testcases[i][11]; + geod_gendirect(&g, lat1, lon1, azi1, flags, a12, + &lat2a, &lon2a, &azi2a, &s12a, &m12a, &M12a, &M21a, &S12a); + result += assertEquals(lat2, lat2a, 1e-13); + result += assertEquals(lon2, lon2a, 1e-13); + result += assertEquals(azi2, azi2a, 1e-13); + result += assertEquals(s12, s12a, 1e-8); + result += assertEquals(m12, m12a, 1e-8); + result += assertEquals(M12, M12a, 1e-15); + result += assertEquals(M21, M21a, 1e-15); + result += assertEquals(S12, S12a, 0.1); + } + return result; +} + +static int GeodSolve0() { + double azi1, azi2, s12; + struct geod_geodesic g; + int result = 0; + geod_init(&g, wgs84_a, wgs84_f); + geod_inverse(&g, 40.6, -73.8, 49.01666667, 2.55, &s12, &azi1, &azi2); + result += assertEquals(azi1, 53.47022, 0.5e-5); + result += assertEquals(azi2, 111.59367, 0.5e-5); + result += assertEquals(s12, 5853226, 0.5); + return result; +} + +static int GeodSolve1() { + double lat2, lon2, azi2; + struct geod_geodesic g; + int result = 0; + geod_init(&g, wgs84_a, wgs84_f); + geod_direct(&g, 40.63972222, -73.77888889, 53.5, 5850e3, + &lat2, &lon2, &azi2); + result += assertEquals(lat2, 49.01467, 0.5e-5); + result += assertEquals(lon2, 2.56106, 0.5e-5); + result += assertEquals(azi2, 111.62947, 0.5e-5); + return result; +} + +static int GeodSolve2() { + /* Check fix for antipodal prolate bug found 2010-09-04 */ + double azi1, azi2, s12; + struct geod_geodesic g; + int result = 0; + geod_init(&g, 6.4e6, -1/150.0); + geod_inverse(&g, 0.07476, 0, -0.07476, 180, &s12, &azi1, &azi2); + result += assertEquals(azi1, 90.00078, 0.5e-5); + result += assertEquals(azi2, 90.00078, 0.5e-5); + result += assertEquals(s12, 20106193, 0.5); + geod_inverse(&g, 0.1, 0, -0.1, 180, &s12, &azi1, &azi2); + result += assertEquals(azi1, 90.00105, 0.5e-5); + result += assertEquals(azi2, 90.00105, 0.5e-5); + result += assertEquals(s12, 20106193, 0.5); + return result; +} + +static int GeodSolve4() { + /* Check fix for short line bug found 2010-05-21 */ + double s12; + struct geod_geodesic g; + int result = 0; + geod_init(&g, wgs84_a, wgs84_f); + geod_inverse(&g, 36.493349428792, 0, 36.49334942879201, .0000008, + &s12, 0, 0); + result += assertEquals(s12, 0.072, 0.5e-3); + return result; +} + +static int GeodSolve5() { + /* Check fix for point2=pole bug found 2010-05-03 */ + double lat2, lon2, azi2; + struct geod_geodesic g; + int result = 0; + geod_init(&g, wgs84_a, wgs84_f); + geod_direct(&g, 0.01777745589997, 30, 0, 10e6, &lat2, &lon2, &azi2); + result += assertEquals(lat2, 90, 0.5e-5); + if (lon2 < 0) { + result += assertEquals(lon2, -150, 0.5e-5); + result += assertEquals(fabs(azi2), 180, 0.5e-5); + } else { + result += assertEquals(lon2, 30, 0.5e-5); + result += assertEquals(azi2, 0, 0.5e-5); + } + return result; +} + +static int GeodSolve6() { + /* Check fix for volatile sbet12a bug found 2011-06-25 (gcc 4.4.4 + * x86 -O3). Found again on 2012-03-27 with tdm-mingw32 (g++ 4.6.1). */ + double s12; + struct geod_geodesic g; + int result = 0; + geod_init(&g, wgs84_a, wgs84_f); + geod_inverse(&g, 88.202499451857, 0, + -88.202499451857, 179.981022032992859592, &s12, 0, 0); + result += assertEquals(s12, 20003898.214, 0.5e-3); + geod_inverse(&g, 89.262080389218, 0, + -89.262080389218, 179.992207982775375662, &s12, 0, 0); + result += assertEquals(s12, 20003925.854, 0.5e-3); + geod_inverse(&g, 89.333123580033, 0, + -89.333123580032997687, 179.99295812360148422, &s12, 0, 0); + result += assertEquals(s12, 20003926.881, 0.5e-3); + return result; +} + +static int GeodSolve9() { + /* Check fix for volatile x bug found 2011-06-25 (gcc 4.4.4 x86 -O3) */ + double s12; + struct geod_geodesic g; + int result = 0; + geod_init(&g, wgs84_a, wgs84_f); + geod_inverse(&g, 56.320923501171, 0, + -56.320923501171, 179.664747671772880215, &s12, 0, 0); + result += assertEquals(s12, 19993558.287, 0.5e-3); + return result; +} + +static int GeodSolve10() { + /* Check fix for adjust tol1_ bug found 2011-06-25 (Visual Studio + * 10 rel + debug) */ + double s12; + struct geod_geodesic g; + int result = 0; + geod_init(&g, wgs84_a, wgs84_f); + geod_inverse(&g, 52.784459512564, 0, + -52.784459512563990912, 179.634407464943777557, &s12, 0, 0); + result += assertEquals(s12, 19991596.095, 0.5e-3); + return result; +} + +static int GeodSolve11() { + /* Check fix for bet2 = -bet1 bug found 2011-06-25 (Visual Studio + * 10 rel + debug) */ + double s12; + struct geod_geodesic g; + int result = 0; + geod_init(&g, wgs84_a, wgs84_f); + geod_inverse(&g, 48.522876735459, 0, + -48.52287673545898293, 179.599720456223079643, &s12, 0, 0); + result += assertEquals(s12, 19989144.774, 0.5e-3); + return result; +} + +static int GeodSolve12() { + /* Check fix for inverse geodesics on extreme prolate/oblate + * ellipsoids Reported 2012-08-29 Stefan Guenther + * ; fixed 2012-10-07 */ + double azi1, azi2, s12; + struct geod_geodesic g; + int result = 0; + geod_init(&g, 89.8, -1.83); + geod_inverse(&g, 0, 0, -10, 160, &s12, &azi1, &azi2); + result += assertEquals(azi1, 120.27, 1e-2); + result += assertEquals(azi2, 105.15, 1e-2); + result += assertEquals(s12, 266.7, 1e-1); + return result; +} + +static int GeodSolve14() { + /* Check fix for inverse ignoring lon12 = nan */ + double azi1, azi2, s12, nan; + struct geod_geodesic g; + int result = 0; + { + double minus1 = -1; + nan = sqrt(minus1); + } + geod_init(&g, wgs84_a, wgs84_f); + geod_inverse(&g, 0, 0, 1, nan, &s12, &azi1, &azi2); + result += azi1 == azi1 ? 1 : 0; + result += azi2 == azi2 ? 1 : 0; + result += s12 == s12 ? 1 : 0; + return result; +} + +static int GeodSolve15() { + /* Initial implementation of Math::eatanhe was wrong for e^2 < 0. This + * checks that this is fixed. */ + double S12; + struct geod_geodesic g; + int result = 0; + geod_init(&g, 6.4e6, -1/150.0); + geod_gendirect(&g, 1, 2, 3, 0, 4, + 0, 0, 0, 0, 0, 0, 0, &S12); + result += assertEquals(S12, 23700, 0.5); + return result; +} + +static int GeodSolve17() { + /* Check fix for LONG_UNROLL bug found on 2015-05-07 */ + double lat2, lon2, azi2; + struct geod_geodesic g; + struct geod_geodesicline l; + int result = 0; + unsigned flags = GEOD_LONG_UNROLL; + geod_init(&g, wgs84_a, wgs84_f); + geod_gendirect(&g, 40, -75, -10, flags, 2e7, + &lat2, &lon2, &azi2, 0, 0, 0, 0, 0); + result += assertEquals(lat2, -39, 1); + result += assertEquals(lon2, -254, 1); + result += assertEquals(azi2, -170, 1); + geod_lineinit(&l, &g, 40, -75, -10, 0); + geod_genposition(&l, flags, 2e7, &lat2, &lon2, &azi2, 0, 0, 0, 0, 0); + result += assertEquals(lat2, -39, 1); + result += assertEquals(lon2, -254, 1); + result += assertEquals(azi2, -170, 1); + geod_direct(&g, 40, -75, -10, 2e7, &lat2, &lon2, &azi2); + result += assertEquals(lat2, -39, 1); + result += assertEquals(lon2, 105, 1); + result += assertEquals(azi2, -170, 1); + geod_position(&l, 2e7, &lat2, &lon2, &azi2); + result += assertEquals(lat2, -39, 1); + result += assertEquals(lon2, 105, 1); + result += assertEquals(azi2, -170, 1); + return result; +} + +static int GeodSolve26() { + /* Check 0/0 problem with area calculation on sphere 2015-09-08 */ + double S12; + struct geod_geodesic g; + int result = 0; + geod_init(&g, 6.4e6, 0); + geod_geninverse(&g, 1, 2, 3, 4, 0, 0, 0, 0, 0, 0, &S12); + result += assertEquals(S12, 49911046115.0, 0.5); + return result; +} + +static int GeodSolve28() { + /* Check for bad placement of assignment of r.a12 with |f| > 0.01 (bug in + * Java implementation fixed on 2015-05-19). */ + double a12; + struct geod_geodesic g; + int result = 0; + geod_init(&g, 6.4e6, 0.1); + a12 = geod_gendirect(&g, 1, 2, 10, 0, 5e6, 0, 0, 0, 0, 0, 0, 0, 0); + result += assertEquals(a12, 48.55570690, 0.5e-8); + return result; +} + +static int GeodSolve33() { + /* Check max(-0.0,+0.0) issues 2015-08-22 (triggered by bugs in Octave -- + * sind(-0.0) = +0.0 -- and in some version of Visual Studio -- + * fmod(-0.0, 360.0) = +0.0. */ + double azi1, azi2, s12; + struct geod_geodesic g; + int result = 0; + geod_init(&g, wgs84_a, wgs84_f); + geod_inverse(&g, 0, 0, 0, 179, &s12, &azi1, &azi2); + result += assertEquals(azi1, 90.00000, 0.5e-5); + result += assertEquals(azi2, 90.00000, 0.5e-5); + result += assertEquals(s12, 19926189, 0.5); + geod_inverse(&g, 0, 0, 0, 179.5, &s12, &azi1, &azi2); + result += assertEquals(azi1, 55.96650, 0.5e-5); + result += assertEquals(azi2, 124.03350, 0.5e-5); + result += assertEquals(s12, 19980862, 0.5); + geod_inverse(&g, 0, 0, 0, 180, &s12, &azi1, &azi2); + result += assertEquals(azi1, 0.00000, 0.5e-5); + result += assertEquals(fabs(azi2), 180.00000, 0.5e-5); + result += assertEquals(s12, 20003931, 0.5); + geod_inverse(&g, 0, 0, 1, 180, &s12, &azi1, &azi2); + result += assertEquals(azi1, 0.00000, 0.5e-5); + result += assertEquals(fabs(azi2), 180.00000, 0.5e-5); + result += assertEquals(s12, 19893357, 0.5); + geod_init(&g, 6.4e6, 0); + geod_inverse(&g, 0, 0, 0, 179, &s12, &azi1, &azi2); + result += assertEquals(azi1, 90.00000, 0.5e-5); + result += assertEquals(azi2, 90.00000, 0.5e-5); + result += assertEquals(s12, 19994492, 0.5); + geod_inverse(&g, 0, 0, 0, 180, &s12, &azi1, &azi2); + result += assertEquals(azi1, 0.00000, 0.5e-5); + result += assertEquals(fabs(azi2), 180.00000, 0.5e-5); + result += assertEquals(s12, 20106193, 0.5); + geod_inverse(&g, 0, 0, 1, 180, &s12, &azi1, &azi2); + result += assertEquals(azi1, 0.00000, 0.5e-5); + result += assertEquals(fabs(azi2), 180.00000, 0.5e-5); + result += assertEquals(s12, 19994492, 0.5); + geod_init(&g, 6.4e6, -1/300.0); + geod_inverse(&g, 0, 0, 0, 179, &s12, &azi1, &azi2); + result += assertEquals(azi1, 90.00000, 0.5e-5); + result += assertEquals(azi2, 90.00000, 0.5e-5); + result += assertEquals(s12, 19994492, 0.5); + geod_inverse(&g, 0, 0, 0, 180, &s12, &azi1, &azi2); + result += assertEquals(azi1, 90.00000, 0.5e-5); + result += assertEquals(azi2, 90.00000, 0.5e-5); + result += assertEquals(s12, 20106193, 0.5); + geod_inverse(&g, 0, 0, 0.5, 180, &s12, &azi1, &azi2); + result += assertEquals(azi1, 33.02493, 0.5e-5); + result += assertEquals(azi2, 146.97364, 0.5e-5); + result += assertEquals(s12, 20082617, 0.5); + geod_inverse(&g, 0, 0, 1, 180, &s12, &azi1, &azi2); + result += assertEquals(azi1, 0.00000, 0.5e-5); + result += assertEquals(fabs(azi2), 180.00000, 0.5e-5); + result += assertEquals(s12, 20027270, 0.5); + + return result; +} + +static int GeodSolve55() { + /* Check fix for nan + point on equator or pole not returning all nans in + * Geodesic::Inverse, found 2015-09-23. */ + double azi1, azi2, s12, nan; + struct geod_geodesic g; + int result = 0; + { + double minus1 = -1; + nan = sqrt(minus1); + } + geod_init(&g, wgs84_a, wgs84_f); + geod_inverse(&g, nan, 0, 0, 90, &s12, &azi1, &azi2); + result += azi1 == azi1 ? 1 : 0; + result += azi2 == azi2 ? 1 : 0; + result += s12 == s12 ? 1 : 0; + geod_inverse(&g, nan, 0, 90, 9, &s12, &azi1, &azi2); + result += azi1 == azi1 ? 1 : 0; + result += azi2 == azi2 ? 1 : 0; + result += s12 == s12 ? 1 : 0; + return result; +} + +static int GeodSolve59() { + /* Check for points close with longitudes close to 180 deg apart. */ + double azi1, azi2, s12; + struct geod_geodesic g; + int result = 0; + geod_init(&g, wgs84_a, wgs84_f); + geod_inverse(&g, 5, 0.00000000000001, 10, 180, &s12, &azi1, &azi2); + result += assertEquals(azi1, 0.000000000000035, 1.5e-14); + result += assertEquals(azi2, 179.99999999999996, 1.5e-14); + result += assertEquals(s12, 18345191.174332713, 2.5e-9); + return result; +} + +static int GeodSolve61() { + /* Make sure small negative azimuths are west-going */ + double lat2, lon2, azi2; + struct geod_geodesic g; + struct geod_geodesicline l; + int result = 0; + unsigned flags = GEOD_LONG_UNROLL; + geod_init(&g, wgs84_a, wgs84_f); + geod_gendirect(&g, 45, 0, -0.000000000000000003, flags, 1e7, + &lat2, &lon2, &azi2, 0, 0, 0, 0, 0); + result += assertEquals(lat2, 45.30632, 0.5e-5); + result += assertEquals(lon2, -180, 0.5e-5); + result += assertEquals(fabs(azi2), 180, 0.5e-5); + geod_inverseline(&l, &g, 45, 0, 80, -0.000000000000000003, 0); + geod_genposition(&l, flags, 1e7, &lat2, &lon2, &azi2, 0, 0, 0, 0, 0); + result += assertEquals(lat2, 45.30632, 0.5e-5); + result += assertEquals(lon2, -180, 0.5e-5); + result += assertEquals(fabs(azi2), 180, 0.5e-5); + return result; +} + +static int GeodSolve65() { + /* Check for bug in east-going check in GeodesicLine (needed to check for + * sign of 0) and sign error in area calculation due to a bogus override of + * the code for alp12. Found/fixed on 2015-12-19. */ + double lat2, lon2, azi2, s12, a12, m12, M12, M21, S12; + struct geod_geodesic g; + struct geod_geodesicline l; + int result = 0; + unsigned flags = GEOD_LONG_UNROLL, caps = GEOD_ALL; + geod_init(&g, wgs84_a, wgs84_f); + geod_inverseline(&l, &g, 30, -0.000000000000000001, -31, 180, caps); + a12 = geod_genposition(&l, flags, 1e7, + &lat2, &lon2, &azi2, &s12, &m12, &M12, &M21, &S12); + result += assertEquals(lat2, -60.23169, 0.5e-5); + result += assertEquals(lon2, -0.00000, 0.5e-5); + result += assertEquals(fabs(azi2), 180.00000, 0.5e-5); + result += assertEquals(s12, 10000000, 0.5); + result += assertEquals(a12, 90.06544, 0.5e-5); + result += assertEquals(m12, 6363636, 0.5); + result += assertEquals(M12, -0.0012834, 0.5e-7); + result += assertEquals(M21, 0.0013749, 0.5e-7); + result += assertEquals(S12, 0, 0.5); + a12 = geod_genposition(&l, flags, 2e7, + &lat2, &lon2, &azi2, &s12, &m12, &M12, &M21, &S12); + result += assertEquals(lat2, -30.03547, 0.5e-5); + result += assertEquals(lon2, -180.00000, 0.5e-5); + result += assertEquals(azi2, -0.00000, 0.5e-5); + result += assertEquals(s12, 20000000, 0.5); + result += assertEquals(a12, 179.96459, 0.5e-5); + result += assertEquals(m12, 54342, 0.5); + result += assertEquals(M12, -1.0045592, 0.5e-7); + result += assertEquals(M21, -0.9954339, 0.5e-7); + result += assertEquals(S12, 127516405431022.0, 0.5); + return result; +} + +static int GeodSolve67() { + /* Check for InverseLine if line is slightly west of S and that s13 is + correctly set. */ + double lat2, lon2, azi2; + struct geod_geodesic g; + struct geod_geodesicline l; + int result = 0; + unsigned flags = GEOD_LONG_UNROLL; + geod_init(&g, wgs84_a, wgs84_f); + geod_inverseline(&l, &g, -5, -0.000000000000002, -10, 180, 0); + geod_genposition(&l, flags, 2e7, &lat2, &lon2, &azi2, 0, 0, 0, 0, 0); + result += assertEquals(lat2, 4.96445, 0.5e-5); + result += assertEquals(lon2, -180.00000, 0.5e-5); + result += assertEquals(azi2, -0.00000, 0.5e-5); + geod_genposition(&l, flags, 0.5 * l.s13, &lat2, &lon2, &azi2, 0, 0, 0, 0, 0); + result += assertEquals(lat2, -87.52461, 0.5e-5); + result += assertEquals(lon2, -0.00000, 0.5e-5); + result += assertEquals(azi2, -180.00000, 0.5e-5); + return result; +} + +static int GeodSolve71() { + /* Check that DirectLine sets s13. */ + double lat2, lon2, azi2; + struct geod_geodesic g; + struct geod_geodesicline l; + int result = 0; + geod_init(&g, wgs84_a, wgs84_f); + geod_directline(&l, &g, 1, 2, 45, 1e7, 0); + geod_position(&l, 0.5 * l.s13, &lat2, &lon2, &azi2); + result += assertEquals(lat2, 30.92625, 0.5e-5); + result += assertEquals(lon2, 37.54640, 0.5e-5); + result += assertEquals(azi2, 55.43104, 0.5e-5); + return result; +} + +static int GeodSolve73() { + /* Check for backwards from the pole bug reported by Anon on 2016-02-13. + * This only affected the Java implementation. It was introduced in Java + * version 1.44 and fixed in 1.46-SNAPSHOT on 2016-01-17. */ + double lat2, lon2, azi2; + struct geod_geodesic g; + int result = 0; + geod_init(&g, wgs84_a, wgs84_f); + geod_direct(&g, 90, 10, 180, -1e6, + &lat2, &lon2, &azi2); + result += assertEquals(lat2, 81.04623, 0.5e-5); + result += assertEquals(lon2, -170, 0.5e-5); + result += assertEquals(azi2, 0, 0.5e-5); + return result; +} + +static void planimeter(const struct geod_geodesic* g, + double points[][2], int N, + double* perimeter, double* area) { + struct geod_polygon p; + int i; + geod_polygon_init(&p, 0); + for (i = 0; i < N; ++i) + geod_polygon_addpoint(g, &p, points[i][0], points[i][1]); + geod_polygon_compute(g, &p, 0, 1, area, perimeter); +} + +static void polylength(const struct geod_geodesic* g, + double points[][2], int N, + double* perimeter) { + struct geod_polygon p; + int i; + geod_polygon_init(&p, 1); + for (i = 0; i < N; ++i) + geod_polygon_addpoint(g, &p, points[i][0], points[i][1]); + geod_polygon_compute(g, &p, 0, 1, 0, perimeter); +} + +static int GeodSolve74() { + /* Check fix for inaccurate areas, bug introduced in v1.46, fixed + 2015-10-16. */ + double a12, s12, azi1, azi2, m12, M12, M21, S12; + struct geod_geodesic g; + int result = 0; + geod_init(&g, wgs84_a, wgs84_f); + a12 = geod_geninverse(&g, 54.1589, 15.3872, 54.1591, 15.3877, + &s12, &azi1, &azi2, &m12, &M12, &M21, &S12); + result += assertEquals(azi1, 55.723110355, 5e-9); + result += assertEquals(azi2, 55.723515675, 5e-9); + result += assertEquals(s12, 39.527686385, 5e-9); + result += assertEquals(a12, 0.000355495, 5e-9); + result += assertEquals(m12, 39.527686385, 5e-9); + result += assertEquals(M12, 0.999999995, 5e-9); + result += assertEquals(M21, 0.999999995, 5e-9); + result += assertEquals(S12, 286698586.30197, 5e-4); + return result; +} + +static int GeodSolve76() { + /* The distance from Wellington and Salamanca (a classic failure of + Vincenty) */ + double azi1, azi2, s12; + struct geod_geodesic g; + int result = 0; + geod_init(&g, wgs84_a, wgs84_f); + geod_inverse(&g, -(41+19/60.0), 174+49/60.0, 40+58/60.0, -(5+30/60.0), + &s12, &azi1, &azi2); + result += assertEquals(azi1, 160.39137649664, 0.5e-11); + result += assertEquals(azi2, 19.50042925176, 0.5e-11); + result += assertEquals(s12, 19960543.857179, 0.5e-6); + return result; +} + +static int GeodSolve78() { + /* An example where the NGS calculator fails to converge */ + double azi1, azi2, s12; + struct geod_geodesic g; + int result = 0; + geod_init(&g, wgs84_a, wgs84_f); + geod_inverse(&g, 27.2, 0.0, -27.1, 179.5, &s12, &azi1, &azi2); + result += assertEquals(azi1, 45.82468716758, 0.5e-11); + result += assertEquals(azi2, 134.22776532670, 0.5e-11); + result += assertEquals(s12, 19974354.765767, 0.5e-6); + return result; +} + +static int Planimeter0() { + /* Check fix for pole-encircling bug found 2011-03-16 */ + double pa[4][2] = {{89, 0}, {89, 90}, {89, 180}, {89, 270}}; + double pb[4][2] = {{-89, 0}, {-89, 90}, {-89, 180}, {-89, 270}}; + double pc[4][2] = {{0, -1}, {-1, 0}, {0, 1}, {1, 0}}; + double pd[3][2] = {{90, 0}, {0, 0}, {0, 90}}; + struct geod_geodesic g; + double perimeter, area; + int result = 0; + geod_init(&g, wgs84_a, wgs84_f); + + planimeter(&g, pa, 4, &perimeter, &area); + result += assertEquals(perimeter, 631819.8745, 1e-4); + result += assertEquals(area, 24952305678.0, 1); + + planimeter(&g, pb, 4, &perimeter, &area); + result += assertEquals(perimeter, 631819.8745, 1e-4); + result += assertEquals(area, -24952305678.0, 1); + + planimeter(&g, pc, 4, &perimeter, &area); + result += assertEquals(perimeter, 627598.2731, 1e-4); + result += assertEquals(area, 24619419146.0, 1); + + planimeter(&g, pd, 3, &perimeter, &area); + result += assertEquals(perimeter, 30022685, 1); + result += assertEquals(area, 63758202715511.0, 1); + + polylength(&g, pd, 3, &perimeter); + result += assertEquals(perimeter, 20020719, 1); + + return result; +} + +static int Planimeter5() { + /* Check fix for Planimeter pole crossing bug found 2011-06-24 */ + double points[3][2] = {{89, 0.1}, {89, 90.1}, {89, -179.9}}; + struct geod_geodesic g; + double perimeter, area; + int result = 0; + geod_init(&g, wgs84_a, wgs84_f); + planimeter(&g, points, 3, &perimeter, &area); + result += assertEquals(perimeter, 539297, 1); + result += assertEquals(area, 12476152838.5, 1); + return result; +} + +static int Planimeter6() { + /* Check fix for Planimeter lon12 rounding bug found 2012-12-03 */ + double pa[3][2] = {{9, -0.00000000000001}, {9, 180}, {9, 0}}; + double pb[3][2] = {{9, 0.00000000000001}, {9, 0}, {9, 180}}; + double pc[3][2] = {{9, 0.00000000000001}, {9, 180}, {9, 0}}; + double pd[3][2] = {{9, -0.00000000000001}, {9, 0}, {9, 180}}; + struct geod_geodesic g; + double perimeter, area; + int result = 0; + geod_init(&g, wgs84_a, wgs84_f); + + planimeter(&g, pa, 3, &perimeter, &area); + result += assertEquals(perimeter, 36026861, 1); + result += assertEquals(area, 0, 1); + planimeter(&g, pb, 3, &perimeter, &area); + result += assertEquals(perimeter, 36026861, 1); + result += assertEquals(area, 0, 1); + planimeter(&g, pc, 3, &perimeter, &area); + result += assertEquals(perimeter, 36026861, 1); + result += assertEquals(area, 0, 1); + planimeter(&g, pd, 3, &perimeter, &area); + result += assertEquals(perimeter, 36026861, 1); + result += assertEquals(area, 0, 1); + return result; +} + +static int Planimeter12() { + /* Area of arctic circle (not really -- adjunct to rhumb-area test) */ + double points[2][2] = {{66.562222222, 0}, {66.562222222, 180}}; + struct geod_geodesic g; + double perimeter, area; + int result = 0; + geod_init(&g, wgs84_a, wgs84_f); + planimeter(&g, points, 2, &perimeter, &area); + result += assertEquals(perimeter, 10465729, 1); + result += assertEquals(area, 0, 1); + return result; +} + +static int Planimeter13() { + /* Check encircling pole twice */ + double points[6][2] = {{89,-360}, {89,-240}, {89,-120}, + {89,0}, {89,120}, {89,240}}; + struct geod_geodesic g; + double perimeter, area; + int result = 0; + geod_init(&g, wgs84_a, wgs84_f); + planimeter(&g, points, 6, &perimeter, &area); + result += assertEquals(perimeter, 1160741, 1); + result += assertEquals(area, 32415230256.0, 1); + return result; +} + +int main() { + int n = 0, i; + if ((i = testinverse())) {++n; printf("testinverse fail: %d\n", i);} + if ((i = testdirect())) {++n; printf("testdirect fail: %d\n", i);} + if ((i = testarcdirect())) {++n; printf("testarcdirect fail: %d\n", i);} + if ((i = GeodSolve0())) {++n; printf("GeodSolve0 fail: %d\n", i);} + if ((i = GeodSolve1())) {++n; printf("GeodSolve1 fail: %d\n", i);} + if ((i = GeodSolve2())) {++n; printf("GeodSolve2 fail: %d\n", i);} + if ((i = GeodSolve4())) {++n; printf("GeodSolve4 fail: %d\n", i);} + if ((i = GeodSolve5())) {++n; printf("GeodSolve5 fail: %d\n", i);} + if ((i = GeodSolve6())) {++n; printf("GeodSolve6 fail: %d\n", i);} + if ((i = GeodSolve9())) {++n; printf("GeodSolve9 fail: %d\n", i);} + if ((i = GeodSolve10())) {++n; printf("GeodSolve10 fail: %d\n", i);} + if ((i = GeodSolve11())) {++n; printf("GeodSolve11 fail: %d\n", i);} + if ((i = GeodSolve12())) {++n; printf("GeodSolve12 fail: %d\n", i);} + if ((i = GeodSolve14())) {++n; printf("GeodSolve14 fail: %d\n", i);} + if ((i = GeodSolve15())) {++n; printf("GeodSolve15 fail: %d\n", i);} + if ((i = GeodSolve17())) {++n; printf("GeodSolve17 fail: %d\n", i);} + if ((i = GeodSolve26())) {++n; printf("GeodSolve26 fail: %d\n", i);} + if ((i = GeodSolve28())) {++n; printf("GeodSolve28 fail: %d\n", i);} + if ((i = GeodSolve33())) {++n; printf("GeodSolve33 fail: %d\n", i);} + if ((i = GeodSolve55())) {++n; printf("GeodSolve55 fail: %d\n", i);} + if ((i = GeodSolve59())) {++n; printf("GeodSolve59 fail: %d\n", i);} + if ((i = GeodSolve61())) {++n; printf("GeodSolve61 fail: %d\n", i);} + if ((i = GeodSolve65())) {++n; printf("GeodSolve65 fail: %d\n", i);} + if ((i = GeodSolve67())) {++n; printf("GeodSolve67 fail: %d\n", i);} + if ((i = GeodSolve71())) {++n; printf("GeodSolve71 fail: %d\n", i);} + if ((i = GeodSolve73())) {++n; printf("GeodSolve73 fail: %d\n", i);} + if ((i = GeodSolve74())) {++n; printf("GeodSolve74 fail: %d\n", i);} + if ((i = GeodSolve76())) {++n; printf("GeodSolve76 fail: %d\n", i);} + if ((i = GeodSolve78())) {++n; printf("GeodSolve78 fail: %d\n", i);} + if ((i = Planimeter0())) {++n; printf("Planimeter0 fail: %d\n", i);} + if ((i = Planimeter5())) {++n; printf("Planimeter5 fail: %d\n", i);} + if ((i = Planimeter6())) {++n; printf("Planimeter6 fail: %d\n", i);} + if ((i = Planimeter12())) {++n; printf("Planimeter12 fail: %d\n", i);} + if ((i = Planimeter13())) {++n; printf("Planimeter13 fail: %d\n", i);} + return n; +} + +/** @endcond */ diff --git a/gtsam/3rdparty/GeographicLib/legacy/C/inverse.c b/gtsam/3rdparty/GeographicLib/legacy/C/inverse.c index 5e96a8ea1..a42fb40dd 100644 --- a/gtsam/3rdparty/GeographicLib/legacy/C/inverse.c +++ b/gtsam/3rdparty/GeographicLib/legacy/C/inverse.c @@ -24,7 +24,7 @@ int main() { struct geod_geodesic g; geod_init(&g, a, f); - while (scanf("%lf %lf %lf %lf\n", &lat1, &lon1, &lat2, &lon2) == 4) { + while (scanf("%lf %lf %lf %lf", &lat1, &lon1, &lat2, &lon2) == 4) { geod_inverse(&g, lat1, lon1, lat2, lon2, &s12, &azi1, &azi2); printf("%.15f %.15f %.10f\n", azi1, azi2, s12); } diff --git a/gtsam/3rdparty/GeographicLib/legacy/C/planimeter.c b/gtsam/3rdparty/GeographicLib/legacy/C/planimeter.c index 12661efd1..932bd258d 100644 --- a/gtsam/3rdparty/GeographicLib/legacy/C/planimeter.c +++ b/gtsam/3rdparty/GeographicLib/legacy/C/planimeter.c @@ -29,7 +29,7 @@ int main() { geod_init(&g, a, f); geod_polygon_init(&p, 0); - while (scanf("%lf %lf\n", &lat, &lon) == 2) + while (scanf("%lf %lf", &lat, &lon) == 2) geod_polygon_addpoint(&g, &p, lat, lon); n = geod_polygon_compute(&g, &p, 0, 1, &A, &P); printf("%d %.8f %.3f\n", n, P, A); diff --git a/gtsam/3rdparty/GeographicLib/legacy/Fortran/00README.txt b/gtsam/3rdparty/GeographicLib/legacy/Fortran/00README.txt index ecc402784..5b7863011 100644 --- a/gtsam/3rdparty/GeographicLib/legacy/Fortran/00README.txt +++ b/gtsam/3rdparty/GeographicLib/legacy/Fortran/00README.txt @@ -3,12 +3,12 @@ This is a Fortran implementation of the geodesic algorithms described in C. F. F. Karney, Algorithms for geodesics, J. Geodesy 87, 43-55 (2013); - http://dx.doi.org/10.1007/s00190-012-0578-z - Addenda: http://geographiclib.sf.net/geod-addenda.html + https://doi.org/10.1007/s00190-012-0578-z + Addenda: https://geographiclib.sourceforge.io/geod-addenda.html For documentation, see - http://geographiclib.sourceforge.net/html/Fortran/ + https://geographiclib.sourceforge.io/html/Fortran/ The code in this directory is entirely self-contained. In particular, it does not depend on the C++ classes. You can compile and link the @@ -25,3 +25,8 @@ Linux systems you might do: cmake .. make echo 30 0 29.5 179.5 | ./geodinverse + +The two tools ngsforward and ngsinverse are replacements for the NGS +tools FORWARD and INVERSE available from + + http://www.ngs.noaa.gov/PC_PROD/Inv_Fwd/ diff --git a/gtsam/3rdparty/GeographicLib/legacy/Fortran/CMakeLists.txt b/gtsam/3rdparty/GeographicLib/legacy/Fortran/CMakeLists.txt index 980ff29bd..fdafbc04d 100644 --- a/gtsam/3rdparty/GeographicLib/legacy/Fortran/CMakeLists.txt +++ b/gtsam/3rdparty/GeographicLib/legacy/Fortran/CMakeLists.txt @@ -1,6 +1,6 @@ -cmake_minimum_required (VERSION 2.6) +project (GeographicLib-Fortran Fortran) -project (GeographicLib-legacy-Fortran Fortran) +cmake_minimum_required (VERSION 2.8.4) # Set a default build type for single-configuration cmake generators if # no build type is set. @@ -8,11 +8,35 @@ if (NOT CMAKE_CONFIGURATION_TYPES AND NOT CMAKE_BUILD_TYPE) set (CMAKE_BUILD_TYPE Release) endif () -set (CMAKE_Fortran_FLAGS - "${CMAKE_Fortran_FLAGS} -Wall -Wextra -pedantic -std=f95 -fimplicit-none") +set (TOOLS geoddirect geodinverse planimeter geodtest) -set (TOOLS geoddirect geodinverse planimeter) +if (CONVERT_WARNINGS_TO_ERRORS) + if (MSVC) + set (CMAKE_Fortran_FLAGS "${CMAKE_Fortran_FLAGS} /WX") + else () + set (CMAKE_Fortran_FLAGS "${CMAKE_Fortran_FLAGS} -Werror") + endif () +endif () foreach (TOOL ${TOOLS}) add_executable (${TOOL} ${TOOL}.for geodesic.for geodesic.inc) endforeach () +# Make the compiler more picky. +if (MSVC) + set_target_properties (${TOOLS} PROPERTIES COMPILE_FLAGS "/W4") +else () + set_target_properties (${TOOLS} PROPERTIES COMPILE_FLAGS + "-Wall -Wextra -pedantic -std=f95 -fimplicit-none -Wno-compare-reals") +endif () + +# Work alikes for NGS geodesic tools. This uses legacy code from NGS +# and so they trigger multiple errors and warnings if compiled with the +# compile flags above. +add_executable (ngsforward ngsforward.for ngscommon.for geodesic.for) +add_executable (ngsinverse ngsinverse.for ngscommon.for geodesic.for) + +# Turn on testing +enable_testing () + +# Run the test suite +add_test (NAME geodtest COMMAND geodtest) diff --git a/gtsam/3rdparty/GeographicLib/legacy/Fortran/geoddirect.for b/gtsam/3rdparty/GeographicLib/legacy/Fortran/geoddirect.for index 98c5e804b..5564aaafd 100644 --- a/gtsam/3rdparty/GeographicLib/legacy/Fortran/geoddirect.for +++ b/gtsam/3rdparty/GeographicLib/legacy/Fortran/geoddirect.for @@ -12,24 +12,25 @@ include 'geodesic.inc' double precision a, f, lat1, lon1, azi1, lat2, lon2, azi2, s12, - + dummy - logical arcmod - integer omask + + dummy1, dummy2, dummy3, dummy4, dummy5 + integer flags, omask * WGS84 values a = 6378137d0 f = 1/298.257223563d0 - arcmod = .false. + flags = 0 omask = 0 10 continue read(*, *, end=90, err=90) lat1, lon1, azi1, s12 - call direct(a, f, lat1, lon1, azi1, s12, arcmod, - + lat2, lon2, azi2, omask, dummy, dummy, dummy, dummy, dummy) + call direct(a, f, lat1, lon1, azi1, s12, flags, + + lat2, lon2, azi2, omask, + + dummy1, dummy2, dummy3, dummy4, dummy5) print 20, lat2, lon2, azi2 - 20 format(f20.15, 1x, f20.15, 1x, f20.15) + 20 format(1x, f20.15, 1x, f20.15, 1x, f20.15) go to 10 90 continue + stop end diff --git a/gtsam/3rdparty/GeographicLib/legacy/Fortran/geodesic.for b/gtsam/3rdparty/GeographicLib/legacy/Fortran/geodesic.for index aaef081c5..2b331dc79 100644 --- a/gtsam/3rdparty/GeographicLib/legacy/Fortran/geodesic.for +++ b/gtsam/3rdparty/GeographicLib/legacy/Fortran/geodesic.for @@ -1,5 +1,5 @@ * The subroutines in this files are documented at -* http://geographiclib.sourceforge.net/html/Fortran/ +* https://geographiclib.sourceforge.io/html/Fortran/ * *> @file geodesic.for *! @brief Implementation of geodesic routines in Fortran @@ -7,12 +7,12 @@ *! This is a Fortran implementation of the geodesic algorithms described *! in *! - C. F. F. Karney, -*! +*! *! Algorithms for geodesics, *! J. Geodesy 87, 43--55 (2013); -*! DOI: +*! DOI: *! 10.1007/s00190-012-0578-z; -*! addenda: +*! addenda: *! geod-addenda.html. *! . *! The principal advantages of these algorithms over previous ones @@ -78,46 +78,47 @@ *! is (obviously) uniquely defined. However, in a few special cases *! there are multiple azimuths which yield the same shortest distance. *! Here is a catalog of those cases: -*! - \e lat1 = −\e lat2 (with neither point at a pole). If \e azi1 = \e -*! azi2, the geodesic is unique. Otherwise there are two geodesics -*! and the second one is obtained by setting [\e azi1, \e azi2] = [\e -*! azi2, \e azi1], [\e MM12, \e MM21] = [\e MM21, \e MM12], \e SS12 = -*! −\e SS12. (This occurs when the longitude difference is near -*! ±180° for oblate ellipsoids.) -*! - \e lon2 = \e lon1 ± 180° (with neither point at a pole). If -*! \e azi1 = 0° or ±180°, the geodesic is unique. +*! - \e lat1 = −\e lat2 (with neither point at a pole). If \e +*! azi1 = \e azi2, the geodesic is unique. Otherwise there are two +*! geodesics and the second one is obtained by setting [\e azi1, \e +*! azi2] → [\e azi2, \e azi1], [\e MM12, \e MM21] → [\e +*! MM21, \e MM12], \e SS12 → −\e SS12. (This occurs when +*! the longitude difference is near ±180° for oblate +*! ellipsoids.) +*! - \e lon2 = \e lon1 ± 180° (with neither point at a pole). +*! If \e azi1 = 0° or ±180°, the geodesic is unique. *! Otherwise there are two geodesics and the second one is obtained by -*! setting [\e azi1, \e azi2] = [−\e azi1, −\e azi2], \e -*! SS12 = −\e SS12. (This occurs when \e lat2 is near +*! setting [\e azi1, \e azi2] → [−\e azi1, −\e azi2], +*! \e SS12 → −\e SS12. (This occurs when \e lat2 is near *! −\e lat1 for prolate ellipsoids.) *! - Points 1 and 2 at opposite poles. There are infinitely many -*! geodesics which can be generated by setting [\e azi1, \e azi2] = -*! [\e azi1, \e azi2] + [\e d, −\e d], for arbitrary \e d. (For -*! spheres, this prescription applies when points 1 and 2 are +*! geodesics which can be generated by setting [\e azi1, \e azi2] +*! → [\e azi1, \e azi2] + [\e d, −\e d], for arbitrary \e +*! d. (For spheres, this prescription applies when points 1 and 2 are *! antipodal.) *! - \e s12 = 0 (coincident points). There are infinitely many -*! geodesics which can be generated by setting [\e azi1, \e azi2] = -*! [\e azi1, \e azi2] + [\e d, \e d], for arbitrary \e d. +*! geodesics which can be generated by setting [\e azi1, \e azi2] +*! → [\e azi1, \e azi2] + [\e d, \e d], for arbitrary \e d. *! *! These routines are a simple transcription of the corresponding C++ -*! classes in GeographicLib. -*! Because of the limitations of Fortran 77, the classes have been -*! replaced by simple subroutines with no attempt to save "state" across -*! subroutine calls. Most of the internal comments have been retained. -*! However, in the process of transcription some documentation has been -*! lost and the documentation for the C++ classes, -*! GeographicLib::Geodesic, GeographicLib::GeodesicLine, and -*! GeographicLib::PolygonArea, should be consulted. The C++ code +*! classes in +*! GeographicLib. Because of the limitations of Fortran 77, the +*! classes have been replaced by simple subroutines with no attempt to +*! save "state" across subroutine calls. Most of the internal comments +*! have been retained. However, in the process of transcription some +*! documentation has been lost and the documentation for the C++ +*! classes, GeographicLib::Geodesic, GeographicLib::GeodesicLine, and +*! GeographicLib::PolygonAreaT, should be consulted. The C++ code *! remains the "reference implementation". Think twice about *! restructuring the internals of the Fortran code since this may make *! porting fixes from the C++ code more difficult. *! -*! Copyright (c) Charles Karney (2012-2013) and +*! Copyright (c) Charles Karney (2012-2017) and *! licensed under the MIT/X11 License. For more information, see -*! http://geographiclib.sourceforge.net/ +*! https://geographiclib.sourceforge.io/ *! *! This library was distributed with -*! GeographicLib 1.31. +*! GeographicLib 1.49. *> Solve the direct geodesic problem *! @@ -127,19 +128,19 @@ *! @param[in] lat1 latitude of point 1 (degrees). *! @param[in] lon1 longitude of point 1 (degrees). *! @param[in] azi1 azimuth at point 1 (degrees). -*! @param[in] s12a12 if \e arcmod is false, this is the distance between -*! point 1 and point 2 (meters); otherwise it is the arc length -*! between point 1 and point 2 (degrees); it can be negative. -*! @param[in] arcmod logical flag determining the meaning of the \e -*! s12a12. +*! @param[in] s12a12 if \e arcmode is not set, this is the distance +*! from point 1 to point 2 (meters); otherwise it is the arc +*! length from point 1 to point 2 (degrees); it can be negative. +*! @param[in] flags a bitor'ed combination of the \e arcmode and \e +*! unroll flags. *! @param[out] lat2 latitude of point 2 (degrees). *! @param[out] lon2 longitude of point 2 (degrees). *! @param[out] azi2 (forward) azimuth at point 2 (degrees). *! @param[in] omask a bitor'ed combination of mask values *! specifying which of the following parameters should be set. -*! @param[out] a12s12 if \e arcmod is false, this is the arc length -*! between point 1 and point 2 (degrees); otherwise it is the distance -*! between point 1 and point 2 (meters). +*! @param[out] a12s12 if \e arcmode is not set, this is the arc length +*! from point 1 to point 2 (degrees); otherwise it is the distance +*! from point 1 to point 2 (meters). *! @param[out] m12 reduced length of geodesic (meters). *! @param[out] MM12 geodesic scale of point 2 relative to point 1 *! (dimensionless). @@ -147,6 +148,18 @@ *! (dimensionless). *! @param[out] SS12 area under the geodesic (meters2). *! +*! \e flags is an integer in [0, 4) whose binary bits are interpreted +*! as follows +*! - 1 the \e arcmode flag +*! - 2 the \e unroll flag +*! . +*! If \e arcmode is not set, \e s12a12 is \e s12 and \e a12s12 is \e +*! a12; otherwise, \e s12a12 is \e a12 and \e a12s12 is \e s12. It \e +*! unroll is not set, the value \e lon2 returned is in the range +*! [−180°, 180°]; if unroll is set, the longitude variable +*! is "unrolled" so that \e lon2 − \e lon1 indicates how many +*! times and in what sense the geodesic encircles the ellipsoid. +*! *! \e omask is an integer in [0, 16) whose binary bits are interpreted *! as follows *! - 1 return \e a12 @@ -154,10 +167,8 @@ *! - 4 return \e MM12 and \e MM21 *! - 8 return \e SS12 *! -*! \e lat1 should be in the range [−90°, 90°]; \e lon1 and -*! \e azi1 should be in the range [−540°, 540°). The -*! values of \e lon2 and \e azi2 returned are in the range -*! [−180°, 180°). +*! \e lat1 should be in the range [−90°, 90°]. The value +*! \e azi2 returned is in the range [−180°, 180°]. *! *! If either point is at a pole, the azimuth is defined by keeping the *! longitude fixed, writing \e lat = \e lat = ±(90° − @@ -166,13 +177,15 @@ *! path. (For a prolate ellipsoid, an additional condition is necessary *! for a shortest path: the longitudinal extent must not exceed of *! 180°.) +*! +*! Example of use: +*! \include geoddirect.for - subroutine direct(a, f, lat1, lon1, azi1, s12a12, arcmod, + subroutine direct(a, f, lat1, lon1, azi1, s12a12, flags, + lat2, lon2, azi2, omask, a12s12, m12, MM12, MM21, SS12) * input double precision a, f, lat1, lon1, azi1, s12a12 - logical arcmod - integer omask + integer flags, omask * output double precision lat2, lon2, azi2 * optional output @@ -186,15 +199,15 @@ double precision A3x(0:nA3x-1), C3x(0:nC3x-1), C4x(0:nC4x-1), + C1a(nC1), C1pa(nC1p), C2a(nC2), C3a(nC3-1), C4a(0:nC4-1) - double precision csmgt, atanhx, hypotx, - + AngNm, AngNm2, AngRnd, TrgSum, A1m1f, A2m1f, A3f - logical arcp, redlp, scalp, areap + double precision atanhx, hypotx, + + AngNm, AngRnd, TrgSum, A1m1f, A2m1f, A3f, atn2dx, LatFix + logical arcmod, unroll, arcp, redlp, scalp, areap double precision e2, f1, ep2, n, b, c2, - + lon1x, azi1x, phi, alp1, salp0, calp0, k2, eps, + + salp0, calp0, k2, eps, + salp1, calp1, ssig1, csig1, cbet1, sbet1, dn1, somg1, comg1, + salp2, calp2, ssig2, csig2, sbet2, cbet2, dn2, somg2, comg2, + ssig12, csig12, salp12, calp12, omg12, lam12, lon12, - + sig12, stau1, ctau1, tau12, s12a, t, s, c, serr, + + sig12, stau1, ctau1, tau12, t, s, c, serr, E, + A1m1, A2m1, A3c, A4, AB1, AB2, + B11, B12, B21, B22, B31, B41, B42, J12 @@ -214,10 +227,13 @@ b = a * f1 c2 = 0 - arcp = mod(omask/1, 2) == 1 - redlp = mod(omask/2, 2) == 1 - scalp = mod(omask/4, 2) == 1 - areap = mod(omask/8, 2) == 1 + arcmod = mod(flags/1, 2) .eq. 1 + unroll = mod(flags/2, 2) .eq. 1 + + arcp = mod(omask/1, 2) .eq. 1 + redlp = mod(omask/2, 2) .eq. 1 + scalp = mod(omask/4, 2) .eq. 1 + areap = mod(omask/8, 2) .eq. 1 if (areap) then if (e2 .eq. 0) then @@ -234,21 +250,13 @@ if (areap) call C4cof(n, C4x) * Guard against underflow in salp0 - azi1x = AngRnd(AngNm(azi1)) - lon1x = AngNm(lon1) + call sncsdx(AngRnd(azi1), salp1, calp1) -* alp1 is in [0, pi] - alp1 = azi1x * degree -* Enforce sin(pi) == 0 and cos(pi/2) == 0. Better to face the ensuing -* problems directly than to skirt them. - salp1 = csmgt(0d0, sin(alp1), azi1x .eq. -180) - calp1 = csmgt(0d0, cos(alp1), abs(azi1x) .eq. 90) - - phi = lat1 * degree + call sncsdx(AngRnd(LatFix(lat1)), sbet1, cbet1) + sbet1 = f1 * sbet1 + call norm2x(sbet1, cbet1) * Ensure cbet1 = +dbleps at poles - sbet1 = f1 * sin(phi) - cbet1 = csmgt(tiny, cos(phi), abs(lat1) .eq. 90) - call Norm(sbet1, cbet1) + cbet1 = max(tiny, cbet1) dn1 = sqrt(1 + ep2 * sbet1**2) * Evaluate alp0 from sin(alp1) * cos(bet1) = sin(alp0), @@ -268,11 +276,15 @@ * With alp0 = 0, omg1 = 0 for alp1 = 0, omg1 = pi for alp1 = pi. ssig1 = sbet1 somg1 = salp0 * sbet1 - csig1 = csmgt(cbet1 * calp1, 1d0, sbet1 .ne. 0 .or. calp1 .ne. 0) + if (sbet1 .ne. 0 .or. calp1 .ne. 0) then + csig1 = cbet1 * calp1 + else + csig1 = 1 + end if comg1 = csig1 * sig1 in (-pi, pi] - call Norm(ssig1, csig1) -* Geodesic::Norm(somg1, comg1); -- don't need to normalize! + call norm2x(ssig1, csig1) +* norm2x(somg1, comg1); -- don't need to normalize! k2 = calp0**2 * ep2 eps = k2 / (2 * (1 + sqrt(1 + k2)) + k2) @@ -318,10 +330,7 @@ if (arcmod) then * Interpret s12a12 as spherical arc length sig12 = s12a12 * degree - s12a = abs(s12a12) - s12a = s12a - 180 * aint(s12a / 180) - ssig12 = csmgt(0d0, sin(sig12), s12a .eq. 0) - csig12 = csmgt(0d0, cos(sig12), s12a .eq. 90) + call sncsdx(s12a12, ssig12, csig12) * Suppress bogus warnings about unitialized variables B12 = 0 else @@ -393,21 +402,29 @@ * No need to normalize salp2 = salp0 calp2 = calp0 * csig2 +* East or west going? + E = sign(1d0, salp0) * omg12 = omg2 - omg1 - omg12 = atan2(somg2 * comg1 - comg2 * somg1, - + comg2 * comg1 + somg2 * somg1) + if (unroll) then + omg12 = E * (sig12 + + - (atan2( ssig2, csig2) - atan2( ssig1, csig1)) + + + (atan2(E * somg2, comg2) - atan2(E * somg1, comg1))) + else + omg12 = atan2(somg2 * comg1 - comg2 * somg1, + + comg2 * comg1 + somg2 * somg1) + end if lam12 = omg12 + A3c * + ( sig12 + (TrgSum(.true., ssig2, csig2, C3a, nC3-1) + - B31)) lon12 = lam12 / degree -* Use Math::AngNm2 because longitude might have wrapped multiple -* times. - lon12 = AngNm2(lon12) - lon2 = AngNm(lon1x + lon12) - lat2 = atan2(sbet2, f1 * cbet2) / degree -* minus signs give range [-180, 180). 0- converts -0 to +0. - azi2 = 0 - atan2(-salp2, calp2) / degree + if (unroll) then + lon2 = lon1 + lon12 + else + lon2 = AngNm(AngNm(lon1) + AngNm(lon12)) + end if + lat2 = atn2dx(sbet2, f1 * cbet2) + azi2 = atn2dx(salp2, calp2) if (redlp .or. scalp) then B22 = TrgSum(.true., ssig2, csig2, C2a, nC2) @@ -427,16 +444,9 @@ if (areap) then B42 = TrgSum(.false., ssig2, csig2, C4a, nC4) if (calp0 .eq. 0 .or. salp0 .eq. 0) then -* alp12 = alp2 - alp1, used in atan2 so no need to normalized +* alp12 = alp2 - alp1, used in atan2 so no need to normalize salp12 = salp2 * calp1 - calp2 * salp1 calp12 = calp2 * calp1 + salp2 * salp1 -* The right thing appears to happen if alp1 = +/-180 and alp2 = 0, viz -* salp12 = -0 and alp12 = -180. However this depends on the sign being -* attached to 0 correctly. The following ensures the correct behavior. - if (salp12 .eq. 0 .and. calp12 .lt. 0) then - salp12 = tiny * calp1 - calp12 = -1 - end if else * tan(alp) = tan(alp0) * sec(sig) * tan(alp2-alp1) = (tan(alp2) -tan(alp1)) / (tan(alp2)*tan(alp1)+1) @@ -446,17 +456,24 @@ * else * csig1 - csig2 = csig1 * (1 - csig12) + ssig12 * ssig1 * No need to normalize - salp12 = calp0 * salp0 * - + csmgt(csig1 * (1 - csig12) + ssig12 * ssig1, - + ssig12 * (csig1 * ssig12 / (1 + csig12) + ssig1), - + csig12 .le. 0) + if (csig12 .le. 0) then + salp12 = csig1 * (1 - csig12) + ssig12 * ssig1 + else + salp12 = ssig12 * (csig1 * ssig12 / (1 + csig12) + ssig1) + end if + salp12 = calp0 * salp0 * salp12 calp12 = salp0**2 + calp0**2 * csig1 * csig2 end if SS12 = c2 * atan2(salp12, calp12) + A4 * (B42 - B41) end if - if (arcp) a12s12 = csmgt(b * ((1 + A1m1) * sig12 + AB1), - + sig12 / degree, arcmod) + if (arcp) then + if (arcmod) then + a12s12 = b * ((1 + A1m1) * sig12 + AB1) + else + a12s12 = sig12 / degree + end if + end if return end @@ -470,12 +487,12 @@ *! @param[in] lon1 longitude of point 1 (degrees). *! @param[in] lat2 latitude of point 2 (degrees). *! @param[in] lon2 longitude of point 2 (degrees). -*! @param[out] s12 distance between point 1 and point 2 (meters). +*! @param[out] s12 distance from point 1 to point 2 (meters). *! @param[out] azi1 azimuth at point 1 (degrees). *! @param[out] azi2 (forward) azimuth at point 2 (degrees). *! @param[in] omask a bitor'ed combination of mask values *! specifying which of the following parameters should be set. -*! @param[out] a12 arc length of between point 1 and point 2 (degrees). +*! @param[out] a12 arc length from point 1 to point 2 (degrees). *! @param[out] m12 reduced length of geodesic (meters). *! @param[out] MM12 geodesic scale of point 2 relative to point 1 *! (dimensionless). @@ -490,10 +507,9 @@ *! - 4 return \e MM12 and \e MM21 *! - 8 return \e SS12 *! -*! \e lat1 and \e lat2 should be in the range [−90°, 90°]; -*! \e lon1 and \e lon2 should be in the range [−540°, -*! 540°). The values of \e azi1 and \e azi2 returned are in the -*! range [−180°, 180°). +*! \e lat1 and \e lat2 should be in the range [−90°, 90°]. +*! The values of \e azi1 and \e azi2 returned are in the range +*! [−180°, 180°]. *! *! If either point is at a pole, the azimuth is defined by keeping the *! longitude fixed, writing \e lat = ±(90° − @@ -503,6 +519,9 @@ *! If this fails to converge (this is very unlikely in geodetic *! applications but does occur for very eccentric ellipsoids), then the *! bisection method is used to refine the solution. +*! +*! Example of use: +*! \include geodinverse.for subroutine invers(a, f, lat1, lon1, lat2, lon2, + s12, azi1, azi2, omask, a12, m12, MM12, MM21, SS12) @@ -514,31 +533,32 @@ * optional output double precision a12, m12, MM12, MM21, SS12 - integer ord, nC1, nC2, nA3, nA3x, nC3, nC3x, nC4, nC4x - parameter (ord = 6, nC1 = ord, nC2 = ord, nA3 = ord, nA3x = nA3, + integer ord, nA3, nA3x, nC3, nC3x, nC4, nC4x, nC + parameter (ord = 6, nA3 = ord, nA3x = nA3, + nC3 = ord, nC3x = (nC3 * (nC3 - 1)) / 2, - + nC4 = ord, nC4x = (nC4 * (nC4 + 1)) / 2) + + nC4 = ord, nC4x = (nC4 * (nC4 + 1)) / 2, + + nC = ord) double precision A3x(0:nA3x-1), C3x(0:nC3x-1), C4x(0:nC4x-1), - + C1a(nC1), C2a(nC2), C3a(nC3-1), C4a(0:nC4-1) + + Ca(nC) - double precision csmgt, atanhx, hypotx, - + AngNm, AngDif, AngRnd, TrgSum, Lam12f, InvSta + double precision atanhx, hypotx, + + AngDif, AngRnd, TrgSum, Lam12f, InvSta, atn2dx, LatFix integer latsgn, lonsgn, swapp, numit logical arcp, redlp, scalp, areap, merid, tripn, tripb double precision e2, f1, ep2, n, b, c2, - + lat1x, lat2x, phi, salp0, calp0, k2, eps, + + lat1x, lat2x, salp0, calp0, k2, eps, + salp1, calp1, ssig1, csig1, cbet1, sbet1, dbet1, dn1, + salp2, calp2, ssig2, csig2, sbet2, cbet2, dbet2, dn2, - + slam12, clam12, salp12, calp12, omg12, lam12, lon12, + + slam12, clam12, salp12, calp12, omg12, lam12, lon12, lon12s, + salp1a, calp1a, salp1b, calp1b, - + dalp1, sdalp1, cdalp1, nsalp1, alp12, somg12, domg12, + + dalp1, sdalp1, cdalp1, nsalp1, alp12, somg12, comg12, domg12, + sig12, v, dv, dnm, dummy, - + A4, B41, B42, s12x, m12x, a12x + + A4, B41, B42, s12x, m12x, a12x, sdomg12, cdomg12 double precision dblmin, dbleps, pi, degree, tiny, + tol0, tol1, tol2, tolb, xthrsh - integer digits, maxit1, maxit2 + integer digits, maxit1, maxit2, lmask logical init common /geocom/ dblmin, dbleps, pi, degree, tiny, + tol0, tol1, tol2, tolb, xthrsh, digits, maxit1, maxit2, init @@ -552,10 +572,15 @@ b = a * f1 c2 = 0 - arcp = mod(omask/1, 2) == 1 - redlp = mod(omask/2, 2) == 1 - scalp = mod(omask/4, 2) == 1 - areap = mod(omask/8, 2) == 1 + arcp = mod(omask/1, 2) .eq. 1 + redlp = mod(omask/2, 2) .eq. 1 + scalp = mod(omask/4, 2) .eq. 1 + areap = mod(omask/8, 2) .eq. 1 + if (scalp) then + lmask = 16 + 2 + 4 + else + lmask = 16 + 2 + end if if (areap) then if (e2 .eq. 0) then @@ -574,24 +599,33 @@ * Compute longitude difference (AngDiff does this carefully). Result is * in [-180, 180] but -180 is only for west-going geodesics. 180 is for * east-going and meridional geodesics. - lon12 = AngDif(AngNm(lon1), AngNm(lon2)) * If very close to being on the same half-meridian, then make it so. - lon12 = AngRnd(lon12) + lon12 = AngDif(lon1, lon2, lon12s) * Make longitude difference positive. if (lon12 .ge. 0) then lonsgn = 1 else lonsgn = -1 end if - lon12 = lon12 * lonsgn -* If really close to the equator, treat as on equator. - lat1x = AngRnd(lat1) - lat2x = AngRnd(lat2) -* Swap points so that point with higher (abs) latitude is point 1 - if (abs(lat1x) .ge. abs(lat2x)) then - swapp = 1 + lon12 = lonsgn * AngRnd(lon12) + lon12s = AngRnd((180 - lon12) - lonsgn * lon12s) + lam12 = lon12 * degree + if (lon12 .gt. 90) then + call sncsdx(lon12s, slam12, clam12) + clam12 = -clam12 else + call sncsdx(lon12, slam12, clam12) + end if + +* If really close to the equator, treat as on equator. + lat1x = AngRnd(LatFix(lat1)) + lat2x = AngRnd(LatFix(lat2)) +* Swap points so that point with higher (abs) latitude is point 1 +* If one latitude is a nan, then it becomes lat1. + if (abs(lat1x) .lt. abs(lat2x)) then swapp = -1 + else + swapp = 1 end if if (swapp .lt. 0) then lonsgn = -lonsgn @@ -617,17 +651,17 @@ * to check, e.g., on verifying quadrants in atan2. In addition, this * enforces some symmetries in the results returned. - phi = lat1x * degree + call sncsdx(lat1x, sbet1, cbet1) + sbet1 = f1 * sbet1 + call norm2x(sbet1, cbet1) * Ensure cbet1 = +dbleps at poles - sbet1 = f1 * sin(phi) - cbet1 = csmgt(tiny, cos(phi), lat1x .eq. -90) - call Norm(sbet1, cbet1) + cbet1 = max(tiny, cbet1) - phi = lat2x * degree + call sncsdx(lat2x, sbet2, cbet2) + sbet2 = f1 * sbet2 + call norm2x(sbet2, cbet2) * Ensure cbet2 = +dbleps at poles - sbet2 = f1 * sin(phi) - cbet2 = csmgt(tiny, cos(phi), abs(lat2x) .eq. 90) - call Norm(sbet2, cbet2) + cbet2 = max(tiny, cbet2) * If cbet1 < -sbet1, then cbet2 - cbet1 is a sensitive measure of the * |bet1| - |bet2|. Alternatively (cbet1 >= -sbet1), abs(sbet2) + sbet1 @@ -647,15 +681,9 @@ dn1 = sqrt(1 + ep2 * sbet1**2) dn2 = sqrt(1 + ep2 * sbet2**2) - lam12 = lon12 * degree - slam12 = sin(lam12) - if (lon12 .eq. 180) slam12 = 0 -* lon12 == 90 isn't interesting - clam12 = cos(lam12) - * Suppress bogus warnings about unitialized variables a12x = 0 - merid = lat1x .eq. -90 .or. slam12 == 0 + merid = lat1x .eq. -90 .or. slam12 .eq. 0 if (merid) then @@ -676,11 +704,11 @@ csig2 = calp2 * cbet2 * sig12 = sig2 - sig1 - sig12 = atan2(max(csig1 * ssig2 - ssig1 * csig2, 0d0), - + csig1 * csig2 + ssig1 * ssig2) + sig12 = atan2(0d0 + max(0d0, csig1 * ssig2 - ssig1 * csig2), + + csig1 * csig2 + ssig1 * ssig2) call Lengs(n, sig12, ssig1, csig1, dn1, ssig2, csig2, dn2, - + cbet1, cbet2, s12x, m12x, dummy, - + scalp, MM12, MM21, ep2, C1a, C2a) + + cbet1, cbet2, lmask, + + s12x, m12x, dummy, MM12, MM21, ep2, Ca) * Add the check for sig12 since zero length geodesics might yield m12 < * 0. Test case was @@ -690,6 +718,11 @@ * In fact, we will have sig12 > pi/2 for meridional geodesic which is * not a shortest path. if (sig12 .lt. 1 .or. m12x .ge. 0) then + if (sig12 .lt. 3 * tiny) then + sig12 = 0 + m12x = 0 + s12x = 0 + end if m12x = m12x * b s12x = s12x * b a12x = sig12 / degree @@ -699,9 +732,12 @@ end if end if -* Mimic the way Lambda12 works with calp1 = 0 + omg12 = 0 +* somg12 > 1 marks that it needs to be calculated + somg12 = 2 + comg12 = 0 if (.not. merid .and. sbet1 .eq. 0 .and. - + (f .le. 0 .or. lam12 .le. pi - f * pi)) then + + (f .le. 0 .or. lon12s .ge. f * 180)) then * Geodesic runs along equator calp1 = 0 @@ -723,7 +759,7 @@ * Figure a starting point for Newton's method sig12 = InvSta(sbet1, cbet1, dn1, sbet2, cbet2, dn2, lam12, - + f, A3x, salp1, calp1, salp2, calp2, dnm, C1a, C2a) + + slam12, clam12, f, A3x, salp1, calp1, salp2, calp2, dnm, Ca) if (sig12 .ge. 0) then * Short lines (InvSta sets salp2, calp2, dnm) @@ -760,14 +796,16 @@ * the WGS84 test set: mean = 1.47, sd = 1.25, max = 16 * WGS84 and random input: mean = 2.85, sd = 0.60 v = Lam12f(sbet1, cbet1, dn1, sbet2, cbet2, dn2, - + salp1, calp1, f, A3x, C3x, salp2, calp2, sig12, - + ssig1, csig1, ssig2, csig2, - + eps, omg12, numit .lt. maxit1, dv, - + C1a, C2a, C3a) - lam12 -* 2 * tol0 is approximately 1 ulp for a number in [0, pi]. + + salp1, calp1, slam12, clam12, f, A3x, C3x, salp2, calp2, + + sig12, ssig1, csig1, ssig2, csig2, + + eps, domg12, numit .lt. maxit1, dv, Ca) * Reversed test to allow escape with NaNs - if (tripb .or. - + .not. (abs(v) .ge. csmgt(8d0, 2d0, tripn) * tol0)) + if (tripn) then + dummy = 8 + else + dummy = 1 + end if + if (tripb .or. .not. (abs(v) .ge. dummy * tol0)) + go to 20 * Update bracketing values if (v .gt. 0 .and. (numit .gt. maxit1 .or. @@ -787,7 +825,7 @@ if (nsalp1 .gt. 0 .and. abs(dalp1) .lt. pi) then calp1 = calp1 * cdalp1 - salp1 * sdalp1 salp1 = nsalp1 - call Norm(salp1, calp1) + call norm2x(salp1, calp1) * In some regimes we don't get quadratic convergence because * slope -> 0. So use convergence conditions based on dbleps * instead of sqrt(dbleps). @@ -795,7 +833,7 @@ go to 10 end if end if -* Either dv was not postive or updated value was outside legal +* Either dv was not positive or updated value was outside legal * range. Use the midpoint of the bracket as the next estimate. * This mechanism is not needed for the WGS84 ellipsoid, but it does * catch problems with more eccentric ellipsoids. Its efficacy is @@ -805,19 +843,24 @@ * WGS84 and random input: mean = 4.74, sd = 0.99 salp1 = (salp1a + salp1b)/2 calp1 = (calp1a + calp1b)/2 - call Norm(salp1, calp1) + call norm2x(salp1, calp1) tripn = .false. tripb = abs(salp1a - salp1) + (calp1a - calp1) .lt. tolb + .or. abs(salp1 - salp1b) + (calp1 - calp1b) .lt. tolb 10 continue 20 continue - call Lengs(eps, sig12, ssig1, csig1, dn1, - + ssig2, csig2, dn2, cbet1, cbet2, s12x, m12x, dummy, - + scalp, MM12, MM21, ep2, C1a, C2a) + call Lengs(eps, sig12, ssig1, csig1, dn1, ssig2, csig2, dn2, + + cbet1, cbet2, lmask, + + s12x, m12x, dummy, MM12, MM21, ep2, Ca) m12x = m12x * b s12x = s12x * b a12x = sig12 / degree - omg12 = lam12 - omg12 + if (areap) then + sdomg12 = sin(domg12) + cdomg12 = cos(domg12) + somg12 = slam12 * cdomg12 - clam12 * sdomg12 + comg12 = clam12 * cdomg12 + slam12 * sdomg12 + end if end if end if @@ -839,24 +882,28 @@ eps = k2 / (2 * (1 + sqrt(1 + k2)) + k2) * Multiplier = a^2 * e^2 * cos(alpha0) * sin(alpha0). A4 = a**2 * calp0 * salp0 * e2 - call Norm(ssig1, csig1) - call Norm(ssig2, csig2) - call C4f(eps, C4x, C4a) - B41 = TrgSum(.false., ssig1, csig1, C4a, nC4) - B42 = TrgSum(.false., ssig2, csig2, C4a, nC4) + call norm2x(ssig1, csig1) + call norm2x(ssig2, csig2) + call C4f(eps, C4x, Ca) + B41 = TrgSum(.false., ssig1, csig1, Ca, nC4) + B42 = TrgSum(.false., ssig2, csig2, Ca, nC4) SS12 = A4 * (B42 - B41) else * Avoid problems with indeterminate sig1, sig2 on equator SS12 = 0 end if - if (.not. merid .and. omg12 .lt. 0.75d0 * pi + if (.not. merid .and. somg12 .gt. 1) then + somg12 = sin(omg12) + comg12 = cos(omg12) + end if + + if (.not. merid .and. comg12 .ge. 0.7071d0 + .and. sbet2 - sbet1 .lt. 1.75d0) then * Use tan(Gamma/2) = tan(omg12/2) * * (tan(bet1/2)+tan(bet2/2))/(1+tan(bet1/2)*tan(bet2/2)) * with tan(x/2) = sin(x)/(1+cos(x)) - somg12 = sin(omg12) - domg12 = 1 + cos(omg12) + domg12 = 1 + comg12 dbet1 = 1 + cbet1 dbet2 = 1 + cbet2 alp12 = 2 * atan2(somg12 * (sbet1 * dbet2 + sbet2 * dbet1), @@ -893,9 +940,8 @@ salp2 = salp2 * swapp * lonsgn calp2 = calp2 * swapp * latsgn -* minus signs give range [-180, 180). 0- converts -0 to +0. - azi1 = 0 - atan2(-salp1, calp1) / degree - azi2 = 0 - atan2(-salp2, calp2) / degree + azi1 = atn2dx(salp1, calp1) + azi2 = atn2dx(salp2, calp2) if (arcp) a12 = a12x @@ -909,12 +955,11 @@ *! a sphere. Negative \e f gives a prolate ellipsoid. *! @param[in] lats an array of the latitudes of the vertices (degrees). *! @param[in] lons an array of the longitudes of the vertices (degrees). -*! @param[in] n the number of vertices -*! @param[out] AA the (signed) area of the polygon (meters2) -*! @param[out] PP the perimeter of the polygon +*! @param[in] n the number of vertices. +*! @param[out] AA the (signed) area of the polygon (meters2). +*! @param[out] PP the perimeter of the polygon. *! -*! \e lats should be in the range [−90°, 90°]; \e lons -*! should be in the range [−540°, 540°). +*! \e lats should be in the range [−90°, 90°]. *! *! Only simple polygons (which are not self-intersecting) are allowed. *! There's no need to "close" the polygon by repeating the first vertex. @@ -979,6 +1024,25 @@ return end +*> Return the version numbers for this package. +*! +*! @param[out] major the major version number. +*! @param[out] minor the minor version number. +*! @param[out] patch the patch number. +*! +*! This subroutine was added with version 1.44. + + subroutine geover(major, minor, patch) +* output + integer major, minor, patch + + major = 1 + minor = 49 + patch = 0 + + return + end + *> @cond SKIP block data geodat @@ -1003,9 +1067,13 @@ dblmin = 0.5d0**1022 dbleps = 0.5d0**(digits-1) - pi = atan2(0.0d0, -1.0d0) + pi = atan2(0d0, -1d0) degree = pi/180 - tiny = sqrt(dblmin) +* This is about cbrt(dblmin). With other implementations, sqrt(dblmin) +* is used. The larger value is used here to avoid complaints about a +* IEEE_UNDERFLOW_FLAG IEEE_DENORMAL signal. This is triggered when +* invers is called with points at opposite poles. + tiny = 0.5d0**((1022+1)/3) tol0 = dbleps * Increase multiplier in defn of tol1 from 100 to 200 to fix inverse * case 52.784459512564 0 -52.784459512563990912 179.634407464943777557 @@ -1023,47 +1091,75 @@ return end - subroutine Lengs(eps, sig12, - + ssig1, csig1, dn1, ssig2, csig2, dn2, - + cbet1, cbet2, s12b, m12b, m0, - + scalp, MM12, MM21, ep2, C1a, C2a) + subroutine Lengs(eps, sig12, ssig1, csig1, dn1, ssig2, csig2, dn2, + + cbet1, cbet2, omask, + + s12b, m12b, m0, MM12, MM21, ep2, Ca) * input double precision eps, sig12, ssig1, csig1, dn1, ssig2, csig2, dn2, + cbet1, cbet2, ep2 - logical scalp -* output - double precision s12b, m12b, m0 + integer omask * optional output - double precision MM12, MM21 + double precision s12b, m12b, m0, MM12, MM21 * temporary storage - double precision C1a(*), C2a(*) + double precision Ca(*) integer ord, nC1, nC2 parameter (ord = 6, nC1 = ord, nC2 = ord) double precision A1m1f, A2m1f, TrgSum - double precision A1m1, AB1, A2m1, AB2, J12, csig12, t + double precision m0x, J12, A1, A2, B1, B2, csig12, t, Cb(nC2) + logical distp, redlp, scalp + integer l * Return m12b = (reduced length)/b; also calculate s12b = distance/b, * and m0 = coefficient of secular term in expression for reduced length. - call C1f(eps, C1a) - call C2f(eps, C2a) - A1m1 = A1m1f(eps) - AB1 = (1 + A1m1) * (TrgSum(.true., ssig2, csig2, C1a, nC1) - - + TrgSum(.true., ssig1, csig1, C1a, nC1)) - A2m1 = A2m1f(eps) - AB2 = (1 + A2m1) * (TrgSum(.true., ssig2, csig2, C2a, nC2) - - + TrgSum(.true., ssig1, csig1, C2a, nC2)) - m0 = A1m1 - A2m1 - J12 = m0 * sig12 + (AB1 - AB2) + distp = (mod(omask/16, 2) .eq. 1) + redlp = (mod(omask/2, 2) .eq. 1) + scalp = (mod(omask/4, 2) .eq. 1) + +* Suppress compiler warnings + m0x = 0 + J12 = 0 + A1 = 0 + A2 = 0 + if (distp .or. redlp .or. scalp) then + A1 = A1m1f(eps) + call C1f(eps, Ca) + if (redlp .or. scalp) then + A2 = A2m1f(eps) + call C2f(eps, Cb) + m0x = A1 - A2 + A2 = 1 + A2 + end if + A1 = 1 + A1 + end if + if (distp) then + B1 = TrgSum(.true., ssig2, csig2, Ca, nC1) - + + TrgSum(.true., ssig1, csig1, Ca, nC1) +* Missing a factor of b + s12b = A1 * (sig12 + B1) + if (redlp .or. scalp) then + B2 = Trgsum(.true., ssig2, csig2, Cb, nC2) - + + TrgSum(.true., ssig1, csig1, Cb, nC2) + J12 = m0x * sig12 + (A1 * B1 - A2 * B2) + end if + else if (redlp .or. scalp) then +* Assume here that nC1 >= nC2 + do 10 l = 1, nC2 + Cb(l) = A1 * Ca(l) - A2 * Cb(l) + 10 continue + J12 = m0x * sig12 + (TrgSum(.true., ssig2, csig2, Cb, nC2) - + + TrgSum(.true., ssig1, csig1, Cb, nC2)) + end if + if (redlp) then + m0 = m0x * Missing a factor of b. * Add parens around (csig1 * ssig2) and (ssig1 * csig2) to ensure * accurate cancellation in the case of coincident points. - m12b = dn2 * (csig1 * ssig2) - dn1 * (ssig1 * csig2) - - + csig1 * csig2 * J12 -* Missing a factor of b - s12b = (1 + A1m1) * sig12 + AB1 + m12b = dn2 * (csig1 * ssig2) - dn1 * (ssig1 * csig2) - + + csig1 * csig2 * J12 + end if if (scalp) then csig12 = csig1 * csig2 + ssig1 * ssig2 t = ep2 * (cbet1 - cbet2) * (cbet1 + cbet2) / (dn1 + dn2) @@ -1080,7 +1176,7 @@ * input double precision x, y - double precision cbrt, csmgt + double precision cbrt double precision k, p, q, r, S, r2, r3, disc, u, + T3, T, ang, v, uv, w @@ -1094,7 +1190,7 @@ S = p * q / 4 r2 = r**2 r3 = r * r2 -* The discrimant of the quadratic equation for T3. This is zero on +* The discriminant of the quadratic equation for T3. This is zero on * the evolute curve p^(1/3)+q^(1/3) = 1 disc = S * (S + 2 * r3) u = r @@ -1104,7 +1200,12 @@ * of precision due to cancellation. The result is unchanged because * of the way the T is used in definition of u. * T3 = (r * t)^3 - T3 = T3 + csmgt(-sqrt(disc), sqrt(disc), T3 .lt. 0) + if (T3 .lt. 0) then + disc = -sqrt(disc) + else + disc = sqrt(disc) + end if + T3 = T3 + disc * N.B. cbrt always returns the real root. cbrt(-8) = -2. * T = r * t T = cbrt(T3) @@ -1121,7 +1222,11 @@ v = sqrt(u**2 + q) * Avoid loss of accuracy when u < 0. * u+v, guaranteed positive - uv = csmgt(q / (v - u), u + v, u .lt. 0) + if (u .lt. 0) then + uv = q / (v - u) + else + uv = u + v + end if * positive? w = (uv - q) / (2 * v) * Rearrange expression for k to avoid loss of accuracy due to @@ -1140,26 +1245,26 @@ end double precision function InvSta(sbet1, cbet1, dn1, - + sbet2, cbet2, dn2, lam12, f, A3x, + + sbet2, cbet2, dn2, lam12, slam12, clam12, f, A3x, + salp1, calp1, salp2, calp2, dnm, - + C1a, C2a) + + Ca) * Return a starting point for Newton's method in salp1 and calp1 * (function value is -1). If Newton's method doesn't need to be used, * return also salp2, calp2, and dnm and function value is sig12. * input - double precision sbet1, cbet1, dn1, sbet2, cbet2, dn2, lam12, - + f, A3x(*) + double precision sbet1, cbet1, dn1, sbet2, cbet2, dn2, + + lam12, slam12, clam12, f, A3x(*) * output double precision salp1, calp1, salp2, calp2, dnm * temporary - double precision C1a(*), C2a(*) + double precision Ca(*) - double precision csmgt, hypotx, A3f, Astrd + double precision hypotx, A3f, Astrd logical shortp double precision f1, e2, ep2, n, etol2, k2, eps, sig12, + sbet12, cbet12, sbt12a, omg12, somg12, comg12, ssig12, csig12, + x, y, lamscl, betscl, cbt12a, bt12a, m12b, m0, dummy, - + k, omg12a, sbetm2 + + k, omg12a, sbetm2, lam12x double precision dblmin, dbleps, pi, degree, tiny, + tol0, tol1, tol2, tolb, xthrsh @@ -1195,22 +1300,26 @@ shortp = cbet12 .ge. 0 .and. sbet12 .lt. 0.5d0 .and. + cbet2 * lam12 .lt. 0.5d0 - omg12 = lam12 if (shortp) then sbetm2 = (sbet1 + sbet2)**2 * sin((bet1+bet2)/2)^2 * = (sbet1 + sbet2)^2 / ((sbet1 + sbet2)^2 + (cbet1 + cbet2)^2) sbetm2 = sbetm2 / (sbetm2 + (cbet1 + cbet2)**2) dnm = sqrt(1 + ep2 * sbetm2) - omg12 = omg12 / (f1 * dnm) + omg12 = lam12 / (f1 * dnm) + somg12 = sin(omg12) + comg12 = cos(omg12) + else + somg12 = slam12 + comg12 = clam12 end if - somg12 = sin(omg12) - comg12 = cos(omg12) salp1 = cbet2 * somg12 - calp1 = csmgt(sbet12 + cbet2 * sbet1 * somg12**2 / (1 + comg12), - + sbt12a - cbet2 * sbet1 * somg12**2 / (1 - comg12), - + comg12 .ge. 0) + if (comg12 .ge. 0) then + calp1 = sbet12 + cbet2 * sbet1 * somg12**2 / (1 + comg12) + else + calp1 = sbt12a - cbet2 * sbet1 * somg12**2 / (1 - comg12) + end if ssig12 = hypotx(salp1, calp1) csig12 = sbet1 * sbet2 + cbet1 * cbet2 * comg12 @@ -1218,9 +1327,13 @@ if (shortp .and. ssig12 .lt. etol2) then * really short lines salp2 = cbet1 * somg12 - calp2 = sbet12 - cbet1 * sbet2 * - + csmgt(somg12**2 / (1 + comg12), 1 - comg12, comg12 .ge. 0) - call Norm(salp2, calp2) + if (comg12 .ge. 0) then + calp2 = somg12**2 / (1 + comg12) + else + calp2 = 1 - comg12 + end if + calp2 = sbet12 - cbet1 * sbet2 * calp2 + call norm2x(salp2, calp2) * Set return value sig12 = atan2(ssig12, csig12) else if (abs(n) .gt. 0.1d0 .or. csig12 .ge. 0 .or. @@ -1228,6 +1341,8 @@ * Nothing to do, zeroth order spherical approximation is OK continue else +* lam12 - pi + lam12x = atan2(-slam12, -clam12) * Scale lam12 and bet2 to x, y coordinate system where antipodal point * is at origin and singular point is at y = 0, x = -1. if (f .ge. 0) then @@ -1236,7 +1351,7 @@ eps = k2 / (2 * (1 + sqrt(1 + k2)) + k2) lamscl = f * cbet1 * A3f(eps, A3x) * pi betscl = lamscl * cbet1 - x = (lam12 - pi) / lamscl + x = lam12x / lamscl y = sbt12a / betscl else * f < 0: x = dlat, y = dlong @@ -1245,14 +1360,16 @@ * In the case of lon12 = 180, this repeats a calculation made in * Inverse. call Lengs(n, pi + bt12a, - + sbet1, -cbet1, dn1, sbet2, cbet2, dn2, - + cbet1, cbet2, dummy, m12b, m0, .false., - + dummy, dummy, ep2, C1a, C2a) + + sbet1, -cbet1, dn1, sbet2, cbet2, dn2, cbet1, cbet2, 2, + + dummy, m12b, m0, dummy, dummy, ep2, Ca) x = -1 + m12b / (cbet1 * cbet2 * m0 * pi) - betscl = csmgt(sbt12a / x, -f * cbet1**2 * pi, - + x .lt. -0.01d0) + if (x .lt. -0.01d0) then + betscl = sbt12a / x + else + betscl = -f * cbet1**2 * pi + end if lamscl = betscl / cbet1 - y = (lam12 - pi) / lamscl + y = lam12x / lamscl end if if (y .gt. -tol1 .and. x .gt. -1 - xthrsh) then @@ -1261,7 +1378,12 @@ salp1 = min(1d0, -x) calp1 = - sqrt(1 - salp1**2) else - calp1 = max(csmgt(0d0, 1d0, x .gt. -tol1), x) + if (x .gt. -tol1) then + calp1 = 0 + else + calp1 = 1 + end if + calp1 = max(calp1, x) salp1 = sqrt(1 - calp1**2) end if else @@ -1300,8 +1422,12 @@ * * Because omg12 is near pi, estimate work with omg12a = pi - omg12 k = Astrd(x, y) - omg12a = lamscl * - + csmgt(-x * k/(1 + k), -y * (1 + k)/k, f .ge. 0) + if (f .ge. 0) then + omg12a = -x * k/(1 + k) + else + omg12a = -y * (1 + k)/k + end if + omg12a = lamscl * omg12a somg12 = sin(omg12a) comg12 = -cos(omg12a) * Update spherical estimate of alp1 using omg12 instead of lam12 @@ -1309,9 +1435,9 @@ calp1 = sbt12a - cbet2 * sbet1 * somg12**2 / (1 - comg12) end if end if -* Sanity check on starting guess - if (salp1 .gt. 0) then - call Norm(salp1, calp1) +* Sanity check on starting guess. Backwards check allows NaN through. + if (.not. (salp1 .le. 0)) then + call norm2x(salp1, calp1) else salp1 = 1 calp1 = 0 @@ -1322,12 +1448,12 @@ end double precision function Lam12f(sbet1, cbet1, dn1, - + sbet2, cbet2, dn2, salp1, calp1, f, A3x, C3x, salp2, calp2, - + sig12, ssig1, csig1, ssig2, csig2, eps, domg12, diffp, dlam12, - + C1a, C2a, C3a) + + sbet2, cbet2, dn2, salp1, calp1, slm120, clm120, f, A3x, C3x, + + salp2, calp2, sig12, ssig1, csig1, ssig2, csig2, eps, + + domg12, diffp, dlam12, Ca) * input double precision sbet1, cbet1, dn1, sbet2, cbet2, dn2, - + salp1, calp1, f, A3x(*), C3x(*) + + salp1, calp1, slm120, clm120, f, A3x(*), C3x(*) logical diffp * output double precision salp2, calp2, sig12, ssig1, csig1, ssig2, csig2, @@ -1335,15 +1461,16 @@ * optional output double precision dlam12 * temporary - double precision C1a(*), C2a(*), C3a(*) + double precision Ca(*) integer ord, nC3 parameter (ord = 6, nC3 = ord) - double precision csmgt, hypotx, A3f, TrgSum + double precision hypotx, A3f, TrgSum double precision f1, e2, ep2, salp0, calp0, - + somg1, comg1, somg2, comg2, omg12, lam12, B312, h0, k2, dummy + + somg1, comg1, somg2, comg2, somg12, comg12, + + lam12, eta, B312, k2, dummy double precision dblmin, dbleps, pi, degree, tiny, + tol0, tol1, tol2, tolb, xthrsh @@ -1370,55 +1497,66 @@ somg1 = salp0 * sbet1 csig1 = calp1 * cbet1 comg1 = csig1 - call Norm(ssig1, csig1) -* Norm(somg1, comg1); -- don't need to normalize! + call norm2x(ssig1, csig1) +* norm2x(somg1, comg1); -- don't need to normalize! * Enforce symmetries in the case abs(bet2) = -bet1. Need to be careful * about this case, since this can yield singularities in the Newton * iteration. * sin(alp2) * cos(bet2) = sin(alp0) - salp2 = csmgt(salp0 / cbet2, salp1, cbet2 .ne. cbet1) + if (cbet2 .ne. cbet1) then + salp2 = salp0 / cbet2 + else + salp2 = salp1 + end if * calp2 = sqrt(1 - sq(salp2)) * = sqrt(sq(calp0) - sq(sbet2)) / cbet2 * and subst for calp0 and rearrange to give (choose positive sqrt * to give alp2 in [0, pi/2]). - calp2 = csmgt(sqrt((calp1 * cbet1)**2 + - + csmgt((cbet2 - cbet1) * (cbet1 + cbet2), - + (sbet1 - sbet2) * (sbet1 + sbet2), - + cbet1 .lt. -sbet1)) / cbet2, - + abs(calp1), cbet2 .ne. cbet1 .or. abs(sbet2) .ne. -sbet1) + if (cbet2 .ne. cbet1 .or. abs(sbet2) .ne. -sbet1) then + if (cbet1 .lt. -sbet1) then + calp2 = (cbet2 - cbet1) * (cbet1 + cbet2) + else + calp2 = (sbet1 - sbet2) * (sbet1 + sbet2) + end if + calp2 = sqrt((calp1 * cbet1)**2 + calp2) / cbet2 + else + calp2 = abs(calp1) + end if * tan(bet2) = tan(sig2) * cos(alp2) * tan(omg2) = sin(alp0) * tan(sig2). ssig2 = sbet2 somg2 = salp0 * sbet2 csig2 = calp2 * cbet2 comg2 = csig2 - call Norm(ssig2, csig2) -* Norm(somg2, comg2); -- don't need to normalize! + call norm2x(ssig2, csig2) +* norm2x(somg2, comg2); -- don't need to normalize! * sig12 = sig2 - sig1, limit to [0, pi] - sig12 = atan2(max(csig1 * ssig2 - ssig1 * csig2, 0d0), - + csig1 * csig2 + ssig1 * ssig2) + sig12 = atan2(0d0 + max(0d0, csig1 * ssig2 - ssig1 * csig2), + + csig1 * csig2 + ssig1 * ssig2) * omg12 = omg2 - omg1, limit to [0, pi] - omg12 = atan2(max(comg1 * somg2 - somg1 * comg2, 0d0), - + comg1 * comg2 + somg1 * somg2) + somg12 = 0d0 + max(0d0, comg1 * somg2 - somg1 * comg2) + comg12 = comg1 * comg2 + somg1 * somg2 +* eta = omg12 - lam120 + eta = atan2(somg12 * clm120 - comg12 * slm120, + + comg12 * clm120 + somg12 * slm120); k2 = calp0**2 * ep2 eps = k2 / (2 * (1 + sqrt(1 + k2)) + k2) - call C3f(eps, C3x, C3a) - B312 = (TrgSum(.true., ssig2, csig2, C3a, nC3-1) - - + TrgSum(.true., ssig1, csig1, C3a, nC3-1)) - h0 = -f * A3f(eps, A3x) - domg12 = salp0 * h0 * (sig12 + B312) - lam12 = omg12 + domg12 + call C3f(eps, C3x, Ca) + B312 = (TrgSum(.true., ssig2, csig2, Ca, nC3-1) - + + TrgSum(.true., ssig1, csig1, Ca, nC3-1)) + domg12 = -f * A3f(eps, A3x) * salp0 * (sig12 + B312) + lam12 = eta + domg12 if (diffp) then if (calp2 .eq. 0) then dlam12 = - 2 * f1 * dn1 / sbet1 else call Lengs(eps, sig12, ssig1, csig1, dn1, ssig2, csig2, dn2, - + cbet1, cbet2, dummy, dlam12, dummy, - + .false., dummy, dummy, ep2, C1a, C2a) + + cbet1, cbet2, 2, + + dummy, dlam12, dummy, dummy, dummy, ep2, Ca) dlam12 = dlam12 * f1 / (calp2 * cbet2) end if end if @@ -1428,7 +1566,7 @@ end double precision function A3f(eps, A3x) -* Evaluate sum(A3x[k] * eps^k, k, 0, nA3x-1) by Horner's method +* Evaluate A3 integer ord, nA3, nA3x parameter (ord = 6, nA3 = ord, nA3x = nA3) @@ -1437,17 +1575,14 @@ * output double precision A3x(0: nA3x-1) - integer i - A3f = 0 - do 10 i = nA3x-1, 0, -1 - A3f = eps * A3f + A3x(i) - 10 continue + double precision polval + A3f = polval(nA3 - 1, A3x, eps) return end subroutine C3f(eps, C3x, c) -* Evaluate C3 coeffs by Horner's method +* Evaluate C3 coeffs * Elements c[1] thru c[nC3-1] are set integer ord, nC3, nC3x parameter (ord = 6, nC3 = ord, nC3x = (nC3 * (nC3 - 1)) / 2) @@ -1457,30 +1592,23 @@ * output double precision c(nC3-1) - integer i, j, k - double precision t, mult - - j = nC3x - do 20 k = nC3-1, 1 , -1 - t = 0 - do 10 i = nC3 - k, 1, -1 - j = j - 1 - t = eps * t + C3x(j) - 10 continue - c(k) = t - 20 continue + integer o, m, l + double precision mult, polval mult = 1 - do 30 k = 1, nC3-1 + o = 0 + do 10 l = 1, nC3 - 1 + m = nC3 - l - 1 mult = mult * eps - c(k) = c(k) * mult - 30 continue + c(l) = mult * polval(m, C3x(o), eps) + o = o + m + 1 + 10 continue return end subroutine C4f(eps, C4x, c) -* Evaluate C4 coeffs by Horner's method +* Evaluate C4 * Elements c[0] thru c[nC4-1] are set integer ord, nC4, nC4x parameter (ord = 6, nC4 = ord, nC4x = (nC4 * (nC4 + 1)) / 2) @@ -1490,39 +1618,35 @@ *output double precision c(0:nC4-1) - integer i, j, k - double precision t, mult - - j = nC4x - do 20 k = nC4-1, 0, -1 - t = 0 - do 10 i = nC4 - k, 1, -1 - j = j - 1 - t = eps * t + C4x(j) - 10 continue - c(k) = t - 20 continue + integer o, m, l + double precision mult, polval mult = 1 - do 30 k = 1, nC4-1 - mult = mult * eps - c(k) = c(k) * mult - 30 continue + o = 0 + do 10 l = 0, nC4 - 1 + m = nC4 - l - 1 + c(l) = mult * polval(m, C4x(o), eps) + o = o + m + 1 + mult = mult * eps + 10 continue return end -* Generated by Maxima on 2010-09-04 10:26:17-04:00 - double precision function A1m1f(eps) * The scale factor A1-1 = mean value of (d/dsigma)I1 - 1 * input double precision eps - double precision eps2, t + double precision t + integer ord, nA1, o, m + parameter (ord = 6, nA1 = ord) + double precision polval, coeff(nA1/2 + 2) + data coeff /1, 4, 64, 0, 256/ - eps2 = eps**2 - t = eps2*(eps2*(eps2+4)+64)/256 + o = 1 + m = nA1/2 + t = polval(m, coeff(o), eps**2) / coeff(o + m + 1) A1m1f = (t + eps) / (1 - eps) return @@ -1539,20 +1663,25 @@ double precision c(nC1) double precision eps2, d + integer o, m, l + double precision polval, coeff((nC1**2 + 7*nC1 - 2*(nC1/2))/4) + data coeff / + + -1, 6, -16, 32, + + -9, 64, -128, 2048, + + 9, -16, 768, + + 3, -5, 512, + + -7, 1280, + + -7, 2048/ eps2 = eps**2 d = eps - c(1) = d*((6-eps2)*eps2-16)/32 - d = d * eps - c(2) = d*((64-9*eps2)*eps2-128)/2048 - d = d * eps - c(3) = d*(9*eps2-16)/768 - d = d * eps - c(4) = d*(3*eps2-5)/512 - d = d * eps - c(5) = -7*d/1280 - d = d * eps - c(6) = -7*d/2048 + o = 1 + do 10 l = 1, nC1 + m = (nC1 - l) / 2 + c(l) = d * polval(m, coeff(o), eps2) / coeff(o + m + 1) + o = o + m + 2 + d = d * eps + 10 continue return end @@ -1568,20 +1697,25 @@ double precision c(nC1p) double precision eps2, d + integer o, m, l + double precision polval, coeff((nC1p**2 + 7*nC1p - 2*(nC1p/2))/4) + data coeff / + + 205, -432, 768, 1536, + + 4005, -4736, 3840, 12288, + + -225, 116, 384, + + -7173, 2695, 7680, + + 3467, 7680, + + 38081, 61440/ eps2 = eps**2 d = eps - c(1) = d*(eps2*(205*eps2-432)+768)/1536 - d = d * eps - c(2) = d*(eps2*(4005*eps2-4736)+3840)/12288 - d = d * eps - c(3) = d*(116-225*eps2)/384 - d = d * eps - c(4) = d*(2695-7173*eps2)/7680 - d = d * eps - c(5) = 3467*d/7680 - d = d * eps - c(6) = 38081*d/61440 + o = 1 + do 10 l = 1, nC1p + m = (nC1p - l) / 2 + c(l) = d * polval(m, coeff(o), eps2) / coeff(o + m + 1) + o = o + m + 2 + d = d * eps + 10 continue return end @@ -1591,11 +1725,16 @@ * input double precision eps - double precision eps2, t + double precision t + integer ord, nA2, o, m + parameter (ord = 6, nA2 = ord) + double precision polval, coeff(nA2/2 + 2) + data coeff /-11, -28, -192, 0, 256/ - eps2 = eps**2 - t = eps2*(eps2*(25*eps2+36)+64)/256 - A2m1f = t * (1 - eps) - eps + o = 1 + m = nA2/2 + t = polval(m, coeff(o), eps**2) / coeff(o + m + 1) + A2m1f = (t - eps) / (1 + eps) return end @@ -1611,20 +1750,25 @@ double precision c(nC2) double precision eps2, d + integer o, m, l + double precision polval, coeff((nC2**2 + 7*nC2 - 2*(nC2/2))/4) + data coeff / + + 1, 2, 16, 32, + + 35, 64, 384, 2048, + + 15, 80, 768, + + 7, 35, 512, + + 63, 1280, + + 77, 2048/ eps2 = eps**2 d = eps - c(1) = d*(eps2*(eps2+2)+16)/32 - d = d * eps - c(2) = d*(eps2*(35*eps2+64)+384)/2048 - d = d * eps - c(3) = d*(15*eps2+80)/768 - d = d * eps - c(4) = d*(7*eps2+35)/512 - d = d * eps - c(5) = 63*d/1280 - d = d * eps - c(6) = 77*d/2048 + o = 1 + do 10 l = 1, nC2 + m = (nC2 - l) / 2 + c(l) = d * polval(m, coeff(o), eps2) / coeff(o + m + 1) + o = o + m + 2 + d = d * eps + 10 continue return end @@ -1639,12 +1783,24 @@ * output double precision A3x(0:nA3x-1) - A3x(0) = 1 - A3x(1) = (n-1)/2 - A3x(2) = (n*(3*n-1)-2)/8 - A3x(3) = ((-n-3)*n-1)/16 - A3x(4) = (-2*n-3)/64 - A3x(5) = -3/128d0 + integer o, m, k, j + double precision polval, coeff((nA3**2 + 7*nA3 - 2*(nA3/2))/4) + data coeff / + + -3, 128, + + -2, -3, 64, + + -1, -3, -1, 16, + + 3, -1, -2, 8, + + 1, -1, 2, + + 1, 1/ + + o = 1 + k = 0 + do 10 j = nA3 - 1, 0, -1 + m = min(nA3 - j - 1, j) + A3x(k) = polval(m, coeff(o), n) / coeff(o + m + 1) + k = k + 1 + o = o + m + 2 + 10 continue return end @@ -1659,27 +1815,40 @@ * output double precision C3x(0:nC3x-1) - C3x(0) = (1-n)/4 - C3x(1) = (1-n*n)/8 - C3x(2) = ((3-n)*n+3)/64 - C3x(3) = (2*n+5)/128 - C3x(4) = 3/128d0 - C3x(5) = ((n-3)*n+2)/32 - C3x(6) = ((-3*n-2)*n+3)/64 - C3x(7) = (n+3)/128 - C3x(8) = 5/256d0 - C3x(9) = (n*(5*n-9)+5)/192 - C3x(10) = (9-10*n)/384 - C3x(11) = 7/512d0 - C3x(12) = (7-14*n)/512 - C3x(13) = 7/512d0 - C3x(14) = 21/2560d0 + integer o, m, l, j, k + double precision polval, + + coeff(((nC3-1)*(nC3**2 + 7*nC3 - 2*(nC3/2)))/8) + data coeff / + + 3, 128, + + 2, 5, 128, + + -1, 3, 3, 64, + + -1, 0, 1, 8, + + -1, 1, 4, + + 5, 256, + + 1, 3, 128, + + -3, -2, 3, 64, + + 1, -3, 2, 32, + + 7, 512, + + -10, 9, 384, + + 5, -9, 5, 192, + + 7, 512, + + -14, 7, 512, + + 21, 2560/ + + o = 1 + k = 0 + do 20 l = 1, nC3 - 1 + do 10 j = nC3 - 1, l, -1 + m = min(nC3 - j - 1, j) + C3x(k) = polval(m, coeff(o), n) / coeff(o + m + 1) + k = k + 1 + o = o + m + 2 + 10 continue + 20 continue return end -* Generated by Maxima on 2012-10-19 08:02:34-04:00 - subroutine C4cof(n, C4x) * The coefficients C4[l] in the Fourier expansion of I4 integer ord, nC4, nC4x @@ -1690,27 +1859,32 @@ * output double precision C4x(0:nC4x-1) - C4x(0) = (n*(n*(n*(n*(100*n+208)+572)+3432)-12012)+30030)/45045 - C4x(1) = (n*(n*(n*(64*n+624)-4576)+6864)-3003)/15015 - C4x(2) = (n*((14144-10656*n)*n-4576)-858)/45045 - C4x(3) = ((-224*n-4784)*n+1573)/45045 - C4x(4) = (1088*n+156)/45045 - C4x(5) = 97/15015d0 - C4x(6) = (n*(n*((-64*n-624)*n+4576)-6864)+3003)/135135 - C4x(7) = (n*(n*(5952*n-11648)+9152)-2574)/135135 - C4x(8) = (n*(5792*n+1040)-1287)/135135 - C4x(9) = (468-2944*n)/135135 - C4x(10) = 1/9009d0 - C4x(11) = (n*((4160-1440*n)*n-4576)+1716)/225225 - C4x(12) = ((4992-8448*n)*n-1144)/225225 - C4x(13) = (1856*n-936)/225225 - C4x(14) = 8/10725d0 - C4x(15) = (n*(3584*n-3328)+1144)/315315 - C4x(16) = (1024*n-208)/105105 - C4x(17) = -136/63063d0 - C4x(18) = (832-2560*n)/405405 - C4x(19) = -128/135135d0 - C4x(20) = 128/99099d0 + integer o, m, l, j, k + double precision polval, coeff((nC4 * (nC4 + 1) * (nC4 + 5)) / 6) + data coeff / + + 97, 15015, 1088, 156, 45045, -224, -4784, 1573, 45045, + + -10656, 14144, -4576, -858, 45045, + + 64, 624, -4576, 6864, -3003, 15015, + + 100, 208, 572, 3432, -12012, 30030, 45045, + + 1, 9009, -2944, 468, 135135, 5792, 1040, -1287, 135135, + + 5952, -11648, 9152, -2574, 135135, + + -64, -624, 4576, -6864, 3003, 135135, + + 8, 10725, 1856, -936, 225225, -8448, 4992, -1144, 225225, + + -1440, 4160, -4576, 1716, 225225, + + -136, 63063, 1024, -208, 105105, + + 3584, -3328, 1144, 315315, + + -128, 135135, -2560, 832, 405405, 128, 99099/ + + o = 1 + k = 0 + do 20 l = 0, nC4 - 1 + do 10 j = nC4 - 1, l, -1 + m = nC4 - j - 1 + C4x(k) = polval(m, coeff(o), n) / coeff(o + m + 1) + k = k + 1 + o = o + m + 2 + 10 continue + 20 continue return end @@ -1736,54 +1910,56 @@ * input double precision x - if (x .ge. 180) then - AngNm = x - 360 - else if (x .lt. -180) then - AngNm = x + 360 - else - AngNm = x + AngNm = mod(x, 360d0) + if (AngNm .le. -180) then + AngNm = AngNm + 360 + else if (AngNm .gt. 180) then + AngNm = AngNm - 360 end if return end - double precision function AngNm2(x) + double precision function LatFix(x) * input double precision x - double precision AngNm - AngNm2 = mod(x, 360d0) - AngNm2 = AngNm(AngNm2) + LatFix = x + if (.not. (abs(x) .gt. 90)) return +* concoct a NaN + LatFix = sqrt(90 - abs(x)) return end - double precision function AngDif(x, y) + double precision function AngDif(x, y, e) * Compute y - x. x and y must both lie in [-180, 180]. The result is * equivalent to computing the difference exactly, reducing it to (-180, * 180] and rounding the result. Note that this prescription allows -180 -* to be returned (e.g., if x is tiny and negative and y = 180). +* to be returned (e.g., if x is tiny and negative and y = 180). The +* error in the difference is returned in e * input double precision x, y +* output + double precision e - double precision d, t, sumx - d = sumx(-x, y, t) - if ((d - 180d0) + t .gt. 0d0) then - d = d - 360d0 - else if ((d + 180d0) + t .le. 0d0) then - d = d + 360d0 + double precision d, t, sumx, AngNm + d = AngNm(sumx(AngNm(-x), AngNm(y), t)) + if (d .eq. 180 .and. t .gt. 0) then + d = -180 end if - AngDif = d + t + AngDif = sumx(d, t, e) return end double precision function AngRnd(x) * The makes the smallest gap in x = 1/16 - nextafter(1/16, 0) = 1/2^57 -* for reals = 0.7 pm on the earth if x is an angle in degrees. (This -* is about 1000 times more resolution than we get with angles around 90 +* for reals = 0.7 pm on the earth if x is an angle in degrees. (This is +* about 1000 times more resolution than we get with angles around 90 * degrees.) We use this to avoid having to deal with near singular -* cases when x is non-zero but tiny (e.g., 1.0e-200). +* cases when x is non-zero but tiny (e.g., 1.0e-200). This also +* converts -0 to +0. * input double precision x @@ -1793,6 +1969,7 @@ * The compiler mustn't "simplify" z - (z - y) to y if (y .lt. z) y = z - (z - y) AngRnd = sign(y, x) + if (x .eq. 0) AngRnd = 0 return end @@ -1813,19 +1990,20 @@ * input double precision x, y +* With Fortran 2008, this becomes: hypotx = hypot(x, y) hypotx = sqrt(x**2 + y**2) return end - subroutine Norm(sinx, cosx) + subroutine norm2x(x, y) * input/output - double precision sinx, cosx + double precision x, y double precision hypotx, r - r = hypotx(sinx, cosx) - sinx = sinx/r - cosx = cosx/r + r = hypotx(x, y) + x = x/r + y = y/r return end @@ -1834,10 +2012,14 @@ * input double precision x - double precision csmgt, y, z + double precision y, z y = 1 + x z = y - 1 - log1px = csmgt(x, x * log(y) / z, z .eq. 0) + if (z .eq. 0) then + log1px = x + else + log1px = x * log(y) / z + end if return end @@ -1846,6 +2028,7 @@ * input double precision x +* With Fortran 2008, this becomes: atanhx = atanh(x) double precision log1px, y y = abs(x) y = log1px(2 * y/(1 - y))/2 @@ -1863,20 +2046,6 @@ return end - double precision function csmgt(x, y, p) -* input - double precision x, y - logical p - - if (p) then - csmgt = x - else - csmgt = y - end if - - return - end - double precision function TrgSum(sinp, sinx, cosx, c, n) * Evaluate * y = sinp ? sum(c[i] * sin( 2*i * x), i, 1, n) : @@ -1923,14 +2092,14 @@ * input double precision lon1, lon2 - double precision lon1x, lon2x, lon12, AngNm, AngDif + double precision lon1x, lon2x, lon12, AngNm, AngDif, e lon1x = AngNm(lon1) lon2x = AngNm(lon2) - lon12 = AngDif(lon1x, lon2x) + lon12 = AngDif(lon1x, lon2x, e) trnsit = 0 - if (lon1x .lt. 0 .and. lon2x .ge. 0 .and. lon12 .gt. 0) then + if (lon1x .le. 0 .and. lon2x .gt. 0 .and. lon12 .gt. 0) then trnsit = 1 - else if (lon2x .lt. 0 .and. lon1x .ge. 0 .and. lon12 .lt. 0) then + else if (lon2x .le. 0 .and. lon1x .gt. 0 .and. lon12 .lt. 0) then trnsit = -1 end if @@ -1967,12 +2136,119 @@ return end -* Table of name abbreviations to conform to the 6-char limit + subroutine sncsdx(x, sinx, cosx) +* Compute sin(x) and cos(x) with x in degrees +* input + double precision x +* input/output + double precision sinx, cosx + + double precision dblmin, dbleps, pi, degree, tiny, + + tol0, tol1, tol2, tolb, xthrsh + integer digits, maxit1, maxit2 + logical init + common /geocom/ dblmin, dbleps, pi, degree, tiny, + + tol0, tol1, tol2, tolb, xthrsh, digits, maxit1, maxit2, init + + double precision r, s, c + integer q + r = mod(x, 360d0) + q = nint(r / 90) + r = (r - 90 * q) * degree + s = sin(r) +* sin(-0) isn't reliably -0, so... + if (x .eq. 0) s = x + c = cos(r) + q = mod(q + 4, 4) + if (q .eq. 0) then + sinx = s + cosx = c + else if (q .eq. 1) then + sinx = c + cosx = -s + else if (q .eq. 2) then + sinx = -s + cosx = -c + else +* q.eq.3 + sinx = -c + cosx = s + end if + + if (x .ne. 0) then + sinx = 0d0 + sinx + cosx = 0d0 + cosx + end if + + return + end + + double precision function atn2dx(y, x) +* input + double precision x, y + + double precision dblmin, dbleps, pi, degree, tiny, + + tol0, tol1, tol2, tolb, xthrsh + integer digits, maxit1, maxit2 + logical init + common /geocom/ dblmin, dbleps, pi, degree, tiny, + + tol0, tol1, tol2, tolb, xthrsh, digits, maxit1, maxit2, init + + double precision xx, yy + integer q + if (abs(y) .gt. abs(x)) then + xx = y + yy = x + q = 2 + else + xx = x + yy = y + q = 0 + end if + if (xx .lt. 0) then + xx = -xx + q = q + 1 + end if + atn2dx = atan2(yy, xx) / degree + if (q .eq. 1) then + if (yy .ge. 0) then + atn2dx = 180 - atn2dx + else + atn2dx = -180 - atn2dx + end if + else if (q .eq. 2) then + atn2dx = 90 - atn2dx + else if (q .eq. 3) then + atn2dx = -90 + atn2dx + end if + + return + end + + double precision function polval(N, p, x) +* input + integer N + double precision p(0:N), x + + integer i + if (N .lt. 0) then + polval = 0 + else + polval = p(0) + end if + do 10 i = 1, N + polval = polval * x + p(i) + 10 continue + + return + end + +* Table of name abbreviations to conform to the 6-char limit and +* potential name conflicts. * A3coeff A3cof * C3coeff C3cof * C4coeff C4cof * AngNormalize AngNm -* AngNormalize2 AngNm2 * AngDiff AngDif * AngRound AngRnd * arcmode arcmod @@ -1993,8 +2269,12 @@ * meridian merid * outmask omask * shortline shortp -* SinCosNorm Norm +* norm norm2x * SinCosSeries TrgSum * xthresh xthrsh * transit trnsit +* polyval polval +* LONG_UNROLL unroll +* sincosd sncsdx +* atan2d atn2dx *> @endcond SKIP diff --git a/gtsam/3rdparty/GeographicLib/legacy/Fortran/geodesic.inc b/gtsam/3rdparty/GeographicLib/legacy/Fortran/geodesic.inc index 9b68660c0..22c1950db 100644 --- a/gtsam/3rdparty/GeographicLib/legacy/Fortran/geodesic.inc +++ b/gtsam/3rdparty/GeographicLib/legacy/Fortran/geodesic.inc @@ -9,11 +9,13 @@ interface - subroutine direct(a, f, lat1, lon1, azi1, s12a12, arcmod, +* omask bits: 1 = a12; 2 = m12; 4 = MM12 + MM21; 8 = SS12 +* flags bits: 1 = arcmode; 2 = unroll + + subroutine direct(a, f, lat1, lon1, azi1, s12a12, flags, + lat2, lon2, azi2, omask, a12s12, m12, MM12, MM21, SS12) double precision, intent(in) :: a, f, lat1, lon1, azi1, s12a12 - logical, intent(in) :: arcmod - integer, intent(in) :: omask + integer, intent(in) :: flags, omask double precision, intent(out) :: lat2, lon2, azi2 double precision, intent(out) :: a12s12, m12, MM12, MM21, SS12 end subroutine direct @@ -32,4 +34,8 @@ double precision, intent(out) :: AA, PP end subroutine area + subroutine geover(major, minor, patch) + integer, intent(out) :: major, minor, patch + end subroutine geover + end interface diff --git a/gtsam/3rdparty/GeographicLib/legacy/Fortran/geodinverse.for b/gtsam/3rdparty/GeographicLib/legacy/Fortran/geodinverse.for index a9883b86e..1e8a2a706 100644 --- a/gtsam/3rdparty/GeographicLib/legacy/Fortran/geodinverse.for +++ b/gtsam/3rdparty/GeographicLib/legacy/Fortran/geodinverse.for @@ -12,7 +12,7 @@ include 'geodesic.inc' double precision a, f, lat1, lon1, azi1, lat2, lon2, azi2, s12, - + dummy + + dummy1, dummy2, dummy3, dummy4, dummy5 integer omask * WGS84 values @@ -24,10 +24,12 @@ 10 continue read(*, *, end=90, err=90) lat1, lon1, lat2, lon2 call invers(a, f, lat1, lon1, lat2, lon2, - + s12, azi1, azi2, omask, dummy, dummy, dummy, dummy, dummy) + + s12, azi1, azi2, omask, + + dummy1, dummy2, dummy3, dummy4, dummy5) print 20, azi1, azi2, s12 - 20 format(f20.15, 1x, f20.15, 1x, f19.10) + 20 format(1x, f20.15, 1x, f20.15, 1x, f19.10) go to 10 90 continue + stop end diff --git a/gtsam/3rdparty/GeographicLib/legacy/Fortran/geodtest.for b/gtsam/3rdparty/GeographicLib/legacy/Fortran/geodtest.for new file mode 100644 index 000000000..f71db9ed6 --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/legacy/Fortran/geodtest.for @@ -0,0 +1,1217 @@ +*> @file geodtest.for +*! @brief Test suite for the geodesic routines in Fortran +*! +*! Run these tests by configuring with cmake and running "make test". +*! +*! Copyright (c) Charles Karney (2015-2017) and +*! licensed under the MIT/X11 License. For more information, see +*! https://geographiclib.sourceforge.io/ + +*> @cond SKIP + + block data tests + + integer j + double precision tstdat(20, 12) + common /tstcom/ tstdat + data (tstdat(1,j), j = 1,12) / + + 35.60777d0,-139.44815d0,111.098748429560326d0, + + -11.17491d0,-69.95921d0,129.289270889708762d0, + + 8935244.5604818305d0,80.50729714281974d0,6273170.2055303837d0, + + 0.16606318447386067d0,0.16479116945612937d0, + + 12841384694976.432d0 / + data (tstdat(2,j), j = 1,12) / + + 55.52454d0,106.05087d0,22.020059880982801d0, + + 77.03196d0,197.18234d0,109.112041110671519d0, + + 4105086.1713924406d0,36.892740690445894d0, + + 3828869.3344387607d0, + + 0.80076349608092607d0,0.80101006984201008d0, + + 61674961290615.615d0 / + data (tstdat(3,j), j = 1,12) / + + -21.97856d0,142.59065d0,-32.44456876433189d0, + + 41.84138d0,98.56635d0,-41.84359951440466d0, + + 8394328.894657671d0,75.62930491011522d0,6161154.5773110616d0, + + 0.24816339233950381d0,0.24930251203627892d0, + + -6637997720646.717d0 / + data (tstdat(4,j), j = 1,12) / + + -66.99028d0,112.2363d0,173.73491240878403d0, + + -12.70631d0,285.90344d0,2.512956620913668d0, + + 11150344.2312080241d0,100.278634181155759d0, + + 6289939.5670446687d0, + + -0.17199490274700385d0,-0.17722569526345708d0, + + -121287239862139.744d0 / + data (tstdat(5,j), j = 1,12) / + + -17.42761d0,173.34268d0,-159.033557661192928d0, + + -15.84784d0,5.93557d0,-20.787484651536988d0, + + 16076603.1631180673d0,144.640108810286253d0, + + 3732902.1583877189d0, + + -0.81273638700070476d0,-0.81299800519154474d0, + + 97825992354058.708d0 / + data (tstdat(6,j), j = 1,12) / + + 32.84994d0,48.28919d0,150.492927788121982d0, + + -56.28556d0,202.29132d0,48.113449399816759d0, + + 16727068.9438164461d0,150.565799985466607d0, + + 3147838.1910180939d0, + + -0.87334918086923126d0,-0.86505036767110637d0, + + -72445258525585.010d0 / + data (tstdat(7,j), j = 1,12) / + + 6.96833d0,52.74123d0,92.581585386317712d0, + + -7.39675d0,206.17291d0,90.721692165923907d0, + + 17102477.2496958388d0,154.147366239113561d0, + + 2772035.6169917581d0, + + -0.89991282520302447d0,-0.89986892177110739d0, + + -1311796973197.995d0 / + data (tstdat(8,j), j = 1,12) / + + -50.56724d0,-16.30485d0,-105.439679907590164d0, + + -33.56571d0,-94.97412d0,-47.348547835650331d0, + + 6455670.5118668696d0,58.083719495371259d0, + + 5409150.7979815838d0, + + 0.53053508035997263d0,0.52988722644436602d0, + + 41071447902810.047d0 / + data (tstdat(9,j), j = 1,12) / + + -58.93002d0,-8.90775d0,140.965397902500679d0, + + -8.91104d0,133.13503d0,19.255429433416599d0, + + 11756066.0219864627d0,105.755691241406877d0, + + 6151101.2270708536d0, + + -0.26548622269867183d0,-0.27068483874510741d0, + + -86143460552774.735d0 / + data (tstdat(10,j), j = 1,12) / + + -68.82867d0,-74.28391d0,93.774347763114881d0, + + -50.63005d0,-8.36685d0,34.65564085411343d0, + + 3956936.926063544d0,35.572254987389284d0,3708890.9544062657d0, + + 0.81443963736383502d0,0.81420859815358342d0, + + -41845309450093.787d0 / + data (tstdat(11,j), j = 1,12) / + + -10.62672d0,-32.0898d0,-86.426713286747751d0, + + 5.883d0,-134.31681d0,-80.473780971034875d0, + + 11470869.3864563009d0,103.387395634504061d0, + + 6184411.6622659713d0, + + -0.23138683500430237d0,-0.23155097622286792d0, + + 4198803992123.548d0 / + data (tstdat(12,j), j = 1,12) / + + -21.76221d0,166.90563d0,29.319421206936428d0, + + 48.72884d0,213.97627d0,43.508671946410168d0, + + 9098627.3986554915d0,81.963476716121964d0, + + 6299240.9166992283d0, + + 0.13965943368590333d0,0.14152969707656796d0, + + 10024709850277.476d0 / + data (tstdat(13,j), j = 1,12) / + + -19.79938d0,-174.47484d0,71.167275780171533d0, + + -11.99349d0,-154.35109d0,65.589099775199228d0, + + 2319004.8601169389d0,20.896611684802389d0, + + 2267960.8703918325d0, + + 0.93427001867125849d0,0.93424887135032789d0, + + -3935477535005.785d0 / + data (tstdat(14,j), j = 1,12) / + + -11.95887d0,-116.94513d0,92.712619830452549d0, + + 4.57352d0,7.16501d0,78.64960934409585d0, + + 13834722.5801401374d0,124.688684161089762d0, + + 5228093.177931598d0, + + -0.56879356755666463d0,-0.56918731952397221d0, + + -9919582785894.853d0 / + data (tstdat(15,j), j = 1,12) / + + -87.85331d0,85.66836d0,-65.120313040242748d0, + + 66.48646d0,16.09921d0,-4.888658719272296d0, + + 17286615.3147144645d0,155.58592449699137d0, + + 2635887.4729110181d0, + + -0.90697975771398578d0,-0.91095608883042767d0, + + 42667211366919.534d0 / + data (tstdat(16,j), j = 1,12) / + + 1.74708d0,128.32011d0,-101.584843631173858d0, + + -11.16617d0,11.87109d0,-86.325793296437476d0, + + 12942901.1241347408d0,116.650512484301857d0, + + 5682744.8413270572d0, + + -0.44857868222697644d0,-0.44824490340007729d0, + + 10763055294345.653d0 / + data (tstdat(17,j), j = 1,12) / + + -25.72959d0,-144.90758d0,-153.647468693117198d0, + + -57.70581d0,-269.17879d0,-48.343983158876487d0, + + 9413446.7452453107d0,84.664533838404295d0, + + 6356176.6898881281d0, + + 0.09492245755254703d0,0.09737058264766572d0, + + 74515122850712.444d0 / + data (tstdat(18,j), j = 1,12) / + + -41.22777d0,122.32875d0,14.285113402275739d0, + + -7.57291d0,130.37946d0,10.805303085187369d0, + + 3812686.035106021d0,34.34330804743883d0,3588703.8812128856d0, + + 0.82605222593217889d0,0.82572158200920196d0, + + -2456961531057.857d0 / + data (tstdat(19,j), j = 1,12) / + + 11.01307d0,138.25278d0,79.43682622782374d0, + + 6.62726d0,247.05981d0,103.708090215522657d0, + + 11911190.819018408d0,107.341669954114577d0, + + 6070904.722786735d0, + + -0.29767608923657404d0,-0.29785143390252321d0, + + 17121631423099.696d0 / + data (tstdat(20,j), j = 1,12) / + + -29.47124d0,95.14681d0,-163.779130441688382d0, + + -27.46601d0,-69.15955d0,-15.909335945554969d0, + + 13487015.8381145492d0,121.294026715742277d0, + + 5481428.9945736388d0, + + -0.51527225545373252d0,-0.51556587964721788d0, + + 104679964020340.318d0 / + end + + integer function assert(x, y, d) + double precision x, y, d + + if (abs(x - y) .le. d) then + assert = 0 + else + assert = 1 + print 10, x, y, d + 10 format(1x, 'assert fails: ', + + g14.7, ' != ', g14.7, ' +/- ', g10.3) + end if + + return + end + + integer function tstinv() + double precision tstdat(20, 12) + common /tstcom/ tstdat + double precision lat1, lon1, azi1, lat2, lon2, azi2, + + s12, a12, m12, MM12, MM21, SS12 + double precision azi1a, azi2a, s12a, a12a, + + m12a, MM12a, MM21a, SS12a + double precision a, f + integer r, assert, i, omask + include 'geodesic.inc' + +* WGS84 values + a = 6378137d0 + f = 1/298.257223563d0 + omask = 1 + 2 + 4 + 8 + r = 0 + + do i = 1,20 + lat1 = tstdat(i, 1) + lon1 = tstdat(i, 2) + azi1 = tstdat(i, 3) + lat2 = tstdat(i, 4) + lon2 = tstdat(i, 5) + azi2 = tstdat(i, 6) + s12 = tstdat(i, 7) + a12 = tstdat(i, 8) + m12 = tstdat(i, 9) + MM12 = tstdat(i, 10) + MM21 = tstdat(i, 11) + SS12 = tstdat(i, 12) + call invers(a, f, lat1, lon1, lat2, lon2, + + s12a, azi1a, azi2a, omask, a12a, m12a, MM12a, MM21a, SS12a) + r = r + assert(azi1, azi1a, 1d-13) + r = r + assert(azi2, azi2a, 1d-13) + r = r + assert(s12, s12a, 1d-8) + r = r + assert(a12, a12a, 1d-13) + r = r + assert(m12, m12a, 1d-8) + r = r + assert(MM12, MM12a, 1d-15) + r = r + assert(MM21, MM21a, 1d-15) + r = r + assert(SS12, SS12a, 0.1d0) + end do + + tstinv = r + return + end + + integer function tstdir() + double precision tstdat(20, 12) + common /tstcom/ tstdat + double precision lat1, lon1, azi1, lat2, lon2, azi2, + + s12, a12, m12, MM12, MM21, SS12 + double precision lat2a, lon2a, azi2a, a12a, + + m12a, MM12a, MM21a, SS12a + double precision a, f + integer r, assert, i, omask, flags + include 'geodesic.inc' + +* WGS84 values + a = 6378137d0 + f = 1/298.257223563d0 + omask = 1 + 2 + 4 + 8 + flags = 2 + r = 0 + + do i = 1,20 + lat1 = tstdat(i, 1) + lon1 = tstdat(i, 2) + azi1 = tstdat(i, 3) + lat2 = tstdat(i, 4) + lon2 = tstdat(i, 5) + azi2 = tstdat(i, 6) + s12 = tstdat(i, 7) + a12 = tstdat(i, 8) + m12 = tstdat(i, 9) + MM12 = tstdat(i, 10) + MM21 = tstdat(i, 11) + SS12 = tstdat(i, 12) + call direct(a, f, lat1, lon1, azi1, s12, flags, + + lat2a, lon2a, azi2a, omask, a12a, m12a, MM12a, MM21a, SS12a) + r = r + assert(lat2, lat2a, 1d-13) + r = r + assert(lon2, lon2a, 1d-13) + r = r + assert(azi2, azi2a, 1d-13) + r = r + assert(a12, a12a, 1d-13) + r = r + assert(m12, m12a, 1d-8) + r = r + assert(MM12, MM12a, 1d-15) + r = r + assert(MM21, MM21a, 1d-15) + r = r + assert(SS12, SS12a, 0.1d0) + end do + + tstdir = r + return + end + + integer function tstarc() + double precision tstdat(20, 12) + common /tstcom/ tstdat + double precision lat1, lon1, azi1, lat2, lon2, azi2, + + s12, a12, m12, MM12, MM21, SS12 + double precision lat2a, lon2a, azi2a, s12a, + + m12a, MM12a, MM21a, SS12a + double precision a, f + integer r, assert, i, omask, flags + include 'geodesic.inc' + +* WGS84 values + a = 6378137d0 + f = 1/298.257223563d0 + omask = 1 + 2 + 4 + 8 + flags = 1 + 2 + r = 0 + + do i = 1,20 + lat1 = tstdat(i, 1) + lon1 = tstdat(i, 2) + azi1 = tstdat(i, 3) + lat2 = tstdat(i, 4) + lon2 = tstdat(i, 5) + azi2 = tstdat(i, 6) + s12 = tstdat(i, 7) + a12 = tstdat(i, 8) + m12 = tstdat(i, 9) + MM12 = tstdat(i, 10) + MM21 = tstdat(i, 11) + SS12 = tstdat(i, 12) + call direct(a, f, lat1, lon1, azi1, a12, flags, + + lat2a, lon2a, azi2a, omask, s12a, m12a, MM12a, MM21a, SS12a) + r = r + assert(lat2, lat2a, 1d-13) + r = r + assert(lon2, lon2a, 1d-13) + r = r + assert(azi2, azi2a, 1d-13) + r = r + assert(s12, s12a, 1d-8) + r = r + assert(m12, m12a, 1d-8) + r = r + assert(MM12, MM12a, 1d-15) + r = r + assert(MM21, MM21a, 1d-15) + r = r + assert(SS12, SS12a, 0.1d0) + end do + + tstarc = r + return + end + + integer function notnan(x) + double precision x + if (x .eq. x) then + notnan = 1 + else + notnan = 0 + end if + + return + end + + integer function tstg0() + double precision azi1, azi2, s12, a12, m12, MM12, MM21, SS12 + double precision a, f + integer r, assert, omask + include 'geodesic.inc' + +* WGS84 values + a = 6378137d0 + f = 1/298.257223563d0 + omask = 0 + r = 0 + call invers(a, f, 40.6d0, -73.8d0, 49.01666667d0, 2.55d0, + + s12, azi1, azi2, omask, a12, m12, MM12, MM21, SS12) + r = r + assert(azi1, 53.47022d0, 0.5d-5) + r = r + assert(azi2, 111.59367d0, 0.5d-5) + r = r + assert(s12, 5853226d0, 0.5d0) + + tstg0 = r + return + end + + integer function tstg1() + double precision lat2, lon2, azi2, a12, m12, MM12, MM21, SS12 + double precision a, f + integer r, assert, omask, flags + include 'geodesic.inc' + +* WGS84 values + a = 6378137d0 + f = 1/298.257223563d0 + omask = 0 + flags = 0 + r = 0 + call direct(a, f, 40.63972222d0, -73.77888889d0, 53.5d0, 5850d3, + + flags, lat2, lon2, azi2, omask, a12, m12, MM12, MM21, SS12) + r = r + assert(lat2, 49.01467d0, 0.5d-5) + r = r + assert(lon2, 2.56106d0, 0.5d-5) + r = r + assert(azi2, 111.62947d0, 0.5d-5) + + tstg1 = r + return + end + + integer function tstg2() +* Check fix for antipodal prolate bug found 2010-09-04 + double precision azi1, azi2, s12, a12, m12, MM12, MM21, SS12 + double precision a, f + integer r, assert, omask + include 'geodesic.inc' + + a = 6.4d6 + f = -1/150d0 + omask = 0 + r = 0 + call invers(a, f, 0.07476d0, 0d0, -0.07476d0, 180d0, + + s12, azi1, azi2, omask, a12, m12, MM12, MM21, SS12) + r = r + assert(azi1, 90.00078d0, 0.5d-5) + r = r + assert(azi2, 90.00078d0, 0.5d-5) + r = r + assert(s12, 20106193d0, 0.5d0) + call invers(a, f, 0.1d0, 0d0, -0.1d0, 180d0, + + s12, azi1, azi2, omask, a12, m12, MM12, MM21, SS12) + r = r + assert(azi1, 90.00105d0, 0.5d-5) + r = r + assert(azi2, 90.00105d0, 0.5d-5) + r = r + assert(s12, 20106193d0, 0.5d0) + + tstg2 = r + return + end + + integer function tstg4() +* Check fix for short line bug found 2010-05-21 + double precision azi1, azi2, s12, a12, m12, MM12, MM21, SS12 + double precision a, f + integer r, assert, omask + include 'geodesic.inc' + +* WGS84 values + a = 6378137d0 + f = 1/298.257223563d0 + omask = 0 + r = 0 + call invers(a, f, + + 36.493349428792d0, 0d0, 36.49334942879201d0, .0000008d0, + + s12, azi1, azi2, omask, a12, m12, MM12, MM21, SS12) + r = r + assert(s12, 0.072d0, 0.5d-3) + + tstg4 = r + return + end + + integer function tstg5() + double precision lat2, lon2, azi2, a12, m12, MM12, MM21, SS12 + double precision a, f + integer r, assert, omask, flags + include 'geodesic.inc' + +* WGS84 values + a = 6378137d0 + f = 1/298.257223563d0 + omask = 0 + flags = 0 + r = 0 + call direct(a, f, 0.01777745589997d0, 30d0, 0d0, 10d6, + + flags, lat2, lon2, azi2, omask, a12, m12, MM12, MM21, SS12) + if (lon2 .lt. 0) then + r = r + assert(lon2, -150d0, 0.5d-5) + r = r + assert(abs(azi2), 180d0, 0.5d-5) + else + r = r + assert(lon2, 30d0, 0.5d-5) + r = r + assert(azi2, 0d0, 0.5d-5) + end if + + tstg5 = r + return + end + + integer function tstg6() +* Check fix for volatile sbet12a bug found 2011-06-25 (gcc 4.4d0.4d0 +* x86 -O3). Found again on 2012-03-27 with tdm-mingw32 (g++ 4.6d0.1d0). + double precision azi1, azi2, s12, a12, m12, MM12, MM21, SS12 + double precision a, f + integer r, assert, omask + include 'geodesic.inc' + +* WGS84 values + a = 6378137d0 + f = 1/298.257223563d0 + omask = 0 + r = 0 + call invers(a, f, 88.202499451857d0, 0d0, + + -88.202499451857d0, 179.981022032992859592d0, + + s12, azi1, azi2, omask, a12, m12, MM12, MM21, SS12) + r = r + assert(s12, 20003898.214d0, 0.5d-3) + call invers(a, f, 89.262080389218d0, 0d0, + + -89.262080389218d0, 179.992207982775375662d0, + + s12, azi1, azi2, omask, a12, m12, MM12, MM21, SS12) + r = r + assert(s12, 20003925.854d0, 0.5d-3) + call invers(a, f, 89.333123580033d0, 0d0, + + -89.333123580032997687d0, 179.99295812360148422d0, + + s12, azi1, azi2, omask, a12, m12, MM12, MM21, SS12) + r = r + assert(s12, 20003926.881d0, 0.5d-3) + + tstg6 = r + return + end + + integer function tstg9() +* Check fix for volatile x bug found 2011-06-25 (gcc 4.4d0.4d0 x86 -O3) + double precision azi1, azi2, s12, a12, m12, MM12, MM21, SS12 + double precision a, f + integer r, assert, omask + include 'geodesic.inc' + +* WGS84 values + a = 6378137d0 + f = 1/298.257223563d0 + omask = 0 + r = 0 + call invers(a, f, 56.320923501171d0, 0d0, + + -56.320923501171d0, 179.664747671772880215d0, + + s12, azi1, azi2, omask, a12, m12, MM12, MM21, SS12) + r = r + assert(s12, 19993558.287d0, 0.5d-3) + + tstg9 = r + return + end + + integer function tstg10() +* Check fix for adjust tol1_ bug found 2011-06-25 (Visual Studio 10 rel +* + debug) + double precision azi1, azi2, s12, a12, m12, MM12, MM21, SS12 + double precision a, f + integer r, assert, omask + include 'geodesic.inc' + +* WGS84 values + a = 6378137d0 + f = 1/298.257223563d0 + omask = 0 + r = 0 + call invers(a, f, 52.784459512564d0, 0d0, + + -52.784459512563990912d0, 179.634407464943777557d0, + + s12, azi1, azi2, omask, a12, m12, MM12, MM21, SS12) + r = r + assert(s12, 19991596.095d0, 0.5d-3) + + tstg10 = r + return + end + + integer function tstg11() +* Check fix for bet2 = -bet1 bug found 2011-06-25 (Visual Studio 10 rel +* + debug) + double precision azi1, azi2, s12, a12, m12, MM12, MM21, SS12 + double precision a, f + integer r, assert, omask + include 'geodesic.inc' + +* WGS84 values + a = 6378137d0 + f = 1/298.257223563d0 + omask = 0 + r = 0 + call invers(a, f, 48.522876735459d0, 0d0, + + -48.52287673545898293d0, 179.599720456223079643d0, + + s12, azi1, azi2, omask, a12, m12, MM12, MM21, SS12) + r = r + assert(s12, 19989144.774d0, 0.5d-3) + + tstg11 = r + return + end + + integer function tstg12() +* Check fix for inverse geodesics on extreme prolate/oblate ellipsoids +* Reported 2012-08-29 Stefan Guenther ; fixed +* 2012-10-07 + double precision azi1, azi2, s12, a12, m12, MM12, MM21, SS12 + double precision a, f + integer r, assert, omask + include 'geodesic.inc' + + a = 89.8d0 + f = -1.83d0 + omask = 0 + r = 0 + call invers(a, f, 0d0, 0d0, -10d0, 160d0, + + s12, azi1, azi2, omask, a12, m12, MM12, MM21, SS12) + r = r + assert(azi1, 120.27d0, 1d-2) + r = r + assert(azi2, 105.15d0, 1d-2) + r = r + assert(s12, 266.7d0, 1d-1) + + tstg12 = r + return + end + + integer function tstg14() +* Check fix for inverse ignoring lon12 = nan + double precision azi1, azi2, s12, a12, m12, MM12, MM21, SS12 + double precision a, f, LatFix + integer r, notnan, omask + include 'geodesic.inc' + +* WGS84 values + a = 6378137d0 + f = 1/298.257223563d0 + omask = 0 + r = 0 + call invers(a, f, 0d0, 0d0, 1d0, LatFix(91d0), + + s12, azi1, azi2, omask, a12, m12, MM12, MM21, SS12) + r = r + notnan(azi1) + r = r + notnan(azi2) + r = r + notnan(s12) + tstg14 = r + return + end + + integer function tstg15() +* Initial implementation of Math::eatanhe was wrong for e^2 < 0. This +* checks that this is fixed. + double precision lat2, lon2, azi2, a12, m12, MM12, MM21, SS12 + double precision a, f + integer r, assert, omask, flags + include 'geodesic.inc' + + a = 6.4d6 + f = -1/150.0d0 + omask = 8 + flags = 0 + r = 0 + call direct(a, f, 1d0, 2d0, 3d0, 4d0, + + flags, lat2, lon2, azi2, omask, a12, m12, MM12, MM21, SS12) + r = r + assert(SS12, 23700d0, 0.5d0) + + tstg15 = r + return + end + + integer function tstg17() +* Check fix for LONG_UNROLL bug found on 2015-05-07 + double precision lat2, lon2, azi2, a12, m12, MM12, MM21, SS12 + double precision a, f + integer r, assert, omask, flags + include 'geodesic.inc' + +* WGS84 values + a = 6378137d0 + f = 1/298.257223563d0 + omask = 0 + flags = 2 + r = 0 + call direct(a, f, 40d0, -75d0, -10d0, 2d7, + + flags, lat2, lon2, azi2, omask, a12, m12, MM12, MM21, SS12) + r = r + assert(lat2, -39d0, 1d0) + r = r + assert(lon2, -254d0, 1d0) + r = r + assert(azi2, -170d0, 1d0) + flags = 0 + call direct(a, f, 40d0, -75d0, -10d0, 2d7, + + flags, lat2, lon2, azi2, omask, a12, m12, MM12, MM21, SS12) + r = r + assert(lat2, -39d0, 1d0) + r = r + assert(lon2, 105d0, 1d0) + r = r + assert(azi2, -170d0, 1d0) + + tstg17 = r + return + end + + integer function tstg26() +* Check 0/0 problem with area calculation on sphere 2015-09-08 + double precision azi1, azi2, s12, a12, m12, MM12, MM21, SS12 + double precision a, f + integer r, assert, omask + include 'geodesic.inc' + + a = 6.4d6 + f = 0 + omask = 8 + r = 0 + call invers(a, f, 1d0, 2d0, 3d0, 4d0, + + s12, azi1, azi2, omask, a12, m12, MM12, MM21, SS12) + r = r + assert(SS12, 49911046115.0d0, 0.5d0) + + tstg26 = r + return + end + + integer function tstg28() +* Check fix for LONG_UNROLL bug found on 2015-05-07 + double precision lat2, lon2, azi2, a12, m12, MM12, MM21, SS12 + double precision a, f + integer r, assert, omask, flags + include 'geodesic.inc' + + a = 6.4d6 + f = 0.1d0 + omask = 1 + 2 + 4 + 8 + flags = 0 + r = 0 + call direct(a, f, 1d0, 2d0, 10d0, 5d6, + + flags, lat2, lon2, azi2, omask, a12, m12, MM12, MM21, SS12) + r = r + assert(a12, 48.55570690d0, 0.5d-8) + + tstg28 = r + return + end + + integer function tstg33() +* Check max(-0.0,+0.0) issues 2015-08-22 (triggered by bugs in Octave -- +* sind(-0.0) = +0.0 -- and in some version of Visual Studio -- +* fmod(-0.0, 360.0) = +0.0. + double precision azi1, azi2, s12, a12, m12, MM12, MM21, SS12 + double precision a, f + integer r, assert, omask + include 'geodesic.inc' + +* WGS84 values + a = 6378137d0 + f = 1/298.257223563d0 + omask = 0 + r = 0 + call invers(a, f, 0d0, 0d0, 0d0, 179d0, + + s12, azi1, azi2, omask, a12, m12, MM12, MM21, SS12) + r = r + assert(azi1, 90.00000d0, 0.5d-5) + r = r + assert(azi2, 90.00000d0, 0.5d-5) + r = r + assert(s12, 19926189d0, 0.5d0) + call invers(a, f, 0d0, 0d0, 0d0, 179.5d0, + + s12, azi1, azi2, omask, a12, m12, MM12, MM21, SS12) + r = r + assert(azi1, 55.96650d0, 0.5d-5) + r = r + assert(azi2, 124.03350d0, 0.5d-5) + r = r + assert(s12, 19980862d0, 0.5d0) + call invers(a, f, 0d0, 0d0, 0d0, 180d0, + + s12, azi1, azi2, omask, a12, m12, MM12, MM21, SS12) + r = r + assert(azi1, 0.00000d0, 0.5d-5) + r = r + assert(abs(azi2), 180.00000d0, 0.5d-5) + r = r + assert(s12, 20003931d0, 0.5d0) + call invers(a, f, 0d0, 0d0, 1d0, 180d0, + + s12, azi1, azi2, omask, a12, m12, MM12, MM21, SS12) + r = r + assert(azi1, 0.00000d0, 0.5d-5) + r = r + assert(abs(azi2), 180.00000d0, 0.5d-5) + r = r + assert(s12, 19893357d0, 0.5d0) + a = 6.4d6 + f = 0 + call invers(a, f, 0d0, 0d0, 0d0, 179d0, + + s12, azi1, azi2, omask, a12, m12, MM12, MM21, SS12) + r = r + assert(azi1, 90.00000d0, 0.5d-5) + r = r + assert(azi2, 90.00000d0, 0.5d-5) + r = r + assert(s12, 19994492d0, 0.5d0) + call invers(a, f, 0d0, 0d0, 0d0, 180d0, + + s12, azi1, azi2, omask, a12, m12, MM12, MM21, SS12) + r = r + assert(azi1, 0.00000d0, 0.5d-5) + r = r + assert(abs(azi2), 180.00000d0, 0.5d-5) + r = r + assert(s12, 20106193d0, 0.5d0) + call invers(a, f, 0d0, 0d0, 1d0, 180d0, + + s12, azi1, azi2, omask, a12, m12, MM12, MM21, SS12) + r = r + assert(azi1, 0.00000d0, 0.5d-5) + r = r + assert(abs(azi2), 180.00000d0, 0.5d-5) + r = r + assert(s12, 19994492d0, 0.5d0) + a = 6.4d6 + f = -1/300.0d0 + call invers(a, f, 0d0, 0d0, 0d0, 179d0, + + s12, azi1, azi2, omask, a12, m12, MM12, MM21, SS12) + r = r + assert(azi1, 90.00000d0, 0.5d-5) + r = r + assert(azi2, 90.00000d0, 0.5d-5) + r = r + assert(s12, 19994492d0, 0.5d0) + call invers(a, f, 0d0, 0d0, 0d0, 180d0, + + s12, azi1, azi2, omask, a12, m12, MM12, MM21, SS12) + r = r + assert(azi1, 90.00000d0, 0.5d-5) + r = r + assert(azi2, 90.00000d0, 0.5d-5) + r = r + assert(s12, 20106193d0, 0.5d0) + call invers(a, f, 0d0, 0d0, 0.5d0, 180d0, + + s12, azi1, azi2, omask, a12, m12, MM12, MM21, SS12) + r = r + assert(azi1, 33.02493d0, 0.5d-5) + r = r + assert(azi2, 146.97364d0, 0.5d-5) + r = r + assert(s12, 20082617d0, 0.5d0) + call invers(a, f, 0d0, 0d0, 1d0, 180d0, + + s12, azi1, azi2, omask, a12, m12, MM12, MM21, SS12) + r = r + assert(azi1, 0.00000d0, 0.5d-5) + r = r + assert(abs(azi2), 180.00000d0, 0.5d-5) + r = r + assert(s12, 20027270d0, 0.5d0) + + tstg33 = r + return + end + + integer function tstg55() +* Check fix for nan + point on equator or pole not returning all nans in +* Geodesic::Inverse, found 2015-09-23. + double precision azi1, azi2, s12, a12, m12, MM12, MM21, SS12 + double precision a, f + integer r, notnan, omask + include 'geodesic.inc' + +* WGS84 values + a = 6378137d0 + f = 1/298.257223563d0 + omask = 0 + r = 0 + call invers(a, f, 91d0, 0d0, 0d0, 90d0, + + s12, azi1, azi2, omask, a12, m12, MM12, MM21, SS12) + r = r + notnan(azi1) + r = r + notnan(azi2) + r = r + notnan(s12) + call invers(a, f, 91d0, 0d0, 90d0, 9d0, + + s12, azi1, azi2, omask, a12, m12, MM12, MM21, SS12) + r = r + notnan(azi1) + r = r + notnan(azi2) + r = r + notnan(s12) + tstg55 = r + return + end + + integer function tstg59() +* Check for points close with longitudes close to 180 deg apart. + double precision azi1, azi2, s12, a12, m12, MM12, MM21, SS12 + double precision a, f + integer r, assert, omask + include 'geodesic.inc' + +* WGS84 values + a = 6378137d0 + f = 1/298.257223563d0 + omask = 0 + r = 0 + call invers(a, f, 5d0, 0.00000000000001d0, 10d0, 180d0, + + s12, azi1, azi2, omask, a12, m12, MM12, MM21, SS12) + r = r + assert(azi1, 0.000000000000035d0, 1.5d-14); + r = r + assert(azi2, 179.99999999999996d0, 1.5d-14); + r = r + assert(s12, 18345191.174332713d0, 2.5d-9); + tstg59 = r + return + end + + integer function tstg61() +* Make sure small negative azimuths are west-going + double precision lat2, lon2, azi2, a12, m12, MM12, MM21, SS12 + double precision a, f + integer r, assert, omask, flags + include 'geodesic.inc' + +* WGS84 values + a = 6378137d0 + f = 1/298.257223563d0 + omask = 0 + flags = 2 + r = 0 + call direct(a, f, 45d0, 0d0, -0.000000000000000003d0, 1d7, + + flags, lat2, lon2, azi2, omask, a12, m12, MM12, MM21, SS12) + r = r + assert(lat2, 45.30632d0, 0.5d-5) + r = r + assert(lon2, -180d0, 0.5d-5) + r = r + assert(abs(azi2), 180d0, 0.5d-5) + + tstg61 = r + return + end + + integer function tstg73() +* Check for backwards from the pole bug reported by Anon on 2016-02-13. +* This only affected the Java implementation. It was introduced in Java +* version 1.44 and fixed in 1.46-SNAPSHOT on 2016-01-17. + double precision lat2, lon2, azi2, a12, m12, MM12, MM21, SS12 + double precision a, f + integer r, assert, omask, flags + include 'geodesic.inc' + +* WGS84 values + a = 6378137d0 + f = 1/298.257223563d0 + omask = 0 + flags = 0 + r = 0 + call direct(a, f, 90d0, 10d0, 180d0, -1d6, + + flags, lat2, lon2, azi2, omask, a12, m12, MM12, MM21, SS12) + r = r + assert(lat2, 81.04623d0, 0.5d-5) + r = r + assert(lon2, -170d0, 0.5d-5) + r = r + assert(azi2, 0d0, 0.5d-5) + + tstg73 = r + return + end + + integer function tstg74() +* Check fix for inaccurate areas, bug introduced in v1.46, fixed +* 2015-10-16. + double precision azi1, azi2, s12, a12, m12, MM12, MM21, SS12 + double precision a, f + integer r, assert, omask + include 'geodesic.inc' + +* WGS84 values + a = 6378137d0 + f = 1/298.257223563d0 + omask = 1 + 2 + 4 + 8 + r = 0 + call invers(a, f, 54.1589d0, 15.3872d0, 54.1591d0, 15.3877d0, + + s12, azi1, azi2, omask, a12, m12, MM12, MM21, SS12) + r = r + assert(azi1, 55.723110355d0, 5d-9); + r = r + assert(azi2, 55.723515675d0, 5d-9); + r = r + assert(s12, 39.527686385d0, 5d-9); + r = r + assert(a12, 0.000355495d0, 5d-9); + r = r + assert(m12, 39.527686385d0, 5d-9); + r = r + assert(MM12, 0.999999995d0, 5d-9); + r = r + assert(MM21, 0.999999995d0, 5d-9); + r = r + assert(SS12, 286698586.30197d0, 5d-4); + tstg74 = r + return + end + + integer function tstg76() +* The distance from Wellington and Salamanca (a classic failure of +* Vincenty + double precision azi1, azi2, s12, a12, m12, MM12, MM21, SS12 + double precision a, f + integer r, assert, omask + include 'geodesic.inc' + +* WGS84 values + a = 6378137d0 + f = 1/298.257223563d0 + omask = 0 + r = 0 + call invers(a, f, + + -(41+19/60d0), 174+49/60d0, 40+58/60d0, -(5+30/60d0), + + s12, azi1, azi2, omask, a12, m12, MM12, MM21, SS12) + r = r + assert(azi1, 160.39137649664d0, 0.5d-11) + r = r + assert(azi2, 19.50042925176d0, 0.5d-11) + r = r + assert(s12, 19960543.857179d0, 0.5d-6) + tstg76 = r + return + end + + integer function tstg78() +* An example where the NGS calculator fails to converge + double precision azi1, azi2, s12, a12, m12, MM12, MM21, SS12 + double precision a, f + integer r, assert, omask + include 'geodesic.inc' + +* WGS84 values + a = 6378137d0 + f = 1/298.257223563d0 + omask = 0 + r = 0 + call invers(a, f, 27.2d0, 0d0, -27.1d0, 179.5d0, + + s12, azi1, azi2, omask, a12, m12, MM12, MM21, SS12) + r = r + assert(azi1, 45.82468716758d0, 0.5d-11) + r = r + assert(azi2, 134.22776532670d0, 0.5d-11) + r = r + assert(s12, 19974354.765767d0, 0.5d-6) + tstg78 = r + return + end + + integer function tstp0() +* Check fix for pole-encircling bug found 2011-03-16 + double precision lata(4), lona(4) + data lata / 89d0, 89d0, 89d0, 89d0 / + data lona / 0d0, 90d0, 180d0, 270d0 / + double precision latb(4), lonb(4) + data latb / -89d0, -89d0, -89d0, -89d0 / + data lonb / 0d0, 90d0, 180d0, 270d0 / + double precision latc(4), lonc(4) + data latc / 0d0, -1d0, 0d0, 1d0 / + data lonc / -1d0, 0d0, 1d0, 0d0 / + double precision latd(3), lond(3) + data latd / 90d0, 0d0, 0d0 / + data lond / 0d0, 0d0, 90d0 / + double precision a, f, AA, PP + integer r, assert + include 'geodesic.inc' + +* WGS84 values + a = 6378137d0 + f = 1/298.257223563d0 + r = 0 + + call area(a, f, lata, lona, 4, AA, PP) + r = r + assert(PP, 631819.8745d0, 1d-4) + r = r + assert(AA, 24952305678.0d0, 1d0) + + call area(a, f, latb, lonb, 4, AA, PP) + r = r + assert(PP, 631819.8745d0, 1d-4) + r = r + assert(AA, -24952305678.0d0, 1d0) + + call area(a, f, latc, lonc, 4, AA, PP) + r = r + assert(PP, 627598.2731d0, 1d-4) + r = r + assert(AA, 24619419146.0d0, 1d0) + + call area(a, f, latd, lond, 3, AA, PP) + r = r + assert(PP, 30022685d0, 1d0) + r = r + assert(AA, 63758202715511.0d0, 1d0) + + tstp0 = r + return + end + + integer function tstp5() +* Check fix for Planimeter pole crossing bug found 2011-06-24 + double precision lat(3), lon(3) + data lat / 89d0, 89d0, 89d0 / + data lon / 0.1d0, 90.1d0, -179.9d0 / + double precision a, f, AA, PP + integer r, assert + include 'geodesic.inc' + +* WGS84 values + a = 6378137d0 + f = 1/298.257223563d0 + r = 0 + + call area(a, f, lat, lon, 3, AA, PP) + r = r + assert(PP, 539297d0, 1d0) + r = r + assert(AA, 12476152838.5d0, 1d0) + + tstp5 = r + return + end + + integer function tstp6() +* Check fix for pole-encircling bug found 2011-03-16 + double precision lata(3), lona(3) + data lata / 9d0, 9d0, 9d0 / + data lona / -0.00000000000001d0, 180d0, 0d0 / + double precision latb(3), lonb(3) + data latb / 9d0, 9d0, 9d0 / + data lonb / 0.00000000000001d0, 0d0, 180d0 / + double precision latc(3), lonc(3) + data latc / 9d0, 9d0, 9d0 / + data lonc / 0.00000000000001d0, 180d0, 0d0 / + double precision latd(3), lond(3) + data latd / 9d0, 9d0, 9d0 / + data lond / -0.00000000000001d0, 0d0, 180d0 / + double precision a, f, AA, PP + integer r, assert + include 'geodesic.inc' + +* WGS84 values + a = 6378137d0 + f = 1/298.257223563d0 + r = 0 + + call area(a, f, lata, lona, 3, AA, PP) + r = r + assert(PP, 36026861d0, 1d0) + r = r + assert(AA, 0d0, 1d0) + + tstp6 = r + return + end + + integer function tstp12() +* AA of arctic circle (not really -- adjunct to rhumb-AA test) + double precision lat(2), lon(2) + data lat / 66.562222222d0, 66.562222222d0 / + data lon / 0d0, 180d0 / + double precision a, f, AA, PP + integer r, assert + include 'geodesic.inc' + +* WGS84 values + a = 6378137d0 + f = 1/298.257223563d0 + r = 0 + + call area(a, f, lat, lon, 2, AA, PP) + r = r + assert(PP, 10465729d0, 1d0) + r = r + assert(AA, 0d0, 1d0) + + tstp12 = r + return + end + + integer function tstp13() +* Check encircling pole twice + double precision lat(6), lon(6) + data lat / 89d0, 89d0, 89d0, 89d0, 89d0, 89d0 / + data lon / -360d0, -240d0, -120d0, 0d0, 120d0, 240d0 / + double precision a, f, AA, PP + integer r, assert + include 'geodesic.inc' + +* WGS84 values + a = 6378137d0 + f = 1/298.257223563d0 + r = 0 + + call area(a, f, lat, lon, 6, AA, PP) + r = r + assert(PP, 1160741d0, 1d0) + r = r + assert(AA, 32415230256.0d0, 1d0) + + tstp13 = r + return + end + + program geodtest + integer n, i + integer tstinv, tstdir, tstarc, + + tstg0, tstg1, tstg2, tstg5, tstg6, tstg9, tstg10, tstg11, + + tstg12, tstg14, tstg15, tstg17, tstg26, tstg28, tstg33, + + tstg55, tstg59, tstg61, tstg73, tstg74, tstg76, tstg78, + + tstp0, tstp5, tstp6, tstp12, tstp13 + + n = 0 + i = tstinv() + if (i .gt. 0) then + n = n + 1 + print *, 'tstinv fail:', i + end if + i = tstdir() + if (i .gt. 0) then + n = n + 1 + print *, 'tstdir fail:', i + end if + i = tstarc() + if (i .gt. 0) then + n = n + 1 + print *, 'tstarc fail:', i + end if + i = tstg0() + if (i .gt. 0) then + n = n + 1 + print *, 'tstg0 fail:', i + end if + i = tstg1() + if (i .gt. 0) then + n = n + 1 + print *, 'tstg1 fail:', i + end if + i = tstg2() + if (i .gt. 0) then + n = n + 1 + print *, 'tstg2 fail:', i + end if + i = tstg5() + if (i .gt. 0) then + n = n + 1 + print *, 'tstg5 fail:', i + end if + i = tstg6() + if (i .gt. 0) then + n = n + 1 + print *, 'tstg6 fail:', i + end if + i = tstg9() + if (i .gt. 0) then + n = n + 1 + print *, 'tstg9 fail:', i + end if + i = tstg10() + if (i .gt. 0) then + n = n + 1 + print *, 'tstg10 fail:', i + end if + i = tstg11() + if (i .gt. 0) then + n = n + 1 + print *, 'tstg11 fail:', i + end if + i = tstg12() + if (i .gt. 0) then + n = n + 1 + print *, 'tstg12 fail:', i + end if + i = tstg14() + if (i .gt. 0) then + n = n + 1 + print *, 'tstg14 fail:', i + end if + i = tstg15() + if (i .gt. 0) then + n = n + 1 + print *, 'tstg15 fail:', i + end if + i = tstg17() + if (i .gt. 0) then + n = n + 1 + print *, 'tstg17 fail:', i + end if + i = tstg26() + if (i .gt. 0) then + n = n + 1 + print *, 'tstg26 fail:', i + end if + i = tstg28() + if (i .gt. 0) then + n = n + 1 + print *, 'tstg28 fail:', i + end if + i = tstg33() + if (i .gt. 0) then + n = n + 1 + print *, 'tstg33 fail:', i + end if + i = tstg55() + if (i .gt. 0) then + n = n + 1 + print *, 'tstg55 fail:', i + end if + i = tstg59() + if (i .gt. 0) then + n = n + 1 + print *, 'tstg59 fail:', i + end if + i = tstg61() + if (i .gt. 0) then + n = n + 1 + print *, 'tstg61 fail:', i + end if + i = tstg73() + if (i .gt. 0) then + n = n + 1 + print *, 'tstg73 fail:', i + end if + i = tstg74() + if (i .gt. 0) then + n = n + 1 + print *, 'tstg74 fail:', i + end if + i = tstg76() + if (i .gt. 0) then + n = n + 1 + print *, 'tstg76 fail:', i + end if + i = tstg78() + if (i .gt. 0) then + n = n + 1 + print *, 'tstg78 fail:', i + end if + i = tstp0() + if (i .gt. 0) then + n = n + 1 + print *, 'tstp0 fail:', i + end if + i = tstp5() + if (i .gt. 0) then + n = n + 1 + print *, 'tstp5 fail:', i + end if + i = tstp6() + if (i .gt. 0) then + n = n + 1 + print *, 'tstp6 fail:', i + end if + i = tstp12() + if (i .gt. 0) then + n = n + 1 + print *, 'tstp12 fail:', i + end if + i = tstp13() + if (i .gt. 0) then + n = n + 1 + print *, 'tstp13 fail:', i + end if + + if (n .gt. 0) then + stop 1 + end if + + stop + end + +*> @endcond SKIP diff --git a/gtsam/3rdparty/GeographicLib/legacy/Fortran/ngscommon.for b/gtsam/3rdparty/GeographicLib/legacy/Fortran/ngscommon.for new file mode 100644 index 000000000..96e5babfb --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/legacy/Fortran/ngscommon.for @@ -0,0 +1,806 @@ + subroutine bufdms (buff,lgh,hem,dd,dm,ds,ierror) + implicit double precision (a-h, o-z) + implicit integer (i-n) +c + logical done,flag +c + character*1 buff(*),abuf(21) + character*1 ch + character*1 hem + integer*4 ll,lgh + integer*4 i4,id,im,is,icond,ierror + real*8 x(5) +c +c set the "error flag" +c + ierror = 0 + icond = 0 +c +c set defaults for dd,dm,ds +c + dd = 0.0d0 + dm = 0.0d0 + ds = 0.0d0 +c +c set default limits for "hem" flag +c + if( hem.eq.'N' .or. hem.eq.'S' )then + ddmax = 90.0d0 + elseif( hem.eq.'E' .or. hem.eq.'W' )then + ddmax = 360.0d0 + elseif( hem.eq.'A' )then + ddmax = 360.0d0 + elseif( hem.eq.'Z' )then + ddmax = 180.0d0 + elseif( hem.eq.'*' )then + ddmax = 0.0d0 + ierror = 1 + else + ddmax = 360.0d0 + endif +c + do 1 i=1,5 + x(i) = 0.0d0 + 1 continue +c + icolon = 0 + ipoint = 0 + icount = 0 + flag = .true. + jlgh = lgh +c + do 2 i=1,jlgh + if( buff(i).eq.':' )then + icolon = icolon+1 + endif + if( buff(i).eq.'.' )then + ipoint = ipoint+1 + flag = .false. + endif + if( flag )then + icount = icount+1 + endif + 2 continue +c + if( ipoint.eq.1 .and. icolon.eq.0 )then +c +c load temp buffer +c + do 3 i=1,jlgh + abuf(i) = buff(i) + 3 continue + abuf(jlgh+1) = '$' + ll = jlgh +c + call gvalr8 (abuf,ll,r8,icond) +c + if( icount.ge.5 )then +c +c value is a packed decimal of ==> DDMMSS.sssss +c + ss = r8/10000.0d0 + id = idint( ss ) +c + r8 = r8-10000.0d0*dble(float(id)) + ss = r8/100.0d0 + im = idint( ss ) +c + r8 = r8-100.0d0*dble(float(im)) + else +c +c value is a decimal of ==> .xx X.xxx X. +c + id = idint( r8 ) + r8 = (r8-id)*60.0d0 + im = idint( r8 ) + r8 = (r8-im)*60.0d0 + endif +c +c account for rounding error +c + is = idnint( r8*1.0d5 ) + if( is.ge.6000000 )then + r8 = 0.0d0 + im = im+1 + endif +c + if( im.ge.60 )then + im = 0 + id = id+1 + endif +c + dd = dble( float( id ) ) + dm = dble( float( im ) ) + ds = r8 + else +c +c buff() value is a d,m,s of ==> NN:NN:XX.xxx +c + k = 0 + next = 1 + done = .false. + ie = jlgh +c + do 100 j=1,5 + ib = next + do 90 i=ib,ie + ch = buff(i) + last = i + if( i.eq.jlgh .or. ch.eq.':' )then + if( i.eq.jlgh )then + done = .true. + endif + if( ch.eq.':' )then + last = i-1 + endif + goto 91 + endif + 90 continue + goto 98 +c + 91 ipoint = 0 + ik = 0 + do 92 i=next,last + ik = ik+1 + ch = buff(i) + if( ch.eq.'.' )then + ipoint = ipoint+1 + endif + abuf(ik) = buff(i) + 92 continue + abuf(ik+1) = '$' +c + ll = ik + if( ipoint.eq.0 )then + call gvali4 (abuf,ll,i4,icond) + r8 = dble(float( i4 )) + else + call gvalr8 (abuf,ll,r8,icond) + endif +c + k = k+1 + x(k) = r8 +c + 98 if( done )then + goto 101 + endif +c + next = last + 99 next = next+1 + if( buff(next).eq.':' )then + goto 99 + endif + 100 continue +c +c load dd,dm,ds +c + 101 if( k.ge.1 )then + dd = x(1) + endif +c + if( k.ge.2 )then + dm = x(2) + endif +c + if( k.ge.3 )then + ds = x(3) + endif + endif +c + if( dd.gt.ddmax .or. + 1 dm.ge.60.0d0 .or. + 1 ds.ge.60.0d0 )then + ierror = 1 + dd = 0.0d0 + dm = 0.0d0 + ds = 0.0d0 + endif +c + if( icond.ne.0 )then + ierror = 1 + endif +c + return + end + + subroutine elipss (elips) + implicit double precision(a-h,o-z) + character*1 answer + character*30 elips + common/elipsoid/a,f + write(*,*) ' Other Ellipsoids.' + write(*,*) ' -----------------' + write(*,*) ' ' + write(*,*) ' A) Airy 1858' + write(*,*) ' B) Airy Modified' + write(*,*) ' C) Australian National' + write(*,*) ' D) Bessel 1841' + write(*,*) ' E) Clarke 1880' + write(*,*) ' F) Everest 1830' + write(*,*) ' G) Everest Modified' + write(*,*) ' H) Fisher 1960' + write(*,*) ' I) Fisher 1968' + write(*,*) ' J) Hough 1956' + write(*,*) ' K) International (Hayford)' + write(*,*) ' L) Krassovsky 1938' + write(*,*) ' M) NWL-9D (WGS 66)' + write(*,*) ' N) South American 1969' + write(*,*) ' O) Soviet Geod. System 1985' + write(*,*) ' P) WGS 72' + write(*,*) ' Q-Z) User defined.' + write(*,*) ' ' + write(*,*) ' Enter choice : ' + read(*,10) answer + 10 format(a1) +c + if(answer.eq.'A'.or.answer.eq.'a') then + a=6377563.396d0 + f=1.d0/299.3249646d0 + elips='Airy 1858' + elseif(answer.eq.'B'.or.answer.eq.'b') then + a=6377340.189d0 + f=1.d0/299.3249646d0 + elips='Airy Modified' + elseif(answer.eq.'C'.or.answer.eq.'c') then + a=6378160.d0 + f=1.d0/298.25d0 + elips='Australian National' + elseif(answer.eq.'D'.or.answer.eq.'d') then + a=6377397.155d0 + f=1.d0/299.1528128d0 + elips='Bessel 1841' + elseif(answer.eq.'E'.or.answer.eq.'e') then + a=6378249.145d0 + f=1.d0/293.465d0 + elips='Clarke 1880' + elseif(answer.eq.'F'.or.answer.eq.'f') then + a=6377276.345d0 + f=1.d0/300.8017d0 + elips='Everest 1830' + elseif(answer.eq.'G'.or.answer.eq.'g') then + a=6377304.063d0 + f=1.d0/300.8017d0 + elips='Everest Modified' + elseif(answer.eq.'H'.or.answer.eq.'h') then + a=6378166.d0 + f=1.d0/298.3d0 + elips='Fisher 1960' + elseif(answer.eq.'I'.or.answer.eq.'i') then + a=6378150.d0 + f=1.d0/298.3d0 + elips='Fisher 1968' + elseif(answer.eq.'J'.or.answer.eq.'j') then + a=6378270.d0 + f=1.d0/297.d0 + elips='Hough 1956' + elseif(answer.eq.'K'.or.answer.eq.'k') then + a=6378388.d0 + f=1.d0/297.d0 + elips='International (Hayford)' + elseif(answer.eq.'L'.or.answer.eq.'l') then + a=6378245.d0 + f=1.d0/298.3d0 + elips='Krassovsky 1938' + elseif(answer.eq.'M'.or.answer.eq.'m') then + a=6378145.d0 + f=1.d0/298.25d0 + elips='NWL-9D (WGS 66)' + elseif(answer.eq.'N'.or.answer.eq.'n') then + a=6378160.d0 + f=1.d0/298.25d0 + elips='South American 1969' + elseif(answer.eq.'O'.or.answer.eq.'o') then + a=6378136.d0 + f=1.d0/298.257d0 + elips='Soviet Geod. System 1985' + elseif(answer.eq.'P'.or.answer.eq.'p') then + a=6378135.d0 + f=1.d0/298.26d0 + elips='WGS 72' + else + elips = 'User defined.' +c + write(*,*) ' Enter Equatorial axis, a : ' + read(*,*) a + a = dabs(a) +c + write(*,*) ' Enter either Polar axis, b or ' + write(*,*) ' Reciprocal flattening, 1/f : ' + read(*,*) ss + ss = dabs(ss) +c + f = 0.0d0 + if( 200.0d0.le.ss .and. ss.le.310.0d0 )then + f = 1.d0/ss + elseif( 6000000.0d0.lt.ss .and. ss.lt.a )then + f = (a-ss)/a + else + elips = 'Error: default GRS80 used.' + a = 6378137.0d0 + f = 1.0d0/298.25722210088d0 + endif + endif +c + return + end + + subroutine fixdms (ideg, min, sec, tol ) +c + implicit double precision (a-h, o-z) + implicit integer (i-n) +c +c test for seconds near 60.0-tol +c + if( sec.ge.( 60.0d0-tol ) )then + sec = 0.0d0 + min = min+1 + endif +c +c test for minutes near 60 +c + if( min.ge.60 )then + min = 0 + ideg = ideg+1 + endif +c +c test for degrees near 360 +c + if( ideg.ge.360 )then + ideg = 0 + endif +c + return + end + + subroutine hem_ns ( lat_sn, hem ) + implicit integer (i-n) + character*6 hem +c + if( lat_sn.eq.1 ) then + hem = 'North ' + else + hem = 'South ' + endif +c + return + end + + subroutine hem_ew ( lon_sn, hem ) + implicit integer (i-n) + character*6 hem +c + if( lon_sn.eq.1 ) then + hem = 'East ' + else + hem = 'West ' + endif +c + return + end + + subroutine getdeg(d,m,sec,isign,val) + +*** comvert deg, min, sec to degrees + + implicit double precision(a-h,j-z) + + val=(d+m/60.d0+sec/3600.d0) + val=dble(isign)*val + + return + end + + subroutine gvali4 (buff,ll,vali4,icond) + implicit integer (i-n) +c + logical plus,sign,done,error + character*1 buff(*) + character*1 ch +c +c integer*2 i +c integer*2 l1 +c + integer*4 ich,icond + integer*4 ll + integer*4 vali4 +c + l1 = ll + vali4 = 0 + icond = 0 + plus = .true. + sign = .false. + done = .false. + error = .false. +c + i = 0 + 10 i = i+1 + if( i.gt.l1 .or. done )then + go to 1000 + else + ch = buff(i) + ich = ichar( buff(i) ) + endif +c + if( ch.eq.'+' )then +c +c enter on plus sign +c + if( sign )then + goto 150 + else + sign = .true. + goto 10 + endif + elseif( ch.eq.'-' )then +c +c enter on minus sign +c + if( sign )then + goto 150 + else + sign = .true. + plus = .false. + goto 10 + endif + elseif( ch.ge.'0' .and. ch.le.'9' )then + goto 100 + elseif( ch.eq.' ' )then +c +c enter on space -- ignore leading spaces +c + if( .not.sign )then + goto 10 + else + buff(i) = '0' + ich = 48 + goto 100 + endif + elseif( ch.eq.':' )then +c +c enter on colon -- ignore +c + if( .not.sign )then + goto 10 + else + goto 1000 + endif + elseif( ch.eq.'$' )then +c +c enter on dollar "$" +c + done = .true. + goto 10 + else +c +c something wrong +c + goto 150 + endif +c +c enter on numeric +c + 100 vali4 = 10*vali4+(ich-48) + sign = .true. + goto 10 +c +c treat illegal character +c + 150 buff(i) = '0' + vali4 = 0 + icond = 1 +c + 1000 if( .not.plus )then + vali4 = -vali4 + endif +c + return + end + + subroutine gvalr8 (buff,ll,valr8,icond) + implicit integer (i-n) +c + logical plus,sign,dpoint,done +c + character*1 buff(*) + character*1 ch +c +c integer*2 i, ip +c integer*2 l1 +c integer*2 nn, num, n48 +c + integer*4 ich,icond + integer*4 ll +c + real*8 ten + real*8 valr8 + real*8 zero +c + data zero,ten/0.0d0,10.0d0/ +c + n48 = 48 + l1 = ll + icond = 0 + valr8 = zero + plus = .true. + sign = .false. + dpoint = .false. + done = .false. +c +c start loop thru buffer +c + i = 0 + 10 i = i+1 + if( i.gt.l1 .or. done )then + go to 1000 + else + ch = buff(i) + nn = ichar( ch ) + ich = nn + endif +c + if( ch.eq.'+' )then +c +c enter on plus sign +c + if( sign )then + goto 150 + else + sign = .true. + goto 10 + endif + elseif( ch.eq.'-' )then +c +c enter on minus sign +c + if( sign )then + goto 150 + else + sign = .true. + plus = .false. + goto 10 + endif + elseif( ch.eq.'.' )then +c +c enter on decimal point +c + ip = 0 + sign = .true. + dpoint = .true. + goto 10 + elseif( ch.ge.'0' .and. ch.le.'9' )then + goto 100 + elseif( ch.eq.' ' )then +c +c enter on space +c + if( .not.sign )then + goto 10 + else + buff(i) = '0' + ich = 48 + goto 100 + endif + elseif( ch.eq.':' .or. ch.eq.'$' )then +c +c enter on colon or "$" sign +c + done = .true. + goto 10 + else +c +c something wrong +c + goto 150 + endif +c +c enter on numeric +c + 100 sign = .true. + if( dpoint )then + ip = ip+1 + endif +c + num = ich + valr8 = ten*valr8+dble(float( num-n48 )) + goto 10 +c +c treat illegal character +c + 150 buff(i) = '0' + valr8 = 0.0d0 + icond = 1 +c + 1000 if( dpoint )then + valr8 = valr8/(ten**ip) + endif +c + if( .not.plus )then + valr8 = -valr8 + endif +c + return + end + + subroutine todmsp(val,id,im,s,isign) + +*** convert position degrees to deg,min,sec +*** range is [-180 to +180] + + implicit double precision(a-h,o-z) + + 1 if(val.gt.180) then + val=val-180-180 + go to 1 + endif + + 2 if(val.lt.-180) then + val=val+180+180 + go to 2 + endif + + if(val.lt.0.d0) then + isign=-1 + else + isign=+1 + endif + + s=dabs(val) + id=idint(s) + s=(s-id)*60.d0 + im=idint(s) + s=(s-im)*60.d0 + +*** account for rounding error + + is=idnint(s*1.d5) + if(is.ge.6000000) then + s=0.d0 + im=im+1 + endif + if(im.ge.60) then + im=0 + id=id+1 + endif + + return + end + + subroutine trim (buff,lgh,hem) +c + implicit integer (i-n) + character*1 ch,hem + character*1 buff(*) + integer*4 lgh +c + ibeg = 1 + do 10 i=1,50 + if( buff(i).ne.' ' )then + goto 11 + endif + ibeg = ibeg+1 + 10 continue + 11 continue + if( ibeg.ge.50 )then + ibeg = 1 + buff(ibeg) = '0' + endif +c + iend = 50 + do 20 i=1,50 + j = 51-i + if( buff(j).eq.' ' )then + iend = iend-1 + else + goto 21 + endif + 20 continue + 21 continue +c + ch = buff(ibeg) + if( hem.eq.'N' )then + if( ch.eq.'N' .or. ch.eq.'n' .or. ch.eq.'+' )then + hem = 'N' + ibeg = ibeg+1 + endif + if( ch.eq.'S' .or. ch.eq.'s' .or. ch.eq.'-' )then + hem = 'S' + ibeg = ibeg+1 + endif +c +c check for wrong hemisphere entry +c + if( ch.eq.'E' .or. ch.eq.'e' )then + hem = '*' + ibeg = ibeg+1 + endif + if( ch.eq.'W' .or. ch.eq.'w' )then + hem = '*' + ibeg = ibeg+1 + endif + elseif( hem.eq.'W' )then + if( ch.eq.'E' .or. ch.eq.'e' .or. ch.eq.'+' )then + hem = 'E' + ibeg = ibeg+1 + endif + if( ch.eq.'W' .or. ch.eq.'w' .or. ch.eq.'-' )then + hem = 'W' + ibeg = ibeg+1 + endif +c +c check for wrong hemisphere entry +c + if( ch.eq.'N' .or. ch.eq.'n' )then + hem = '*' + ibeg = ibeg+1 + endif + if( ch.eq.'S' .or. ch.eq.'s' )then + hem = '*' + ibeg = ibeg+1 + endif + elseif( hem.eq.'A' )then + if( .not.('0'.le.ch .and. ch.le.'9') )then + hem = '*' + ibeg = ibeg+1 + endif + else +c do nothing + endif +c +c + do 30 i=ibeg,iend + ch = buff(i) +c + if( ch.eq.':' .or. ch.eq.'.' )then + goto 30 + elseif( ch.eq.' ' .or. ch.eq.',' )then + buff(i) = ':' + elseif( '0'.le.ch .and. ch.le.'9' )then + goto 30 + else + buff(i) = ':' + endif +c + 30 continue +c +c left justify buff() array to its first character position +c also check for a ":" char in the starting position, +c if found!! skip it +c + j = 0 + ib = ibeg + ie = iend +c + do 40 i=ib,ie + if( i.eq.ibeg .and. buff(i).eq.':' )then +c +c move the 1st position pointer to the next char & +c do not put ":" char in buff(j) array where j=1 +c + ibeg = ibeg+1 + goto 40 + endif + j = j+1 + buff(j) = buff(i) + 40 continue +c +c + lgh = iend-ibeg+1 + j = lgh+1 + buff(j) = '$' +c +c clean-up the rest of the buff() array +c + do 50 i=j+1,50 + buff(i) = ' ' + 50 continue +c +c save a maximum of 20 characters +c + if( lgh.gt.20 )then + lgh = 20 + j = lgh+1 + buff(j) = '$' + endif +c + return + end diff --git a/gtsam/3rdparty/GeographicLib/legacy/Fortran/ngsforward.for b/gtsam/3rdparty/GeographicLib/legacy/Fortran/ngsforward.for new file mode 100644 index 000000000..a279b9535 --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/legacy/Fortran/ngsforward.for @@ -0,0 +1,490 @@ +cb::forward +c + program forward +c +c********1*********2*********3*********4*********5*********6*********7** +c +c name: forward +c version: 201211.29 +c author: stephen j. frakes +c last mod: Charles Karney +c purpose: to compute a geodetic forward (direct problem) +c and then display output information +c +c input parameters: +c ----------------- +c +c output parameters: +c ------------------ +c +c local variables and constants: +c ------------------------------ +c answer user prompt response +c arc meridional arc distance latitude p1 to p2 (meters) +c b semiminor axis polar (in meters) +c baz azimuth back (in radians) +c blimit geodetic distance allowed on ellipsoid (in meters) +c buff input char buffer array +c dd,dm,ds temporary values for degrees, minutes, seconds +c dmt,d_mt char constants for units (in meters) +c dd_max maximum ellipsoid distance -1 (in meters) +c edist ellipsoid distance (in meters) +c elips ellipsoid choice +c esq eccentricity squared for reference ellipsoid +c faz azimuth forward (in radians) +c filout output file name +c finv reciprocal flattening +c hem hemisphere flag for lat & lon entry +c ierror error condition flag with d,m,s conversion +c lgh length of buff() array +c option user prompt response +c r1,r2 temporary variables +c ss temporary value for ellipsoid distance +c tol tolerance for conversion of seconds +c +c name1 name of station one +c ld1,lm1,sl1 latitude sta one - degrees,minutes,seconds +c ald1,alm1,sl1 latitude sta one - degrees,minutes,seconds +c lat1sn latitude sta one - sign (+/- 1) +c d_ns1 latitude sta one - char ('N','S') +c lod1,lom1,slo1 longitude sta one - degrees,minutes,seconds +c alod1,alom1,slo1 longitude sta one - degrees,minutes,seconds +c lon1sn longitude sta one - sign (+/- 1) +c d_ew1 longitude sta one - char ('E','W') +c iaz1,maz1,saz1 forward azimuth - degrees,minutes,seconds +c isign1 forward azimuth - flag (+/- 1) +c azd1,azm1,saz1 forward azimuth - degrees,minutes,seconds +c iazsn forward azimuth - flag (+/- 1) +c glat1,glon1 station one - (lat & lon in radians ) +c +c name2 name of station two +c ld2,lm2,sl2 latitude sta two - degrees,minutes,seconds +c lat2sn latitude sta two - sign (+/- 1) +c d_ns2 latitude sta two - char ('N','S') +c lod2,lom2,slo2 longitude sta two - degrees,minutes,seconds +c lon2sn longitude sta two - sign (+/- 1) +c d_ew2 longitude sta two - char ('E','W') +c iaz2,maz2,saz2 back azimuth - degrees,minutes,seconds +c isign2 back azimuth - flag (+/- 1) +c glat2,glon2 station two - (lat & lon in radians ) +c +c global variables and constants: +c ------------------------------- +c a semimajor axis equatorial (in meters) +c f flattening +c pi constant 3.14159.... +c rad constant 180.0/pi +c +c this module called by: n/a +c +c this module calls: elipss, getdeg, dirct1, todmsp +c gethem, trim, bufdms, gvalr8, gvali4, fixdms +c datan, write, read, dabs, open, stop +c +c include files used: n/a +c +c common blocks used: const, elipsoid +c +c references: see comments within subroutines +c +c comments: +c +c********1*********2*********3*********4*********5*********6*********7** +c::modification history +c::1990mm.dd, sjf, creation of program +c::199412.15, bmt, creation of program on viper +c::200203.08, crs, modified by c.schwarz to correct spelling of Clarke +c:: at request of Dave Doyle +c::200207.18, rws, modified i/o & standardized program documentation +c:: added subs trim, bufdms, gethem, gvali4, gvalr8 +c::200207.23, rws, added sub gpnarc +c::200208.15, rws, fixed an error in bufdms +c:: - renamed ellips to elipss "common error" with dirct2 +c:: - added FAZ & BAZ to printed output +c::200208.19, rws, added more error flags for web interface +c:: - added logical nowebb +c::200208.xx, sjf, program version number 2.0 +c::201211.29, cffk, program version number 3.1 +c:: - drop in replacement routines from +c:: "Algorithms for Geodesics" +c********1*********2*********3*********4*********5*********6*********7** +ce::forward +c + implicit double precision (a-h, o-z) + implicit integer (i-n) +c + logical nowebb +c + character*1 answer,option,dmt,buff(50),hem + character*6 d_ns1, d_ew1, d_ns2, d_ew2, d_mt + character*30 filout,name1,name2,elips +c + integer*4 ierror + integer*4 lgh +c + common/const/pi,rad + common/elipsoid/a,f +c +c ms_unix 0 = web version +c 1 = ms_dos or unix +c + parameter ( ms_unix = 0 ) +c + pi=4.d0*datan(1.d0) + rad=180.d0/pi + dmt='m' + d_mt='Meters' +c + if( ms_unix.eq.1 )then + nowebb = .true. + else + nowebb = .false. + endif +c + 1 do 2 i=1,25 + write(*,*) ' ' + 2 continue + + 5 write(*,*) ' Program Forward - Version 3.1 ' + write(*,*) ' ' + write(*,*) ' Ellipsoid options : ' + write(*,*) ' ' + write(*,*) ' 1) GRS80 / WGS84 (NAD83) ' + write(*,*) ' 2) Clarke 1866 (NAD27) ' + write(*,*) ' 3) Any other ellipsoid ' + write(*,*) ' ' + write(*,*) ' Enter choice : ' + read(*,10) option + 10 format(a1) +c + if(option.eq.'1') then + a=6378137.d0 + f=1.d0/298.25722210088d0 + elips='GRS80 / WGS84 (NAD83)' + elseif(option.eq.'2') then + a=6378206.4d0 + f=1.d0/294.9786982138d0 + elips='Clarke 1866 (NAD27)' + elseif(option.eq.'3') then + call elipss (elips) + else + write(*,*) ' Enter 1, 2, or 3 ! Try again --' + goto 5 + endif +c + esq = f*(2.0d0-f) +c +c compute the geodetic limit distance (blimit), it is equal +c to twice the equatorial circumference minus one meter +c + blimit = 2*pi*a-1.0d0 +c +c maximum distance allowed on ellipsoid +c + dd_max = blimit +c + write(*,*) ' ' + write(*,*) ' ' + write(*,*) ' ' + write(*,*) ' ' +c + 15 write(*,*) ' Enter First Station ' + write(*,16) + 16 format(18x,'(Separate D,M,S by blanks or commas)') + write(*,*) 'hDD MM SS.sssss Latitude : (h default = N )' +c + 11 format(50a1) +c + 22 hem='N' + read(*,11) buff + call trim (buff,lgh,hem) + call bufdms (buff,lgh,hem,dd,dm,ds,ierror) +c + if( ierror.eq.0 )then + irlat1 = 0 + else + irlat1 = 1 + write(*,*) ' Invalid Latitude ... Please re-enter it ' + write(*,*) ' ' + if( nowebb )then + goto 22 + endif + endif +c + ald1 = dd + alm1 = dm + sl1 = ds +c + if( hem.eq.'N' ) then + lat1sn = +1 + else + lat1sn = -1 + endif +c + write(*,*) 'hDDD MM SS.sssss Longitude : (h default = W )' +c + 23 hem='W' + read(*,11) buff + call trim (buff,lgh,hem) + call bufdms (buff,lgh,hem,dd,dm,ds,ierror) +c + if( ierror.eq.0 )then + irlon1 = 0 + else + irlon1 = 1 + write(*,*) ' Invalid Longitude ... Please re-enter it ' + write(*,*) ' ' + if( nowebb )then + goto 23 + endif + endif +c + alod1 = dd + alom1 = dm + slo1 = ds +c + if( hem.eq.'E' ) then + lon1sn = +1 + else + lon1sn = -1 + endif +c + call getdeg(ald1, alm1, sl1, lat1sn, glat1) + call getdeg(alod1,alom1,slo1,lon1sn, glon1) +c + 20 write(*,*) 'DDD MM SS.sss Forward Azimuth : (from north)' +c + 24 hem='A' + read(*,11) buff + call trim (buff,lgh,hem) + call bufdms (buff,lgh,hem,dd,dm,ds,ierror) +c + if( ierror.eq.0 )then + iazsn = 1 + irazi1 = 0 + else + irazi1 = 1 + write(*,*) ' Invalid Azimuth ... Please re-enter it ' + write(*,*) ' ' + if( nowebb )then + goto 24 + endif + endif +c + azd1 = dd + azm1 = dm + saz1 = ds +c + call getdeg(azd1,azm1,saz1,iazsn,faz) +c + write(*,*) 'DDDDDD.dddd Ellipsoidal Distance : (in meters)' +c + 25 ss = 0.0d0 + read(*,*) ss + ss = dabs(ss) +c + if( ss.lt.dd_max )then + edist = ss + irdst1 = 0 + else + irdst1 = 1 + write(*,*) ' Invalid Distance ... Please re-enter it ' + write(*,*) ' ' + if( nowebb )then + goto 25 + endif + edist = 0.001d0 + endif +c + call direct (a, f, glat1, glon1, faz, edist, 0, + + glat2, glon2, baz, 0, dummy, dummy, dummy, dummy, dummy) + if (baz .ge. 0) then + baz = baz - 180 + else + baz = baz + 180 + end if +c +c set the azimuth seconds tolerance +c + tol = 0.00005d0 +c + call todmsp(faz,iaz1,maz1,saz1,isign1) + if(isign1.lt.0) then + iaz1=359-iaz1 + maz1=59-maz1 + saz1=60.d0-saz1 + endif + call fixdms ( iaz1, maz1, saz1, tol ) +c + call todmsp(baz,iaz2,maz2,saz2,isign2) + if(isign2.lt.0) then + iaz2=359-iaz2 + maz2=59-maz2 + saz2=60.d0-saz2 + endif + call fixdms ( iaz2, maz2, saz2, tol ) +c + call todmsp(glat1, ld1, lm1, sl1, lat1sn) + call todmsp(glon1, lod1, lom1, slo1, lon1sn) + call todmsp(glat2, ld2, lm2, sl2, lat2sn) + call todmsp(glon2, lod2, lom2, slo2, lon2sn) +c + call hem_ns ( lat1sn, d_ns1 ) + call hem_ew ( lon1sn, d_ew1 ) + call hem_ns ( lat2sn, d_ns2 ) + call hem_ew ( lon2sn, d_ew2 ) +c + write(*,*) ' ' + write(*,*) ' ' + write(*,*) ' ' + write(*,*) ' ' + write(*,*) ' ' + write(*,49) elips + 49 format(' Ellipsoid : ',a30) + finv=1.d0/f + b=a*(1.d0-f) + write(*,50) a,b,finv + 50 format(' Equatorial axis, a = ',f15.4,/, + * ' Polar axis, b = ',f15.4,/, + * ' Inverse flattening, 1/f = ',f16.11) +c + 18 format(' LAT = ',i3,1x,i2,1x,f8.5,1x,a6) + 19 format(' LON = ',i3,1x,i2,1x,f8.5,1x,a6) +c + write(*,*) ' ' + write(*,*) ' First Station : ' + write(*,*) ' ---------------- ' + write(*,18) ld1, lm1, sl1, d_ns1 + write(*,19) lod1,lom1,slo1,d_ew1 +c + write(*,*) ' ' + write(*,*) ' Second Station : ' + write(*,*) ' ---------------- ' + write(*,18) ld2, lm2, sl2, d_ns2 + write(*,19) lod2,lom2,slo2,d_ew2 +c +c + 32 format(' Ellipsoidal distance S = ',f14.4,1x,a1) + 34 format(' Forward azimuth FAZ = ',i3,1x,i2,1x,f7.4, + 1 ' From North') + 35 format(' Back azimuth BAZ = ',i3,1x,i2,1x,f7.4, + 1 ' From North') +c + write(*,*) ' ' + write(*,34) iaz1,maz1,saz1 + write(*,35) iaz2,maz2,saz2 + write(*,32) edist,dmt + write(*,*) ' ' + write(*,*) ' Do you want to save this output into a file (y/n)?' + read(*,10) answer +c + if( answer.eq.'Y'.or.answer.eq.'y' )then + 39 write(*,*) ' Enter the output filename : ' + read(*,40) filout + 40 format(a30) + open(3,file=filout,status='new',err=99) + goto 98 +c + 99 write(*,*) ' File already exists, try again.' + go to 39 +c + 98 continue + write(3,*) ' ' + write(3,49) elips + write(3,50) a,b,finv + write(*,*) ' Enter the First Station name : ' + read(*,40) name1 + write(*,*) ' Enter the Second Station name : ' + read(*,40) name2 +c + 41 format(' First Station : ',a30) + 42 format(' Second Station : ',a30) + 84 format(' Error: First Station ... Invalid Latitude ') + 85 format(' Error: First Station ... Invalid Longitude ') + 86 format(' Error: Forward Azimuth .. Invalid Entry ') + 87 format(' Error: Ellipsoid Distance .. Invalid Entry ') + 88 format(1x,65(1h*)) + 91 format(' DD(0-89) MM(0-59) SS(0-59.999...) ') + 92 format(' DDD(0-359) MM(0-59) SS(0-59.999...) ') + 93 format(' Geodetic distance is too long ') +c + write(3,*) ' ' + write(3,41) name1 + write(3,*) ' ---------------- ' +c + if( irlat1.eq.0 )then + write(3,18) ld1, lm1, sl1, d_ns1 + else + write(3,88) + write(3,84) + write(3,91) + write(3,88) + endif +c + if( irlon1.eq.0 )then + write(3,19) lod1,lom1,slo1,d_ew1 + else + write(3,88) + write(3,85) + write(3,92) + write(3,88) + endif +c + write(3,*) ' ' + write(3,42) name2 + write(3,*) ' ---------------- ' + write(3,18) ld2, lm2, sl2, d_ns2 + write(3,19) lod2,lom2,slo2,d_ew2 +c + write(3,*) ' ' + if( irazi1.eq.0 )then + write(3,34) iaz1,maz1,saz1 + else + write(3,88) + write(3,86) + write(3,92) + write(3,88) + endif +c + write(3,35) iaz2,maz2,saz2 +c + if( irdst1.eq.0 )then + write(3,32) edist,dmt + else + write(3,88) + write(3,87) + write(3,93) + write(3,88) + endif +c + write(3,*) ' ' + endif +c + write(*,*) ' ' + write(*,*) ' ' + write(*,*) ' ' + write(*,*) ' 1) Another forward, different ellipsoid.' + write(*,*) ' 2) Same ellipsoid, two new stations.' + write(*,*) ' 3) Same ellipsoid, same First Station.' + write(*,*) ' 4) Let the Second Station be the First Station.' + write(*,*) ' 5) Done.' + write(*,*) ' ' + write(*,*) ' Enter choice : ' + read(*,10) answer +c + if( answer.eq.'1')then + goto 1 + elseif(answer.eq.'2')then + goto 15 + elseif(answer.eq.'3')then + goto 20 + elseif(answer.eq.'4')then + glat1 = glat2 + glon1 = glon2 + goto 20 + else + write(*,*) ' Thats all, folks!' + endif +c +c stop + end diff --git a/gtsam/3rdparty/GeographicLib/legacy/Fortran/ngsinverse.for b/gtsam/3rdparty/GeographicLib/legacy/Fortran/ngsinverse.for new file mode 100644 index 000000000..e6c1d7ea7 --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/legacy/Fortran/ngsinverse.for @@ -0,0 +1,513 @@ +cb::inverse +c + program inverse +c +c********1*********2*********3*********4*********5*********6*********7** +c +c name: inverse +c version: 201211.29 +c author: stephen j. frakes +c last mod: Charles Karney +c purpose: to compute a geodetic inverse +c and then display output information +c +c input parameters: +c ----------------- +c +c output parameters: +c ------------------ +c +c local variables and constants: +c ------------------------------ +c answer user prompt response +c b semiminor axis polar (in meters) +c baz azimuth back (in radians) +c buff input char buffer array +c dd,dm,ds temporary values for degrees, minutes, seconds +c dlon temporary value for difference in longitude (radians) +c dmt,d_mt char constants for meter units +c edist ellipsoid distance (in meters) +c elips ellipsoid choice +c esq eccentricity squared for reference ellipsoid +c faz azimuth forward (in radians) +c filout output file name +c finv reciprocal flattening +c hem hemisphere flag for lat & lon entry +c ierror error condition flag with d,m,s conversion +c lgh length of buff() array +c option user prompt response +c r1,r2 temporary variables +c ss temporary variable +c tol tolerance for conversion of seconds +c +c name1 name of station one +c ld1,lm1,sl1 latitude sta one - degrees,minutes,seconds +c ald1,alm1,sl1 latitude sta one - degrees,minutes,seconds +c lat1sn latitude sta one - sign (+/- 1) +c d_ns1 latitude sta one - char ('N','S') +c lod1,lom1,slo1 longitude sta one - degrees,minutes,seconds +c alod1,alom1,slo1 longitude sta one - degrees,minutes,seconds +c lon1sn longitude sta one - sign (+/- 1) +c d_ew1 longitude sta one - char ('E','W') +c iaz1,maz1,saz1 forward azimuth - degrees,minutes,seconds +c isign1 forward azimuth - flag (+/- 1) +c glat1,glon1 station one - (lat & lon in radians ) +c p1,e1 standpoint one - (lat & lon in radians ) +c +c name2 name of station two +c ld2,lm2,sl2 latitude sta two - degrees,minutes,seconds +c ald2,alm2,sl2 latitude sta two - degrees,minutes,seconds +c lat2sn latitude sta two - sign (+/- 1) +c d_ns2 latitude sta two - char ('N','S') +c lod2,lom2,slo2 longitude sta two - degrees,minutes,seconds +c alod2,alom2,slo2 longitude sta one - degrees,minutes,seconds +c lon2sn longitude sta two - sign (+/- 1) +c d_ew2 longitude sta two - char ('E','W') +c iaz2,maz2,saz2 back azimuth - degrees,minutes,seconds +c isign2 back azimuth - flag (+/- 1) +c glat2,glon2 station two - (lat & lon in radians ) +c p2,e2 forepoint two - (lat & lon in radians ) +c +c global variables and constants: +c ------------------------------- +c a semimajor axis equatorial (in meters) +c f flattening +c pi constant 3.14159.... +c rad constant 180.0/pi +c +c this module called by: n/a +c +c this module calls: elipss, getdeg, inver1, todmsp +c gethem, trim, bufdms, gvalr8, gvali4, fixdms, gpnhri *********** +c gethem, trim, bufdms, gvalr8, gvali4, fixdms, invers <---------- +c datan, write, read, dabs, open, stop +c +c include files used: n/a +c +c common blocks used: const, elipsoid +c +c references: see comments within subroutines +c +c comments: +c +c********1*********2*********3*********4*********5*********6*********7** +c::modification history +c::1990mm.dd, sjf, creation of program +c::199412.15, bmt, creation of program on viper +c::200203.08, crs, modified by c.schwarz to correct spelling of Clarke +c::200207.15, rws, modified i/o & standardized program documentation +c:: added subs trim, bufdms, gethem, gvali4, gvalr8 +c::200207.23, rws, replaced sub inver1 with gpnarc, gpnloa, gpnhri +c::200208.15, rws, fixed an error in bufdms +c:: - renamed ellips to elipss "common error" with dirct2 +c:: - added FAZ & BAZ to printed output +c::200208.19, rws, added more error flags for web interface code +c:: - added logical nowebb +c::200208.xx, sjf, program version number 2.0 +c::201105.xx, dgm, program version number 3.0 +c:: - replaced sub gpnarc, gpnloa, gpnhri with invers +c:: - tested for valid antipodal solutions (+/- 0.1 mm) +c:: - tested for polar solutions (+/- 0.1 mm) +c:: - needs improvement for long-line/antipodal boundary +c::201211.29, cffk, program version numer 3.1 +c:: - drop in replacement routines from +c:: "Algorithms for Geodesics" +c********1*********2*********3*********4*********5*********6*********7** +ce::inverse +c + implicit double precision (a-h, o-z) + implicit integer (i-n) +c + logical nowebb +c + character*1 answer,option,dmt,buff(50),hem + character*6 d_ns1, d_ew1, d_ns2, d_ew2, d_mt + character*30 filout,name1,name2,elips +c + integer*4 ierror + integer*4 lgh +c + common/const/pi,rad + common/elipsoid/a,f +c +c ms_unix 0 = web version +c 1 = ms_dos or unix version +c + parameter ( ms_unix = 0 ) +c + pi = 4.d0*datan(1.d0) + rad = 180.d0/pi + dmt = 'm' + d_mt = 'Meters' +c + if( ms_unix.eq.1 )then + nowebb = .true. + else + nowebb = .false. + endif +c + 1 do 2 i=1,25 + write(*,*) ' ' + 2 continue +c + 5 write(*,*) ' Program Inverse - Version 3.1 ' + write(*,*) ' ' + write(*,*) ' Ellipsoid options : ' + write(*,*) ' ' + write(*,*) ' 1) GRS80 / WGS84 (NAD83) ' + write(*,*) ' 2) Clarke 1866 (NAD27) ' + write(*,*) ' 3) Any other ellipsoid ' + write(*,*) ' ' + write(*,*) ' Enter choice : ' + read(*,10) option + 10 format(a1) +c + if(option.eq.'1') then + a=6378137.d0 + f=1.d0/298.257222100882711243162836600094d0 + elips='GRS80 / WGS84 (NAD83)' + elseif(option.eq.'2') then + a=6378206.4d0 + f=1.d0/294.9786982138d0 + elips='Clarke 1866 (NAD27)' + elseif(option.eq.'3') then + call elipss (elips) + else + write(*,*) ' Enter 1, 2, or 3 ! Try again --' + goto 5 + endif +c + esq = f*(2.0d0-f) +c + write(*,*) ' ' + write(*,*) ' ' + write(*,*) ' ' + write(*,*) ' ' +c + 15 write(*,*) ' Enter First Station ' + write(*,16) + 16 format(18x,'(Separate D,M,S by blanks or commas)') + write(*,*) 'hDD MM SS.sssss Latitude : (h default = N )' + 11 format(50a1) +c + 22 hem='N' + read(*,11) buff + call trim (buff,lgh,hem) + call bufdms (buff,lgh,hem,dd,dm,ds,ierror) +c + if( ierror.eq.0 )then + irlat1 = 0 + else + irlat1 = 1 + write(*,*) ' Invalid Latitude ... Please re-enter it ' + write(*,*) ' ' + if( nowebb )then + goto 22 + endif + endif +c + ald1 = dd + alm1 = dm + sl1 = ds +c + if( hem.eq.'N' ) then + lat1sn = +1 + else + lat1sn = -1 + endif +c + write(*,*) 'hDDD MM SS.sssss Longitude : (h default = W )' +c + 23 hem='W' + read(*,11) buff + call trim (buff,lgh,hem) + call bufdms (buff,lgh,hem,dd,dm,ds,ierror) +c + if( ierror.eq.0 )then + irlon1 = 0 + else + irlon1 = 1 + write(*,*) ' Invalid Longitude ... Please re-enter it ' + write(*,*) ' ' + if( nowebb )then + goto 23 + endif + endif +c + alod1 = dd + alom1 = dm + slo1 = ds +c + if( hem.eq.'E' ) then + lon1sn = +1 + else + lon1sn = -1 + endif +c + call getdeg(ald1, alm1, sl1, lat1sn, glat1) + call getdeg(alod1,alom1,slo1,lon1sn, glon1) +c + write(*,*) ' ' + write(*,*) ' ' +c + 20 write(*,*) ' Enter Second Station ' + write(*,16) + write(*,*) 'hDD MM SS.sssss Latitude : (h default = N )' +c + 24 hem='N' + read(*,11) buff + call trim (buff,lgh,hem) + call bufdms (buff,lgh,hem,dd,dm,ds,ierror) +c + if( ierror.eq.0 )then + irlat2 = 0 + else + irlat2 = 1 + write(*,*) ' Invalid Latitude ... Please re-enter it ' + write(*,*) ' ' + if( nowebb )then + goto 24 + endif + endif +c + ald2 = dd + alm2 = dm + sl2 = ds +c + if( hem.eq.'N' ) then + lat2sn = +1 + else + lat2sn = -1 + endif +c + write(*,*) 'hDDD MM SS.sssss Longitude : (h default = W )' +c + 25 hem='W' + read(*,11) buff + call trim (buff,lgh,hem) + call bufdms (buff,lgh,hem,dd,dm,ds,ierror) +c + if( ierror.eq.0 )then + irlon2 = 0 + else + irlon2 = 1 + write(*,*) ' Invalid Longitude ... Please re-enter it ' + write(*,*) ' ' + if( nowebb )then + goto 25 + endif + endif +c + alod2 = dd + alom2 = dm + slo2 = ds +c + if( hem.eq.'E' )then + lon2sn = +1 + else + lon2sn = -1 + endif +c + call getdeg(ald2, alm2, sl2, lat2sn, glat2) + call getdeg(alod2,alom2,slo2,lon2sn, glon2) +c + p1 = glat1 + e1 = glon1 + p2 = glat2 + e2 = glon2 +c + if( e1.lt.0.0d0 )then + e1 = e1+2.0d0*pi + endif + if( e2.lt.0.0d0 )then + e2 = e2+2.0d0*pi + endif +c +c compute the geodetic inverse +c + call invers(a, f, p1, e1, p2, e2, + + edist, faz, baz, 0, dummy, dummy, dummy, dummy, dummy) + if (baz .ge. 0) then + baz = baz - 180 + else + baz = baz + 180 + end if +c +c set the tolerance (in seconds) for the azimuth conversion +c + tol = 0.00005d0 +c + call todmsp(faz,iaz1,maz1,saz1,isign1) + if(isign1.lt.0) then + iaz1=359-iaz1 + maz1=59-maz1 + saz1=60.d0-saz1 + endif + call fixdms ( iaz1, maz1, saz1, tol ) +c + call todmsp(baz,iaz2,maz2,saz2,isign2) + if(isign2.lt.0) then + iaz2=359-iaz2 + maz2=59-maz2 + saz2=60.d0-saz2 + endif + call fixdms ( iaz2, maz2, saz2, tol ) +c + call todmsp(glat1, ld1, lm1, sl1, lat1sn) + call todmsp(glon1, lod1, lom1, slo1, lon1sn) + call todmsp(glat2, ld2, lm2, sl2, lat2sn) + call todmsp(glon2, lod2, lom2, slo2, lon2sn) +c + call hem_ns ( lat1sn, d_ns1 ) + call hem_ew ( lon1sn, d_ew1 ) + call hem_ns ( lat2sn, d_ns2 ) + call hem_ew ( lon2sn, d_ew2 ) +c + write(*,*) ' ' + write(*,*) ' ' + write(*,*) ' ' + write(*,*) ' ' + write(*,*) ' ' + write(*,49) elips + 49 format(' Ellipsoid : ',a30) + finv=1.d0/f + b=a*(1.d0-f) + write(*,50) a,b,finv + 50 format(' Equatorial axis, a = ',f15.4,/, + * ' Polar axis, b = ',f15.4,/, + * ' Inverse flattening, 1/f = ',f16.11) +c + 18 format(' LAT = ',i3,1x,i2,1x,f8.5,1x,a6) + 19 format(' LON = ',i3,1x,i2,1x,f8.5,1x,a6) +c + write(*,*) ' ' + write(*,*) ' First Station : ' + write(*,*) ' ---------------- ' + write(*,18) ld1, lm1, sl1, d_ns1 + write(*,19) lod1,lom1,slo1,d_ew1 +c + write(*,*) ' ' + write(*,*) ' Second Station : ' + write(*,*) ' ---------------- ' + write(*,18) ld2, lm2, sl2, d_ns2 + write(*,19) lod2,lom2,slo2,d_ew2 +c + 32 format(' Ellipsoidal distance S = ',f14.4,1x,a1) + 34 format(' Forward azimuth FAZ = ',i3,1x,i2,1x,f7.4, + 1 ' From North') + 35 format(' Back azimuth BAZ = ',i3,1x,i2,1x,f7.4, + 1 ' From North') +c + write(*,*) ' ' + write(*,34) iaz1,maz1,saz1 + write(*,35) iaz2,maz2,saz2 + write(*,32) edist,dmt + write(*,*) ' ' + write(*,*) ' Do you want to save this output into a file (y/n)?' + read(*,10) answer +c + if( answer.eq.'Y'.or.answer.eq.'y' )then + 39 write(*,*) ' Enter the output filename : ' + read(*,40) filout + 40 format(a30) + open(3,file=filout,status='new',err=99) + goto 98 +c + 99 write(*,*) ' File already exists, try again.' + go to 39 +c + 98 continue + write(3,*) ' ' + write(3,49) elips + finv=1.d0/f + b=a*(1.d0-f) + write(3,50) a,b,finv + write(*,*) ' Enter the First Station name : ' + read(*,40) name1 + write(*,*) ' Enter the Second Station name : ' + read(*,40) name2 +c + 41 format(' First Station : ',a30) + 42 format(' Second Station : ',a30) + 84 format(' Error: First Station ... Invalid Latitude ') + 85 format(' Error: First Station ... Invalid Longitude ') + 86 format(' Error: Second Station ... Invalid Latitude ') + 87 format(' Error: Second Station ... Invalid Longitude ') + 88 format(1x,65(1h*)) + 91 format(' DD(0-89) MM(0-59) SS(0-59.999...) ') + 92 format(' DDD(0-359) MM(0-59) SS(0-59.999...) ') +c + write(3,*) ' ' + write(3,41) name1 + write(3,*) ' ---------------- ' + + if( irlat1.eq.0 )then + write(3,18) ld1, lm1, sl1, d_ns1 + else + write(3,88) + write(3,84) + write(3,91) + write(3,88) + endif +c + if( irlon1.eq.0 )then + write(3,19) lod1,lom1,slo1,d_ew1 + else + write(3,88) + write(3,85) + write(3,92) + write(3,88) + endif +c + write(3,*) ' ' + write(3,42) name2 + write(3,*) ' ---------------- ' +c + if( irlat2.eq.0 )then + write(3,18) ld2, lm2, sl2, d_ns2 + else + write(3,88) + write(3,86) + write(3,91) + write(3,88) + endif +c + if( irlon2.eq.0 )then + write(3,19) lod2,lom2,slo2,d_ew2 + else + write(3,88) + write(3,87) + write(3,92) + write(3,88) + endif +c + write(3,*) ' ' + write(3,34) iaz1,maz1,saz1 + write(3,35) iaz2,maz2,saz2 + write(3,32) edist,dmt + write(3,*) ' ' + endif +c + 80 write(*,*) ' ' + write(*,*) ' ' + write(*,*) ' ' + write(*,*) ' 1) Another inverse, different ellipsoid.' + write(*,*) ' 2) Same ellipsoid, two new stations.' + write(*,*) ' 3) Same ellipsoid, same First Station.' + write(*,*) ' 4) Done.' + write(*,*) ' ' + write(*,*) ' Enter choice : ' + read(*,10) answer +c + if( answer.eq.'1' )then + goto 1 + elseif( answer.eq.'2' )then + goto 15 + elseif( answer.eq.'3' )then + goto 20 + else + write(*,*) ' Thats all, folks!' + endif + +c stop + end diff --git a/gtsam/3rdparty/GeographicLib/ltmain.sh b/gtsam/3rdparty/GeographicLib/ltmain.sh index 63ae69dc6..0f0a2da3f 100644 --- a/gtsam/3rdparty/GeographicLib/ltmain.sh +++ b/gtsam/3rdparty/GeographicLib/ltmain.sh @@ -1,9 +1,12 @@ +#! /bin/sh +## DO NOT EDIT - This file generated from ./build-aux/ltmain.in +## by inline-source v2014-01-03.01 -# libtool (GNU libtool) 2.4.2 +# libtool (GNU libtool) 2.4.6 +# Provide generalized library-building support services. # Written by Gordon Matzigkeit , 1996 -# Copyright (C) 1996, 1997, 1998, 1999, 2000, 2001, 2003, 2004, 2005, 2006, -# 2007, 2008, 2009, 2010, 2011 Free Software Foundation, Inc. +# Copyright (C) 1996-2015 Free Software Foundation, Inc. # This is free software; see the source for copying conditions. There is NO # warranty; not even for MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. @@ -23,166 +26,670 @@ # General Public License for more details. # # You should have received a copy of the GNU General Public License -# along with GNU Libtool; see the file COPYING. If not, a copy -# can be downloaded from http://www.gnu.org/licenses/gpl.html, -# or obtained by writing to the Free Software Foundation, Inc., -# 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301, USA. +# along with this program. If not, see . -# Usage: $progname [OPTION]... [MODE-ARG]... -# -# Provide generalized library-building support services. -# -# --config show all configuration variables -# --debug enable verbose shell tracing -# -n, --dry-run display commands without modifying any files -# --features display basic configuration information and exit -# --mode=MODE use operation mode MODE -# --preserve-dup-deps don't remove duplicate dependency libraries -# --quiet, --silent don't print informational messages -# --no-quiet, --no-silent -# print informational messages (default) -# --no-warn don't display warning messages -# --tag=TAG use configuration variables from tag TAG -# -v, --verbose print more informational messages than default -# --no-verbose don't print the extra informational messages -# --version print version information -# -h, --help, --help-all print short, long, or detailed help message -# -# MODE must be one of the following: -# -# clean remove files from the build directory -# compile compile a source file into a libtool object -# execute automatically set library path, then run a program -# finish complete the installation of libtool libraries -# install install libraries or executables -# link create a library or an executable -# uninstall remove libraries from an installed directory -# -# MODE-ARGS vary depending on the MODE. When passed as first option, -# `--mode=MODE' may be abbreviated as `MODE' or a unique abbreviation of that. -# Try `$progname --help --mode=MODE' for a more detailed description of MODE. -# -# When reporting a bug, please describe a test case to reproduce it and -# include the following information: -# -# host-triplet: $host -# shell: $SHELL -# compiler: $LTCC -# compiler flags: $LTCFLAGS -# linker: $LD (gnu? $with_gnu_ld) -# $progname: (GNU libtool) 2.4.2 -# automake: $automake_version -# autoconf: $autoconf_version -# -# Report bugs to . -# GNU libtool home page: . -# General help using GNU software: . PROGRAM=libtool PACKAGE=libtool -VERSION=2.4.2 -TIMESTAMP="" -package_revision=1.3337 +VERSION=2.4.6 +package_revision=2.4.6 -# Be Bourne compatible -if test -n "${ZSH_VERSION+set}" && (emulate sh) >/dev/null 2>&1; then + +## ------ ## +## Usage. ## +## ------ ## + +# Run './libtool --help' for help with using this script from the +# command line. + + +## ------------------------------- ## +## User overridable command paths. ## +## ------------------------------- ## + +# After configure completes, it has a better idea of some of the +# shell tools we need than the defaults used by the functions shared +# with bootstrap, so set those here where they can still be over- +# ridden by the user, but otherwise take precedence. + +: ${AUTOCONF="autoconf"} +: ${AUTOMAKE="automake"} + + +## -------------------------- ## +## Source external libraries. ## +## -------------------------- ## + +# Much of our low-level functionality needs to be sourced from external +# libraries, which are installed to $pkgauxdir. + +# Set a version string for this script. +scriptversion=2015-01-20.17; # UTC + +# General shell script boiler plate, and helper functions. +# Written by Gary V. Vaughan, 2004 + +# Copyright (C) 2004-2015 Free Software Foundation, Inc. +# This is free software; see the source for copying conditions. There is NO +# warranty; not even for MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + +# 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. + +# As a special exception to the GNU General Public License, if you distribute +# this file as part of a program or library that is built using GNU Libtool, +# you may include this file under the same distribution terms that you use +# for the rest of that program. + +# This program is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY; without even the implied warranty of +# MERCHANTABILITY or FITNES 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 . + +# Please report bugs or propose patches to gary@gnu.org. + + +## ------ ## +## Usage. ## +## ------ ## + +# Evaluate this file near the top of your script to gain access to +# the functions and variables defined here: +# +# . `echo "$0" | ${SED-sed} 's|[^/]*$||'`/build-aux/funclib.sh +# +# If you need to override any of the default environment variable +# settings, do that before evaluating this file. + + +## -------------------- ## +## Shell normalisation. ## +## -------------------- ## + +# Some shells need a little help to be as Bourne compatible as possible. +# Before doing anything else, make sure all that help has been provided! + +DUALCASE=1; export DUALCASE # for MKS sh +if test -n "${ZSH_VERSION+set}" && (emulate sh) >/dev/null 2>&1; then : emulate sh NULLCMD=: - # Zsh 3.x and 4.x performs word splitting on ${1+"$@"}, which + # Pre-4.2 versions of Zsh do word splitting on ${1+"$@"}, which # is contrary to our usage. Disable this feature. alias -g '${1+"$@"}'='"$@"' setopt NO_GLOB_SUBST else - case `(set -o) 2>/dev/null` in *posix*) set -o posix;; esac + case `(set -o) 2>/dev/null` in *posix*) set -o posix ;; esac fi -BIN_SH=xpg4; export BIN_SH # for Tru64 -DUALCASE=1; export DUALCASE # for MKS sh -# A function that is used when there is no print builtin or printf. -func_fallback_echo () -{ - eval 'cat <<_LTECHO_EOF -$1 -_LTECHO_EOF' -} - -# NLS nuisances: We save the old values to restore during execute mode. -lt_user_locale= -lt_safe_locale= -for lt_var in LANG LANGUAGE LC_ALL LC_CTYPE LC_COLLATE LC_MESSAGES +# NLS nuisances: We save the old values in case they are required later. +_G_user_locale= +_G_safe_locale= +for _G_var in LANG LANGUAGE LC_ALL LC_CTYPE LC_COLLATE LC_MESSAGES do - eval "if test \"\${$lt_var+set}\" = set; then - save_$lt_var=\$$lt_var - $lt_var=C - export $lt_var - lt_user_locale=\"$lt_var=\\\$save_\$lt_var; \$lt_user_locale\" - lt_safe_locale=\"$lt_var=C; \$lt_safe_locale\" + eval "if test set = \"\${$_G_var+set}\"; then + save_$_G_var=\$$_G_var + $_G_var=C + export $_G_var + _G_user_locale=\"$_G_var=\\\$save_\$_G_var; \$_G_user_locale\" + _G_safe_locale=\"$_G_var=C; \$_G_safe_locale\" fi" done -LC_ALL=C -LANGUAGE=C -export LANGUAGE LC_ALL -$lt_unset CDPATH +# CDPATH. +(unset CDPATH) >/dev/null 2>&1 && unset CDPATH +# Make sure IFS has a sensible default +sp=' ' +nl=' +' +IFS="$sp $nl" + +# There are apparently some retarded systems that use ';' as a PATH separator! +if test "${PATH_SEPARATOR+set}" != set; then + PATH_SEPARATOR=: + (PATH='/bin;/bin'; FPATH=$PATH; sh -c :) >/dev/null 2>&1 && { + (PATH='/bin:/bin'; FPATH=$PATH; sh -c :) >/dev/null 2>&1 || + PATH_SEPARATOR=';' + } +fi + + + +## ------------------------- ## +## Locate command utilities. ## +## ------------------------- ## + + +# func_executable_p FILE +# ---------------------- +# Check that FILE is an executable regular file. +func_executable_p () +{ + test -f "$1" && test -x "$1" +} + + +# func_path_progs PROGS_LIST CHECK_FUNC [PATH] +# -------------------------------------------- +# Search for either a program that responds to --version with output +# containing "GNU", or else returned by CHECK_FUNC otherwise, by +# trying all the directories in PATH with each of the elements of +# PROGS_LIST. +# +# CHECK_FUNC should accept the path to a candidate program, and +# set $func_check_prog_result if it truncates its output less than +# $_G_path_prog_max characters. +func_path_progs () +{ + _G_progs_list=$1 + _G_check_func=$2 + _G_PATH=${3-"$PATH"} + + _G_path_prog_max=0 + _G_path_prog_found=false + _G_save_IFS=$IFS; IFS=${PATH_SEPARATOR-:} + for _G_dir in $_G_PATH; do + IFS=$_G_save_IFS + test -z "$_G_dir" && _G_dir=. + for _G_prog_name in $_G_progs_list; do + for _exeext in '' .EXE; do + _G_path_prog=$_G_dir/$_G_prog_name$_exeext + func_executable_p "$_G_path_prog" || continue + case `"$_G_path_prog" --version 2>&1` in + *GNU*) func_path_progs_result=$_G_path_prog _G_path_prog_found=: ;; + *) $_G_check_func $_G_path_prog + func_path_progs_result=$func_check_prog_result + ;; + esac + $_G_path_prog_found && break 3 + done + done + done + IFS=$_G_save_IFS + test -z "$func_path_progs_result" && { + echo "no acceptable sed could be found in \$PATH" >&2 + exit 1 + } +} + + +# We want to be able to use the functions in this file before configure +# has figured out where the best binaries are kept, which means we have +# to search for them ourselves - except when the results are already set +# where we skip the searches. + +# Unless the user overrides by setting SED, search the path for either GNU +# sed, or the sed that truncates its output the least. +test -z "$SED" && { + _G_sed_script=s/aaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaa/bbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbb/ + for _G_i in 1 2 3 4 5 6 7; do + _G_sed_script=$_G_sed_script$nl$_G_sed_script + done + echo "$_G_sed_script" 2>/dev/null | sed 99q >conftest.sed + _G_sed_script= + + func_check_prog_sed () + { + _G_path_prog=$1 + + _G_count=0 + printf 0123456789 >conftest.in + while : + do + cat conftest.in conftest.in >conftest.tmp + mv conftest.tmp conftest.in + cp conftest.in conftest.nl + echo '' >> conftest.nl + "$_G_path_prog" -f conftest.sed conftest.out 2>/dev/null || break + diff conftest.out conftest.nl >/dev/null 2>&1 || break + _G_count=`expr $_G_count + 1` + if test "$_G_count" -gt "$_G_path_prog_max"; then + # Best one so far, save it but keep looking for a better one + func_check_prog_result=$_G_path_prog + _G_path_prog_max=$_G_count + fi + # 10*(2^10) chars as input seems more than enough + test 10 -lt "$_G_count" && break + done + rm -f conftest.in conftest.tmp conftest.nl conftest.out + } + + func_path_progs "sed gsed" func_check_prog_sed $PATH:/usr/xpg4/bin + rm -f conftest.sed + SED=$func_path_progs_result +} + + +# Unless the user overrides by setting GREP, search the path for either GNU +# grep, or the grep that truncates its output the least. +test -z "$GREP" && { + func_check_prog_grep () + { + _G_path_prog=$1 + + _G_count=0 + _G_path_prog_max=0 + printf 0123456789 >conftest.in + while : + do + cat conftest.in conftest.in >conftest.tmp + mv conftest.tmp conftest.in + cp conftest.in conftest.nl + echo 'GREP' >> conftest.nl + "$_G_path_prog" -e 'GREP$' -e '-(cannot match)-' conftest.out 2>/dev/null || break + diff conftest.out conftest.nl >/dev/null 2>&1 || break + _G_count=`expr $_G_count + 1` + if test "$_G_count" -gt "$_G_path_prog_max"; then + # Best one so far, save it but keep looking for a better one + func_check_prog_result=$_G_path_prog + _G_path_prog_max=$_G_count + fi + # 10*(2^10) chars as input seems more than enough + test 10 -lt "$_G_count" && break + done + rm -f conftest.in conftest.tmp conftest.nl conftest.out + } + + func_path_progs "grep ggrep" func_check_prog_grep $PATH:/usr/xpg4/bin + GREP=$func_path_progs_result +} + + +## ------------------------------- ## +## User overridable command paths. ## +## ------------------------------- ## + +# All uppercase variable names are used for environment variables. These +# variables can be overridden by the user before calling a script that +# uses them if a suitable command of that name is not already available +# in the command search PATH. + +: ${CP="cp -f"} +: ${ECHO="printf %s\n"} +: ${EGREP="$GREP -E"} +: ${FGREP="$GREP -F"} +: ${LN_S="ln -s"} +: ${MAKE="make"} +: ${MKDIR="mkdir"} +: ${MV="mv -f"} +: ${RM="rm -f"} +: ${SHELL="${CONFIG_SHELL-/bin/sh}"} + + +## -------------------- ## +## Useful sed snippets. ## +## -------------------- ## + +sed_dirname='s|/[^/]*$||' +sed_basename='s|^.*/||' + +# Sed substitution that helps us do robust quoting. It backslashifies +# metacharacters that are still active within double-quoted strings. +sed_quote_subst='s|\([`"$\\]\)|\\\1|g' + +# Same as above, but do not quote variable references. +sed_double_quote_subst='s/\(["`\\]\)/\\\1/g' + +# Sed substitution that turns a string into a regex matching for the +# string literally. +sed_make_literal_regex='s|[].[^$\\*\/]|\\&|g' + +# Sed substitution that converts a w32 file name or path +# that contains forward slashes, into one that contains +# (escaped) backslashes. A very naive implementation. +sed_naive_backslashify='s|\\\\*|\\|g;s|/|\\|g;s|\\|\\\\|g' + +# Re-'\' parameter expansions in output of sed_double_quote_subst that +# were '\'-ed in input to the same. If an odd number of '\' preceded a +# '$' in input to sed_double_quote_subst, that '$' was protected from +# expansion. Since each input '\' is now two '\'s, look for any number +# of runs of four '\'s followed by two '\'s and then a '$'. '\' that '$'. +_G_bs='\\' +_G_bs2='\\\\' +_G_bs4='\\\\\\\\' +_G_dollar='\$' +sed_double_backslash="\ + s/$_G_bs4/&\\ +/g + s/^$_G_bs2$_G_dollar/$_G_bs&/ + s/\\([^$_G_bs]\\)$_G_bs2$_G_dollar/\\1$_G_bs2$_G_bs$_G_dollar/g + s/\n//g" + + +## ----------------- ## +## Global variables. ## +## ----------------- ## + +# Except for the global variables explicitly listed below, the following +# functions in the '^func_' namespace, and the '^require_' namespace +# variables initialised in the 'Resource management' section, sourcing +# this file will not pollute your global namespace with anything +# else. There's no portable way to scope variables in Bourne shell +# though, so actually running these functions will sometimes place +# results into a variable named after the function, and often use +# temporary variables in the '^_G_' namespace. If you are careful to +# avoid using those namespaces casually in your sourcing script, things +# should continue to work as you expect. And, of course, you can freely +# overwrite any of the functions or variables defined here before +# calling anything to customize them. + +EXIT_SUCCESS=0 +EXIT_FAILURE=1 +EXIT_MISMATCH=63 # $? = 63 is used to indicate version mismatch to missing. +EXIT_SKIP=77 # $? = 77 is used to indicate a skipped test to automake. + +# Allow overriding, eg assuming that you follow the convention of +# putting '$debug_cmd' at the start of all your functions, you can get +# bash to show function call trace with: +# +# debug_cmd='eval echo "${FUNCNAME[0]} $*" >&2' bash your-script-name +debug_cmd=${debug_cmd-":"} +exit_cmd=: + +# By convention, finish your script with: +# +# exit $exit_status +# +# so that you can set exit_status to non-zero if you want to indicate +# something went wrong during execution without actually bailing out at +# the point of failure. +exit_status=$EXIT_SUCCESS # Work around backward compatibility issue on IRIX 6.5. On IRIX 6.4+, sh # is ksh but when the shell is invoked as "sh" and the current value of # the _XPG environment variable is not equal to 1 (one), the special # positional parameter $0, within a function call, is the name of the # function. -progpath="$0" +progpath=$0 + +# The name of this program. +progname=`$ECHO "$progpath" |$SED "$sed_basename"` + +# Make sure we have an absolute progpath for reexecution: +case $progpath in + [\\/]*|[A-Za-z]:\\*) ;; + *[\\/]*) + progdir=`$ECHO "$progpath" |$SED "$sed_dirname"` + progdir=`cd "$progdir" && pwd` + progpath=$progdir/$progname + ;; + *) + _G_IFS=$IFS + IFS=${PATH_SEPARATOR-:} + for progdir in $PATH; do + IFS=$_G_IFS + test -x "$progdir/$progname" && break + done + IFS=$_G_IFS + test -n "$progdir" || progdir=`pwd` + progpath=$progdir/$progname + ;; +esac +## ----------------- ## +## Standard options. ## +## ----------------- ## -: ${CP="cp -f"} -test "${ECHO+set}" = set || ECHO=${as_echo-'printf %s\n'} -: ${MAKE="make"} -: ${MKDIR="mkdir"} -: ${MV="mv -f"} -: ${RM="rm -f"} -: ${SHELL="${CONFIG_SHELL-/bin/sh}"} -: ${Xsed="$SED -e 1s/^X//"} +# The following options affect the operation of the functions defined +# below, and should be set appropriately depending on run-time para- +# meters passed on the command line. -# Global variables: -EXIT_SUCCESS=0 -EXIT_FAILURE=1 -EXIT_MISMATCH=63 # $? = 63 is used to indicate version mismatch to missing. -EXIT_SKIP=77 # $? = 77 is used to indicate a skipped test to automake. +opt_dry_run=false +opt_quiet=false +opt_verbose=false -exit_status=$EXIT_SUCCESS +# Categories 'all' and 'none' are always available. Append any others +# you will pass as the first argument to func_warning from your own +# code. +warning_categories= -# Make sure IFS has a sensible default -lt_nl=' -' -IFS=" $lt_nl" +# By default, display warnings according to 'opt_warning_types'. Set +# 'warning_func' to ':' to elide all warnings, or func_fatal_error to +# treat the next displayed warning as a fatal error. +warning_func=func_warn_and_continue -dirname="s,/[^/]*$,," -basename="s,^.*/,," +# Set to 'all' to display all warnings, 'none' to suppress all +# warnings, or a space delimited list of some subset of +# 'warning_categories' to display only the listed warnings. +opt_warning_types=all -# func_dirname file append nondir_replacement + +## -------------------- ## +## Resource management. ## +## -------------------- ## + +# This section contains definitions for functions that each ensure a +# particular resource (a file, or a non-empty configuration variable for +# example) is available, and if appropriate to extract default values +# from pertinent package files. Call them using their associated +# 'require_*' variable to ensure that they are executed, at most, once. +# +# It's entirely deliberate that calling these functions can set +# variables that don't obey the namespace limitations obeyed by the rest +# of this file, in order that that they be as useful as possible to +# callers. + + +# require_term_colors +# ------------------- +# Allow display of bold text on terminals that support it. +require_term_colors=func_require_term_colors +func_require_term_colors () +{ + $debug_cmd + + test -t 1 && { + # COLORTERM and USE_ANSI_COLORS environment variables take + # precedence, because most terminfo databases neglect to describe + # whether color sequences are supported. + test -n "${COLORTERM+set}" && : ${USE_ANSI_COLORS="1"} + + if test 1 = "$USE_ANSI_COLORS"; then + # Standard ANSI escape sequences + tc_reset='' + tc_bold=''; tc_standout='' + tc_red=''; tc_green='' + tc_blue=''; tc_cyan='' + else + # Otherwise trust the terminfo database after all. + test -n "`tput sgr0 2>/dev/null`" && { + tc_reset=`tput sgr0` + test -n "`tput bold 2>/dev/null`" && tc_bold=`tput bold` + tc_standout=$tc_bold + test -n "`tput smso 2>/dev/null`" && tc_standout=`tput smso` + test -n "`tput setaf 1 2>/dev/null`" && tc_red=`tput setaf 1` + test -n "`tput setaf 2 2>/dev/null`" && tc_green=`tput setaf 2` + test -n "`tput setaf 4 2>/dev/null`" && tc_blue=`tput setaf 4` + test -n "`tput setaf 5 2>/dev/null`" && tc_cyan=`tput setaf 5` + } + fi + } + + require_term_colors=: +} + + +## ----------------- ## +## Function library. ## +## ----------------- ## + +# This section contains a variety of useful functions to call in your +# scripts. Take note of the portable wrappers for features provided by +# some modern shells, which will fall back to slower equivalents on +# less featureful shells. + + +# func_append VAR VALUE +# --------------------- +# Append VALUE onto the existing contents of VAR. + + # We should try to minimise forks, especially on Windows where they are + # unreasonably slow, so skip the feature probes when bash or zsh are + # being used: + if test set = "${BASH_VERSION+set}${ZSH_VERSION+set}"; then + : ${_G_HAVE_ARITH_OP="yes"} + : ${_G_HAVE_XSI_OPS="yes"} + # The += operator was introduced in bash 3.1 + case $BASH_VERSION in + [12].* | 3.0 | 3.0*) ;; + *) + : ${_G_HAVE_PLUSEQ_OP="yes"} + ;; + esac + fi + + # _G_HAVE_PLUSEQ_OP + # Can be empty, in which case the shell is probed, "yes" if += is + # useable or anything else if it does not work. + test -z "$_G_HAVE_PLUSEQ_OP" \ + && (eval 'x=a; x+=" b"; test "a b" = "$x"') 2>/dev/null \ + && _G_HAVE_PLUSEQ_OP=yes + +if test yes = "$_G_HAVE_PLUSEQ_OP" +then + # This is an XSI compatible shell, allowing a faster implementation... + eval 'func_append () + { + $debug_cmd + + eval "$1+=\$2" + }' +else + # ...otherwise fall back to using expr, which is often a shell builtin. + func_append () + { + $debug_cmd + + eval "$1=\$$1\$2" + } +fi + + +# func_append_quoted VAR VALUE +# ---------------------------- +# Quote VALUE and append to the end of shell variable VAR, separated +# by a space. +if test yes = "$_G_HAVE_PLUSEQ_OP"; then + eval 'func_append_quoted () + { + $debug_cmd + + func_quote_for_eval "$2" + eval "$1+=\\ \$func_quote_for_eval_result" + }' +else + func_append_quoted () + { + $debug_cmd + + func_quote_for_eval "$2" + eval "$1=\$$1\\ \$func_quote_for_eval_result" + } +fi + + +# func_append_uniq VAR VALUE +# -------------------------- +# Append unique VALUE onto the existing contents of VAR, assuming +# entries are delimited by the first character of VALUE. For example: +# +# func_append_uniq options " --another-option option-argument" +# +# will only append to $options if " --another-option option-argument " +# is not already present somewhere in $options already (note spaces at +# each end implied by leading space in second argument). +func_append_uniq () +{ + $debug_cmd + + eval _G_current_value='`$ECHO $'$1'`' + _G_delim=`expr "$2" : '\(.\)'` + + case $_G_delim$_G_current_value$_G_delim in + *"$2$_G_delim"*) ;; + *) func_append "$@" ;; + esac +} + + +# func_arith TERM... +# ------------------ +# Set func_arith_result to the result of evaluating TERMs. + test -z "$_G_HAVE_ARITH_OP" \ + && (eval 'test 2 = $(( 1 + 1 ))') 2>/dev/null \ + && _G_HAVE_ARITH_OP=yes + +if test yes = "$_G_HAVE_ARITH_OP"; then + eval 'func_arith () + { + $debug_cmd + + func_arith_result=$(( $* )) + }' +else + func_arith () + { + $debug_cmd + + func_arith_result=`expr "$@"` + } +fi + + +# func_basename FILE +# ------------------ +# Set func_basename_result to FILE with everything up to and including +# the last / stripped. +if test yes = "$_G_HAVE_XSI_OPS"; then + # If this shell supports suffix pattern removal, then use it to avoid + # forking. Hide the definitions single quotes in case the shell chokes + # on unsupported syntax... + _b='func_basename_result=${1##*/}' + _d='case $1 in + */*) func_dirname_result=${1%/*}$2 ;; + * ) func_dirname_result=$3 ;; + esac' + +else + # ...otherwise fall back to using sed. + _b='func_basename_result=`$ECHO "$1" |$SED "$sed_basename"`' + _d='func_dirname_result=`$ECHO "$1" |$SED "$sed_dirname"` + if test "X$func_dirname_result" = "X$1"; then + func_dirname_result=$3 + else + func_append func_dirname_result "$2" + fi' +fi + +eval 'func_basename () +{ + $debug_cmd + + '"$_b"' +}' + + +# func_dirname FILE APPEND NONDIR_REPLACEMENT +# ------------------------------------------- # Compute the dirname of FILE. If nonempty, add APPEND to the result, # otherwise set result to NONDIR_REPLACEMENT. -func_dirname () +eval 'func_dirname () { - func_dirname_result=`$ECHO "${1}" | $SED "$dirname"` - if test "X$func_dirname_result" = "X${1}"; then - func_dirname_result="${3}" - else - func_dirname_result="$func_dirname_result${2}" - fi -} # func_dirname may be replaced by extended shell implementation + $debug_cmd + + '"$_d"' +}' -# func_basename file -func_basename () -{ - func_basename_result=`$ECHO "${1}" | $SED "$basename"` -} # func_basename may be replaced by extended shell implementation - - -# func_dirname_and_basename file append nondir_replacement -# perform func_basename and func_dirname in a single function +# func_dirname_and_basename FILE APPEND NONDIR_REPLACEMENT +# -------------------------------------------------------- +# Perform func_basename and func_dirname in a single function # call: # dirname: Compute the dirname of FILE. If nonempty, # add APPEND to the result, otherwise set result @@ -190,263 +697,327 @@ func_basename () # value returned in "$func_dirname_result" # basename: Compute filename of FILE. # value retuned in "$func_basename_result" -# Implementation must be kept synchronized with func_dirname -# and func_basename. For efficiency, we do not delegate to -# those functions but instead duplicate the functionality here. -func_dirname_and_basename () +# For efficiency, we do not delegate to the functions above but instead +# duplicate the functionality here. +eval 'func_dirname_and_basename () { - # Extract subdirectory from the argument. - func_dirname_result=`$ECHO "${1}" | $SED -e "$dirname"` - if test "X$func_dirname_result" = "X${1}"; then - func_dirname_result="${3}" - else - func_dirname_result="$func_dirname_result${2}" + $debug_cmd + + '"$_b"' + '"$_d"' +}' + + +# func_echo ARG... +# ---------------- +# Echo program name prefixed message. +func_echo () +{ + $debug_cmd + + _G_message=$* + + func_echo_IFS=$IFS + IFS=$nl + for _G_line in $_G_message; do + IFS=$func_echo_IFS + $ECHO "$progname: $_G_line" + done + IFS=$func_echo_IFS +} + + +# func_echo_all ARG... +# -------------------- +# Invoke $ECHO with all args, space-separated. +func_echo_all () +{ + $ECHO "$*" +} + + +# func_echo_infix_1 INFIX ARG... +# ------------------------------ +# Echo program name, followed by INFIX on the first line, with any +# additional lines not showing INFIX. +func_echo_infix_1 () +{ + $debug_cmd + + $require_term_colors + + _G_infix=$1; shift + _G_indent=$_G_infix + _G_prefix="$progname: $_G_infix: " + _G_message=$* + + # Strip color escape sequences before counting printable length + for _G_tc in "$tc_reset" "$tc_bold" "$tc_standout" "$tc_red" "$tc_green" "$tc_blue" "$tc_cyan" + do + test -n "$_G_tc" && { + _G_esc_tc=`$ECHO "$_G_tc" | $SED "$sed_make_literal_regex"` + _G_indent=`$ECHO "$_G_indent" | $SED "s|$_G_esc_tc||g"` + } + done + _G_indent="$progname: "`echo "$_G_indent" | $SED 's|.| |g'`" " ## exclude from sc_prohibit_nested_quotes + + func_echo_infix_1_IFS=$IFS + IFS=$nl + for _G_line in $_G_message; do + IFS=$func_echo_infix_1_IFS + $ECHO "$_G_prefix$tc_bold$_G_line$tc_reset" >&2 + _G_prefix=$_G_indent + done + IFS=$func_echo_infix_1_IFS +} + + +# func_error ARG... +# ----------------- +# Echo program name prefixed message to standard error. +func_error () +{ + $debug_cmd + + $require_term_colors + + func_echo_infix_1 " $tc_standout${tc_red}error$tc_reset" "$*" >&2 +} + + +# func_fatal_error ARG... +# ----------------------- +# Echo program name prefixed message to standard error, and exit. +func_fatal_error () +{ + $debug_cmd + + func_error "$*" + exit $EXIT_FAILURE +} + + +# func_grep EXPRESSION FILENAME +# ----------------------------- +# Check whether EXPRESSION matches any line of FILENAME, without output. +func_grep () +{ + $debug_cmd + + $GREP "$1" "$2" >/dev/null 2>&1 +} + + +# func_len STRING +# --------------- +# Set func_len_result to the length of STRING. STRING may not +# start with a hyphen. + test -z "$_G_HAVE_XSI_OPS" \ + && (eval 'x=a/b/c; + test 5aa/bb/cc = "${#x}${x%%/*}${x%/*}${x#*/}${x##*/}"') 2>/dev/null \ + && _G_HAVE_XSI_OPS=yes + +if test yes = "$_G_HAVE_XSI_OPS"; then + eval 'func_len () + { + $debug_cmd + + func_len_result=${#1} + }' +else + func_len () + { + $debug_cmd + + func_len_result=`expr "$1" : ".*" 2>/dev/null || echo $max_cmd_len` + } +fi + + +# func_mkdir_p DIRECTORY-PATH +# --------------------------- +# Make sure the entire path to DIRECTORY-PATH is available. +func_mkdir_p () +{ + $debug_cmd + + _G_directory_path=$1 + _G_dir_list= + + if test -n "$_G_directory_path" && test : != "$opt_dry_run"; then + + # Protect directory names starting with '-' + case $_G_directory_path in + -*) _G_directory_path=./$_G_directory_path ;; + esac + + # While some portion of DIR does not yet exist... + while test ! -d "$_G_directory_path"; do + # ...make a list in topmost first order. Use a colon delimited + # list incase some portion of path contains whitespace. + _G_dir_list=$_G_directory_path:$_G_dir_list + + # If the last portion added has no slash in it, the list is done + case $_G_directory_path in */*) ;; *) break ;; esac + + # ...otherwise throw away the child directory and loop + _G_directory_path=`$ECHO "$_G_directory_path" | $SED -e "$sed_dirname"` + done + _G_dir_list=`$ECHO "$_G_dir_list" | $SED 's|:*$||'` + + func_mkdir_p_IFS=$IFS; IFS=: + for _G_dir in $_G_dir_list; do + IFS=$func_mkdir_p_IFS + # mkdir can fail with a 'File exist' error if two processes + # try to create one of the directories concurrently. Don't + # stop in that case! + $MKDIR "$_G_dir" 2>/dev/null || : + done + IFS=$func_mkdir_p_IFS + + # Bail out if we (or some other process) failed to create a directory. + test -d "$_G_directory_path" || \ + func_fatal_error "Failed to create '$1'" fi - func_basename_result=`$ECHO "${1}" | $SED -e "$basename"` -} # func_dirname_and_basename may be replaced by extended shell implementation +} -# func_stripname prefix suffix name -# strip PREFIX and SUFFIX off of NAME. -# PREFIX and SUFFIX must not contain globbing or regex special -# characters, hashes, percent signs, but SUFFIX may contain a leading -# dot (in which case that matches only a dot). -# func_strip_suffix prefix name -func_stripname () +# func_mktempdir [BASENAME] +# ------------------------- +# Make a temporary directory that won't clash with other running +# libtool processes, and avoids race conditions if possible. If +# given, BASENAME is the basename for that directory. +func_mktempdir () { - case ${2} in - .*) func_stripname_result=`$ECHO "${3}" | $SED "s%^${1}%%; s%\\\\${2}\$%%"`;; - *) func_stripname_result=`$ECHO "${3}" | $SED "s%^${1}%%; s%${2}\$%%"`;; - esac -} # func_stripname may be replaced by extended shell implementation + $debug_cmd + _G_template=${TMPDIR-/tmp}/${1-$progname} + + if test : = "$opt_dry_run"; then + # Return a directory name, but don't create it in dry-run mode + _G_tmpdir=$_G_template-$$ + else + + # If mktemp works, use that first and foremost + _G_tmpdir=`mktemp -d "$_G_template-XXXXXXXX" 2>/dev/null` + + if test ! -d "$_G_tmpdir"; then + # Failing that, at least try and use $RANDOM to avoid a race + _G_tmpdir=$_G_template-${RANDOM-0}$$ + + func_mktempdir_umask=`umask` + umask 0077 + $MKDIR "$_G_tmpdir" + umask $func_mktempdir_umask + fi + + # If we're not in dry-run mode, bomb out on failure + test -d "$_G_tmpdir" || \ + func_fatal_error "cannot create temporary directory '$_G_tmpdir'" + fi + + $ECHO "$_G_tmpdir" +} -# These SED scripts presuppose an absolute path with a trailing slash. -pathcar='s,^/\([^/]*\).*$,\1,' -pathcdr='s,^/[^/]*,,' -removedotparts=':dotsl - s@/\./@/@g - t dotsl - s,/\.$,/,' -collapseslashes='s@/\{1,\}@/@g' -finalslash='s,/*$,/,' # func_normal_abspath PATH +# ------------------------ # Remove doubled-up and trailing slashes, "." path components, # and cancel out any ".." path components in PATH after making # it an absolute path. -# value returned in "$func_normal_abspath_result" func_normal_abspath () { - # Start from root dir and reassemble the path. - func_normal_abspath_result= - func_normal_abspath_tpath=$1 - func_normal_abspath_altnamespace= - case $func_normal_abspath_tpath in - "") - # Empty path, that just means $cwd. - func_stripname '' '/' "`pwd`" - func_normal_abspath_result=$func_stripname_result - return - ;; - # The next three entries are used to spot a run of precisely - # two leading slashes without using negated character classes; - # we take advantage of case's first-match behaviour. - ///*) - # Unusual form of absolute path, do nothing. - ;; - //*) - # Not necessarily an ordinary path; POSIX reserves leading '//' - # and for example Cygwin uses it to access remote file shares - # over CIFS/SMB, so we conserve a leading double slash if found. - func_normal_abspath_altnamespace=/ - ;; - /*) - # Absolute path, do nothing. - ;; - *) - # Relative path, prepend $cwd. - func_normal_abspath_tpath=`pwd`/$func_normal_abspath_tpath - ;; - esac - # Cancel out all the simple stuff to save iterations. We also want - # the path to end with a slash for ease of parsing, so make sure - # there is one (and only one) here. - func_normal_abspath_tpath=`$ECHO "$func_normal_abspath_tpath" | $SED \ - -e "$removedotparts" -e "$collapseslashes" -e "$finalslash"` - while :; do - # Processed it all yet? - if test "$func_normal_abspath_tpath" = / ; then - # If we ascended to the root using ".." the result may be empty now. - if test -z "$func_normal_abspath_result" ; then - func_normal_abspath_result=/ - fi - break - fi - func_normal_abspath_tcomponent=`$ECHO "$func_normal_abspath_tpath" | $SED \ - -e "$pathcar"` - func_normal_abspath_tpath=`$ECHO "$func_normal_abspath_tpath" | $SED \ - -e "$pathcdr"` - # Figure out what to do with it - case $func_normal_abspath_tcomponent in + $debug_cmd + + # These SED scripts presuppose an absolute path with a trailing slash. + _G_pathcar='s|^/\([^/]*\).*$|\1|' + _G_pathcdr='s|^/[^/]*||' + _G_removedotparts=':dotsl + s|/\./|/|g + t dotsl + s|/\.$|/|' + _G_collapseslashes='s|/\{1,\}|/|g' + _G_finalslash='s|/*$|/|' + + # Start from root dir and reassemble the path. + func_normal_abspath_result= + func_normal_abspath_tpath=$1 + func_normal_abspath_altnamespace= + case $func_normal_abspath_tpath in "") - # Trailing empty path component, ignore it. - ;; - ..) - # Parent dir; strip last assembled component from result. - func_dirname "$func_normal_abspath_result" - func_normal_abspath_result=$func_dirname_result - ;; - *) - # Actual path component, append it. - func_normal_abspath_result=$func_normal_abspath_result/$func_normal_abspath_tcomponent - ;; - esac - done - # Restore leading double-slash if one was found on entry. - func_normal_abspath_result=$func_normal_abspath_altnamespace$func_normal_abspath_result -} - -# func_relative_path SRCDIR DSTDIR -# generates a relative path from SRCDIR to DSTDIR, with a trailing -# slash if non-empty, suitable for immediately appending a filename -# without needing to append a separator. -# value returned in "$func_relative_path_result" -func_relative_path () -{ - func_relative_path_result= - func_normal_abspath "$1" - func_relative_path_tlibdir=$func_normal_abspath_result - func_normal_abspath "$2" - func_relative_path_tbindir=$func_normal_abspath_result - - # Ascend the tree starting from libdir - while :; do - # check if we have found a prefix of bindir - case $func_relative_path_tbindir in - $func_relative_path_tlibdir) - # found an exact match - func_relative_path_tcancelled= - break + # Empty path, that just means $cwd. + func_stripname '' '/' "`pwd`" + func_normal_abspath_result=$func_stripname_result + return ;; - $func_relative_path_tlibdir*) - # found a matching prefix - func_stripname "$func_relative_path_tlibdir" '' "$func_relative_path_tbindir" - func_relative_path_tcancelled=$func_stripname_result - if test -z "$func_relative_path_result"; then - func_relative_path_result=. - fi - break + # The next three entries are used to spot a run of precisely + # two leading slashes without using negated character classes; + # we take advantage of case's first-match behaviour. + ///*) + # Unusual form of absolute path, do nothing. + ;; + //*) + # Not necessarily an ordinary path; POSIX reserves leading '//' + # and for example Cygwin uses it to access remote file shares + # over CIFS/SMB, so we conserve a leading double slash if found. + func_normal_abspath_altnamespace=/ + ;; + /*) + # Absolute path, do nothing. ;; *) - func_dirname $func_relative_path_tlibdir - func_relative_path_tlibdir=${func_dirname_result} - if test "x$func_relative_path_tlibdir" = x ; then - # Have to descend all the way to the root! - func_relative_path_result=../$func_relative_path_result - func_relative_path_tcancelled=$func_relative_path_tbindir - break - fi - func_relative_path_result=../$func_relative_path_result + # Relative path, prepend $cwd. + func_normal_abspath_tpath=`pwd`/$func_normal_abspath_tpath ;; esac - done - # Now calculate path; take care to avoid doubling-up slashes. - func_stripname '' '/' "$func_relative_path_result" - func_relative_path_result=$func_stripname_result - func_stripname '/' '/' "$func_relative_path_tcancelled" - if test "x$func_stripname_result" != x ; then - func_relative_path_result=${func_relative_path_result}/${func_stripname_result} - fi - - # Normalisation. If bindir is libdir, return empty string, - # else relative path ending with a slash; either way, target - # file name can be directly appended. - if test ! -z "$func_relative_path_result"; then - func_stripname './' '' "$func_relative_path_result/" - func_relative_path_result=$func_stripname_result - fi + # Cancel out all the simple stuff to save iterations. We also want + # the path to end with a slash for ease of parsing, so make sure + # there is one (and only one) here. + func_normal_abspath_tpath=`$ECHO "$func_normal_abspath_tpath" | $SED \ + -e "$_G_removedotparts" -e "$_G_collapseslashes" -e "$_G_finalslash"` + while :; do + # Processed it all yet? + if test / = "$func_normal_abspath_tpath"; then + # If we ascended to the root using ".." the result may be empty now. + if test -z "$func_normal_abspath_result"; then + func_normal_abspath_result=/ + fi + break + fi + func_normal_abspath_tcomponent=`$ECHO "$func_normal_abspath_tpath" | $SED \ + -e "$_G_pathcar"` + func_normal_abspath_tpath=`$ECHO "$func_normal_abspath_tpath" | $SED \ + -e "$_G_pathcdr"` + # Figure out what to do with it + case $func_normal_abspath_tcomponent in + "") + # Trailing empty path component, ignore it. + ;; + ..) + # Parent dir; strip last assembled component from result. + func_dirname "$func_normal_abspath_result" + func_normal_abspath_result=$func_dirname_result + ;; + *) + # Actual path component, append it. + func_append func_normal_abspath_result "/$func_normal_abspath_tcomponent" + ;; + esac + done + # Restore leading double-slash if one was found on entry. + func_normal_abspath_result=$func_normal_abspath_altnamespace$func_normal_abspath_result } -# The name of this program: -func_dirname_and_basename "$progpath" -progname=$func_basename_result -# Make sure we have an absolute path for reexecution: -case $progpath in - [\\/]*|[A-Za-z]:\\*) ;; - *[\\/]*) - progdir=$func_dirname_result - progdir=`cd "$progdir" && pwd` - progpath="$progdir/$progname" - ;; - *) - save_IFS="$IFS" - IFS=${PATH_SEPARATOR-:} - for progdir in $PATH; do - IFS="$save_IFS" - test -x "$progdir/$progname" && break - done - IFS="$save_IFS" - test -n "$progdir" || progdir=`pwd` - progpath="$progdir/$progname" - ;; -esac - -# Sed substitution that helps us do robust quoting. It backslashifies -# metacharacters that are still active within double-quoted strings. -Xsed="${SED}"' -e 1s/^X//' -sed_quote_subst='s/\([`"$\\]\)/\\\1/g' - -# Same as above, but do not quote variable references. -double_quote_subst='s/\(["`\\]\)/\\\1/g' - -# Sed substitution that turns a string into a regex matching for the -# string literally. -sed_make_literal_regex='s,[].[^$\\*\/],\\&,g' - -# Sed substitution that converts a w32 file name or path -# which contains forward slashes, into one that contains -# (escaped) backslashes. A very naive implementation. -lt_sed_naive_backslashify='s|\\\\*|\\|g;s|/|\\|g;s|\\|\\\\|g' - -# Re-`\' parameter expansions in output of double_quote_subst that were -# `\'-ed in input to the same. If an odd number of `\' preceded a '$' -# in input to double_quote_subst, that '$' was protected from expansion. -# Since each input `\' is now two `\'s, look for any number of runs of -# four `\'s followed by two `\'s and then a '$'. `\' that '$'. -bs='\\' -bs2='\\\\' -bs4='\\\\\\\\' -dollar='\$' -sed_double_backslash="\ - s/$bs4/&\\ -/g - s/^$bs2$dollar/$bs&/ - s/\\([^$bs]\\)$bs2$dollar/\\1$bs2$bs$dollar/g - s/\n//g" - -# Standard options: -opt_dry_run=false -opt_help=false -opt_quiet=false -opt_verbose=false -opt_warning=: - -# func_echo arg... -# Echo program name prefixed message, along with the current mode -# name if it has been set yet. -func_echo () +# func_notquiet ARG... +# -------------------- +# Echo program name prefixed message only when not in quiet mode. +func_notquiet () { - $ECHO "$progname: ${opt_mode+$opt_mode: }$*" -} + $debug_cmd -# func_verbose arg... -# Echo program name prefixed message in verbose mode only. -func_verbose () -{ - $opt_verbose && func_echo ${1+"$@"} + $opt_quiet || func_echo ${1+"$@"} # A bug in bash halts the script if the last line of a function # fails when set -e is in force, so we need another command to @@ -454,450 +1025,1113 @@ func_verbose () : } -# func_echo_all arg... -# Invoke $ECHO with all args, space-separated. -func_echo_all () -{ - $ECHO "$*" -} -# func_error arg... -# Echo program name prefixed message to standard error. -func_error () +# func_relative_path SRCDIR DSTDIR +# -------------------------------- +# Set func_relative_path_result to the relative path from SRCDIR to DSTDIR. +func_relative_path () { - $ECHO "$progname: ${opt_mode+$opt_mode: }"${1+"$@"} 1>&2 -} + $debug_cmd -# func_warning arg... -# Echo program name prefixed warning message to standard error. -func_warning () -{ - $opt_warning && $ECHO "$progname: ${opt_mode+$opt_mode: }warning: "${1+"$@"} 1>&2 + func_relative_path_result= + func_normal_abspath "$1" + func_relative_path_tlibdir=$func_normal_abspath_result + func_normal_abspath "$2" + func_relative_path_tbindir=$func_normal_abspath_result + + # Ascend the tree starting from libdir + while :; do + # check if we have found a prefix of bindir + case $func_relative_path_tbindir in + $func_relative_path_tlibdir) + # found an exact match + func_relative_path_tcancelled= + break + ;; + $func_relative_path_tlibdir*) + # found a matching prefix + func_stripname "$func_relative_path_tlibdir" '' "$func_relative_path_tbindir" + func_relative_path_tcancelled=$func_stripname_result + if test -z "$func_relative_path_result"; then + func_relative_path_result=. + fi + break + ;; + *) + func_dirname $func_relative_path_tlibdir + func_relative_path_tlibdir=$func_dirname_result + if test -z "$func_relative_path_tlibdir"; then + # Have to descend all the way to the root! + func_relative_path_result=../$func_relative_path_result + func_relative_path_tcancelled=$func_relative_path_tbindir + break + fi + func_relative_path_result=../$func_relative_path_result + ;; + esac + done + + # Now calculate path; take care to avoid doubling-up slashes. + func_stripname '' '/' "$func_relative_path_result" + func_relative_path_result=$func_stripname_result + func_stripname '/' '/' "$func_relative_path_tcancelled" + if test -n "$func_stripname_result"; then + func_append func_relative_path_result "/$func_stripname_result" + fi + + # Normalisation. If bindir is libdir, return '.' else relative path. + if test -n "$func_relative_path_result"; then + func_stripname './' '' "$func_relative_path_result" + func_relative_path_result=$func_stripname_result + fi + + test -n "$func_relative_path_result" || func_relative_path_result=. - # bash bug again: : } -# func_fatal_error arg... -# Echo program name prefixed message to standard error, and exit. -func_fatal_error () -{ - func_error ${1+"$@"} - exit $EXIT_FAILURE -} -# func_fatal_help arg... -# Echo program name prefixed message to standard error, followed by -# a help hint, and exit. -func_fatal_help () -{ - func_error ${1+"$@"} - func_fatal_error "$help" -} -help="Try \`$progname --help' for more information." ## default - - -# func_grep expression filename -# Check whether EXPRESSION matches any line of FILENAME, without output. -func_grep () -{ - $GREP "$1" "$2" >/dev/null 2>&1 -} - - -# func_mkdir_p directory-path -# Make sure the entire path to DIRECTORY-PATH is available. -func_mkdir_p () -{ - my_directory_path="$1" - my_dir_list= - - if test -n "$my_directory_path" && test "$opt_dry_run" != ":"; then - - # Protect directory names starting with `-' - case $my_directory_path in - -*) my_directory_path="./$my_directory_path" ;; - esac - - # While some portion of DIR does not yet exist... - while test ! -d "$my_directory_path"; do - # ...make a list in topmost first order. Use a colon delimited - # list incase some portion of path contains whitespace. - my_dir_list="$my_directory_path:$my_dir_list" - - # If the last portion added has no slash in it, the list is done - case $my_directory_path in */*) ;; *) break ;; esac - - # ...otherwise throw away the child directory and loop - my_directory_path=`$ECHO "$my_directory_path" | $SED -e "$dirname"` - done - my_dir_list=`$ECHO "$my_dir_list" | $SED 's,:*$,,'` - - save_mkdir_p_IFS="$IFS"; IFS=':' - for my_dir in $my_dir_list; do - IFS="$save_mkdir_p_IFS" - # mkdir can fail with a `File exist' error if two processes - # try to create one of the directories concurrently. Don't - # stop in that case! - $MKDIR "$my_dir" 2>/dev/null || : - done - IFS="$save_mkdir_p_IFS" - - # Bail out if we (or some other process) failed to create a directory. - test -d "$my_directory_path" || \ - func_fatal_error "Failed to create \`$1'" - fi -} - - -# func_mktempdir [string] -# Make a temporary directory that won't clash with other running -# libtool processes, and avoids race conditions if possible. If -# given, STRING is the basename for that directory. -func_mktempdir () -{ - my_template="${TMPDIR-/tmp}/${1-$progname}" - - if test "$opt_dry_run" = ":"; then - # Return a directory name, but don't create it in dry-run mode - my_tmpdir="${my_template}-$$" - else - - # If mktemp works, use that first and foremost - my_tmpdir=`mktemp -d "${my_template}-XXXXXXXX" 2>/dev/null` - - if test ! -d "$my_tmpdir"; then - # Failing that, at least try and use $RANDOM to avoid a race - my_tmpdir="${my_template}-${RANDOM-0}$$" - - save_mktempdir_umask=`umask` - umask 0077 - $MKDIR "$my_tmpdir" - umask $save_mktempdir_umask - fi - - # If we're not in dry-run mode, bomb out on failure - test -d "$my_tmpdir" || \ - func_fatal_error "cannot create temporary directory \`$my_tmpdir'" - fi - - $ECHO "$my_tmpdir" -} - - -# func_quote_for_eval arg -# Aesthetically quote ARG to be evaled later. -# This function returns two values: FUNC_QUOTE_FOR_EVAL_RESULT -# is double-quoted, suitable for a subsequent eval, whereas -# FUNC_QUOTE_FOR_EVAL_UNQUOTED_RESULT has merely all characters -# which are still active within double quotes backslashified. +# func_quote_for_eval ARG... +# -------------------------- +# Aesthetically quote ARGs to be evaled later. +# This function returns two values: +# i) func_quote_for_eval_result +# double-quoted, suitable for a subsequent eval +# ii) func_quote_for_eval_unquoted_result +# has all characters that are still active within double +# quotes backslashified. func_quote_for_eval () { - case $1 in - *[\\\`\"\$]*) - func_quote_for_eval_unquoted_result=`$ECHO "$1" | $SED "$sed_quote_subst"` ;; - *) - func_quote_for_eval_unquoted_result="$1" ;; - esac + $debug_cmd - case $func_quote_for_eval_unquoted_result in - # Double-quote args containing shell metacharacters to delay - # word splitting, command substitution and and variable - # expansion for a subsequent eval. - # Many Bourne shells cannot handle close brackets correctly - # in scan sets, so we specify it separately. - *[\[\~\#\^\&\*\(\)\{\}\|\;\<\>\?\'\ \ ]*|*]*|"") - func_quote_for_eval_result="\"$func_quote_for_eval_unquoted_result\"" - ;; - *) - func_quote_for_eval_result="$func_quote_for_eval_unquoted_result" - esac + func_quote_for_eval_unquoted_result= + func_quote_for_eval_result= + while test 0 -lt $#; do + case $1 in + *[\\\`\"\$]*) + _G_unquoted_arg=`printf '%s\n' "$1" |$SED "$sed_quote_subst"` ;; + *) + _G_unquoted_arg=$1 ;; + esac + if test -n "$func_quote_for_eval_unquoted_result"; then + func_append func_quote_for_eval_unquoted_result " $_G_unquoted_arg" + else + func_append func_quote_for_eval_unquoted_result "$_G_unquoted_arg" + fi + + case $_G_unquoted_arg in + # Double-quote args containing shell metacharacters to delay + # word splitting, command substitution and variable expansion + # for a subsequent eval. + # Many Bourne shells cannot handle close brackets correctly + # in scan sets, so we specify it separately. + *[\[\~\#\^\&\*\(\)\{\}\|\;\<\>\?\'\ \ ]*|*]*|"") + _G_quoted_arg=\"$_G_unquoted_arg\" + ;; + *) + _G_quoted_arg=$_G_unquoted_arg + ;; + esac + + if test -n "$func_quote_for_eval_result"; then + func_append func_quote_for_eval_result " $_G_quoted_arg" + else + func_append func_quote_for_eval_result "$_G_quoted_arg" + fi + shift + done } -# func_quote_for_expand arg +# func_quote_for_expand ARG +# ------------------------- # Aesthetically quote ARG to be evaled later; same as above, # but do not quote variable references. func_quote_for_expand () { + $debug_cmd + case $1 in *[\\\`\"]*) - my_arg=`$ECHO "$1" | $SED \ - -e "$double_quote_subst" -e "$sed_double_backslash"` ;; + _G_arg=`$ECHO "$1" | $SED \ + -e "$sed_double_quote_subst" -e "$sed_double_backslash"` ;; *) - my_arg="$1" ;; + _G_arg=$1 ;; esac - case $my_arg in + case $_G_arg in # Double-quote args containing shell metacharacters to delay # word splitting and command substitution for a subsequent eval. # Many Bourne shells cannot handle close brackets correctly # in scan sets, so we specify it separately. *[\[\~\#\^\&\*\(\)\{\}\|\;\<\>\?\'\ \ ]*|*]*|"") - my_arg="\"$my_arg\"" + _G_arg=\"$_G_arg\" ;; esac - func_quote_for_expand_result="$my_arg" + func_quote_for_expand_result=$_G_arg } -# func_show_eval cmd [fail_exp] -# Unless opt_silent is true, then output CMD. Then, if opt_dryrun is +# func_stripname PREFIX SUFFIX NAME +# --------------------------------- +# strip PREFIX and SUFFIX from NAME, and store in func_stripname_result. +# PREFIX and SUFFIX must not contain globbing or regex special +# characters, hashes, percent signs, but SUFFIX may contain a leading +# dot (in which case that matches only a dot). +if test yes = "$_G_HAVE_XSI_OPS"; then + eval 'func_stripname () + { + $debug_cmd + + # pdksh 5.2.14 does not do ${X%$Y} correctly if both X and Y are + # positional parameters, so assign one to ordinary variable first. + func_stripname_result=$3 + func_stripname_result=${func_stripname_result#"$1"} + func_stripname_result=${func_stripname_result%"$2"} + }' +else + func_stripname () + { + $debug_cmd + + case $2 in + .*) func_stripname_result=`$ECHO "$3" | $SED -e "s%^$1%%" -e "s%\\\\$2\$%%"`;; + *) func_stripname_result=`$ECHO "$3" | $SED -e "s%^$1%%" -e "s%$2\$%%"`;; + esac + } +fi + + +# func_show_eval CMD [FAIL_EXP] +# ----------------------------- +# Unless opt_quiet is true, then output CMD. Then, if opt_dryrun is # not true, evaluate CMD. If the evaluation of CMD fails, and FAIL_EXP # is given, then evaluate it. func_show_eval () { - my_cmd="$1" - my_fail_exp="${2-:}" + $debug_cmd - ${opt_silent-false} || { - func_quote_for_expand "$my_cmd" - eval "func_echo $func_quote_for_expand_result" - } + _G_cmd=$1 + _G_fail_exp=${2-':'} - if ${opt_dry_run-false}; then :; else - eval "$my_cmd" - my_status=$? - if test "$my_status" -eq 0; then :; else - eval "(exit $my_status); $my_fail_exp" + func_quote_for_expand "$_G_cmd" + eval "func_notquiet $func_quote_for_expand_result" + + $opt_dry_run || { + eval "$_G_cmd" + _G_status=$? + if test 0 -ne "$_G_status"; then + eval "(exit $_G_status); $_G_fail_exp" fi - fi + } } -# func_show_eval_locale cmd [fail_exp] -# Unless opt_silent is true, then output CMD. Then, if opt_dryrun is +# func_show_eval_locale CMD [FAIL_EXP] +# ------------------------------------ +# Unless opt_quiet is true, then output CMD. Then, if opt_dryrun is # not true, evaluate CMD. If the evaluation of CMD fails, and FAIL_EXP # is given, then evaluate it. Use the saved locale for evaluation. func_show_eval_locale () { - my_cmd="$1" - my_fail_exp="${2-:}" + $debug_cmd - ${opt_silent-false} || { - func_quote_for_expand "$my_cmd" + _G_cmd=$1 + _G_fail_exp=${2-':'} + + $opt_quiet || { + func_quote_for_expand "$_G_cmd" eval "func_echo $func_quote_for_expand_result" } - if ${opt_dry_run-false}; then :; else - eval "$lt_user_locale - $my_cmd" - my_status=$? - eval "$lt_safe_locale" - if test "$my_status" -eq 0; then :; else - eval "(exit $my_status); $my_fail_exp" + $opt_dry_run || { + eval "$_G_user_locale + $_G_cmd" + _G_status=$? + eval "$_G_safe_locale" + if test 0 -ne "$_G_status"; then + eval "(exit $_G_status); $_G_fail_exp" fi - fi + } } + # func_tr_sh +# ---------- # Turn $1 into a string suitable for a shell variable name. # Result is stored in $func_tr_sh_result. All characters # not in the set a-zA-Z0-9_ are replaced with '_'. Further, # if $1 begins with a digit, a '_' is prepended as well. func_tr_sh () { - case $1 in - [0-9]* | *[!a-zA-Z0-9_]*) - func_tr_sh_result=`$ECHO "$1" | $SED 's/^\([0-9]\)/_\1/; s/[^a-zA-Z0-9_]/_/g'` - ;; - * ) - func_tr_sh_result=$1 - ;; - esac + $debug_cmd + + case $1 in + [0-9]* | *[!a-zA-Z0-9_]*) + func_tr_sh_result=`$ECHO "$1" | $SED -e 's/^\([0-9]\)/_\1/' -e 's/[^a-zA-Z0-9_]/_/g'` + ;; + * ) + func_tr_sh_result=$1 + ;; + esac } -# func_version -# Echo version message to standard output and exit. -func_version () +# func_verbose ARG... +# ------------------- +# Echo program name prefixed message in verbose mode only. +func_verbose () { - $opt_debug + $debug_cmd - $SED -n '/(C)/!b go - :more - /\./!{ - N - s/\n# / / - b more - } - :go - /^# '$PROGRAM' (GNU /,/# warranty; / { - s/^# // - s/^# *$// - s/\((C)\)[ 0-9,-]*\( [1-9][0-9]*\)/\1\2/ - p - }' < "$progpath" - exit $? + $opt_verbose && func_echo "$*" + + : } -# func_usage -# Echo short help message to standard output and exit. -func_usage () + +# func_warn_and_continue ARG... +# ----------------------------- +# Echo program name prefixed warning message to standard error. +func_warn_and_continue () { - $opt_debug + $debug_cmd - $SED -n '/^# Usage:/,/^# *.*--help/ { - s/^# // - s/^# *$// - s/\$progname/'$progname'/ - p - }' < "$progpath" - echo - $ECHO "run \`$progname --help | more' for full usage" - exit $? + $require_term_colors + + func_echo_infix_1 "${tc_red}warning$tc_reset" "$*" >&2 } -# func_help [NOEXIT] -# Echo long help message to standard output and exit, -# unless 'noexit' is passed as argument. + +# func_warning CATEGORY ARG... +# ---------------------------- +# Echo program name prefixed warning message to standard error. Warning +# messages can be filtered according to CATEGORY, where this function +# elides messages where CATEGORY is not listed in the global variable +# 'opt_warning_types'. +func_warning () +{ + $debug_cmd + + # CATEGORY must be in the warning_categories list! + case " $warning_categories " in + *" $1 "*) ;; + *) func_internal_error "invalid warning category '$1'" ;; + esac + + _G_category=$1 + shift + + case " $opt_warning_types " in + *" $_G_category "*) $warning_func ${1+"$@"} ;; + esac +} + + +# func_sort_ver VER1 VER2 +# ----------------------- +# 'sort -V' is not generally available. +# Note this deviates from the version comparison in automake +# in that it treats 1.5 < 1.5.0, and treats 1.4.4a < 1.4-p3a +# but this should suffice as we won't be specifying old +# version formats or redundant trailing .0 in bootstrap.conf. +# If we did want full compatibility then we should probably +# use m4_version_compare from autoconf. +func_sort_ver () +{ + $debug_cmd + + printf '%s\n%s\n' "$1" "$2" \ + | sort -t. -k 1,1n -k 2,2n -k 3,3n -k 4,4n -k 5,5n -k 6,6n -k 7,7n -k 8,8n -k 9,9n +} + +# func_lt_ver PREV CURR +# --------------------- +# Return true if PREV and CURR are in the correct order according to +# func_sort_ver, otherwise false. Use it like this: +# +# func_lt_ver "$prev_ver" "$proposed_ver" || func_fatal_error "..." +func_lt_ver () +{ + $debug_cmd + + test "x$1" = x`func_sort_ver "$1" "$2" | $SED 1q` +} + + +# Local variables: +# mode: shell-script +# sh-indentation: 2 +# eval: (add-hook 'before-save-hook 'time-stamp) +# time-stamp-pattern: "10/scriptversion=%:y-%02m-%02d.%02H; # UTC" +# time-stamp-time-zone: "UTC" +# End: +#! /bin/sh + +# Set a version string for this script. +scriptversion=2014-01-07.03; # UTC + +# A portable, pluggable option parser for Bourne shell. +# Written by Gary V. Vaughan, 2010 + +# Copyright (C) 2010-2015 Free Software Foundation, Inc. +# This is free software; see the source for copying conditions. There is NO +# warranty; not even for MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + +# 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 . + +# Please report bugs or propose patches to gary@gnu.org. + + +## ------ ## +## Usage. ## +## ------ ## + +# This file is a library for parsing options in your shell scripts along +# with assorted other useful supporting features that you can make use +# of too. +# +# For the simplest scripts you might need only: +# +# #!/bin/sh +# . relative/path/to/funclib.sh +# . relative/path/to/options-parser +# scriptversion=1.0 +# func_options ${1+"$@"} +# eval set dummy "$func_options_result"; shift +# ...rest of your script... +# +# In order for the '--version' option to work, you will need to have a +# suitably formatted comment like the one at the top of this file +# starting with '# Written by ' and ending with '# warranty; '. +# +# For '-h' and '--help' to work, you will also need a one line +# description of your script's purpose in a comment directly above the +# '# Written by ' line, like the one at the top of this file. +# +# The default options also support '--debug', which will turn on shell +# execution tracing (see the comment above debug_cmd below for another +# use), and '--verbose' and the func_verbose function to allow your script +# to display verbose messages only when your user has specified +# '--verbose'. +# +# After sourcing this file, you can plug processing for additional +# options by amending the variables from the 'Configuration' section +# below, and following the instructions in the 'Option parsing' +# section further down. + +## -------------- ## +## Configuration. ## +## -------------- ## + +# You should override these variables in your script after sourcing this +# file so that they reflect the customisations you have added to the +# option parser. + +# The usage line for option parsing errors and the start of '-h' and +# '--help' output messages. You can embed shell variables for delayed +# expansion at the time the message is displayed, but you will need to +# quote other shell meta-characters carefully to prevent them being +# expanded when the contents are evaled. +usage='$progpath [OPTION]...' + +# Short help message in response to '-h' and '--help'. Add to this or +# override it after sourcing this library to reflect the full set of +# options your script accepts. +usage_message="\ + --debug enable verbose shell tracing + -W, --warnings=CATEGORY + report the warnings falling in CATEGORY [all] + -v, --verbose verbosely report processing + --version print version information and exit + -h, --help print short or long help message and exit +" + +# Additional text appended to 'usage_message' in response to '--help'. +long_help_message=" +Warning categories include: + 'all' show all warnings + 'none' turn off all the warnings + 'error' warnings are treated as fatal errors" + +# Help message printed before fatal option parsing errors. +fatal_help="Try '\$progname --help' for more information." + + + +## ------------------------- ## +## Hook function management. ## +## ------------------------- ## + +# This section contains functions for adding, removing, and running hooks +# to the main code. A hook is just a named list of of function, that can +# be run in order later on. + +# func_hookable FUNC_NAME +# ----------------------- +# Declare that FUNC_NAME will run hooks added with +# 'func_add_hook FUNC_NAME ...'. +func_hookable () +{ + $debug_cmd + + func_append hookable_fns " $1" +} + + +# func_add_hook FUNC_NAME HOOK_FUNC +# --------------------------------- +# Request that FUNC_NAME call HOOK_FUNC before it returns. FUNC_NAME must +# first have been declared "hookable" by a call to 'func_hookable'. +func_add_hook () +{ + $debug_cmd + + case " $hookable_fns " in + *" $1 "*) ;; + *) func_fatal_error "'$1' does not accept hook functions." ;; + esac + + eval func_append ${1}_hooks '" $2"' +} + + +# func_remove_hook FUNC_NAME HOOK_FUNC +# ------------------------------------ +# Remove HOOK_FUNC from the list of functions called by FUNC_NAME. +func_remove_hook () +{ + $debug_cmd + + eval ${1}_hooks='`$ECHO "\$'$1'_hooks" |$SED "s| '$2'||"`' +} + + +# func_run_hooks FUNC_NAME [ARG]... +# --------------------------------- +# Run all hook functions registered to FUNC_NAME. +# It is assumed that the list of hook functions contains nothing more +# than a whitespace-delimited list of legal shell function names, and +# no effort is wasted trying to catch shell meta-characters or preserve +# whitespace. +func_run_hooks () +{ + $debug_cmd + + case " $hookable_fns " in + *" $1 "*) ;; + *) func_fatal_error "'$1' does not support hook funcions.n" ;; + esac + + eval _G_hook_fns=\$$1_hooks; shift + + for _G_hook in $_G_hook_fns; do + eval $_G_hook '"$@"' + + # store returned options list back into positional + # parameters for next 'cmd' execution. + eval _G_hook_result=\$${_G_hook}_result + eval set dummy "$_G_hook_result"; shift + done + + func_quote_for_eval ${1+"$@"} + func_run_hooks_result=$func_quote_for_eval_result +} + + + +## --------------- ## +## Option parsing. ## +## --------------- ## + +# In order to add your own option parsing hooks, you must accept the +# full positional parameter list in your hook function, remove any +# options that you action, and then pass back the remaining unprocessed +# options in '_result', escaped suitably for +# 'eval'. Like this: +# +# my_options_prep () +# { +# $debug_cmd +# +# # Extend the existing usage message. +# usage_message=$usage_message' +# -s, --silent don'\''t print informational messages +# ' +# +# func_quote_for_eval ${1+"$@"} +# my_options_prep_result=$func_quote_for_eval_result +# } +# func_add_hook func_options_prep my_options_prep +# +# +# my_silent_option () +# { +# $debug_cmd +# +# # Note that for efficiency, we parse as many options as we can +# # recognise in a loop before passing the remainder back to the +# # caller on the first unrecognised argument we encounter. +# while test $# -gt 0; do +# opt=$1; shift +# case $opt in +# --silent|-s) opt_silent=: ;; +# # Separate non-argument short options: +# -s*) func_split_short_opt "$_G_opt" +# set dummy "$func_split_short_opt_name" \ +# "-$func_split_short_opt_arg" ${1+"$@"} +# shift +# ;; +# *) set dummy "$_G_opt" "$*"; shift; break ;; +# esac +# done +# +# func_quote_for_eval ${1+"$@"} +# my_silent_option_result=$func_quote_for_eval_result +# } +# func_add_hook func_parse_options my_silent_option +# +# +# my_option_validation () +# { +# $debug_cmd +# +# $opt_silent && $opt_verbose && func_fatal_help "\ +# '--silent' and '--verbose' options are mutually exclusive." +# +# func_quote_for_eval ${1+"$@"} +# my_option_validation_result=$func_quote_for_eval_result +# } +# func_add_hook func_validate_options my_option_validation +# +# You'll alse need to manually amend $usage_message to reflect the extra +# options you parse. It's preferable to append if you can, so that +# multiple option parsing hooks can be added safely. + + +# func_options [ARG]... +# --------------------- +# All the functions called inside func_options are hookable. See the +# individual implementations for details. +func_hookable func_options +func_options () +{ + $debug_cmd + + func_options_prep ${1+"$@"} + eval func_parse_options \ + ${func_options_prep_result+"$func_options_prep_result"} + eval func_validate_options \ + ${func_parse_options_result+"$func_parse_options_result"} + + eval func_run_hooks func_options \ + ${func_validate_options_result+"$func_validate_options_result"} + + # save modified positional parameters for caller + func_options_result=$func_run_hooks_result +} + + +# func_options_prep [ARG]... +# -------------------------- +# All initialisations required before starting the option parse loop. +# Note that when calling hook functions, we pass through the list of +# positional parameters. If a hook function modifies that list, and +# needs to propogate that back to rest of this script, then the complete +# modified list must be put in 'func_run_hooks_result' before +# returning. +func_hookable func_options_prep +func_options_prep () +{ + $debug_cmd + + # Option defaults: + opt_verbose=false + opt_warning_types= + + func_run_hooks func_options_prep ${1+"$@"} + + # save modified positional parameters for caller + func_options_prep_result=$func_run_hooks_result +} + + +# func_parse_options [ARG]... +# --------------------------- +# The main option parsing loop. +func_hookable func_parse_options +func_parse_options () +{ + $debug_cmd + + func_parse_options_result= + + # this just eases exit handling + while test $# -gt 0; do + # Defer to hook functions for initial option parsing, so they + # get priority in the event of reusing an option name. + func_run_hooks func_parse_options ${1+"$@"} + + # Adjust func_parse_options positional parameters to match + eval set dummy "$func_run_hooks_result"; shift + + # Break out of the loop if we already parsed every option. + test $# -gt 0 || break + + _G_opt=$1 + shift + case $_G_opt in + --debug|-x) debug_cmd='set -x' + func_echo "enabling shell trace mode" + $debug_cmd + ;; + + --no-warnings|--no-warning|--no-warn) + set dummy --warnings none ${1+"$@"} + shift + ;; + + --warnings|--warning|-W) + test $# = 0 && func_missing_arg $_G_opt && break + case " $warning_categories $1" in + *" $1 "*) + # trailing space prevents matching last $1 above + func_append_uniq opt_warning_types " $1" + ;; + *all) + opt_warning_types=$warning_categories + ;; + *none) + opt_warning_types=none + warning_func=: + ;; + *error) + opt_warning_types=$warning_categories + warning_func=func_fatal_error + ;; + *) + func_fatal_error \ + "unsupported warning category: '$1'" + ;; + esac + shift + ;; + + --verbose|-v) opt_verbose=: ;; + --version) func_version ;; + -\?|-h) func_usage ;; + --help) func_help ;; + + # Separate optargs to long options (plugins may need this): + --*=*) func_split_equals "$_G_opt" + set dummy "$func_split_equals_lhs" \ + "$func_split_equals_rhs" ${1+"$@"} + shift + ;; + + # Separate optargs to short options: + -W*) + func_split_short_opt "$_G_opt" + set dummy "$func_split_short_opt_name" \ + "$func_split_short_opt_arg" ${1+"$@"} + shift + ;; + + # Separate non-argument short options: + -\?*|-h*|-v*|-x*) + func_split_short_opt "$_G_opt" + set dummy "$func_split_short_opt_name" \ + "-$func_split_short_opt_arg" ${1+"$@"} + shift + ;; + + --) break ;; + -*) func_fatal_help "unrecognised option: '$_G_opt'" ;; + *) set dummy "$_G_opt" ${1+"$@"}; shift; break ;; + esac + done + + # save modified positional parameters for caller + func_quote_for_eval ${1+"$@"} + func_parse_options_result=$func_quote_for_eval_result +} + + +# func_validate_options [ARG]... +# ------------------------------ +# Perform any sanity checks on option settings and/or unconsumed +# arguments. +func_hookable func_validate_options +func_validate_options () +{ + $debug_cmd + + # Display all warnings if -W was not given. + test -n "$opt_warning_types" || opt_warning_types=" $warning_categories" + + func_run_hooks func_validate_options ${1+"$@"} + + # Bail if the options were screwed! + $exit_cmd $EXIT_FAILURE + + # save modified positional parameters for caller + func_validate_options_result=$func_run_hooks_result +} + + + +## ----------------- ## +## Helper functions. ## +## ----------------- ## + +# This section contains the helper functions used by the rest of the +# hookable option parser framework in ascii-betical order. + + +# func_fatal_help ARG... +# ---------------------- +# Echo program name prefixed message to standard error, followed by +# a help hint, and exit. +func_fatal_help () +{ + $debug_cmd + + eval \$ECHO \""Usage: $usage"\" + eval \$ECHO \""$fatal_help"\" + func_error ${1+"$@"} + exit $EXIT_FAILURE +} + + +# func_help +# --------- +# Echo long help message to standard output and exit. func_help () { - $opt_debug + $debug_cmd - $SED -n '/^# Usage:/,/# Report bugs to/ { - :print - s/^# // - s/^# *$// - s*\$progname*'$progname'* - s*\$host*'"$host"'* - s*\$SHELL*'"$SHELL"'* - s*\$LTCC*'"$LTCC"'* - s*\$LTCFLAGS*'"$LTCFLAGS"'* - s*\$LD*'"$LD"'* - s/\$with_gnu_ld/'"$with_gnu_ld"'/ - s/\$automake_version/'"`(${AUTOMAKE-automake} --version) 2>/dev/null |$SED 1q`"'/ - s/\$autoconf_version/'"`(${AUTOCONF-autoconf} --version) 2>/dev/null |$SED 1q`"'/ - p - d - } - /^# .* home page:/b print - /^# General help using/b print - ' < "$progpath" - ret=$? - if test -z "$1"; then - exit $ret - fi + func_usage_message + $ECHO "$long_help_message" + exit 0 } -# func_missing_arg argname + +# func_missing_arg ARGNAME +# ------------------------ # Echo program name prefixed message to standard error and set global # exit_cmd. func_missing_arg () { - $opt_debug + $debug_cmd - func_error "missing argument for $1." + func_error "Missing argument for '$1'." exit_cmd=exit } -# func_split_short_opt shortopt +# func_split_equals STRING +# ------------------------ +# Set func_split_equals_lhs and func_split_equals_rhs shell variables after +# splitting STRING at the '=' sign. +test -z "$_G_HAVE_XSI_OPS" \ + && (eval 'x=a/b/c; + test 5aa/bb/cc = "${#x}${x%%/*}${x%/*}${x#*/}${x##*/}"') 2>/dev/null \ + && _G_HAVE_XSI_OPS=yes + +if test yes = "$_G_HAVE_XSI_OPS" +then + # This is an XSI compatible shell, allowing a faster implementation... + eval 'func_split_equals () + { + $debug_cmd + + func_split_equals_lhs=${1%%=*} + func_split_equals_rhs=${1#*=} + test "x$func_split_equals_lhs" = "x$1" \ + && func_split_equals_rhs= + }' +else + # ...otherwise fall back to using expr, which is often a shell builtin. + func_split_equals () + { + $debug_cmd + + func_split_equals_lhs=`expr "x$1" : 'x\([^=]*\)'` + func_split_equals_rhs= + test "x$func_split_equals_lhs" = "x$1" \ + || func_split_equals_rhs=`expr "x$1" : 'x[^=]*=\(.*\)$'` + } +fi #func_split_equals + + +# func_split_short_opt SHORTOPT +# ----------------------------- # Set func_split_short_opt_name and func_split_short_opt_arg shell # variables after splitting SHORTOPT after the 2nd character. -func_split_short_opt () +if test yes = "$_G_HAVE_XSI_OPS" +then + # This is an XSI compatible shell, allowing a faster implementation... + eval 'func_split_short_opt () + { + $debug_cmd + + func_split_short_opt_arg=${1#??} + func_split_short_opt_name=${1%"$func_split_short_opt_arg"} + }' +else + # ...otherwise fall back to using expr, which is often a shell builtin. + func_split_short_opt () + { + $debug_cmd + + func_split_short_opt_name=`expr "x$1" : 'x-\(.\)'` + func_split_short_opt_arg=`expr "x$1" : 'x-.\(.*\)$'` + } +fi #func_split_short_opt + + +# func_usage +# ---------- +# Echo short help message to standard output and exit. +func_usage () { - my_sed_short_opt='1s/^\(..\).*$/\1/;q' - my_sed_short_rest='1s/^..\(.*\)$/\1/;q' + $debug_cmd - func_split_short_opt_name=`$ECHO "$1" | $SED "$my_sed_short_opt"` - func_split_short_opt_arg=`$ECHO "$1" | $SED "$my_sed_short_rest"` -} # func_split_short_opt may be replaced by extended shell implementation + func_usage_message + $ECHO "Run '$progname --help |${PAGER-more}' for full usage" + exit 0 +} -# func_split_long_opt longopt -# Set func_split_long_opt_name and func_split_long_opt_arg shell -# variables after splitting LONGOPT at the `=' sign. -func_split_long_opt () +# func_usage_message +# ------------------ +# Echo short help message to standard output. +func_usage_message () { - my_sed_long_opt='1s/^\(--[^=]*\)=.*/\1/;q' - my_sed_long_arg='1s/^--[^=]*=//' + $debug_cmd - func_split_long_opt_name=`$ECHO "$1" | $SED "$my_sed_long_opt"` - func_split_long_opt_arg=`$ECHO "$1" | $SED "$my_sed_long_arg"` -} # func_split_long_opt may be replaced by extended shell implementation - -exit_cmd=: + eval \$ECHO \""Usage: $usage"\" + echo + $SED -n 's|^# || + /^Written by/{ + x;p;x + } + h + /^Written by/q' < "$progpath" + echo + eval \$ECHO \""$usage_message"\" +} - - - -magic="%%%MAGIC variable%%%" -magic_exe="%%%MAGIC EXE variable%%%" - -# Global variables. -nonopt= -preserve_args= -lo2o="s/\\.lo\$/.${objext}/" -o2lo="s/\\.${objext}\$/.lo/" -extracted_archives= -extracted_serial=0 - -# If this variable is set in any of the actions, the command in it -# will be execed at the end. This prevents here-documents from being -# left over by shells. -exec_cmd= - -# func_append var value -# Append VALUE to the end of shell variable VAR. -func_append () +# func_version +# ------------ +# Echo version message to standard output and exit. +func_version () { - eval "${1}=\$${1}\${2}" -} # func_append may be replaced by extended shell implementation + $debug_cmd -# func_append_quoted var value -# Quote VALUE and append to the end of shell variable VAR, separated -# by a space. -func_append_quoted () + printf '%s\n' "$progname $scriptversion" + $SED -n ' + /(C)/!b go + :more + /\./!{ + N + s|\n# | | + b more + } + :go + /^# Written by /,/# warranty; / { + s|^# || + s|^# *$|| + s|\((C)\)[ 0-9,-]*[ ,-]\([1-9][0-9]* \)|\1 \2| + p + } + /^# Written by / { + s|^# || + p + } + /^warranty; /q' < "$progpath" + + exit $? +} + + +# Local variables: +# mode: shell-script +# sh-indentation: 2 +# eval: (add-hook 'before-save-hook 'time-stamp) +# time-stamp-pattern: "10/scriptversion=%:y-%02m-%02d.%02H; # UTC" +# time-stamp-time-zone: "UTC" +# End: + +# Set a version string. +scriptversion='(GNU libtool) 2.4.6' + + +# func_echo ARG... +# ---------------- +# Libtool also displays the current mode in messages, so override +# funclib.sh func_echo with this custom definition. +func_echo () { - func_quote_for_eval "${2}" - eval "${1}=\$${1}\\ \$func_quote_for_eval_result" -} # func_append_quoted may be replaced by extended shell implementation + $debug_cmd + + _G_message=$* + + func_echo_IFS=$IFS + IFS=$nl + for _G_line in $_G_message; do + IFS=$func_echo_IFS + $ECHO "$progname${opt_mode+: $opt_mode}: $_G_line" + done + IFS=$func_echo_IFS +} -# func_arith arithmetic-term... -func_arith () +# func_warning ARG... +# ------------------- +# Libtool warnings are not categorized, so override funclib.sh +# func_warning with this simpler definition. +func_warning () { - func_arith_result=`expr "${@}"` -} # func_arith may be replaced by extended shell implementation + $debug_cmd + + $warning_func ${1+"$@"} +} -# func_len string -# STRING may not start with a hyphen. -func_len () +## ---------------- ## +## Options parsing. ## +## ---------------- ## + +# Hook in the functions to make sure our own options are parsed during +# the option parsing loop. + +usage='$progpath [OPTION]... [MODE-ARG]...' + +# Short help message in response to '-h'. +usage_message="Options: + --config show all configuration variables + --debug enable verbose shell tracing + -n, --dry-run display commands without modifying any files + --features display basic configuration information and exit + --mode=MODE use operation mode MODE + --no-warnings equivalent to '-Wnone' + --preserve-dup-deps don't remove duplicate dependency libraries + --quiet, --silent don't print informational messages + --tag=TAG use configuration variables from tag TAG + -v, --verbose print more informational messages than default + --version print version information + -W, --warnings=CATEGORY report the warnings falling in CATEGORY [all] + -h, --help, --help-all print short, long, or detailed help message +" + +# Additional text appended to 'usage_message' in response to '--help'. +func_help () { - func_len_result=`expr "${1}" : ".*" 2>/dev/null || echo $max_cmd_len` -} # func_len may be replaced by extended shell implementation + $debug_cmd + + func_usage_message + $ECHO "$long_help_message + +MODE must be one of the following: + + clean remove files from the build directory + compile compile a source file into a libtool object + execute automatically set library path, then run a program + finish complete the installation of libtool libraries + install install libraries or executables + link create a library or an executable + uninstall remove libraries from an installed directory + +MODE-ARGS vary depending on the MODE. When passed as first option, +'--mode=MODE' may be abbreviated as 'MODE' or a unique abbreviation of that. +Try '$progname --help --mode=MODE' for a more detailed description of MODE. + +When reporting a bug, please describe a test case to reproduce it and +include the following information: + + host-triplet: $host + shell: $SHELL + compiler: $LTCC + compiler flags: $LTCFLAGS + linker: $LD (gnu? $with_gnu_ld) + version: $progname (GNU libtool) 2.4.6 + automake: `($AUTOMAKE --version) 2>/dev/null |$SED 1q` + autoconf: `($AUTOCONF --version) 2>/dev/null |$SED 1q` + +Report bugs to . +GNU libtool home page: . +General help using GNU software: ." + exit 0 +} -# func_lo2o object -func_lo2o () -{ - func_lo2o_result=`$ECHO "${1}" | $SED "$lo2o"` -} # func_lo2o may be replaced by extended shell implementation +# func_lo2o OBJECT-NAME +# --------------------- +# Transform OBJECT-NAME from a '.lo' suffix to the platform specific +# object suffix. + +lo2o=s/\\.lo\$/.$objext/ +o2lo=s/\\.$objext\$/.lo/ + +if test yes = "$_G_HAVE_XSI_OPS"; then + eval 'func_lo2o () + { + case $1 in + *.lo) func_lo2o_result=${1%.lo}.$objext ;; + * ) func_lo2o_result=$1 ;; + esac + }' + + # func_xform LIBOBJ-OR-SOURCE + # --------------------------- + # Transform LIBOBJ-OR-SOURCE from a '.o' or '.c' (or otherwise) + # suffix to a '.lo' libtool-object suffix. + eval 'func_xform () + { + func_xform_result=${1%.*}.lo + }' +else + # ...otherwise fall back to using sed. + func_lo2o () + { + func_lo2o_result=`$ECHO "$1" | $SED "$lo2o"` + } + + func_xform () + { + func_xform_result=`$ECHO "$1" | $SED 's|\.[^.]*$|.lo|'` + } +fi -# func_xform libobj-or-source -func_xform () -{ - func_xform_result=`$ECHO "${1}" | $SED 's/\.[^.]*$/.lo/'` -} # func_xform may be replaced by extended shell implementation - - -# func_fatal_configuration arg... +# func_fatal_configuration ARG... +# ------------------------------- # Echo program name prefixed message to standard error, followed by # a configuration failure hint, and exit. func_fatal_configuration () { - func_error ${1+"$@"} - func_error "See the $PACKAGE documentation for more information." - func_fatal_error "Fatal configuration error." + func__fatal_error ${1+"$@"} \ + "See the $PACKAGE documentation for more information." \ + "Fatal configuration error." } # func_config +# ----------- # Display the configuration for all the tags in this script. func_config () { @@ -915,17 +2149,19 @@ func_config () exit $? } + # func_features +# ------------- # Display the features supported by this script. func_features () { echo "host: $host" - if test "$build_libtool_libs" = yes; then + if test yes = "$build_libtool_libs"; then echo "enable shared libraries" else echo "disable shared libraries" fi - if test "$build_old_libs" = yes; then + if test yes = "$build_old_libs"; then echo "enable static libraries" else echo "disable static libraries" @@ -934,314 +2170,350 @@ func_features () exit $? } -# func_enable_tag tagname + +# func_enable_tag TAGNAME +# ----------------------- # Verify that TAGNAME is valid, and either flag an error and exit, or # enable the TAGNAME tag. We also add TAGNAME to the global $taglist # variable here. func_enable_tag () { - # Global variable: - tagname="$1" + # Global variable: + tagname=$1 - re_begincf="^# ### BEGIN LIBTOOL TAG CONFIG: $tagname\$" - re_endcf="^# ### END LIBTOOL TAG CONFIG: $tagname\$" - sed_extractcf="/$re_begincf/,/$re_endcf/p" + re_begincf="^# ### BEGIN LIBTOOL TAG CONFIG: $tagname\$" + re_endcf="^# ### END LIBTOOL TAG CONFIG: $tagname\$" + sed_extractcf=/$re_begincf/,/$re_endcf/p - # Validate tagname. - case $tagname in - *[!-_A-Za-z0-9,/]*) - func_fatal_error "invalid tag name: $tagname" - ;; - esac + # Validate tagname. + case $tagname in + *[!-_A-Za-z0-9,/]*) + func_fatal_error "invalid tag name: $tagname" + ;; + esac - # Don't test for the "default" C tag, as we know it's - # there but not specially marked. - case $tagname in - CC) ;; + # Don't test for the "default" C tag, as we know it's + # there but not specially marked. + case $tagname in + CC) ;; *) - if $GREP "$re_begincf" "$progpath" >/dev/null 2>&1; then - taglist="$taglist $tagname" + if $GREP "$re_begincf" "$progpath" >/dev/null 2>&1; then + taglist="$taglist $tagname" - # Evaluate the configuration. Be careful to quote the path - # and the sed script, to avoid splitting on whitespace, but - # also don't use non-portable quotes within backquotes within - # quotes we have to do it in 2 steps: - extractedcf=`$SED -n -e "$sed_extractcf" < "$progpath"` - eval "$extractedcf" - else - func_error "ignoring unknown tag $tagname" - fi - ;; - esac + # Evaluate the configuration. Be careful to quote the path + # and the sed script, to avoid splitting on whitespace, but + # also don't use non-portable quotes within backquotes within + # quotes we have to do it in 2 steps: + extractedcf=`$SED -n -e "$sed_extractcf" < "$progpath"` + eval "$extractedcf" + else + func_error "ignoring unknown tag $tagname" + fi + ;; + esac } + # func_check_version_match +# ------------------------ # Ensure that we are using m4 macros, and libtool script from the same # release of libtool. func_check_version_match () { - if test "$package_revision" != "$macro_revision"; then - if test "$VERSION" != "$macro_version"; then - if test -z "$macro_version"; then - cat >&2 <<_LT_EOF + if test "$package_revision" != "$macro_revision"; then + if test "$VERSION" != "$macro_version"; then + if test -z "$macro_version"; then + cat >&2 <<_LT_EOF $progname: Version mismatch error. This is $PACKAGE $VERSION, but the $progname: definition of this LT_INIT comes from an older release. $progname: You should recreate aclocal.m4 with macros from $PACKAGE $VERSION $progname: and run autoconf again. _LT_EOF - else - cat >&2 <<_LT_EOF + else + cat >&2 <<_LT_EOF $progname: Version mismatch error. This is $PACKAGE $VERSION, but the $progname: definition of this LT_INIT comes from $PACKAGE $macro_version. $progname: You should recreate aclocal.m4 with macros from $PACKAGE $VERSION $progname: and run autoconf again. _LT_EOF - fi - else - cat >&2 <<_LT_EOF + fi + else + cat >&2 <<_LT_EOF $progname: Version mismatch error. This is $PACKAGE $VERSION, revision $package_revision, $progname: but the definition of this LT_INIT comes from revision $macro_revision. $progname: You should recreate aclocal.m4 with macros from revision $package_revision $progname: of $PACKAGE $VERSION and run autoconf again. _LT_EOF - fi + fi - exit $EXIT_MISMATCH - fi + exit $EXIT_MISMATCH + fi } -# Shorthand for --mode=foo, only valid as the first argument -case $1 in -clean|clea|cle|cl) - shift; set dummy --mode clean ${1+"$@"}; shift - ;; -compile|compil|compi|comp|com|co|c) - shift; set dummy --mode compile ${1+"$@"}; shift - ;; -execute|execut|execu|exec|exe|ex|e) - shift; set dummy --mode execute ${1+"$@"}; shift - ;; -finish|finis|fini|fin|fi|f) - shift; set dummy --mode finish ${1+"$@"}; shift - ;; -install|instal|insta|inst|ins|in|i) - shift; set dummy --mode install ${1+"$@"}; shift - ;; -link|lin|li|l) - shift; set dummy --mode link ${1+"$@"}; shift - ;; -uninstall|uninstal|uninsta|uninst|unins|unin|uni|un|u) - shift; set dummy --mode uninstall ${1+"$@"}; shift - ;; -esac - - - -# Option defaults: -opt_debug=: -opt_dry_run=false -opt_config=false -opt_preserve_dup_deps=false -opt_features=false -opt_finish=false -opt_help=false -opt_help_all=false -opt_silent=: -opt_warning=: -opt_verbose=: -opt_silent=false -opt_verbose=false - - -# Parse options once, thoroughly. This comes as soon as possible in the -# script to make things like `--version' happen as quickly as we can. +# libtool_options_prep [ARG]... +# ----------------------------- +# Preparation for options parsed by libtool. +libtool_options_prep () { - # this just eases exit handling - while test $# -gt 0; do - opt="$1" - shift - case $opt in - --debug|-x) opt_debug='set -x' - func_echo "enabling shell trace mode" - $opt_debug - ;; - --dry-run|--dryrun|-n) - opt_dry_run=: - ;; - --config) - opt_config=: -func_config - ;; - --dlopen|-dlopen) - optarg="$1" - opt_dlopen="${opt_dlopen+$opt_dlopen -}$optarg" - shift - ;; - --preserve-dup-deps) - opt_preserve_dup_deps=: - ;; - --features) - opt_features=: -func_features - ;; - --finish) - opt_finish=: -set dummy --mode finish ${1+"$@"}; shift - ;; - --help) - opt_help=: - ;; - --help-all) - opt_help_all=: -opt_help=': help-all' - ;; - --mode) - test $# = 0 && func_missing_arg $opt && break - optarg="$1" - opt_mode="$optarg" -case $optarg in - # Valid mode arguments: - clean|compile|execute|finish|install|link|relink|uninstall) ;; + $debug_mode - # Catch anything else as an error - *) func_error "invalid argument for $opt" - exit_cmd=exit - break - ;; -esac - shift - ;; - --no-silent|--no-quiet) - opt_silent=false -func_append preserve_args " $opt" - ;; - --no-warning|--no-warn) - opt_warning=false -func_append preserve_args " $opt" - ;; - --no-verbose) - opt_verbose=false -func_append preserve_args " $opt" - ;; - --silent|--quiet) - opt_silent=: -func_append preserve_args " $opt" - opt_verbose=false - ;; - --verbose|-v) - opt_verbose=: -func_append preserve_args " $opt" -opt_silent=false - ;; - --tag) - test $# = 0 && func_missing_arg $opt && break - optarg="$1" - opt_tag="$optarg" -func_append preserve_args " $opt $optarg" -func_enable_tag "$optarg" - shift - ;; + # Option defaults: + opt_config=false + opt_dlopen= + opt_dry_run=false + opt_help=false + opt_mode= + opt_preserve_dup_deps=false + opt_quiet=false - -\?|-h) func_usage ;; - --help) func_help ;; - --version) func_version ;; + nonopt= + preserve_args= - # Separate optargs to long options: - --*=*) - func_split_long_opt "$opt" - set dummy "$func_split_long_opt_name" "$func_split_long_opt_arg" ${1+"$@"} - shift - ;; - - # Separate non-argument short options: - -\?*|-h*|-n*|-v*) - func_split_short_opt "$opt" - set dummy "$func_split_short_opt_name" "-$func_split_short_opt_arg" ${1+"$@"} - shift - ;; - - --) break ;; - -*) func_fatal_help "unrecognized option \`$opt'" ;; - *) set dummy "$opt" ${1+"$@"}; shift; break ;; + # Shorthand for --mode=foo, only valid as the first argument + case $1 in + clean|clea|cle|cl) + shift; set dummy --mode clean ${1+"$@"}; shift + ;; + compile|compil|compi|comp|com|co|c) + shift; set dummy --mode compile ${1+"$@"}; shift + ;; + execute|execut|execu|exec|exe|ex|e) + shift; set dummy --mode execute ${1+"$@"}; shift + ;; + finish|finis|fini|fin|fi|f) + shift; set dummy --mode finish ${1+"$@"}; shift + ;; + install|instal|insta|inst|ins|in|i) + shift; set dummy --mode install ${1+"$@"}; shift + ;; + link|lin|li|l) + shift; set dummy --mode link ${1+"$@"}; shift + ;; + uninstall|uninstal|uninsta|uninst|unins|unin|uni|un|u) + shift; set dummy --mode uninstall ${1+"$@"}; shift + ;; esac - done - # Validate options: - - # save first non-option argument - if test "$#" -gt 0; then - nonopt="$opt" - shift - fi - - # preserve --debug - test "$opt_debug" = : || func_append preserve_args " --debug" - - case $host in - *cygwin* | *mingw* | *pw32* | *cegcc*) - # don't eliminate duplications in $postdeps and $predeps - opt_duplicate_compiler_generated_deps=: - ;; - *) - opt_duplicate_compiler_generated_deps=$opt_preserve_dup_deps - ;; - esac - - $opt_help || { - # Sanity checks first: - func_check_version_match - - if test "$build_libtool_libs" != yes && test "$build_old_libs" != yes; then - func_fatal_configuration "not configured to build any kind of library" - fi - - # Darwin sucks - eval std_shrext=\"$shrext_cmds\" - - # Only execute mode is allowed to have -dlopen flags. - if test -n "$opt_dlopen" && test "$opt_mode" != execute; then - func_error "unrecognized option \`-dlopen'" - $ECHO "$help" 1>&2 - exit $EXIT_FAILURE - fi - - # Change the help message to a mode-specific one. - generic_help="$help" - help="Try \`$progname --help --mode=$opt_mode' for more information." - } - - - # Bail if the options were screwed - $exit_cmd $EXIT_FAILURE + # Pass back the list of options. + func_quote_for_eval ${1+"$@"} + libtool_options_prep_result=$func_quote_for_eval_result } +func_add_hook func_options_prep libtool_options_prep +# libtool_parse_options [ARG]... +# --------------------------------- +# Provide handling for libtool specific options. +libtool_parse_options () +{ + $debug_cmd + + # Perform our own loop to consume as many options as possible in + # each iteration. + while test $# -gt 0; do + _G_opt=$1 + shift + case $_G_opt in + --dry-run|--dryrun|-n) + opt_dry_run=: + ;; + + --config) func_config ;; + + --dlopen|-dlopen) + opt_dlopen="${opt_dlopen+$opt_dlopen +}$1" + shift + ;; + + --preserve-dup-deps) + opt_preserve_dup_deps=: ;; + + --features) func_features ;; + + --finish) set dummy --mode finish ${1+"$@"}; shift ;; + + --help) opt_help=: ;; + + --help-all) opt_help=': help-all' ;; + + --mode) test $# = 0 && func_missing_arg $_G_opt && break + opt_mode=$1 + case $1 in + # Valid mode arguments: + clean|compile|execute|finish|install|link|relink|uninstall) ;; + + # Catch anything else as an error + *) func_error "invalid argument for $_G_opt" + exit_cmd=exit + break + ;; + esac + shift + ;; + + --no-silent|--no-quiet) + opt_quiet=false + func_append preserve_args " $_G_opt" + ;; + + --no-warnings|--no-warning|--no-warn) + opt_warning=false + func_append preserve_args " $_G_opt" + ;; + + --no-verbose) + opt_verbose=false + func_append preserve_args " $_G_opt" + ;; + + --silent|--quiet) + opt_quiet=: + opt_verbose=false + func_append preserve_args " $_G_opt" + ;; + + --tag) test $# = 0 && func_missing_arg $_G_opt && break + opt_tag=$1 + func_append preserve_args " $_G_opt $1" + func_enable_tag "$1" + shift + ;; + + --verbose|-v) opt_quiet=false + opt_verbose=: + func_append preserve_args " $_G_opt" + ;; + + # An option not handled by this hook function: + *) set dummy "$_G_opt" ${1+"$@"}; shift; break ;; + esac + done + + + # save modified positional parameters for caller + func_quote_for_eval ${1+"$@"} + libtool_parse_options_result=$func_quote_for_eval_result +} +func_add_hook func_parse_options libtool_parse_options + + + +# libtool_validate_options [ARG]... +# --------------------------------- +# Perform any sanity checks on option settings and/or unconsumed +# arguments. +libtool_validate_options () +{ + # save first non-option argument + if test 0 -lt $#; then + nonopt=$1 + shift + fi + + # preserve --debug + test : = "$debug_cmd" || func_append preserve_args " --debug" + + case $host in + # Solaris2 added to fix http://debbugs.gnu.org/cgi/bugreport.cgi?bug=16452 + # see also: http://gcc.gnu.org/bugzilla/show_bug.cgi?id=59788 + *cygwin* | *mingw* | *pw32* | *cegcc* | *solaris2* | *os2*) + # don't eliminate duplications in $postdeps and $predeps + opt_duplicate_compiler_generated_deps=: + ;; + *) + opt_duplicate_compiler_generated_deps=$opt_preserve_dup_deps + ;; + esac + + $opt_help || { + # Sanity checks first: + func_check_version_match + + test yes != "$build_libtool_libs" \ + && test yes != "$build_old_libs" \ + && func_fatal_configuration "not configured to build any kind of library" + + # Darwin sucks + eval std_shrext=\"$shrext_cmds\" + + # Only execute mode is allowed to have -dlopen flags. + if test -n "$opt_dlopen" && test execute != "$opt_mode"; then + func_error "unrecognized option '-dlopen'" + $ECHO "$help" 1>&2 + exit $EXIT_FAILURE + fi + + # Change the help message to a mode-specific one. + generic_help=$help + help="Try '$progname --help --mode=$opt_mode' for more information." + } + + # Pass back the unparsed argument list + func_quote_for_eval ${1+"$@"} + libtool_validate_options_result=$func_quote_for_eval_result +} +func_add_hook func_validate_options libtool_validate_options + + +# Process options as early as possible so that --help and --version +# can return quickly. +func_options ${1+"$@"} +eval set dummy "$func_options_result"; shift + ## ----------- ## ## Main. ## ## ----------- ## +magic='%%%MAGIC variable%%%' +magic_exe='%%%MAGIC EXE variable%%%' + +# Global variables. +extracted_archives= +extracted_serial=0 + +# If this variable is set in any of the actions, the command in it +# will be execed at the end. This prevents here-documents from being +# left over by shells. +exec_cmd= + + +# A function that is used when there is no print builtin or printf. +func_fallback_echo () +{ + eval 'cat <<_LTECHO_EOF +$1 +_LTECHO_EOF' +} + +# func_generated_by_libtool +# True iff stdin has been generated by Libtool. This function is only +# a basic sanity check; it will hardly flush out determined imposters. +func_generated_by_libtool_p () +{ + $GREP "^# Generated by .*$PACKAGE" > /dev/null 2>&1 +} + # func_lalib_p file -# True iff FILE is a libtool `.la' library or `.lo' object file. +# True iff FILE is a libtool '.la' library or '.lo' object file. # This function is only a basic sanity check; it will hardly flush out # determined imposters. func_lalib_p () { test -f "$1" && - $SED -e 4q "$1" 2>/dev/null \ - | $GREP "^# Generated by .*$PACKAGE" > /dev/null 2>&1 + $SED -e 4q "$1" 2>/dev/null | func_generated_by_libtool_p } # func_lalib_unsafe_p file -# True iff FILE is a libtool `.la' library or `.lo' object file. +# True iff FILE is a libtool '.la' library or '.lo' object file. # This function implements the same check as func_lalib_p without # resorting to external programs. To this end, it redirects stdin and # closes it afterwards, without saving the original file descriptor. # As a safety measure, use it only where a negative result would be -# fatal anyway. Works if `file' does not exist. +# fatal anyway. Works if 'file' does not exist. func_lalib_unsafe_p () { lalib_p=no @@ -1249,13 +2521,13 @@ func_lalib_unsafe_p () for lalib_p_l in 1 2 3 4 do read lalib_p_line - case "$lalib_p_line" in + case $lalib_p_line in \#\ Generated\ by\ *$PACKAGE* ) lalib_p=yes; break;; esac done exec 0<&5 5<&- fi - test "$lalib_p" = yes + test yes = "$lalib_p" } # func_ltwrapper_script_p file @@ -1264,7 +2536,8 @@ func_lalib_unsafe_p () # determined imposters. func_ltwrapper_script_p () { - func_lalib_p "$1" + test -f "$1" && + $lt_truncate_bin < "$1" 2>/dev/null | func_generated_by_libtool_p } # func_ltwrapper_executable_p file @@ -1289,7 +2562,7 @@ func_ltwrapper_scriptname () { func_dirname_and_basename "$1" "" "." func_stripname '' '.exe' "$func_basename_result" - func_ltwrapper_scriptname_result="$func_dirname_result/$objdir/${func_stripname_result}_ltshwrapper" + func_ltwrapper_scriptname_result=$func_dirname_result/$objdir/${func_stripname_result}_ltshwrapper } # func_ltwrapper_p file @@ -1308,11 +2581,13 @@ func_ltwrapper_p () # FAIL_CMD may read-access the current command in variable CMD! func_execute_cmds () { - $opt_debug + $debug_cmd + save_ifs=$IFS; IFS='~' for cmd in $1; do - IFS=$save_ifs + IFS=$sp$nl eval cmd=\"$cmd\" + IFS=$save_ifs func_show_eval "$cmd" "${2-:}" done IFS=$save_ifs @@ -1324,10 +2599,11 @@ func_execute_cmds () # Note that it is not necessary on cygwin/mingw to append a dot to # FILE even if both FILE and FILE.exe exist: automatic-append-.exe # behavior happens only for exec(3), not for open(2)! Also, sourcing -# `FILE.' does not work on cygwin managed mounts. +# 'FILE.' does not work on cygwin managed mounts. func_source () { - $opt_debug + $debug_cmd + case $1 in */* | *\\*) . "$1" ;; *) . "./$1" ;; @@ -1354,10 +2630,10 @@ func_resolve_sysroot () # store the result into func_replace_sysroot_result. func_replace_sysroot () { - case "$lt_sysroot:$1" in + case $lt_sysroot:$1 in ?*:"$lt_sysroot"*) func_stripname "$lt_sysroot" '' "$1" - func_replace_sysroot_result="=$func_stripname_result" + func_replace_sysroot_result='='$func_stripname_result ;; *) # Including no sysroot. @@ -1374,7 +2650,8 @@ func_replace_sysroot () # arg is usually of the form 'gcc ...' func_infer_tag () { - $opt_debug + $debug_cmd + if test -n "$available_tags" && test -z "$tagname"; then CC_quoted= for arg in $CC; do @@ -1393,7 +2670,7 @@ func_infer_tag () for z in $available_tags; do if $GREP "^# ### BEGIN LIBTOOL TAG CONFIG: $z$" < "$progpath" > /dev/null; then # Evaluate the configuration. - eval "`${SED} -n -e '/^# ### BEGIN LIBTOOL TAG CONFIG: '$z'$/,/^# ### END LIBTOOL TAG CONFIG: '$z'$/p' < $progpath`" + eval "`$SED -n -e '/^# ### BEGIN LIBTOOL TAG CONFIG: '$z'$/,/^# ### END LIBTOOL TAG CONFIG: '$z'$/p' < $progpath`" CC_quoted= for arg in $CC; do # Double-quote args containing other shell metacharacters. @@ -1418,7 +2695,7 @@ func_infer_tag () # line option must be used. if test -z "$tagname"; then func_echo "unable to infer tagged configuration" - func_fatal_error "specify a tag with \`--tag'" + func_fatal_error "specify a tag with '--tag'" # else # func_verbose "using $tagname tagged configuration" fi @@ -1434,15 +2711,15 @@ func_infer_tag () # but don't create it if we're doing a dry run. func_write_libtool_object () { - write_libobj=${1} - if test "$build_libtool_libs" = yes; then - write_lobj=\'${2}\' + write_libobj=$1 + if test yes = "$build_libtool_libs"; then + write_lobj=\'$2\' else write_lobj=none fi - if test "$build_old_libs" = yes; then - write_oldobj=\'${3}\' + if test yes = "$build_old_libs"; then + write_oldobj=\'$3\' else write_oldobj=none fi @@ -1450,7 +2727,7 @@ func_write_libtool_object () $opt_dry_run || { cat >${write_libobj}T </dev/null` - if test "$?" -eq 0 && test -n "${func_convert_core_file_wine_to_w32_tmp}"; then + if test "$?" -eq 0 && test -n "$func_convert_core_file_wine_to_w32_tmp"; then func_convert_core_file_wine_to_w32_result=`$ECHO "$func_convert_core_file_wine_to_w32_tmp" | - $SED -e "$lt_sed_naive_backslashify"` + $SED -e "$sed_naive_backslashify"` else func_convert_core_file_wine_to_w32_result= fi @@ -1514,18 +2792,19 @@ func_convert_core_file_wine_to_w32 () # are convertible, then the result may be empty. func_convert_core_path_wine_to_w32 () { - $opt_debug + $debug_cmd + # unfortunately, winepath doesn't convert paths, only file names - func_convert_core_path_wine_to_w32_result="" + func_convert_core_path_wine_to_w32_result= if test -n "$1"; then oldIFS=$IFS IFS=: for func_convert_core_path_wine_to_w32_f in $1; do IFS=$oldIFS func_convert_core_file_wine_to_w32 "$func_convert_core_path_wine_to_w32_f" - if test -n "$func_convert_core_file_wine_to_w32_result" ; then + if test -n "$func_convert_core_file_wine_to_w32_result"; then if test -z "$func_convert_core_path_wine_to_w32_result"; then - func_convert_core_path_wine_to_w32_result="$func_convert_core_file_wine_to_w32_result" + func_convert_core_path_wine_to_w32_result=$func_convert_core_file_wine_to_w32_result else func_append func_convert_core_path_wine_to_w32_result ";$func_convert_core_file_wine_to_w32_result" fi @@ -1554,7 +2833,8 @@ func_convert_core_path_wine_to_w32 () # environment variable; do not put it in $PATH. func_cygpath () { - $opt_debug + $debug_cmd + if test -n "$LT_CYGPATH" && test -f "$LT_CYGPATH"; then func_cygpath_result=`$LT_CYGPATH "$@" 2>/dev/null` if test "$?" -ne 0; then @@ -1563,7 +2843,7 @@ func_cygpath () fi else func_cygpath_result= - func_error "LT_CYGPATH is empty or specifies non-existent file: \`$LT_CYGPATH'" + func_error "LT_CYGPATH is empty or specifies non-existent file: '$LT_CYGPATH'" fi } #end: func_cygpath @@ -1574,10 +2854,11 @@ func_cygpath () # result in func_convert_core_msys_to_w32_result. func_convert_core_msys_to_w32 () { - $opt_debug + $debug_cmd + # awkward: cmd appends spaces to result func_convert_core_msys_to_w32_result=`( cmd //c echo "$1" ) 2>/dev/null | - $SED -e 's/[ ]*$//' -e "$lt_sed_naive_backslashify"` + $SED -e 's/[ ]*$//' -e "$sed_naive_backslashify"` } #end: func_convert_core_msys_to_w32 @@ -1588,13 +2869,14 @@ func_convert_core_msys_to_w32 () # func_to_host_file_result to ARG1). func_convert_file_check () { - $opt_debug - if test -z "$2" && test -n "$1" ; then + $debug_cmd + + if test -z "$2" && test -n "$1"; then func_error "Could not determine host file name corresponding to" - func_error " \`$1'" + func_error " '$1'" func_error "Continuing, but uninstalled executables may not work." # Fallback: - func_to_host_file_result="$1" + func_to_host_file_result=$1 fi } # end func_convert_file_check @@ -1606,10 +2888,11 @@ func_convert_file_check () # func_to_host_file_result to a simplistic fallback value (see below). func_convert_path_check () { - $opt_debug + $debug_cmd + if test -z "$4" && test -n "$3"; then func_error "Could not determine the host path corresponding to" - func_error " \`$3'" + func_error " '$3'" func_error "Continuing, but uninstalled executables may not work." # Fallback. This is a deliberately simplistic "conversion" and # should not be "improved". See libtool.info. @@ -1618,7 +2901,7 @@ func_convert_path_check () func_to_host_path_result=`echo "$3" | $SED -e "$lt_replace_pathsep_chars"` else - func_to_host_path_result="$3" + func_to_host_path_result=$3 fi fi } @@ -1630,9 +2913,10 @@ func_convert_path_check () # and appending REPL if ORIG matches BACKPAT. func_convert_path_front_back_pathsep () { - $opt_debug + $debug_cmd + case $4 in - $1 ) func_to_host_path_result="$3$func_to_host_path_result" + $1 ) func_to_host_path_result=$3$func_to_host_path_result ;; esac case $4 in @@ -1646,7 +2930,7 @@ func_convert_path_front_back_pathsep () ################################################## # $build to $host FILE NAME CONVERSION FUNCTIONS # ################################################## -# invoked via `$to_host_file_cmd ARG' +# invoked via '$to_host_file_cmd ARG' # # In each case, ARG is the path to be converted from $build to $host format. # Result will be available in $func_to_host_file_result. @@ -1657,7 +2941,8 @@ func_convert_path_front_back_pathsep () # in func_to_host_file_result. func_to_host_file () { - $opt_debug + $debug_cmd + $to_host_file_cmd "$1" } # end func_to_host_file @@ -1669,7 +2954,8 @@ func_to_host_file () # in (the comma separated) LAZY, no conversion takes place. func_to_tool_file () { - $opt_debug + $debug_cmd + case ,$2, in *,"$to_tool_file_cmd",*) func_to_tool_file_result=$1 @@ -1687,7 +2973,7 @@ func_to_tool_file () # Copy ARG to func_to_host_file_result. func_convert_file_noop () { - func_to_host_file_result="$1" + func_to_host_file_result=$1 } # end func_convert_file_noop @@ -1698,11 +2984,12 @@ func_convert_file_noop () # func_to_host_file_result. func_convert_file_msys_to_w32 () { - $opt_debug - func_to_host_file_result="$1" + $debug_cmd + + func_to_host_file_result=$1 if test -n "$1"; then func_convert_core_msys_to_w32 "$1" - func_to_host_file_result="$func_convert_core_msys_to_w32_result" + func_to_host_file_result=$func_convert_core_msys_to_w32_result fi func_convert_file_check "$1" "$func_to_host_file_result" } @@ -1714,8 +3001,9 @@ func_convert_file_msys_to_w32 () # func_to_host_file_result. func_convert_file_cygwin_to_w32 () { - $opt_debug - func_to_host_file_result="$1" + $debug_cmd + + func_to_host_file_result=$1 if test -n "$1"; then # because $build is cygwin, we call "the" cygpath in $PATH; no need to use # LT_CYGPATH in this case. @@ -1731,11 +3019,12 @@ func_convert_file_cygwin_to_w32 () # and a working winepath. Returns result in func_to_host_file_result. func_convert_file_nix_to_w32 () { - $opt_debug - func_to_host_file_result="$1" + $debug_cmd + + func_to_host_file_result=$1 if test -n "$1"; then func_convert_core_file_wine_to_w32 "$1" - func_to_host_file_result="$func_convert_core_file_wine_to_w32_result" + func_to_host_file_result=$func_convert_core_file_wine_to_w32_result fi func_convert_file_check "$1" "$func_to_host_file_result" } @@ -1747,12 +3036,13 @@ func_convert_file_nix_to_w32 () # Returns result in func_to_host_file_result. func_convert_file_msys_to_cygwin () { - $opt_debug - func_to_host_file_result="$1" + $debug_cmd + + func_to_host_file_result=$1 if test -n "$1"; then func_convert_core_msys_to_w32 "$1" func_cygpath -u "$func_convert_core_msys_to_w32_result" - func_to_host_file_result="$func_cygpath_result" + func_to_host_file_result=$func_cygpath_result fi func_convert_file_check "$1" "$func_to_host_file_result" } @@ -1765,13 +3055,14 @@ func_convert_file_msys_to_cygwin () # in func_to_host_file_result. func_convert_file_nix_to_cygwin () { - $opt_debug - func_to_host_file_result="$1" + $debug_cmd + + func_to_host_file_result=$1 if test -n "$1"; then # convert from *nix to w32, then use cygpath to convert from w32 to cygwin. func_convert_core_file_wine_to_w32 "$1" func_cygpath -u "$func_convert_core_file_wine_to_w32_result" - func_to_host_file_result="$func_cygpath_result" + func_to_host_file_result=$func_cygpath_result fi func_convert_file_check "$1" "$func_to_host_file_result" } @@ -1781,7 +3072,7 @@ func_convert_file_nix_to_cygwin () ############################################# # $build to $host PATH CONVERSION FUNCTIONS # ############################################# -# invoked via `$to_host_path_cmd ARG' +# invoked via '$to_host_path_cmd ARG' # # In each case, ARG is the path to be converted from $build to $host format. # The result will be available in $func_to_host_path_result. @@ -1805,10 +3096,11 @@ func_convert_file_nix_to_cygwin () to_host_path_cmd= func_init_to_host_path_cmd () { - $opt_debug + $debug_cmd + if test -z "$to_host_path_cmd"; then func_stripname 'func_convert_file_' '' "$to_host_file_cmd" - to_host_path_cmd="func_convert_path_${func_stripname_result}" + to_host_path_cmd=func_convert_path_$func_stripname_result fi } @@ -1818,7 +3110,8 @@ func_init_to_host_path_cmd () # in func_to_host_path_result. func_to_host_path () { - $opt_debug + $debug_cmd + func_init_to_host_path_cmd $to_host_path_cmd "$1" } @@ -1829,7 +3122,7 @@ func_to_host_path () # Copy ARG to func_to_host_path_result. func_convert_path_noop () { - func_to_host_path_result="$1" + func_to_host_path_result=$1 } # end func_convert_path_noop @@ -1840,8 +3133,9 @@ func_convert_path_noop () # func_to_host_path_result. func_convert_path_msys_to_w32 () { - $opt_debug - func_to_host_path_result="$1" + $debug_cmd + + func_to_host_path_result=$1 if test -n "$1"; then # Remove leading and trailing path separator characters from ARG. MSYS # behavior is inconsistent here; cygpath turns them into '.;' and ';.'; @@ -1849,7 +3143,7 @@ func_convert_path_msys_to_w32 () func_stripname : : "$1" func_to_host_path_tmp1=$func_stripname_result func_convert_core_msys_to_w32 "$func_to_host_path_tmp1" - func_to_host_path_result="$func_convert_core_msys_to_w32_result" + func_to_host_path_result=$func_convert_core_msys_to_w32_result func_convert_path_check : ";" \ "$func_to_host_path_tmp1" "$func_to_host_path_result" func_convert_path_front_back_pathsep ":*" "*:" ";" "$1" @@ -1863,8 +3157,9 @@ func_convert_path_msys_to_w32 () # func_to_host_file_result. func_convert_path_cygwin_to_w32 () { - $opt_debug - func_to_host_path_result="$1" + $debug_cmd + + func_to_host_path_result=$1 if test -n "$1"; then # See func_convert_path_msys_to_w32: func_stripname : : "$1" @@ -1883,14 +3178,15 @@ func_convert_path_cygwin_to_w32 () # a working winepath. Returns result in func_to_host_file_result. func_convert_path_nix_to_w32 () { - $opt_debug - func_to_host_path_result="$1" + $debug_cmd + + func_to_host_path_result=$1 if test -n "$1"; then # See func_convert_path_msys_to_w32: func_stripname : : "$1" func_to_host_path_tmp1=$func_stripname_result func_convert_core_path_wine_to_w32 "$func_to_host_path_tmp1" - func_to_host_path_result="$func_convert_core_path_wine_to_w32_result" + func_to_host_path_result=$func_convert_core_path_wine_to_w32_result func_convert_path_check : ";" \ "$func_to_host_path_tmp1" "$func_to_host_path_result" func_convert_path_front_back_pathsep ":*" "*:" ";" "$1" @@ -1904,15 +3200,16 @@ func_convert_path_nix_to_w32 () # Returns result in func_to_host_file_result. func_convert_path_msys_to_cygwin () { - $opt_debug - func_to_host_path_result="$1" + $debug_cmd + + func_to_host_path_result=$1 if test -n "$1"; then # See func_convert_path_msys_to_w32: func_stripname : : "$1" func_to_host_path_tmp1=$func_stripname_result func_convert_core_msys_to_w32 "$func_to_host_path_tmp1" func_cygpath -u -p "$func_convert_core_msys_to_w32_result" - func_to_host_path_result="$func_cygpath_result" + func_to_host_path_result=$func_cygpath_result func_convert_path_check : : \ "$func_to_host_path_tmp1" "$func_to_host_path_result" func_convert_path_front_back_pathsep ":*" "*:" : "$1" @@ -1927,8 +3224,9 @@ func_convert_path_msys_to_cygwin () # func_to_host_file_result. func_convert_path_nix_to_cygwin () { - $opt_debug - func_to_host_path_result="$1" + $debug_cmd + + func_to_host_path_result=$1 if test -n "$1"; then # Remove leading and trailing path separator characters from # ARG. msys behavior is inconsistent here, cygpath turns them @@ -1937,7 +3235,7 @@ func_convert_path_nix_to_cygwin () func_to_host_path_tmp1=$func_stripname_result func_convert_core_path_wine_to_w32 "$func_to_host_path_tmp1" func_cygpath -u -p "$func_convert_core_path_wine_to_w32_result" - func_to_host_path_result="$func_cygpath_result" + func_to_host_path_result=$func_cygpath_result func_convert_path_check : : \ "$func_to_host_path_tmp1" "$func_to_host_path_result" func_convert_path_front_back_pathsep ":*" "*:" : "$1" @@ -1946,13 +3244,31 @@ func_convert_path_nix_to_cygwin () # end func_convert_path_nix_to_cygwin +# func_dll_def_p FILE +# True iff FILE is a Windows DLL '.def' file. +# Keep in sync with _LT_DLL_DEF_P in libtool.m4 +func_dll_def_p () +{ + $debug_cmd + + func_dll_def_p_tmp=`$SED -n \ + -e 's/^[ ]*//' \ + -e '/^\(;.*\)*$/d' \ + -e 's/^\(EXPORTS\|LIBRARY\)\([ ].*\)*$/DEF/p' \ + -e q \ + "$1"` + test DEF = "$func_dll_def_p_tmp" +} + + # func_mode_compile arg... func_mode_compile () { - $opt_debug + $debug_cmd + # Get the compilation command and the source file. base_compile= - srcfile="$nonopt" # always keep a non-empty value in "srcfile" + srcfile=$nonopt # always keep a non-empty value in "srcfile" suppress_opt=yes suppress_output= arg_mode=normal @@ -1965,12 +3281,12 @@ func_mode_compile () case $arg_mode in arg ) # do not "continue". Instead, add this to base_compile - lastarg="$arg" + lastarg=$arg arg_mode=normal ;; target ) - libobj="$arg" + libobj=$arg arg_mode=normal continue ;; @@ -1980,7 +3296,7 @@ func_mode_compile () case $arg in -o) test -n "$libobj" && \ - func_fatal_error "you cannot specify \`-o' more than once" + func_fatal_error "you cannot specify '-o' more than once" arg_mode=target continue ;; @@ -2009,12 +3325,12 @@ func_mode_compile () func_stripname '-Wc,' '' "$arg" args=$func_stripname_result lastarg= - save_ifs="$IFS"; IFS=',' + save_ifs=$IFS; IFS=, for arg in $args; do - IFS="$save_ifs" + IFS=$save_ifs func_append_quoted lastarg "$arg" done - IFS="$save_ifs" + IFS=$save_ifs func_stripname ' ' '' "$lastarg" lastarg=$func_stripname_result @@ -2027,8 +3343,8 @@ func_mode_compile () # Accept the current argument as the source file. # The previous "srcfile" becomes the current argument. # - lastarg="$srcfile" - srcfile="$arg" + lastarg=$srcfile + srcfile=$arg ;; esac # case $arg ;; @@ -2043,13 +3359,13 @@ func_mode_compile () func_fatal_error "you must specify an argument for -Xcompile" ;; target) - func_fatal_error "you must specify a target with \`-o'" + func_fatal_error "you must specify a target with '-o'" ;; *) # Get the name of the library object. test -z "$libobj" && { func_basename "$srcfile" - libobj="$func_basename_result" + libobj=$func_basename_result } ;; esac @@ -2069,7 +3385,7 @@ func_mode_compile () case $libobj in *.lo) func_lo2o "$libobj"; obj=$func_lo2o_result ;; *) - func_fatal_error "cannot determine name of library object from \`$libobj'" + func_fatal_error "cannot determine name of library object from '$libobj'" ;; esac @@ -2078,8 +3394,8 @@ func_mode_compile () for arg in $later; do case $arg in -shared) - test "$build_libtool_libs" != yes && \ - func_fatal_configuration "can not build a shared library" + test yes = "$build_libtool_libs" \ + || func_fatal_configuration "cannot build a shared library" build_old_libs=no continue ;; @@ -2105,17 +3421,17 @@ func_mode_compile () func_quote_for_eval "$libobj" test "X$libobj" != "X$func_quote_for_eval_result" \ && $ECHO "X$libobj" | $GREP '[]~#^*{};<>?"'"'"' &()|`$[]' \ - && func_warning "libobj name \`$libobj' may not contain shell special characters." + && func_warning "libobj name '$libobj' may not contain shell special characters." func_dirname_and_basename "$obj" "/" "" - objname="$func_basename_result" - xdir="$func_dirname_result" - lobj=${xdir}$objdir/$objname + objname=$func_basename_result + xdir=$func_dirname_result + lobj=$xdir$objdir/$objname test -z "$base_compile" && \ func_fatal_help "you must specify a compilation command" # Delete any leftover library objects. - if test "$build_old_libs" = yes; then + if test yes = "$build_old_libs"; then removelist="$obj $lobj $libobj ${libobj}T" else removelist="$lobj $libobj ${libobj}T" @@ -2127,16 +3443,16 @@ func_mode_compile () pic_mode=default ;; esac - if test "$pic_mode" = no && test "$deplibs_check_method" != pass_all; then + if test no = "$pic_mode" && test pass_all != "$deplibs_check_method"; then # non-PIC code in shared libraries is not supported pic_mode=default fi # Calculate the filename of the output object if compiler does # not support -o with -c - if test "$compiler_c_o" = no; then - output_obj=`$ECHO "$srcfile" | $SED 's%^.*/%%; s%\.[^.]*$%%'`.${objext} - lockfile="$output_obj.lock" + if test no = "$compiler_c_o"; then + output_obj=`$ECHO "$srcfile" | $SED 's%^.*/%%; s%\.[^.]*$%%'`.$objext + lockfile=$output_obj.lock else output_obj= need_locks=no @@ -2145,12 +3461,12 @@ func_mode_compile () # Lock this critical section if it is needed # We use this script file to make the link, it avoids creating a new file - if test "$need_locks" = yes; then + if test yes = "$need_locks"; then until $opt_dry_run || ln "$progpath" "$lockfile" 2>/dev/null; do func_echo "Waiting for $lockfile to be removed" sleep 2 done - elif test "$need_locks" = warn; then + elif test warn = "$need_locks"; then if test -f "$lockfile"; then $ECHO "\ *** ERROR, $lockfile exists and contains: @@ -2158,7 +3474,7 @@ func_mode_compile () This indicates that another process is trying to use the same temporary object file, and libtool could not work around it because -your compiler does not support \`-c' and \`-o' together. If you +your compiler does not support '-c' and '-o' together. If you repeat this compilation, it may succeed, by chance, but you had better avoid parallel builds (make -j) in this platform, or get a better compiler." @@ -2180,11 +3496,11 @@ compiler." qsrcfile=$func_quote_for_eval_result # Only build a PIC object if we are building libtool libraries. - if test "$build_libtool_libs" = yes; then + if test yes = "$build_libtool_libs"; then # Without this assignment, base_compile gets emptied. fbsd_hideous_sh_bug=$base_compile - if test "$pic_mode" != no; then + if test no != "$pic_mode"; then command="$base_compile $qsrcfile $pic_flag" else # Don't build PIC code @@ -2201,7 +3517,7 @@ compiler." func_show_eval_locale "$command" \ 'test -n "$output_obj" && $RM $removelist; exit $EXIT_FAILURE' - if test "$need_locks" = warn && + if test warn = "$need_locks" && test "X`cat $lockfile 2>/dev/null`" != "X$srcfile"; then $ECHO "\ *** ERROR, $lockfile contains: @@ -2212,7 +3528,7 @@ $srcfile This indicates that another process is trying to use the same temporary object file, and libtool could not work around it because -your compiler does not support \`-c' and \`-o' together. If you +your compiler does not support '-c' and '-o' together. If you repeat this compilation, it may succeed, by chance, but you had better avoid parallel builds (make -j) in this platform, or get a better compiler." @@ -2228,20 +3544,20 @@ compiler." fi # Allow error messages only from the first compilation. - if test "$suppress_opt" = yes; then + if test yes = "$suppress_opt"; then suppress_output=' >/dev/null 2>&1' fi fi # Only build a position-dependent object if we build old libraries. - if test "$build_old_libs" = yes; then - if test "$pic_mode" != yes; then + if test yes = "$build_old_libs"; then + if test yes != "$pic_mode"; then # Don't build PIC code command="$base_compile $qsrcfile$pie_flag" else command="$base_compile $qsrcfile $pic_flag" fi - if test "$compiler_c_o" = yes; then + if test yes = "$compiler_c_o"; then func_append command " -o $obj" fi @@ -2250,7 +3566,7 @@ compiler." func_show_eval_locale "$command" \ '$opt_dry_run || $RM $removelist; exit $EXIT_FAILURE' - if test "$need_locks" = warn && + if test warn = "$need_locks" && test "X`cat $lockfile 2>/dev/null`" != "X$srcfile"; then $ECHO "\ *** ERROR, $lockfile contains: @@ -2261,7 +3577,7 @@ $srcfile This indicates that another process is trying to use the same temporary object file, and libtool could not work around it because -your compiler does not support \`-c' and \`-o' together. If you +your compiler does not support '-c' and '-o' together. If you repeat this compilation, it may succeed, by chance, but you had better avoid parallel builds (make -j) in this platform, or get a better compiler." @@ -2281,7 +3597,7 @@ compiler." func_write_libtool_object "$libobj" "$objdir/$objname" "$objname" # Unlock the critical section if it was locked - if test "$need_locks" != no; then + if test no != "$need_locks"; then removelist=$lockfile $RM "$lockfile" fi @@ -2291,7 +3607,7 @@ compiler." } $opt_help || { - test "$opt_mode" = compile && func_mode_compile ${1+"$@"} + test compile = "$opt_mode" && func_mode_compile ${1+"$@"} } func_mode_help () @@ -2311,7 +3627,7 @@ func_mode_help () Remove files from the build directory. RM is the name of the program to use to delete files associated with each FILE -(typically \`/bin/rm'). RM-OPTIONS are options (such as \`-f') to be passed +(typically '/bin/rm'). RM-OPTIONS are options (such as '-f') to be passed to RM. If FILE is a libtool library, object or program, all the files associated @@ -2330,16 +3646,16 @@ This mode accepts the following additional options: -no-suppress do not suppress compiler output for multiple passes -prefer-pic try to build PIC objects only -prefer-non-pic try to build non-PIC objects only - -shared do not build a \`.o' file suitable for static linking - -static only build a \`.o' file suitable for static linking + -shared do not build a '.o' file suitable for static linking + -static only build a '.o' file suitable for static linking -Wc,FLAG pass FLAG directly to the compiler -COMPILE-COMMAND is a command to be used in creating a \`standard' object file +COMPILE-COMMAND is a command to be used in creating a 'standard' object file from the given SOURCEFILE. The output file name is determined by removing the directory component from -SOURCEFILE, then substituting the C source code suffix \`.c' with the -library object suffix, \`.lo'." +SOURCEFILE, then substituting the C source code suffix '.c' with the +library object suffix, '.lo'." ;; execute) @@ -2352,7 +3668,7 @@ This mode accepts the following additional options: -dlopen FILE add the directory containing FILE to the library path -This mode sets the library path environment variable according to \`-dlopen' +This mode sets the library path environment variable according to '-dlopen' flags. If any of the ARGS are libtool executable wrappers, then they are translated @@ -2371,7 +3687,7 @@ Complete the installation of libtool libraries. Each LIBDIR is a directory that contains libtool libraries. The commands that this mode executes may require superuser privileges. Use -the \`--dry-run' option if you just want to see what would be executed." +the '--dry-run' option if you just want to see what would be executed." ;; install) @@ -2381,7 +3697,7 @@ the \`--dry-run' option if you just want to see what would be executed." Install executables or libraries. INSTALL-COMMAND is the installation command. The first component should be -either the \`install' or \`cp' program. +either the 'install' or 'cp' program. The following components of INSTALL-COMMAND are treated specially: @@ -2407,7 +3723,7 @@ The following components of LINK-COMMAND are treated specially: -avoid-version do not add a version suffix if possible -bindir BINDIR specify path to binaries directory (for systems where libraries must be found in the PATH setting at runtime) - -dlopen FILE \`-dlpreopen' FILE if it cannot be dlopened at runtime + -dlopen FILE '-dlpreopen' FILE if it cannot be dlopened at runtime -dlpreopen FILE link in FILE and add its symbols to lt_preloaded_symbols -export-dynamic allow symbols from OUTPUT-FILE to be resolved with dlsym(3) -export-symbols SYMFILE @@ -2421,7 +3737,8 @@ The following components of LINK-COMMAND are treated specially: -no-install link a not-installable executable -no-undefined declare that a library does not refer to external symbols -o OUTPUT-FILE create OUTPUT-FILE from the specified objects - -objectlist FILE Use a list of object files found in FILE to specify objects + -objectlist FILE use a list of object files found in FILE to specify objects + -os2dllname NAME force a short DLL name on OS/2 (no effect on other OSes) -precious-files-regex REGEX don't remove output files matching REGEX -release RELEASE specify package release information @@ -2441,20 +3758,20 @@ The following components of LINK-COMMAND are treated specially: -Xlinker FLAG pass linker-specific FLAG directly to the linker -XCClinker FLAG pass link-specific FLAG to the compiler driver (CC) -All other options (arguments beginning with \`-') are ignored. +All other options (arguments beginning with '-') are ignored. -Every other argument is treated as a filename. Files ending in \`.la' are +Every other argument is treated as a filename. Files ending in '.la' are treated as uninstalled libtool libraries, other files are standard or library object files. -If the OUTPUT-FILE ends in \`.la', then a libtool library is created, -only library objects (\`.lo' files) may be specified, and \`-rpath' is +If the OUTPUT-FILE ends in '.la', then a libtool library is created, +only library objects ('.lo' files) may be specified, and '-rpath' is required, except when creating a convenience library. -If OUTPUT-FILE ends in \`.a' or \`.lib', then a standard library is created -using \`ar' and \`ranlib', or on Windows using \`lib'. +If OUTPUT-FILE ends in '.a' or '.lib', then a standard library is created +using 'ar' and 'ranlib', or on Windows using 'lib'. -If OUTPUT-FILE ends in \`.lo' or \`.${objext}', then a reloadable object file +If OUTPUT-FILE ends in '.lo' or '.$objext', then a reloadable object file is created, otherwise an executable program is created." ;; @@ -2465,7 +3782,7 @@ is created, otherwise an executable program is created." Remove libraries from an installation directory. RM is the name of the program to use to delete files associated with each FILE -(typically \`/bin/rm'). RM-OPTIONS are options (such as \`-f') to be passed +(typically '/bin/rm'). RM-OPTIONS are options (such as '-f') to be passed to RM. If FILE is a libtool library, all the files associated with it are deleted. @@ -2473,17 +3790,17 @@ Otherwise, only FILE itself is deleted using RM." ;; *) - func_fatal_help "invalid operation mode \`$opt_mode'" + func_fatal_help "invalid operation mode '$opt_mode'" ;; esac echo - $ECHO "Try \`$progname --help' for more information about other modes." + $ECHO "Try '$progname --help' for more information about other modes." } # Now that we've collected a possible --mode arg, show help if necessary if $opt_help; then - if test "$opt_help" = :; then + if test : = "$opt_help"; then func_mode_help else { @@ -2491,7 +3808,7 @@ if $opt_help; then for opt_mode in compile link execute install finish uninstall clean; do func_mode_help done - } | sed -n '1p; 2,$s/^Usage:/ or: /p' + } | $SED -n '1p; 2,$s/^Usage:/ or: /p' { func_help noexit for opt_mode in compile link execute install finish uninstall clean; do @@ -2499,7 +3816,7 @@ if $opt_help; then func_mode_help done } | - sed '1d + $SED '1d /^When reporting/,/^Report/{ H d @@ -2516,16 +3833,17 @@ fi # func_mode_execute arg... func_mode_execute () { - $opt_debug + $debug_cmd + # The first argument is the command name. - cmd="$nonopt" + cmd=$nonopt test -z "$cmd" && \ func_fatal_help "you must specify a COMMAND" # Handle -dlopen flags immediately. for file in $opt_dlopen; do test -f "$file" \ - || func_fatal_help "\`$file' is not a file" + || func_fatal_help "'$file' is not a file" dir= case $file in @@ -2535,7 +3853,7 @@ func_mode_execute () # Check to see that this really is a libtool archive. func_lalib_unsafe_p "$file" \ - || func_fatal_help "\`$lib' is not a valid libtool archive" + || func_fatal_help "'$lib' is not a valid libtool archive" # Read the libtool library. dlname= @@ -2546,18 +3864,18 @@ func_mode_execute () if test -z "$dlname"; then # Warn if it was a shared library. test -n "$library_names" && \ - func_warning "\`$file' was not linked with \`-export-dynamic'" + func_warning "'$file' was not linked with '-export-dynamic'" continue fi func_dirname "$file" "" "." - dir="$func_dirname_result" + dir=$func_dirname_result if test -f "$dir/$objdir/$dlname"; then func_append dir "/$objdir" else if test ! -f "$dir/$dlname"; then - func_fatal_error "cannot find \`$dlname' in \`$dir' or \`$dir/$objdir'" + func_fatal_error "cannot find '$dlname' in '$dir' or '$dir/$objdir'" fi fi ;; @@ -2565,18 +3883,18 @@ func_mode_execute () *.lo) # Just add the directory containing the .lo file. func_dirname "$file" "" "." - dir="$func_dirname_result" + dir=$func_dirname_result ;; *) - func_warning "\`-dlopen' is ignored for non-libtool libraries and objects" + func_warning "'-dlopen' is ignored for non-libtool libraries and objects" continue ;; esac # Get the absolute pathname. absdir=`cd "$dir" && pwd` - test -n "$absdir" && dir="$absdir" + test -n "$absdir" && dir=$absdir # Now add the directory to shlibpath_var. if eval "test -z \"\$$shlibpath_var\""; then @@ -2588,7 +3906,7 @@ func_mode_execute () # This variable tells wrapper scripts just to set shlibpath_var # rather than running their programs. - libtool_execute_magic="$magic" + libtool_execute_magic=$magic # Check if any of the arguments is a wrapper script. args= @@ -2601,12 +3919,12 @@ func_mode_execute () if func_ltwrapper_script_p "$file"; then func_source "$file" # Transform arg to wrapped name. - file="$progdir/$program" + file=$progdir/$program elif func_ltwrapper_executable_p "$file"; then func_ltwrapper_scriptname "$file" func_source "$func_ltwrapper_scriptname_result" # Transform arg to wrapped name. - file="$progdir/$program" + file=$progdir/$program fi ;; esac @@ -2614,7 +3932,15 @@ func_mode_execute () func_append_quoted args "$file" done - if test "X$opt_dry_run" = Xfalse; then + if $opt_dry_run; then + # Display what would be done. + if test -n "$shlibpath_var"; then + eval "\$ECHO \"\$shlibpath_var=\$$shlibpath_var\"" + echo "export $shlibpath_var" + fi + $ECHO "$cmd$args" + exit $EXIT_SUCCESS + else if test -n "$shlibpath_var"; then # Export the shlibpath_var. eval "export $shlibpath_var" @@ -2631,25 +3957,18 @@ func_mode_execute () done # Now prepare to actually exec the command. - exec_cmd="\$cmd$args" - else - # Display what would be done. - if test -n "$shlibpath_var"; then - eval "\$ECHO \"\$shlibpath_var=\$$shlibpath_var\"" - echo "export $shlibpath_var" - fi - $ECHO "$cmd$args" - exit $EXIT_SUCCESS + exec_cmd=\$cmd$args fi } -test "$opt_mode" = execute && func_mode_execute ${1+"$@"} +test execute = "$opt_mode" && func_mode_execute ${1+"$@"} # func_mode_finish arg... func_mode_finish () { - $opt_debug + $debug_cmd + libs= libdirs= admincmds= @@ -2663,11 +3982,11 @@ func_mode_finish () if func_lalib_unsafe_p "$opt"; then func_append libs " $opt" else - func_warning "\`$opt' is not a valid libtool archive" + func_warning "'$opt' is not a valid libtool archive" fi else - func_fatal_error "invalid argument \`$opt'" + func_fatal_error "invalid argument '$opt'" fi done @@ -2682,12 +4001,12 @@ func_mode_finish () # Remove sysroot references if $opt_dry_run; then for lib in $libs; do - echo "removing references to $lt_sysroot and \`=' prefixes from $lib" + echo "removing references to $lt_sysroot and '=' prefixes from $lib" done else tmpdir=`func_mktempdir` for lib in $libs; do - sed -e "${sysroot_cmd} s/\([ ']-[LR]\)=/\1/g; s/\([ ']\)=/\1/g" $lib \ + $SED -e "$sysroot_cmd s/\([ ']-[LR]\)=/\1/g; s/\([ ']\)=/\1/g" $lib \ > $tmpdir/tmp-la mv -f $tmpdir/tmp-la $lib done @@ -2712,7 +4031,7 @@ func_mode_finish () fi # Exit here if they wanted silent mode. - $opt_silent && exit $EXIT_SUCCESS + $opt_quiet && exit $EXIT_SUCCESS if test -n "$finish_cmds$finish_eval" && test -n "$libdirs"; then echo "----------------------------------------------------------------------" @@ -2723,27 +4042,27 @@ func_mode_finish () echo echo "If you ever happen to want to link against installed libraries" echo "in a given directory, LIBDIR, you must either use libtool, and" - echo "specify the full pathname of the library, or use the \`-LLIBDIR'" + echo "specify the full pathname of the library, or use the '-LLIBDIR'" echo "flag during linking and do at least one of the following:" if test -n "$shlibpath_var"; then - echo " - add LIBDIR to the \`$shlibpath_var' environment variable" + echo " - add LIBDIR to the '$shlibpath_var' environment variable" echo " during execution" fi if test -n "$runpath_var"; then - echo " - add LIBDIR to the \`$runpath_var' environment variable" + echo " - add LIBDIR to the '$runpath_var' environment variable" echo " during linking" fi if test -n "$hardcode_libdir_flag_spec"; then libdir=LIBDIR eval flag=\"$hardcode_libdir_flag_spec\" - $ECHO " - use the \`$flag' linker flag" + $ECHO " - use the '$flag' linker flag" fi if test -n "$admincmds"; then $ECHO " - have your system administrator run these commands:$admincmds" fi if test -f /etc/ld.so.conf; then - echo " - have your system administrator add LIBDIR to \`/etc/ld.so.conf'" + echo " - have your system administrator add LIBDIR to '/etc/ld.so.conf'" fi echo @@ -2762,18 +4081,20 @@ func_mode_finish () exit $EXIT_SUCCESS } -test "$opt_mode" = finish && func_mode_finish ${1+"$@"} +test finish = "$opt_mode" && func_mode_finish ${1+"$@"} # func_mode_install arg... func_mode_install () { - $opt_debug + $debug_cmd + # There may be an optional sh(1) argument at the beginning of # install_prog (especially on Windows NT). - if test "$nonopt" = "$SHELL" || test "$nonopt" = /bin/sh || + if test "$SHELL" = "$nonopt" || test /bin/sh = "$nonopt" || # Allow the use of GNU shtool's install command. - case $nonopt in *shtool*) :;; *) false;; esac; then + case $nonopt in *shtool*) :;; *) false;; esac + then # Aesthetically quote it. func_quote_for_eval "$nonopt" install_prog="$func_quote_for_eval_result " @@ -2800,7 +4121,7 @@ func_mode_install () opts= prev= install_type= - isdir=no + isdir=false stripme= no_mode=: for arg @@ -2813,7 +4134,7 @@ func_mode_install () fi case $arg in - -d) isdir=yes ;; + -d) isdir=: ;; -f) if $install_cp; then :; else prev=$arg @@ -2831,7 +4152,7 @@ func_mode_install () *) # If the previous option needed an argument, then skip it. if test -n "$prev"; then - if test "x$prev" = x-m && test -n "$install_override_mode"; then + if test X-m = "X$prev" && test -n "$install_override_mode"; then arg2=$install_override_mode no_mode=false fi @@ -2856,7 +4177,7 @@ func_mode_install () func_fatal_help "you must specify an install program" test -n "$prev" && \ - func_fatal_help "the \`$prev' option requires an argument" + func_fatal_help "the '$prev' option requires an argument" if test -n "$install_override_mode" && $no_mode; then if $install_cp; then :; else @@ -2878,19 +4199,19 @@ func_mode_install () dest=$func_stripname_result # Check to see that the destination is a directory. - test -d "$dest" && isdir=yes - if test "$isdir" = yes; then - destdir="$dest" + test -d "$dest" && isdir=: + if $isdir; then + destdir=$dest destname= else func_dirname_and_basename "$dest" "" "." - destdir="$func_dirname_result" - destname="$func_basename_result" + destdir=$func_dirname_result + destname=$func_basename_result # Not a directory, so check to see that there is only one file specified. set dummy $files; shift test "$#" -gt 1 && \ - func_fatal_help "\`$dest' is not a directory" + func_fatal_help "'$dest' is not a directory" fi case $destdir in [\\/]* | [A-Za-z]:[\\/]*) ;; @@ -2899,7 +4220,7 @@ func_mode_install () case $file in *.lo) ;; *) - func_fatal_help "\`$destdir' must be an absolute directory name" + func_fatal_help "'$destdir' must be an absolute directory name" ;; esac done @@ -2908,7 +4229,7 @@ func_mode_install () # This variable tells wrapper scripts just to set variables rather # than running their programs. - libtool_install_magic="$magic" + libtool_install_magic=$magic staticlibs= future_libdirs= @@ -2928,7 +4249,7 @@ func_mode_install () # Check to see that this really is a libtool archive. func_lalib_unsafe_p "$file" \ - || func_fatal_help "\`$file' is not a valid libtool archive" + || func_fatal_help "'$file' is not a valid libtool archive" library_names= old_library= @@ -2950,7 +4271,7 @@ func_mode_install () fi func_dirname "$file" "/" "" - dir="$func_dirname_result" + dir=$func_dirname_result func_append dir "$objdir" if test -n "$relink_command"; then @@ -2964,7 +4285,7 @@ func_mode_install () # are installed into $libdir/../bin (currently, that works fine) # but it's something to keep an eye on. test "$inst_prefix_dir" = "$destdir" && \ - func_fatal_error "error: cannot install \`$file' to a directory not ending in $libdir" + func_fatal_error "error: cannot install '$file' to a directory not ending in $libdir" if test -n "$inst_prefix_dir"; then # Stick the inst_prefix_dir data into the link command. @@ -2973,29 +4294,36 @@ func_mode_install () relink_command=`$ECHO "$relink_command" | $SED "s%@inst_prefix_dir@%%"` fi - func_warning "relinking \`$file'" + func_warning "relinking '$file'" func_show_eval "$relink_command" \ - 'func_fatal_error "error: relink \`$file'\'' with the above command before installing it"' + 'func_fatal_error "error: relink '\''$file'\'' with the above command before installing it"' fi # See the names of the shared library. set dummy $library_names; shift if test -n "$1"; then - realname="$1" + realname=$1 shift - srcname="$realname" - test -n "$relink_command" && srcname="$realname"T + srcname=$realname + test -n "$relink_command" && srcname=${realname}T # Install the shared library and build the symlinks. func_show_eval "$install_shared_prog $dir/$srcname $destdir/$realname" \ 'exit $?' - tstripme="$stripme" + tstripme=$stripme case $host_os in cygwin* | mingw* | pw32* | cegcc*) case $realname in *.dll.a) - tstripme="" + tstripme= + ;; + esac + ;; + os2*) + case $realname in + *_dll.a) + tstripme= ;; esac ;; @@ -3006,7 +4334,7 @@ func_mode_install () if test "$#" -gt 0; then # Delete the old symlinks, and create new ones. - # Try `ln -sf' first, because the `ln' binary might depend on + # Try 'ln -sf' first, because the 'ln' binary might depend on # the symlink we replace! Solaris /bin/ln does not understand -f, # so we also need to try rm && ln -s. for linkname @@ -3017,14 +4345,14 @@ func_mode_install () fi # Do each command in the postinstall commands. - lib="$destdir/$realname" + lib=$destdir/$realname func_execute_cmds "$postinstall_cmds" 'exit $?' fi # Install the pseudo-library for information purposes. func_basename "$file" - name="$func_basename_result" - instname="$dir/$name"i + name=$func_basename_result + instname=$dir/${name}i func_show_eval "$install_prog $instname $destdir/$name" 'exit $?' # Maybe install the static library, too. @@ -3036,11 +4364,11 @@ func_mode_install () # Figure out destination file name, if it wasn't already specified. if test -n "$destname"; then - destfile="$destdir/$destname" + destfile=$destdir/$destname else func_basename "$file" - destfile="$func_basename_result" - destfile="$destdir/$destfile" + destfile=$func_basename_result + destfile=$destdir/$destfile fi # Deduce the name of the destination old-style object file. @@ -3050,11 +4378,11 @@ func_mode_install () staticdest=$func_lo2o_result ;; *.$objext) - staticdest="$destfile" + staticdest=$destfile destfile= ;; *) - func_fatal_help "cannot copy a libtool object to \`$destfile'" + func_fatal_help "cannot copy a libtool object to '$destfile'" ;; esac @@ -3063,7 +4391,7 @@ func_mode_install () func_show_eval "$install_prog $file $destfile" 'exit $?' # Install the old object if enabled. - if test "$build_old_libs" = yes; then + if test yes = "$build_old_libs"; then # Deduce the name of the old-style object file. func_lo2o "$file" staticobj=$func_lo2o_result @@ -3075,23 +4403,23 @@ func_mode_install () *) # Figure out destination file name, if it wasn't already specified. if test -n "$destname"; then - destfile="$destdir/$destname" + destfile=$destdir/$destname else func_basename "$file" - destfile="$func_basename_result" - destfile="$destdir/$destfile" + destfile=$func_basename_result + destfile=$destdir/$destfile fi # If the file is missing, and there is a .exe on the end, strip it # because it is most likely a libtool script we actually want to # install - stripped_ext="" + stripped_ext= case $file in *.exe) if test ! -f "$file"; then func_stripname '' '.exe' "$file" file=$func_stripname_result - stripped_ext=".exe" + stripped_ext=.exe fi ;; esac @@ -3119,19 +4447,19 @@ func_mode_install () # Check the variables that should have been set. test -z "$generated_by_libtool_version" && \ - func_fatal_error "invalid libtool wrapper script \`$wrapper'" + func_fatal_error "invalid libtool wrapper script '$wrapper'" - finalize=yes + finalize=: for lib in $notinst_deplibs; do # Check to see that each library is installed. libdir= if test -f "$lib"; then func_source "$lib" fi - libfile="$libdir/"`$ECHO "$lib" | $SED 's%^.*/%%g'` ### testsuite: skip nested quoting test + libfile=$libdir/`$ECHO "$lib" | $SED 's%^.*/%%g'` if test -n "$libdir" && test ! -f "$libfile"; then - func_warning "\`$lib' has not been installed in \`$libdir'" - finalize=no + func_warning "'$lib' has not been installed in '$libdir'" + finalize=false fi done @@ -3139,29 +4467,29 @@ func_mode_install () func_source "$wrapper" outputname= - if test "$fast_install" = no && test -n "$relink_command"; then + if test no = "$fast_install" && test -n "$relink_command"; then $opt_dry_run || { - if test "$finalize" = yes; then + if $finalize; then tmpdir=`func_mktempdir` func_basename "$file$stripped_ext" - file="$func_basename_result" - outputname="$tmpdir/$file" + file=$func_basename_result + outputname=$tmpdir/$file # Replace the output file specification. relink_command=`$ECHO "$relink_command" | $SED 's%@OUTPUT@%'"$outputname"'%g'` - $opt_silent || { + $opt_quiet || { func_quote_for_expand "$relink_command" eval "func_echo $func_quote_for_expand_result" } if eval "$relink_command"; then : else - func_error "error: relink \`$file' with the above command before installing it" + func_error "error: relink '$file' with the above command before installing it" $opt_dry_run || ${RM}r "$tmpdir" continue fi - file="$outputname" + file=$outputname else - func_warning "cannot relink \`$file'" + func_warning "cannot relink '$file'" fi } else @@ -3198,10 +4526,10 @@ func_mode_install () for file in $staticlibs; do func_basename "$file" - name="$func_basename_result" + name=$func_basename_result # Set up the ranlib parameters. - oldlib="$destdir/$name" + oldlib=$destdir/$name func_to_tool_file "$oldlib" func_convert_file_msys_to_w32 tool_oldlib=$func_to_tool_file_result @@ -3216,18 +4544,18 @@ func_mode_install () done test -n "$future_libdirs" && \ - func_warning "remember to run \`$progname --finish$future_libdirs'" + func_warning "remember to run '$progname --finish$future_libdirs'" if test -n "$current_libdirs"; then # Maybe just do a dry run. $opt_dry_run && current_libdirs=" -n$current_libdirs" - exec_cmd='$SHELL $progpath $preserve_args --finish$current_libdirs' + exec_cmd='$SHELL "$progpath" $preserve_args --finish$current_libdirs' else exit $EXIT_SUCCESS fi } -test "$opt_mode" = install && func_mode_install ${1+"$@"} +test install = "$opt_mode" && func_mode_install ${1+"$@"} # func_generate_dlsyms outputname originator pic_p @@ -3235,16 +4563,17 @@ test "$opt_mode" = install && func_mode_install ${1+"$@"} # a dlpreopen symbol table. func_generate_dlsyms () { - $opt_debug - my_outputname="$1" - my_originator="$2" - my_pic_p="${3-no}" - my_prefix=`$ECHO "$my_originator" | sed 's%[^a-zA-Z0-9]%_%g'` + $debug_cmd + + my_outputname=$1 + my_originator=$2 + my_pic_p=${3-false} + my_prefix=`$ECHO "$my_originator" | $SED 's%[^a-zA-Z0-9]%_%g'` my_dlsyms= - if test -n "$dlfiles$dlprefiles" || test "$dlself" != no; then + if test -n "$dlfiles$dlprefiles" || test no != "$dlself"; then if test -n "$NM" && test -n "$global_symbol_pipe"; then - my_dlsyms="${my_outputname}S.c" + my_dlsyms=${my_outputname}S.c else func_error "not configured to extract global symbols from dlpreopened files" fi @@ -3255,7 +4584,7 @@ func_generate_dlsyms () "") ;; *.c) # Discover the nlist of each of the dlfiles. - nlist="$output_objdir/${my_outputname}.nm" + nlist=$output_objdir/$my_outputname.nm func_show_eval "$RM $nlist ${nlist}S ${nlist}T" @@ -3263,34 +4592,36 @@ func_generate_dlsyms () func_verbose "creating $output_objdir/$my_dlsyms" $opt_dry_run || $ECHO > "$output_objdir/$my_dlsyms" "\ -/* $my_dlsyms - symbol resolution table for \`$my_outputname' dlsym emulation. */ -/* Generated by $PROGRAM (GNU $PACKAGE$TIMESTAMP) $VERSION */ +/* $my_dlsyms - symbol resolution table for '$my_outputname' dlsym emulation. */ +/* Generated by $PROGRAM (GNU $PACKAGE) $VERSION */ #ifdef __cplusplus extern \"C\" { #endif -#if defined(__GNUC__) && (((__GNUC__ == 4) && (__GNUC_MINOR__ >= 4)) || (__GNUC__ > 4)) +#if defined __GNUC__ && (((__GNUC__ == 4) && (__GNUC_MINOR__ >= 4)) || (__GNUC__ > 4)) #pragma GCC diagnostic ignored \"-Wstrict-prototypes\" #endif /* Keep this code in sync between libtool.m4, ltmain, lt_system.h, and tests. */ -#if defined(_WIN32) || defined(__CYGWIN__) || defined(_WIN32_WCE) -/* DATA imports from DLLs on WIN32 con't be const, because runtime +#if defined _WIN32 || defined __CYGWIN__ || defined _WIN32_WCE +/* DATA imports from DLLs on WIN32 can't be const, because runtime relocations are performed -- see ld's documentation on pseudo-relocs. */ # define LT_DLSYM_CONST -#elif defined(__osf__) +#elif defined __osf__ /* This system does not cope well with relocations in const data. */ # define LT_DLSYM_CONST #else # define LT_DLSYM_CONST const #endif +#define STREQ(s1, s2) (strcmp ((s1), (s2)) == 0) + /* External symbol declarations for the compiler. */\ " - if test "$dlself" = yes; then - func_verbose "generating symbol list for \`$output'" + if test yes = "$dlself"; then + func_verbose "generating symbol list for '$output'" $opt_dry_run || echo ': @PROGRAM@ ' > "$nlist" @@ -3298,7 +4629,7 @@ extern \"C\" { progfiles=`$ECHO "$objs$old_deplibs" | $SP2NL | $SED "$lo2o" | $NL2SP` for progfile in $progfiles; do func_to_tool_file "$progfile" func_convert_file_msys_to_w32 - func_verbose "extracting global C symbols from \`$func_to_tool_file_result'" + func_verbose "extracting global C symbols from '$func_to_tool_file_result'" $opt_dry_run || eval "$NM $func_to_tool_file_result | $global_symbol_pipe >> '$nlist'" done @@ -3318,10 +4649,10 @@ extern \"C\" { # Prepare the list of exported symbols if test -z "$export_symbols"; then - export_symbols="$output_objdir/$outputname.exp" + export_symbols=$output_objdir/$outputname.exp $opt_dry_run || { $RM $export_symbols - eval "${SED} -n -e '/^: @PROGRAM@ $/d' -e 's/^.* \(.*\)$/\1/p' "'< "$nlist" > "$export_symbols"' + eval "$SED -n -e '/^: @PROGRAM@ $/d' -e 's/^.* \(.*\)$/\1/p' "'< "$nlist" > "$export_symbols"' case $host in *cygwin* | *mingw* | *cegcc* ) eval "echo EXPORTS "'> "$output_objdir/$outputname.def"' @@ -3331,7 +4662,7 @@ extern \"C\" { } else $opt_dry_run || { - eval "${SED} -e 's/\([].[*^$]\)/\\\\\1/g' -e 's/^/ /' -e 's/$/$/'"' < "$export_symbols" > "$output_objdir/$outputname.exp"' + eval "$SED -e 's/\([].[*^$]\)/\\\\\1/g' -e 's/^/ /' -e 's/$/$/'"' < "$export_symbols" > "$output_objdir/$outputname.exp"' eval '$GREP -f "$output_objdir/$outputname.exp" < "$nlist" > "$nlist"T' eval '$MV "$nlist"T "$nlist"' case $host in @@ -3345,22 +4676,22 @@ extern \"C\" { fi for dlprefile in $dlprefiles; do - func_verbose "extracting global C symbols from \`$dlprefile'" + func_verbose "extracting global C symbols from '$dlprefile'" func_basename "$dlprefile" - name="$func_basename_result" + name=$func_basename_result case $host in *cygwin* | *mingw* | *cegcc* ) # if an import library, we need to obtain dlname if func_win32_import_lib_p "$dlprefile"; then func_tr_sh "$dlprefile" eval "curr_lafile=\$libfile_$func_tr_sh_result" - dlprefile_dlbasename="" + dlprefile_dlbasename= if test -n "$curr_lafile" && func_lalib_p "$curr_lafile"; then # Use subshell, to avoid clobbering current variable values dlprefile_dlname=`source "$curr_lafile" && echo "$dlname"` - if test -n "$dlprefile_dlname" ; then + if test -n "$dlprefile_dlname"; then func_basename "$dlprefile_dlname" - dlprefile_dlbasename="$func_basename_result" + dlprefile_dlbasename=$func_basename_result else # no lafile. user explicitly requested -dlpreopen . $sharedlib_from_linklib_cmd "$dlprefile" @@ -3368,7 +4699,7 @@ extern \"C\" { fi fi $opt_dry_run || { - if test -n "$dlprefile_dlbasename" ; then + if test -n "$dlprefile_dlbasename"; then eval '$ECHO ": $dlprefile_dlbasename" >> "$nlist"' else func_warning "Could not compute DLL name from $name" @@ -3424,6 +4755,11 @@ extern \"C\" { echo '/* NONE */' >> "$output_objdir/$my_dlsyms" fi + func_show_eval '$RM "${nlist}I"' + if test -n "$global_symbol_to_import"; then + eval "$global_symbol_to_import"' < "$nlist"S > "$nlist"I' + fi + echo >> "$output_objdir/$my_dlsyms" "\ /* The mapping between symbol names and symbols. */ @@ -3432,11 +4768,30 @@ typedef struct { void *address; } lt_dlsymlist; extern LT_DLSYM_CONST lt_dlsymlist -lt_${my_prefix}_LTX_preloaded_symbols[]; +lt_${my_prefix}_LTX_preloaded_symbols[];\ +" + + if test -s "$nlist"I; then + echo >> "$output_objdir/$my_dlsyms" "\ +static void lt_syminit(void) +{ + LT_DLSYM_CONST lt_dlsymlist *symbol = lt_${my_prefix}_LTX_preloaded_symbols; + for (; symbol->name; ++symbol) + {" + $SED 's/.*/ if (STREQ (symbol->name, \"&\")) symbol->address = (void *) \&&;/' < "$nlist"I >> "$output_objdir/$my_dlsyms" + echo >> "$output_objdir/$my_dlsyms" "\ + } +}" + fi + echo >> "$output_objdir/$my_dlsyms" "\ LT_DLSYM_CONST lt_dlsymlist lt_${my_prefix}_LTX_preloaded_symbols[] = -{\ - { \"$my_originator\", (void *) 0 }," +{ {\"$my_originator\", (void *) 0}," + + if test -s "$nlist"I; then + echo >> "$output_objdir/$my_dlsyms" "\ + {\"@INIT@\", (void *) <_syminit}," + fi case $need_lib_prefix in no) @@ -3478,9 +4833,7 @@ static const void *lt_preloaded_setup() { *-*-hpux*) pic_flag_for_symtable=" $pic_flag" ;; *) - if test "X$my_pic_p" != Xno; then - pic_flag_for_symtable=" $pic_flag" - fi + $my_pic_p && pic_flag_for_symtable=" $pic_flag" ;; esac ;; @@ -3497,10 +4850,10 @@ static const void *lt_preloaded_setup() { func_show_eval '(cd $output_objdir && $LTCC$symtab_cflags -c$no_builtin_flag$pic_flag_for_symtable "$my_dlsyms")' 'exit $?' # Clean up the generated files. - func_show_eval '$RM "$output_objdir/$my_dlsyms" "$nlist" "${nlist}S" "${nlist}T"' + func_show_eval '$RM "$output_objdir/$my_dlsyms" "$nlist" "${nlist}S" "${nlist}T" "${nlist}I"' # Transform the symbol file into the correct name. - symfileobj="$output_objdir/${my_outputname}S.$objext" + symfileobj=$output_objdir/${my_outputname}S.$objext case $host in *cygwin* | *mingw* | *cegcc* ) if test -f "$output_objdir/$my_outputname.def"; then @@ -3518,7 +4871,7 @@ static const void *lt_preloaded_setup() { esac ;; *) - func_fatal_error "unknown suffix for \`$my_dlsyms'" + func_fatal_error "unknown suffix for '$my_dlsyms'" ;; esac else @@ -3532,6 +4885,32 @@ static const void *lt_preloaded_setup() { fi } +# func_cygming_gnu_implib_p ARG +# This predicate returns with zero status (TRUE) if +# ARG is a GNU/binutils-style import library. Returns +# with nonzero status (FALSE) otherwise. +func_cygming_gnu_implib_p () +{ + $debug_cmd + + func_to_tool_file "$1" func_convert_file_msys_to_w32 + func_cygming_gnu_implib_tmp=`$NM "$func_to_tool_file_result" | eval "$global_symbol_pipe" | $EGREP ' (_head_[A-Za-z0-9_]+_[ad]l*|[A-Za-z0-9_]+_[ad]l*_iname)$'` + test -n "$func_cygming_gnu_implib_tmp" +} + +# func_cygming_ms_implib_p ARG +# This predicate returns with zero status (TRUE) if +# ARG is an MS-style import library. Returns +# with nonzero status (FALSE) otherwise. +func_cygming_ms_implib_p () +{ + $debug_cmd + + func_to_tool_file "$1" func_convert_file_msys_to_w32 + func_cygming_ms_implib_tmp=`$NM "$func_to_tool_file_result" | eval "$global_symbol_pipe" | $GREP '_NULL_IMPORT_DESCRIPTOR'` + test -n "$func_cygming_ms_implib_tmp" +} + # func_win32_libid arg # return the library type of file 'arg' # @@ -3541,8 +4920,9 @@ static const void *lt_preloaded_setup() { # Despite the name, also deal with 64 bit binaries. func_win32_libid () { - $opt_debug - win32_libid_type="unknown" + $debug_cmd + + win32_libid_type=unknown win32_fileres=`file -L $1 2>/dev/null` case $win32_fileres in *ar\ archive\ import\ library*) # definitely import @@ -3552,16 +4932,29 @@ func_win32_libid () # Keep the egrep pattern in sync with the one in _LT_CHECK_MAGIC_METHOD. if eval $OBJDUMP -f $1 | $SED -e '10q' 2>/dev/null | $EGREP 'file format (pei*-i386(.*architecture: i386)?|pe-arm-wince|pe-x86-64)' >/dev/null; then - func_to_tool_file "$1" func_convert_file_msys_to_w32 - win32_nmres=`eval $NM -f posix -A \"$func_to_tool_file_result\" | - $SED -n -e ' + case $nm_interface in + "MS dumpbin") + if func_cygming_ms_implib_p "$1" || + func_cygming_gnu_implib_p "$1" + then + win32_nmres=import + else + win32_nmres= + fi + ;; + *) + func_to_tool_file "$1" func_convert_file_msys_to_w32 + win32_nmres=`eval $NM -f posix -A \"$func_to_tool_file_result\" | + $SED -n -e ' 1,100{ / I /{ - s,.*,import, + s|.*|import| p q } }'` + ;; + esac case $win32_nmres in import*) win32_libid_type="x86 archive import";; *) win32_libid_type="x86 archive static";; @@ -3593,7 +4986,8 @@ func_win32_libid () # $sharedlib_from_linklib_result func_cygming_dll_for_implib () { - $opt_debug + $debug_cmd + sharedlib_from_linklib_result=`$DLLTOOL --identify-strict --identify "$1"` } @@ -3610,7 +5004,8 @@ func_cygming_dll_for_implib () # specified import library. func_cygming_dll_for_implib_fallback_core () { - $opt_debug + $debug_cmd + match_literal=`$ECHO "$1" | $SED "$sed_make_literal_regex"` $OBJDUMP -s --section "$1" "$2" 2>/dev/null | $SED '/^Contents of section '"$match_literal"':/{ @@ -3646,8 +5041,8 @@ func_cygming_dll_for_implib_fallback_core () /./p' | # we now have a list, one entry per line, of the stringified # contents of the appropriate section of all members of the - # archive which possess that section. Heuristic: eliminate - # all those which have a first or second character that is + # archive that possess that section. Heuristic: eliminate + # all those that have a first or second character that is # a '.' (that is, objdump's representation of an unprintable # character.) This should work for all archives with less than # 0x302f exports -- but will fail for DLLs whose name actually @@ -3658,30 +5053,6 @@ func_cygming_dll_for_implib_fallback_core () $SED -e '/^\./d;/^.\./d;q' } -# func_cygming_gnu_implib_p ARG -# This predicate returns with zero status (TRUE) if -# ARG is a GNU/binutils-style import library. Returns -# with nonzero status (FALSE) otherwise. -func_cygming_gnu_implib_p () -{ - $opt_debug - func_to_tool_file "$1" func_convert_file_msys_to_w32 - func_cygming_gnu_implib_tmp=`$NM "$func_to_tool_file_result" | eval "$global_symbol_pipe" | $EGREP ' (_head_[A-Za-z0-9_]+_[ad]l*|[A-Za-z0-9_]+_[ad]l*_iname)$'` - test -n "$func_cygming_gnu_implib_tmp" -} - -# func_cygming_ms_implib_p ARG -# This predicate returns with zero status (TRUE) if -# ARG is an MS-style import library. Returns -# with nonzero status (FALSE) otherwise. -func_cygming_ms_implib_p () -{ - $opt_debug - func_to_tool_file "$1" func_convert_file_msys_to_w32 - func_cygming_ms_implib_tmp=`$NM "$func_to_tool_file_result" | eval "$global_symbol_pipe" | $GREP '_NULL_IMPORT_DESCRIPTOR'` - test -n "$func_cygming_ms_implib_tmp" -} - # func_cygming_dll_for_implib_fallback ARG # Platform-specific function to extract the # name of the DLL associated with the specified @@ -3695,16 +5066,17 @@ func_cygming_ms_implib_p () # $sharedlib_from_linklib_result func_cygming_dll_for_implib_fallback () { - $opt_debug - if func_cygming_gnu_implib_p "$1" ; then + $debug_cmd + + if func_cygming_gnu_implib_p "$1"; then # binutils import library sharedlib_from_linklib_result=`func_cygming_dll_for_implib_fallback_core '.idata$7' "$1"` - elif func_cygming_ms_implib_p "$1" ; then + elif func_cygming_ms_implib_p "$1"; then # ms-generated import library sharedlib_from_linklib_result=`func_cygming_dll_for_implib_fallback_core '.idata$6' "$1"` else # unknown - sharedlib_from_linklib_result="" + sharedlib_from_linklib_result= fi } @@ -3712,10 +5084,11 @@ func_cygming_dll_for_implib_fallback () # func_extract_an_archive dir oldlib func_extract_an_archive () { - $opt_debug - f_ex_an_ar_dir="$1"; shift - f_ex_an_ar_oldlib="$1" - if test "$lock_old_archive_extraction" = yes; then + $debug_cmd + + f_ex_an_ar_dir=$1; shift + f_ex_an_ar_oldlib=$1 + if test yes = "$lock_old_archive_extraction"; then lockfile=$f_ex_an_ar_oldlib.lock until $opt_dry_run || ln "$progpath" "$lockfile" 2>/dev/null; do func_echo "Waiting for $lockfile to be removed" @@ -3724,7 +5097,7 @@ func_extract_an_archive () fi func_show_eval "(cd \$f_ex_an_ar_dir && $AR x \"\$f_ex_an_ar_oldlib\")" \ 'stat=$?; rm -f "$lockfile"; exit $stat' - if test "$lock_old_archive_extraction" = yes; then + if test yes = "$lock_old_archive_extraction"; then $opt_dry_run || rm -f "$lockfile" fi if ($AR t "$f_ex_an_ar_oldlib" | sort | sort -uc >/dev/null 2>&1); then @@ -3738,22 +5111,23 @@ func_extract_an_archive () # func_extract_archives gentop oldlib ... func_extract_archives () { - $opt_debug - my_gentop="$1"; shift + $debug_cmd + + my_gentop=$1; shift my_oldlibs=${1+"$@"} - my_oldobjs="" - my_xlib="" - my_xabs="" - my_xdir="" + my_oldobjs= + my_xlib= + my_xabs= + my_xdir= for my_xlib in $my_oldlibs; do # Extract the objects. case $my_xlib in - [\\/]* | [A-Za-z]:[\\/]*) my_xabs="$my_xlib" ;; + [\\/]* | [A-Za-z]:[\\/]*) my_xabs=$my_xlib ;; *) my_xabs=`pwd`"/$my_xlib" ;; esac func_basename "$my_xlib" - my_xlib="$func_basename_result" + my_xlib=$func_basename_result my_xlib_u=$my_xlib while :; do case " $extracted_archives " in @@ -3765,7 +5139,7 @@ func_extract_archives () esac done extracted_archives="$extracted_archives $my_xlib_u" - my_xdir="$my_gentop/$my_xlib_u" + my_xdir=$my_gentop/$my_xlib_u func_mkdir_p "$my_xdir" @@ -3778,22 +5152,23 @@ func_extract_archives () cd $my_xdir || exit $? darwin_archive=$my_xabs darwin_curdir=`pwd` - darwin_base_archive=`basename "$darwin_archive"` + func_basename "$darwin_archive" + darwin_base_archive=$func_basename_result darwin_arches=`$LIPO -info "$darwin_archive" 2>/dev/null | $GREP Architectures 2>/dev/null || true` if test -n "$darwin_arches"; then darwin_arches=`$ECHO "$darwin_arches" | $SED -e 's/.*are://'` darwin_arch= func_verbose "$darwin_base_archive has multiple architectures $darwin_arches" - for darwin_arch in $darwin_arches ; do - func_mkdir_p "unfat-$$/${darwin_base_archive}-${darwin_arch}" - $LIPO -thin $darwin_arch -output "unfat-$$/${darwin_base_archive}-${darwin_arch}/${darwin_base_archive}" "${darwin_archive}" - cd "unfat-$$/${darwin_base_archive}-${darwin_arch}" - func_extract_an_archive "`pwd`" "${darwin_base_archive}" + for darwin_arch in $darwin_arches; do + func_mkdir_p "unfat-$$/$darwin_base_archive-$darwin_arch" + $LIPO -thin $darwin_arch -output "unfat-$$/$darwin_base_archive-$darwin_arch/$darwin_base_archive" "$darwin_archive" + cd "unfat-$$/$darwin_base_archive-$darwin_arch" + func_extract_an_archive "`pwd`" "$darwin_base_archive" cd "$darwin_curdir" - $RM "unfat-$$/${darwin_base_archive}-${darwin_arch}/${darwin_base_archive}" + $RM "unfat-$$/$darwin_base_archive-$darwin_arch/$darwin_base_archive" done # $darwin_arches ## Okay now we've a bunch of thin objects, gotta fatten them up :) - darwin_filelist=`find unfat-$$ -type f -name \*.o -print -o -name \*.lo -print | $SED -e "$basename" | sort -u` + darwin_filelist=`find unfat-$$ -type f -name \*.o -print -o -name \*.lo -print | $SED -e "$sed_basename" | sort -u` darwin_file= darwin_files= for darwin_file in $darwin_filelist; do @@ -3815,7 +5190,7 @@ func_extract_archives () my_oldobjs="$my_oldobjs "`find $my_xdir -name \*.$objext -print -o -name \*.lo -print | sort | $NL2SP` done - func_extract_archives_result="$my_oldobjs" + func_extract_archives_result=$my_oldobjs } @@ -3830,7 +5205,7 @@ func_extract_archives () # # ARG is the value that the WRAPPER_SCRIPT_BELONGS_IN_OBJDIR # variable will take. If 'yes', then the emitted script -# will assume that the directory in which it is stored is +# will assume that the directory where it is stored is # the $objdir directory. This is a cygwin/mingw-specific # behavior. func_emit_wrapper () @@ -3841,7 +5216,7 @@ func_emit_wrapper () #! $SHELL # $output - temporary wrapper script for $objdir/$outputname -# Generated by $PROGRAM (GNU $PACKAGE$TIMESTAMP) $VERSION +# Generated by $PROGRAM (GNU $PACKAGE) $VERSION # # The $output program cannot be directly executed until all the libtool # libraries that it depends on are installed. @@ -3898,9 +5273,9 @@ _LTECHO_EOF' # Very basic option parsing. These options are (a) specific to # the libtool wrapper, (b) are identical between the wrapper -# /script/ and the wrapper /executable/ which is used only on +# /script/ and the wrapper /executable/ that is used only on # windows platforms, and (c) all begin with the string "--lt-" -# (application programs are unlikely to have options which match +# (application programs are unlikely to have options that match # this pattern). # # There are only two supported options: --lt-debug and @@ -3933,7 +5308,7 @@ func_parse_lt_options () # Print the debug banner immediately: if test -n \"\$lt_option_debug\"; then - echo \"${outputname}:${output}:\${LINENO}: libtool wrapper (GNU $PACKAGE$TIMESTAMP) $VERSION\" 1>&2 + echo \"$outputname:$output:\$LINENO: libtool wrapper (GNU $PACKAGE) $VERSION\" 1>&2 fi } @@ -3944,7 +5319,7 @@ func_lt_dump_args () lt_dump_args_N=1; for lt_arg do - \$ECHO \"${outputname}:${output}:\${LINENO}: newargv[\$lt_dump_args_N]: \$lt_arg\" + \$ECHO \"$outputname:$output:\$LINENO: newargv[\$lt_dump_args_N]: \$lt_arg\" lt_dump_args_N=\`expr \$lt_dump_args_N + 1\` done } @@ -3958,7 +5333,7 @@ func_exec_program_core () *-*-mingw | *-*-os2* | *-cegcc*) $ECHO "\ if test -n \"\$lt_option_debug\"; then - \$ECHO \"${outputname}:${output}:\${LINENO}: newargv[0]: \$progdir\\\\\$program\" 1>&2 + \$ECHO \"$outputname:$output:\$LINENO: newargv[0]: \$progdir\\\\\$program\" 1>&2 func_lt_dump_args \${1+\"\$@\"} 1>&2 fi exec \"\$progdir\\\\\$program\" \${1+\"\$@\"} @@ -3968,7 +5343,7 @@ func_exec_program_core () *) $ECHO "\ if test -n \"\$lt_option_debug\"; then - \$ECHO \"${outputname}:${output}:\${LINENO}: newargv[0]: \$progdir/\$program\" 1>&2 + \$ECHO \"$outputname:$output:\$LINENO: newargv[0]: \$progdir/\$program\" 1>&2 func_lt_dump_args \${1+\"\$@\"} 1>&2 fi exec \"\$progdir/\$program\" \${1+\"\$@\"} @@ -4043,13 +5418,13 @@ func_exec_program () test -n \"\$absdir\" && thisdir=\"\$absdir\" " - if test "$fast_install" = yes; then + if test yes = "$fast_install"; then $ECHO "\ program=lt-'$outputname'$exeext progdir=\"\$thisdir/$objdir\" if test ! -f \"\$progdir/\$program\" || - { file=\`ls -1dt \"\$progdir/\$program\" \"\$progdir/../\$program\" 2>/dev/null | ${SED} 1q\`; \\ + { file=\`ls -1dt \"\$progdir/\$program\" \"\$progdir/../\$program\" 2>/dev/null | $SED 1q\`; \\ test \"X\$file\" != \"X\$progdir/\$program\"; }; then file=\"\$\$-\$program\" @@ -4066,7 +5441,7 @@ func_exec_program () if test -n \"\$relink_command\"; then if relink_command_output=\`eval \$relink_command 2>&1\`; then : else - $ECHO \"\$relink_command_output\" >&2 + \$ECHO \"\$relink_command_output\" >&2 $RM \"\$progdir/\$file\" exit 1 fi @@ -4101,7 +5476,7 @@ func_exec_program () fi # Export our shlibpath_var if we have one. - if test "$shlibpath_overrides_runpath" = yes && test -n "$shlibpath_var" && test -n "$temp_rpath"; then + if test yes = "$shlibpath_overrides_runpath" && test -n "$shlibpath_var" && test -n "$temp_rpath"; then $ECHO "\ # Add our own library path to $shlibpath_var $shlibpath_var=\"$temp_rpath\$$shlibpath_var\" @@ -4121,7 +5496,7 @@ func_exec_program () fi else # The program doesn't exist. - \$ECHO \"\$0: error: \\\`\$progdir/\$program' does not exist\" 1>&2 + \$ECHO \"\$0: error: '\$progdir/\$program' does not exist\" 1>&2 \$ECHO \"This script is just a wrapper for \$program.\" 1>&2 \$ECHO \"See the $PACKAGE documentation for more information.\" 1>&2 exit 1 @@ -4140,7 +5515,7 @@ func_emit_cwrapperexe_src () cat < #include +#define STREQ(s1, s2) (strcmp ((s1), (s2)) == 0) + /* declarations of non-ANSI functions */ -#if defined(__MINGW32__) +#if defined __MINGW32__ # ifdef __STRICT_ANSI__ int _putenv (const char *); # endif -#elif defined(__CYGWIN__) +#elif defined __CYGWIN__ # ifdef __STRICT_ANSI__ char *realpath (const char *, char *); int putenv (char *); int setenv (const char *, const char *, int); # endif -/* #elif defined (other platforms) ... */ +/* #elif defined other_platform || defined ... */ #endif /* portability defines, excluding path handling macros */ -#if defined(_MSC_VER) +#if defined _MSC_VER # define setmode _setmode # define stat _stat # define chmod _chmod # define getcwd _getcwd # define putenv _putenv # define S_IXUSR _S_IEXEC -# ifndef _INTPTR_T_DEFINED -# define _INTPTR_T_DEFINED -# define intptr_t int -# endif -#elif defined(__MINGW32__) +#elif defined __MINGW32__ # define setmode _setmode # define stat _stat # define chmod _chmod # define getcwd _getcwd # define putenv _putenv -#elif defined(__CYGWIN__) +#elif defined __CYGWIN__ # define HAVE_SETENV # define FOPEN_WB "wb" -/* #elif defined (other platforms) ... */ +/* #elif defined other platforms ... */ #endif -#if defined(PATH_MAX) +#if defined PATH_MAX # define LT_PATHMAX PATH_MAX -#elif defined(MAXPATHLEN) +#elif defined MAXPATHLEN # define LT_PATHMAX MAXPATHLEN #else # define LT_PATHMAX 1024 @@ -4234,8 +5607,8 @@ int setenv (const char *, const char *, int); # define PATH_SEPARATOR ':' #endif -#if defined (_WIN32) || defined (__MSDOS__) || defined (__DJGPP__) || \ - defined (__OS2__) +#if defined _WIN32 || defined __MSDOS__ || defined __DJGPP__ || \ + defined __OS2__ # define HAVE_DOS_BASED_FILE_SYSTEM # define FOPEN_WB "wb" # ifndef DIR_SEPARATOR_2 @@ -4268,10 +5641,10 @@ int setenv (const char *, const char *, int); #define XMALLOC(type, num) ((type *) xmalloc ((num) * sizeof(type))) #define XFREE(stale) do { \ - if (stale) { free ((void *) stale); stale = 0; } \ + if (stale) { free (stale); stale = 0; } \ } while (0) -#if defined(LT_DEBUGWRAPPER) +#if defined LT_DEBUGWRAPPER static int lt_debug = 1; #else static int lt_debug = 0; @@ -4300,11 +5673,16 @@ void lt_dump_script (FILE *f); EOF cat < 0) && IS_PATH_SEPARATOR (new_value[len-1])) + size_t len = strlen (new_value); + while ((len > 0) && IS_PATH_SEPARATOR (new_value[len-1])) { - new_value[len-1] = '\0'; + new_value[--len] = '\0'; } lt_setenv (name, new_value); XFREE (new_value); @@ -5082,27 +6460,47 @@ EOF # True if ARG is an import lib, as indicated by $file_magic_cmd func_win32_import_lib_p () { - $opt_debug + $debug_cmd + case `eval $file_magic_cmd \"\$1\" 2>/dev/null | $SED -e 10q` in *import*) : ;; *) false ;; esac } +# func_suncc_cstd_abi +# !!ONLY CALL THIS FOR SUN CC AFTER $compile_command IS FULLY EXPANDED!! +# Several compiler flags select an ABI that is incompatible with the +# Cstd library. Avoid specifying it if any are in CXXFLAGS. +func_suncc_cstd_abi () +{ + $debug_cmd + + case " $compile_command " in + *" -compat=g "*|*\ -std=c++[0-9][0-9]\ *|*" -library=stdcxx4 "*|*" -library=stlport4 "*) + suncc_use_cstd_abi=no + ;; + *) + suncc_use_cstd_abi=yes + ;; + esac +} + # func_mode_link arg... func_mode_link () { - $opt_debug + $debug_cmd + case $host in *-*-cygwin* | *-*-mingw* | *-*-pw32* | *-*-os2* | *-cegcc*) # It is impossible to link a dll without this setting, and # we shouldn't force the makefile maintainer to figure out - # which system we are compiling for in order to pass an extra + # what system we are compiling for in order to pass an extra # flag for every libtool invocation. # allow_undefined=no # FIXME: Unfortunately, there are problems with the above when trying - # to make a dll which has undefined symbols, in which case not + # to make a dll that has undefined symbols, in which case not # even a static library is built. For now, we need to specify # -no-undefined on the libtool link line when we can be certain # that all symbols are satisfied, otherwise we get a static library. @@ -5146,10 +6544,11 @@ func_mode_link () module=no no_install=no objs= + os2dllname= non_pic_objects= precious_files_regex= prefer_static_libs=no - preload=no + preload=false prev= prevarg= release= @@ -5161,7 +6560,7 @@ func_mode_link () vinfo= vinfo_number=no weak_libs= - single_module="${wl}-single_module" + single_module=$wl-single_module func_infer_tag $base_compile # We need to know -static, to get the right output filenames. @@ -5169,15 +6568,15 @@ func_mode_link () do case $arg in -shared) - test "$build_libtool_libs" != yes && \ - func_fatal_configuration "can not build a shared library" + test yes != "$build_libtool_libs" \ + && func_fatal_configuration "cannot build a shared library" build_old_libs=no break ;; -all-static | -static | -static-libtool-libs) case $arg in -all-static) - if test "$build_libtool_libs" = yes && test -z "$link_static_flag"; then + if test yes = "$build_libtool_libs" && test -z "$link_static_flag"; then func_warning "complete static linking is impossible in this configuration" fi if test -n "$link_static_flag"; then @@ -5210,7 +6609,7 @@ func_mode_link () # Go through the arguments, transforming them on the way. while test "$#" -gt 0; do - arg="$1" + arg=$1 shift func_quote_for_eval "$arg" qarg=$func_quote_for_eval_unquoted_result @@ -5227,21 +6626,21 @@ func_mode_link () case $prev in bindir) - bindir="$arg" + bindir=$arg prev= continue ;; dlfiles|dlprefiles) - if test "$preload" = no; then + $preload || { # Add the symbol object into the linking commands. func_append compile_command " @SYMFILE@" func_append finalize_command " @SYMFILE@" - preload=yes - fi + preload=: + } case $arg in *.la | *.lo) ;; # We handle these cases below. force) - if test "$dlself" = no; then + if test no = "$dlself"; then dlself=needless export_dynamic=yes fi @@ -5249,9 +6648,9 @@ func_mode_link () continue ;; self) - if test "$prev" = dlprefiles; then + if test dlprefiles = "$prev"; then dlself=yes - elif test "$prev" = dlfiles && test "$dlopen_self" != yes; then + elif test dlfiles = "$prev" && test yes != "$dlopen_self"; then dlself=yes else dlself=needless @@ -5261,7 +6660,7 @@ func_mode_link () continue ;; *) - if test "$prev" = dlfiles; then + if test dlfiles = "$prev"; then func_append dlfiles " $arg" else func_append dlprefiles " $arg" @@ -5272,14 +6671,14 @@ func_mode_link () esac ;; expsyms) - export_symbols="$arg" + export_symbols=$arg test -f "$arg" \ - || func_fatal_error "symbol file \`$arg' does not exist" + || func_fatal_error "symbol file '$arg' does not exist" prev= continue ;; expsyms_regex) - export_symbols_regex="$arg" + export_symbols_regex=$arg prev= continue ;; @@ -5297,7 +6696,13 @@ func_mode_link () continue ;; inst_prefix) - inst_prefix_dir="$arg" + inst_prefix_dir=$arg + prev= + continue + ;; + mllvm) + # Clang does not use LLVM to link, so we can simply discard any + # '-mllvm $arg' options when doing the link step. prev= continue ;; @@ -5321,21 +6726,21 @@ func_mode_link () if test -z "$pic_object" || test -z "$non_pic_object" || - test "$pic_object" = none && - test "$non_pic_object" = none; then - func_fatal_error "cannot find name of object for \`$arg'" + test none = "$pic_object" && + test none = "$non_pic_object"; then + func_fatal_error "cannot find name of object for '$arg'" fi # Extract subdirectory from the argument. func_dirname "$arg" "/" "" - xdir="$func_dirname_result" + xdir=$func_dirname_result - if test "$pic_object" != none; then + if test none != "$pic_object"; then # Prepend the subdirectory the object is found in. - pic_object="$xdir$pic_object" + pic_object=$xdir$pic_object - if test "$prev" = dlfiles; then - if test "$build_libtool_libs" = yes && test "$dlopen_support" = yes; then + if test dlfiles = "$prev"; then + if test yes = "$build_libtool_libs" && test yes = "$dlopen_support"; then func_append dlfiles " $pic_object" prev= continue @@ -5346,7 +6751,7 @@ func_mode_link () fi # CHECK ME: I think I busted this. -Ossama - if test "$prev" = dlprefiles; then + if test dlprefiles = "$prev"; then # Preload the old-style object. func_append dlprefiles " $pic_object" prev= @@ -5354,23 +6759,23 @@ func_mode_link () # A PIC object. func_append libobjs " $pic_object" - arg="$pic_object" + arg=$pic_object fi # Non-PIC object. - if test "$non_pic_object" != none; then + if test none != "$non_pic_object"; then # Prepend the subdirectory the object is found in. - non_pic_object="$xdir$non_pic_object" + non_pic_object=$xdir$non_pic_object # A standard non-PIC object func_append non_pic_objects " $non_pic_object" - if test -z "$pic_object" || test "$pic_object" = none ; then - arg="$non_pic_object" + if test -z "$pic_object" || test none = "$pic_object"; then + arg=$non_pic_object fi else # If the PIC object exists, use it instead. # $xdir was prepended to $pic_object above. - non_pic_object="$pic_object" + non_pic_object=$pic_object func_append non_pic_objects " $non_pic_object" fi else @@ -5378,7 +6783,7 @@ func_mode_link () if $opt_dry_run; then # Extract subdirectory from the argument. func_dirname "$arg" "/" "" - xdir="$func_dirname_result" + xdir=$func_dirname_result func_lo2o "$arg" pic_object=$xdir$objdir/$func_lo2o_result @@ -5386,24 +6791,29 @@ func_mode_link () func_append libobjs " $pic_object" func_append non_pic_objects " $non_pic_object" else - func_fatal_error "\`$arg' is not a valid libtool object" + func_fatal_error "'$arg' is not a valid libtool object" fi fi done else - func_fatal_error "link input file \`$arg' does not exist" + func_fatal_error "link input file '$arg' does not exist" fi arg=$save_arg prev= continue ;; + os2dllname) + os2dllname=$arg + prev= + continue + ;; precious_regex) - precious_files_regex="$arg" + precious_files_regex=$arg prev= continue ;; release) - release="-$arg" + release=-$arg prev= continue ;; @@ -5415,7 +6825,7 @@ func_mode_link () func_fatal_error "only absolute run-paths are allowed" ;; esac - if test "$prev" = rpath; then + if test rpath = "$prev"; then case "$rpath " in *" $arg "*) ;; *) func_append rpath " $arg" ;; @@ -5430,7 +6840,7 @@ func_mode_link () continue ;; shrext) - shrext_cmds="$arg" + shrext_cmds=$arg prev= continue ;; @@ -5470,7 +6880,7 @@ func_mode_link () esac fi # test -n "$prev" - prevarg="$arg" + prevarg=$arg case $arg in -all-static) @@ -5484,7 +6894,7 @@ func_mode_link () -allow-undefined) # FIXME: remove this flag sometime in the future. - func_fatal_error "\`-allow-undefined' must not be used because it is the default" + func_fatal_error "'-allow-undefined' must not be used because it is the default" ;; -avoid-version) @@ -5516,7 +6926,7 @@ func_mode_link () if test -n "$export_symbols" || test -n "$export_symbols_regex"; then func_fatal_error "more than one -exported-symbols argument is not allowed" fi - if test "X$arg" = "X-export-symbols"; then + if test X-export-symbols = "X$arg"; then prev=expsyms else prev=expsyms_regex @@ -5550,9 +6960,9 @@ func_mode_link () func_stripname "-L" '' "$arg" if test -z "$func_stripname_result"; then if test "$#" -gt 0; then - func_fatal_error "require no space between \`-L' and \`$1'" + func_fatal_error "require no space between '-L' and '$1'" else - func_fatal_error "need path for \`-L' option" + func_fatal_error "need path for '-L' option" fi fi func_resolve_sysroot "$func_stripname_result" @@ -5563,8 +6973,8 @@ func_mode_link () *) absdir=`cd "$dir" && pwd` test -z "$absdir" && \ - func_fatal_error "cannot determine absolute directory name of \`$dir'" - dir="$absdir" + func_fatal_error "cannot determine absolute directory name of '$dir'" + dir=$absdir ;; esac case "$deplibs " in @@ -5599,7 +7009,7 @@ func_mode_link () ;; -l*) - if test "X$arg" = "X-lc" || test "X$arg" = "X-lm"; then + if test X-lc = "X$arg" || test X-lm = "X$arg"; then case $host in *-*-cygwin* | *-*-mingw* | *-*-pw32* | *-*-beos* | *-cegcc* | *-*-haiku*) # These systems don't actually have a C or math library (as such) @@ -5607,11 +7017,11 @@ func_mode_link () ;; *-*-os2*) # These systems don't actually have a C library (as such) - test "X$arg" = "X-lc" && continue + test X-lc = "X$arg" && continue ;; - *-*-openbsd* | *-*-freebsd* | *-*-dragonfly*) + *-*-openbsd* | *-*-freebsd* | *-*-dragonfly* | *-*-bitrig*) # Do not include libc due to us having libc/libc_r. - test "X$arg" = "X-lc" && continue + test X-lc = "X$arg" && continue ;; *-*-rhapsody* | *-*-darwin1.[012]) # Rhapsody C and math libraries are in the System framework @@ -5620,16 +7030,16 @@ func_mode_link () ;; *-*-sco3.2v5* | *-*-sco5v6*) # Causes problems with __ctype - test "X$arg" = "X-lc" && continue + test X-lc = "X$arg" && continue ;; *-*-sysv4.2uw2* | *-*-sysv5* | *-*-unixware* | *-*-OpenUNIX*) # Compiler inserts libc in the correct place for threads to work - test "X$arg" = "X-lc" && continue + test X-lc = "X$arg" && continue ;; esac - elif test "X$arg" = "X-lc_r"; then + elif test X-lc_r = "X$arg"; then case $host in - *-*-openbsd* | *-*-freebsd* | *-*-dragonfly*) + *-*-openbsd* | *-*-freebsd* | *-*-dragonfly* | *-*-bitrig*) # Do not include libc_r directly, use -pthread flag. continue ;; @@ -5639,6 +7049,11 @@ func_mode_link () continue ;; + -mllvm) + prev=mllvm + continue + ;; + -module) module=yes continue @@ -5668,7 +7083,7 @@ func_mode_link () ;; -multi_module) - single_module="${wl}-multi_module" + single_module=$wl-multi_module continue ;; @@ -5682,8 +7097,8 @@ func_mode_link () *-*-cygwin* | *-*-mingw* | *-*-pw32* | *-*-os2* | *-*-darwin* | *-cegcc*) # The PATH hackery in wrapper scripts is required on Windows # and Darwin in order for the loader to find any dlls it needs. - func_warning "\`-no-install' is ignored for $host" - func_warning "assuming \`-no-fast-install' instead" + func_warning "'-no-install' is ignored for $host" + func_warning "assuming '-no-fast-install' instead" fast_install=no ;; *) no_install=yes ;; @@ -5701,6 +7116,11 @@ func_mode_link () continue ;; + -os2dllname) + prev=os2dllname + continue + ;; + -o) prev=output ;; -precious-files-regex) @@ -5788,14 +7208,14 @@ func_mode_link () func_stripname '-Wc,' '' "$arg" args=$func_stripname_result arg= - save_ifs="$IFS"; IFS=',' + save_ifs=$IFS; IFS=, for flag in $args; do - IFS="$save_ifs" + IFS=$save_ifs func_quote_for_eval "$flag" func_append arg " $func_quote_for_eval_result" func_append compiler_flags " $func_quote_for_eval_result" done - IFS="$save_ifs" + IFS=$save_ifs func_stripname ' ' '' "$arg" arg=$func_stripname_result ;; @@ -5804,15 +7224,15 @@ func_mode_link () func_stripname '-Wl,' '' "$arg" args=$func_stripname_result arg= - save_ifs="$IFS"; IFS=',' + save_ifs=$IFS; IFS=, for flag in $args; do - IFS="$save_ifs" + IFS=$save_ifs func_quote_for_eval "$flag" func_append arg " $wl$func_quote_for_eval_result" func_append compiler_flags " $wl$func_quote_for_eval_result" func_append linker_flags " $func_quote_for_eval_result" done - IFS="$save_ifs" + IFS=$save_ifs func_stripname ' ' '' "$arg" arg=$func_stripname_result ;; @@ -5835,7 +7255,7 @@ func_mode_link () # -msg_* for osf cc -msg_*) func_quote_for_eval "$arg" - arg="$func_quote_for_eval_result" + arg=$func_quote_for_eval_result ;; # Flags to be passed through unchanged, with rationale: @@ -5847,25 +7267,46 @@ func_mode_link () # -m*, -t[45]*, -txscale* architecture-specific flags for GCC # -F/path path to uninstalled frameworks, gcc on darwin # -p, -pg, --coverage, -fprofile-* profiling flags for GCC + # -fstack-protector* stack protector flags for GCC # @file GCC response files # -tp=* Portland pgcc target processor selection # --sysroot=* for sysroot support - # -O*, -flto*, -fwhopr*, -fuse-linker-plugin GCC link-time optimization + # -O*, -g*, -flto*, -fwhopr*, -fuse-linker-plugin GCC link-time optimization + # -stdlib=* select c++ std lib with clang -64|-mips[0-9]|-r[0-9][0-9]*|-xarch=*|-xtarget=*|+DA*|+DD*|-q*|-m*| \ -t[45]*|-txscale*|-p|-pg|--coverage|-fprofile-*|-F*|@*|-tp=*|--sysroot=*| \ - -O*|-flto*|-fwhopr*|-fuse-linker-plugin) + -O*|-g*|-flto*|-fwhopr*|-fuse-linker-plugin|-fstack-protector*|-stdlib=*) func_quote_for_eval "$arg" - arg="$func_quote_for_eval_result" + arg=$func_quote_for_eval_result func_append compile_command " $arg" func_append finalize_command " $arg" func_append compiler_flags " $arg" continue ;; + -Z*) + if test os2 = "`expr $host : '.*\(os2\)'`"; then + # OS/2 uses -Zxxx to specify OS/2-specific options + compiler_flags="$compiler_flags $arg" + func_append compile_command " $arg" + func_append finalize_command " $arg" + case $arg in + -Zlinker | -Zstack) + prev=xcompiler + ;; + esac + continue + else + # Otherwise treat like 'Some other compiler flag' below + func_quote_for_eval "$arg" + arg=$func_quote_for_eval_result + fi + ;; + # Some other compiler flag. -* | +*) func_quote_for_eval "$arg" - arg="$func_quote_for_eval_result" + arg=$func_quote_for_eval_result ;; *.$objext) @@ -5886,21 +7327,21 @@ func_mode_link () if test -z "$pic_object" || test -z "$non_pic_object" || - test "$pic_object" = none && - test "$non_pic_object" = none; then - func_fatal_error "cannot find name of object for \`$arg'" + test none = "$pic_object" && + test none = "$non_pic_object"; then + func_fatal_error "cannot find name of object for '$arg'" fi # Extract subdirectory from the argument. func_dirname "$arg" "/" "" - xdir="$func_dirname_result" + xdir=$func_dirname_result - if test "$pic_object" != none; then + test none = "$pic_object" || { # Prepend the subdirectory the object is found in. - pic_object="$xdir$pic_object" + pic_object=$xdir$pic_object - if test "$prev" = dlfiles; then - if test "$build_libtool_libs" = yes && test "$dlopen_support" = yes; then + if test dlfiles = "$prev"; then + if test yes = "$build_libtool_libs" && test yes = "$dlopen_support"; then func_append dlfiles " $pic_object" prev= continue @@ -5911,7 +7352,7 @@ func_mode_link () fi # CHECK ME: I think I busted this. -Ossama - if test "$prev" = dlprefiles; then + if test dlprefiles = "$prev"; then # Preload the old-style object. func_append dlprefiles " $pic_object" prev= @@ -5919,23 +7360,23 @@ func_mode_link () # A PIC object. func_append libobjs " $pic_object" - arg="$pic_object" - fi + arg=$pic_object + } # Non-PIC object. - if test "$non_pic_object" != none; then + if test none != "$non_pic_object"; then # Prepend the subdirectory the object is found in. - non_pic_object="$xdir$non_pic_object" + non_pic_object=$xdir$non_pic_object # A standard non-PIC object func_append non_pic_objects " $non_pic_object" - if test -z "$pic_object" || test "$pic_object" = none ; then - arg="$non_pic_object" + if test -z "$pic_object" || test none = "$pic_object"; then + arg=$non_pic_object fi else # If the PIC object exists, use it instead. # $xdir was prepended to $pic_object above. - non_pic_object="$pic_object" + non_pic_object=$pic_object func_append non_pic_objects " $non_pic_object" fi else @@ -5943,7 +7384,7 @@ func_mode_link () if $opt_dry_run; then # Extract subdirectory from the argument. func_dirname "$arg" "/" "" - xdir="$func_dirname_result" + xdir=$func_dirname_result func_lo2o "$arg" pic_object=$xdir$objdir/$func_lo2o_result @@ -5951,7 +7392,7 @@ func_mode_link () func_append libobjs " $pic_object" func_append non_pic_objects " $non_pic_object" else - func_fatal_error "\`$arg' is not a valid libtool object" + func_fatal_error "'$arg' is not a valid libtool object" fi fi ;; @@ -5967,11 +7408,11 @@ func_mode_link () # A libtool-controlled library. func_resolve_sysroot "$arg" - if test "$prev" = dlfiles; then + if test dlfiles = "$prev"; then # This library was specified with -dlopen. func_append dlfiles " $func_resolve_sysroot_result" prev= - elif test "$prev" = dlprefiles; then + elif test dlprefiles = "$prev"; then # The library was specified with -dlpreopen. func_append dlprefiles " $func_resolve_sysroot_result" prev= @@ -5986,7 +7427,7 @@ func_mode_link () # Unknown arguments in both finalize_command and compile_command need # to be aesthetically quoted because they are evaled later. func_quote_for_eval "$arg" - arg="$func_quote_for_eval_result" + arg=$func_quote_for_eval_result ;; esac # arg @@ -5998,9 +7439,9 @@ func_mode_link () done # argument parsing loop test -n "$prev" && \ - func_fatal_help "the \`$prevarg' option requires an argument" + func_fatal_help "the '$prevarg' option requires an argument" - if test "$export_dynamic" = yes && test -n "$export_dynamic_flag_spec"; then + if test yes = "$export_dynamic" && test -n "$export_dynamic_flag_spec"; then eval arg=\"$export_dynamic_flag_spec\" func_append compile_command " $arg" func_append finalize_command " $arg" @@ -6009,20 +7450,23 @@ func_mode_link () oldlibs= # calculate the name of the file, without its directory func_basename "$output" - outputname="$func_basename_result" - libobjs_save="$libobjs" + outputname=$func_basename_result + libobjs_save=$libobjs if test -n "$shlibpath_var"; then # get the directories listed in $shlibpath_var - eval shlib_search_path=\`\$ECHO \"\${$shlibpath_var}\" \| \$SED \'s/:/ /g\'\` + eval shlib_search_path=\`\$ECHO \"\$$shlibpath_var\" \| \$SED \'s/:/ /g\'\` else shlib_search_path= fi eval sys_lib_search_path=\"$sys_lib_search_path_spec\" eval sys_lib_dlsearch_path=\"$sys_lib_dlsearch_path_spec\" + # Definition is injected by LT_CONFIG during libtool generation. + func_munge_path_list sys_lib_dlsearch_path "$LT_SYS_LIBRARY_PATH" + func_dirname "$output" "/" "" - output_objdir="$func_dirname_result$objdir" + output_objdir=$func_dirname_result$objdir func_to_tool_file "$output_objdir/" tool_output_objdir=$func_to_tool_file_result # Create the object directory. @@ -6045,7 +7489,7 @@ func_mode_link () # Find all interdependent deplibs by searching for libraries # that are linked more than once (e.g. -la -lb -la) for deplib in $deplibs; do - if $opt_preserve_dup_deps ; then + if $opt_preserve_dup_deps; then case "$libs " in *" $deplib "*) func_append specialdeplibs " $deplib" ;; esac @@ -6053,7 +7497,7 @@ func_mode_link () func_append libs " $deplib" done - if test "$linkmode" = lib; then + if test lib = "$linkmode"; then libs="$predeps $libs $compiler_lib_search_path $postdeps" # Compute libraries that are listed more than once in $predeps @@ -6085,7 +7529,7 @@ func_mode_link () case $file in *.la) ;; *) - func_fatal_help "libraries can \`-dlopen' only libtool libraries: $file" + func_fatal_help "libraries can '-dlopen' only libtool libraries: $file" ;; esac done @@ -6093,7 +7537,7 @@ func_mode_link () prog) compile_deplibs= finalize_deplibs= - alldeplibs=no + alldeplibs=false newdlfiles= newdlprefiles= passes="conv scan dlopen dlpreopen link" @@ -6105,29 +7549,29 @@ func_mode_link () for pass in $passes; do # The preopen pass in lib mode reverses $deplibs; put it back here # so that -L comes before libs that need it for instance... - if test "$linkmode,$pass" = "lib,link"; then + if test lib,link = "$linkmode,$pass"; then ## FIXME: Find the place where the list is rebuilt in the wrong ## order, and fix it there properly tmp_deplibs= for deplib in $deplibs; do tmp_deplibs="$deplib $tmp_deplibs" done - deplibs="$tmp_deplibs" + deplibs=$tmp_deplibs fi - if test "$linkmode,$pass" = "lib,link" || - test "$linkmode,$pass" = "prog,scan"; then - libs="$deplibs" + if test lib,link = "$linkmode,$pass" || + test prog,scan = "$linkmode,$pass"; then + libs=$deplibs deplibs= fi - if test "$linkmode" = prog; then + if test prog = "$linkmode"; then case $pass in - dlopen) libs="$dlfiles" ;; - dlpreopen) libs="$dlprefiles" ;; + dlopen) libs=$dlfiles ;; + dlpreopen) libs=$dlprefiles ;; link) libs="$deplibs %DEPLIBS% $dependency_libs" ;; esac fi - if test "$linkmode,$pass" = "lib,dlpreopen"; then + if test lib,dlpreopen = "$linkmode,$pass"; then # Collect and forward deplibs of preopened libtool libs for lib in $dlprefiles; do # Ignore non-libtool-libs @@ -6148,26 +7592,26 @@ func_mode_link () esac done done - libs="$dlprefiles" + libs=$dlprefiles fi - if test "$pass" = dlopen; then + if test dlopen = "$pass"; then # Collect dlpreopened libraries - save_deplibs="$deplibs" + save_deplibs=$deplibs deplibs= fi for deplib in $libs; do lib= - found=no + found=false case $deplib in -mt|-mthreads|-kthread|-Kthread|-pthread|-pthreads|--thread-safe \ |-threads|-fopenmp|-openmp|-mp|-xopenmp|-omp|-qsmp=*) - if test "$linkmode,$pass" = "prog,link"; then + if test prog,link = "$linkmode,$pass"; then compile_deplibs="$deplib $compile_deplibs" finalize_deplibs="$deplib $finalize_deplibs" else func_append compiler_flags " $deplib" - if test "$linkmode" = lib ; then + if test lib = "$linkmode"; then case "$new_inherited_linker_flags " in *" $deplib "*) ;; * ) func_append new_inherited_linker_flags " $deplib" ;; @@ -6177,13 +7621,13 @@ func_mode_link () continue ;; -l*) - if test "$linkmode" != lib && test "$linkmode" != prog; then - func_warning "\`-l' is ignored for archives/objects" + if test lib != "$linkmode" && test prog != "$linkmode"; then + func_warning "'-l' is ignored for archives/objects" continue fi func_stripname '-l' '' "$deplib" name=$func_stripname_result - if test "$linkmode" = lib; then + if test lib = "$linkmode"; then searchdirs="$newlib_search_path $lib_search_path $compiler_lib_search_dirs $sys_lib_search_path $shlib_search_path" else searchdirs="$newlib_search_path $lib_search_path $sys_lib_search_path $shlib_search_path" @@ -6191,31 +7635,22 @@ func_mode_link () for searchdir in $searchdirs; do for search_ext in .la $std_shrext .so .a; do # Search the libtool library - lib="$searchdir/lib${name}${search_ext}" + lib=$searchdir/lib$name$search_ext if test -f "$lib"; then - if test "$search_ext" = ".la"; then - found=yes + if test .la = "$search_ext"; then + found=: else - found=no + found=false fi break 2 fi done done - if test "$found" != yes; then - # deplib doesn't seem to be a libtool library - if test "$linkmode,$pass" = "prog,link"; then - compile_deplibs="$deplib $compile_deplibs" - finalize_deplibs="$deplib $finalize_deplibs" - else - deplibs="$deplib $deplibs" - test "$linkmode" = lib && newdependency_libs="$deplib $newdependency_libs" - fi - continue - else # deplib is a libtool library + if $found; then + # deplib is a libtool library # If $allow_libtool_libs_with_static_runtimes && $deplib is a stdlib, # We need to do some special things here, and not later. - if test "X$allow_libtool_libs_with_static_runtimes" = "Xyes" ; then + if test yes = "$allow_libtool_libs_with_static_runtimes"; then case " $predeps $postdeps " in *" $deplib "*) if func_lalib_p "$lib"; then @@ -6223,19 +7658,19 @@ func_mode_link () old_library= func_source "$lib" for l in $old_library $library_names; do - ll="$l" + ll=$l done - if test "X$ll" = "X$old_library" ; then # only static version available - found=no + if test "X$ll" = "X$old_library"; then # only static version available + found=false func_dirname "$lib" "" "." - ladir="$func_dirname_result" + ladir=$func_dirname_result lib=$ladir/$old_library - if test "$linkmode,$pass" = "prog,link"; then + if test prog,link = "$linkmode,$pass"; then compile_deplibs="$deplib $compile_deplibs" finalize_deplibs="$deplib $finalize_deplibs" else deplibs="$deplib $deplibs" - test "$linkmode" = lib && newdependency_libs="$deplib $newdependency_libs" + test lib = "$linkmode" && newdependency_libs="$deplib $newdependency_libs" fi continue fi @@ -6244,15 +7679,25 @@ func_mode_link () *) ;; esac fi + else + # deplib doesn't seem to be a libtool library + if test prog,link = "$linkmode,$pass"; then + compile_deplibs="$deplib $compile_deplibs" + finalize_deplibs="$deplib $finalize_deplibs" + else + deplibs="$deplib $deplibs" + test lib = "$linkmode" && newdependency_libs="$deplib $newdependency_libs" + fi + continue fi ;; # -l *.ltframework) - if test "$linkmode,$pass" = "prog,link"; then + if test prog,link = "$linkmode,$pass"; then compile_deplibs="$deplib $compile_deplibs" finalize_deplibs="$deplib $finalize_deplibs" else deplibs="$deplib $deplibs" - if test "$linkmode" = lib ; then + if test lib = "$linkmode"; then case "$new_inherited_linker_flags " in *" $deplib "*) ;; * ) func_append new_inherited_linker_flags " $deplib" ;; @@ -6265,18 +7710,18 @@ func_mode_link () case $linkmode in lib) deplibs="$deplib $deplibs" - test "$pass" = conv && continue + test conv = "$pass" && continue newdependency_libs="$deplib $newdependency_libs" func_stripname '-L' '' "$deplib" func_resolve_sysroot "$func_stripname_result" func_append newlib_search_path " $func_resolve_sysroot_result" ;; prog) - if test "$pass" = conv; then + if test conv = "$pass"; then deplibs="$deplib $deplibs" continue fi - if test "$pass" = scan; then + if test scan = "$pass"; then deplibs="$deplib $deplibs" else compile_deplibs="$deplib $compile_deplibs" @@ -6287,13 +7732,13 @@ func_mode_link () func_append newlib_search_path " $func_resolve_sysroot_result" ;; *) - func_warning "\`-L' is ignored for archives/objects" + func_warning "'-L' is ignored for archives/objects" ;; esac # linkmode continue ;; # -L -R*) - if test "$pass" = link; then + if test link = "$pass"; then func_stripname '-R' '' "$deplib" func_resolve_sysroot "$func_stripname_result" dir=$func_resolve_sysroot_result @@ -6311,7 +7756,7 @@ func_mode_link () lib=$func_resolve_sysroot_result ;; *.$libext) - if test "$pass" = conv; then + if test conv = "$pass"; then deplibs="$deplib $deplibs" continue fi @@ -6322,21 +7767,26 @@ func_mode_link () case " $dlpreconveniencelibs " in *" $deplib "*) ;; *) - valid_a_lib=no + valid_a_lib=false case $deplibs_check_method in match_pattern*) set dummy $deplibs_check_method; shift match_pattern_regex=`expr "$deplibs_check_method" : "$1 \(.*\)"` if eval "\$ECHO \"$deplib\"" 2>/dev/null | $SED 10q \ | $EGREP "$match_pattern_regex" > /dev/null; then - valid_a_lib=yes + valid_a_lib=: fi ;; pass_all) - valid_a_lib=yes + valid_a_lib=: ;; esac - if test "$valid_a_lib" != yes; then + if $valid_a_lib; then + echo + $ECHO "*** Warning: Linking the shared library $output against the" + $ECHO "*** static library $deplib is not portable!" + deplibs="$deplib $deplibs" + else echo $ECHO "*** Warning: Trying to link with static lib archive $deplib." echo "*** I have the capability to make that library automatically link in when" @@ -6344,18 +7794,13 @@ func_mode_link () echo "*** shared version of the library, which you do not appear to have" echo "*** because the file extensions .$libext of this argument makes me believe" echo "*** that it is just a static archive that I should not use here." - else - echo - $ECHO "*** Warning: Linking the shared library $output against the" - $ECHO "*** static library $deplib is not portable!" - deplibs="$deplib $deplibs" fi ;; esac continue ;; prog) - if test "$pass" != link; then + if test link != "$pass"; then deplibs="$deplib $deplibs" else compile_deplibs="$deplib $compile_deplibs" @@ -6366,10 +7811,10 @@ func_mode_link () esac # linkmode ;; # *.$libext *.lo | *.$objext) - if test "$pass" = conv; then + if test conv = "$pass"; then deplibs="$deplib $deplibs" - elif test "$linkmode" = prog; then - if test "$pass" = dlpreopen || test "$dlopen_support" != yes || test "$build_libtool_libs" = no; then + elif test prog = "$linkmode"; then + if test dlpreopen = "$pass" || test yes != "$dlopen_support" || test no = "$build_libtool_libs"; then # If there is no dlopen support or we're linking statically, # we need to preload. func_append newdlprefiles " $deplib" @@ -6382,22 +7827,20 @@ func_mode_link () continue ;; %DEPLIBS%) - alldeplibs=yes + alldeplibs=: continue ;; esac # case $deplib - if test "$found" = yes || test -f "$lib"; then : - else - func_fatal_error "cannot find the library \`$lib' or unhandled argument \`$deplib'" - fi + $found || test -f "$lib" \ + || func_fatal_error "cannot find the library '$lib' or unhandled argument '$deplib'" # Check to see that this really is a libtool archive. func_lalib_unsafe_p "$lib" \ - || func_fatal_error "\`$lib' is not a valid libtool archive" + || func_fatal_error "'$lib' is not a valid libtool archive" func_dirname "$lib" "" "." - ladir="$func_dirname_result" + ladir=$func_dirname_result dlname= dlopen= @@ -6427,30 +7870,30 @@ func_mode_link () done fi dependency_libs=`$ECHO " $dependency_libs" | $SED 's% \([^ $]*\).ltframework% -framework \1%g'` - if test "$linkmode,$pass" = "lib,link" || - test "$linkmode,$pass" = "prog,scan" || - { test "$linkmode" != prog && test "$linkmode" != lib; }; then + if test lib,link = "$linkmode,$pass" || + test prog,scan = "$linkmode,$pass" || + { test prog != "$linkmode" && test lib != "$linkmode"; }; then test -n "$dlopen" && func_append dlfiles " $dlopen" test -n "$dlpreopen" && func_append dlprefiles " $dlpreopen" fi - if test "$pass" = conv; then + if test conv = "$pass"; then # Only check for convenience libraries deplibs="$lib $deplibs" if test -z "$libdir"; then if test -z "$old_library"; then - func_fatal_error "cannot find name of link library for \`$lib'" + func_fatal_error "cannot find name of link library for '$lib'" fi # It is a libtool convenience library, so add in its objects. func_append convenience " $ladir/$objdir/$old_library" func_append old_convenience " $ladir/$objdir/$old_library" - elif test "$linkmode" != prog && test "$linkmode" != lib; then - func_fatal_error "\`$lib' is not a convenience library" + elif test prog != "$linkmode" && test lib != "$linkmode"; then + func_fatal_error "'$lib' is not a convenience library" fi tmp_libs= for deplib in $dependency_libs; do deplibs="$deplib $deplibs" - if $opt_preserve_dup_deps ; then + if $opt_preserve_dup_deps; then case "$tmp_libs " in *" $deplib "*) func_append specialdeplibs " $deplib" ;; esac @@ -6464,26 +7907,26 @@ func_mode_link () # Get the name of the library we link against. linklib= if test -n "$old_library" && - { test "$prefer_static_libs" = yes || - test "$prefer_static_libs,$installed" = "built,no"; }; then + { test yes = "$prefer_static_libs" || + test built,no = "$prefer_static_libs,$installed"; }; then linklib=$old_library else for l in $old_library $library_names; do - linklib="$l" + linklib=$l done fi if test -z "$linklib"; then - func_fatal_error "cannot find name of link library for \`$lib'" + func_fatal_error "cannot find name of link library for '$lib'" fi # This library was specified with -dlopen. - if test "$pass" = dlopen; then - if test -z "$libdir"; then - func_fatal_error "cannot -dlopen a convenience library: \`$lib'" - fi + if test dlopen = "$pass"; then + test -z "$libdir" \ + && func_fatal_error "cannot -dlopen a convenience library: '$lib'" if test -z "$dlname" || - test "$dlopen_support" != yes || - test "$build_libtool_libs" = no; then + test yes != "$dlopen_support" || + test no = "$build_libtool_libs" + then # If there is no dlname, no dlopen support or we're linking # statically, we need to preload. We also need to preload any # dependent libraries so libltdl's deplib preloader doesn't @@ -6497,40 +7940,40 @@ func_mode_link () # We need an absolute path. case $ladir in - [\\/]* | [A-Za-z]:[\\/]*) abs_ladir="$ladir" ;; + [\\/]* | [A-Za-z]:[\\/]*) abs_ladir=$ladir ;; *) abs_ladir=`cd "$ladir" && pwd` if test -z "$abs_ladir"; then - func_warning "cannot determine absolute directory name of \`$ladir'" + func_warning "cannot determine absolute directory name of '$ladir'" func_warning "passing it literally to the linker, although it might fail" - abs_ladir="$ladir" + abs_ladir=$ladir fi ;; esac func_basename "$lib" - laname="$func_basename_result" + laname=$func_basename_result # Find the relevant object directory and library name. - if test "X$installed" = Xyes; then + if test yes = "$installed"; then if test ! -f "$lt_sysroot$libdir/$linklib" && test -f "$abs_ladir/$linklib"; then - func_warning "library \`$lib' was moved." - dir="$ladir" - absdir="$abs_ladir" - libdir="$abs_ladir" + func_warning "library '$lib' was moved." + dir=$ladir + absdir=$abs_ladir + libdir=$abs_ladir else - dir="$lt_sysroot$libdir" - absdir="$lt_sysroot$libdir" + dir=$lt_sysroot$libdir + absdir=$lt_sysroot$libdir fi - test "X$hardcode_automatic" = Xyes && avoidtemprpath=yes + test yes = "$hardcode_automatic" && avoidtemprpath=yes else if test ! -f "$ladir/$objdir/$linklib" && test -f "$abs_ladir/$linklib"; then - dir="$ladir" - absdir="$abs_ladir" + dir=$ladir + absdir=$abs_ladir # Remove this search path later func_append notinst_path " $abs_ladir" else - dir="$ladir/$objdir" - absdir="$abs_ladir/$objdir" + dir=$ladir/$objdir + absdir=$abs_ladir/$objdir # Remove this search path later func_append notinst_path " $abs_ladir" fi @@ -6539,11 +7982,11 @@ func_mode_link () name=$func_stripname_result # This library was specified with -dlpreopen. - if test "$pass" = dlpreopen; then - if test -z "$libdir" && test "$linkmode" = prog; then - func_fatal_error "only libraries may -dlpreopen a convenience library: \`$lib'" + if test dlpreopen = "$pass"; then + if test -z "$libdir" && test prog = "$linkmode"; then + func_fatal_error "only libraries may -dlpreopen a convenience library: '$lib'" fi - case "$host" in + case $host in # special handling for platforms with PE-DLLs. *cygwin* | *mingw* | *cegcc* ) # Linker will automatically link against shared library if both @@ -6587,9 +8030,9 @@ func_mode_link () if test -z "$libdir"; then # Link the convenience library - if test "$linkmode" = lib; then + if test lib = "$linkmode"; then deplibs="$dir/$old_library $deplibs" - elif test "$linkmode,$pass" = "prog,link"; then + elif test prog,link = "$linkmode,$pass"; then compile_deplibs="$dir/$old_library $compile_deplibs" finalize_deplibs="$dir/$old_library $finalize_deplibs" else @@ -6599,14 +8042,14 @@ func_mode_link () fi - if test "$linkmode" = prog && test "$pass" != link; then + if test prog = "$linkmode" && test link != "$pass"; then func_append newlib_search_path " $ladir" deplibs="$lib $deplibs" - linkalldeplibs=no - if test "$link_all_deplibs" != no || test -z "$library_names" || - test "$build_libtool_libs" = no; then - linkalldeplibs=yes + linkalldeplibs=false + if test no != "$link_all_deplibs" || test -z "$library_names" || + test no = "$build_libtool_libs"; then + linkalldeplibs=: fi tmp_libs= @@ -6618,14 +8061,14 @@ func_mode_link () ;; esac # Need to link against all dependency_libs? - if test "$linkalldeplibs" = yes; then + if $linkalldeplibs; then deplibs="$deplib $deplibs" else # Need to hardcode shared library paths # or/and link against static libraries newdependency_libs="$deplib $newdependency_libs" fi - if $opt_preserve_dup_deps ; then + if $opt_preserve_dup_deps; then case "$tmp_libs " in *" $deplib "*) func_append specialdeplibs " $deplib" ;; esac @@ -6635,15 +8078,15 @@ func_mode_link () continue fi # $linkmode = prog... - if test "$linkmode,$pass" = "prog,link"; then + if test prog,link = "$linkmode,$pass"; then if test -n "$library_names" && - { { test "$prefer_static_libs" = no || - test "$prefer_static_libs,$installed" = "built,yes"; } || + { { test no = "$prefer_static_libs" || + test built,yes = "$prefer_static_libs,$installed"; } || test -z "$old_library"; }; then # We need to hardcode the library path - if test -n "$shlibpath_var" && test -z "$avoidtemprpath" ; then + if test -n "$shlibpath_var" && test -z "$avoidtemprpath"; then # Make sure the rpath contains only unique directories. - case "$temp_rpath:" in + case $temp_rpath: in *"$absdir:"*) ;; *) func_append temp_rpath "$absdir:" ;; esac @@ -6672,9 +8115,9 @@ func_mode_link () esac fi # $linkmode,$pass = prog,link... - if test "$alldeplibs" = yes && - { test "$deplibs_check_method" = pass_all || - { test "$build_libtool_libs" = yes && + if $alldeplibs && + { test pass_all = "$deplibs_check_method" || + { test yes = "$build_libtool_libs" && test -n "$library_names"; }; }; then # We only need to search for static libraries continue @@ -6683,19 +8126,19 @@ func_mode_link () link_static=no # Whether the deplib will be linked statically use_static_libs=$prefer_static_libs - if test "$use_static_libs" = built && test "$installed" = yes; then + if test built = "$use_static_libs" && test yes = "$installed"; then use_static_libs=no fi if test -n "$library_names" && - { test "$use_static_libs" = no || test -z "$old_library"; }; then + { test no = "$use_static_libs" || test -z "$old_library"; }; then case $host in - *cygwin* | *mingw* | *cegcc*) + *cygwin* | *mingw* | *cegcc* | *os2*) # No point in relinking DLLs because paths are not encoded func_append notinst_deplibs " $lib" need_relink=no ;; *) - if test "$installed" = no; then + if test no = "$installed"; then func_append notinst_deplibs " $lib" need_relink=yes fi @@ -6705,24 +8148,24 @@ func_mode_link () # Warn about portability, can't link against -module's on some # systems (darwin). Don't bleat about dlopened modules though! - dlopenmodule="" + dlopenmodule= for dlpremoduletest in $dlprefiles; do if test "X$dlpremoduletest" = "X$lib"; then - dlopenmodule="$dlpremoduletest" + dlopenmodule=$dlpremoduletest break fi done - if test -z "$dlopenmodule" && test "$shouldnotlink" = yes && test "$pass" = link; then + if test -z "$dlopenmodule" && test yes = "$shouldnotlink" && test link = "$pass"; then echo - if test "$linkmode" = prog; then + if test prog = "$linkmode"; then $ECHO "*** Warning: Linking the executable $output against the loadable module" else $ECHO "*** Warning: Linking the shared library $output against the loadable module" fi $ECHO "*** $linklib is not portable!" fi - if test "$linkmode" = lib && - test "$hardcode_into_libs" = yes; then + if test lib = "$linkmode" && + test yes = "$hardcode_into_libs"; then # Hardcode the library path. # Skip directories that are in the system default run-time # search path. @@ -6750,43 +8193,43 @@ func_mode_link () # figure out the soname set dummy $library_names shift - realname="$1" + realname=$1 shift libname=`eval "\\$ECHO \"$libname_spec\""` # use dlname if we got it. it's perfectly good, no? if test -n "$dlname"; then - soname="$dlname" + soname=$dlname elif test -n "$soname_spec"; then # bleh windows case $host in - *cygwin* | mingw* | *cegcc*) + *cygwin* | mingw* | *cegcc* | *os2*) func_arith $current - $age major=$func_arith_result - versuffix="-$major" + versuffix=-$major ;; esac eval soname=\"$soname_spec\" else - soname="$realname" + soname=$realname fi # Make a new name for the extract_expsyms_cmds to use - soroot="$soname" + soroot=$soname func_basename "$soroot" - soname="$func_basename_result" + soname=$func_basename_result func_stripname 'lib' '.dll' "$soname" newlib=libimp-$func_stripname_result.a # If the library has no export list, then create one now if test -f "$output_objdir/$soname-def"; then : else - func_verbose "extracting exported symbol list from \`$soname'" + func_verbose "extracting exported symbol list from '$soname'" func_execute_cmds "$extract_expsyms_cmds" 'exit $?' fi # Create $newlib if test -f "$output_objdir/$newlib"; then :; else - func_verbose "generating import library for \`$soname'" + func_verbose "generating import library for '$soname'" func_execute_cmds "$old_archive_from_expsyms_cmds" 'exit $?' fi # make sure the library variables are pointing to the new library @@ -6794,58 +8237,58 @@ func_mode_link () linklib=$newlib fi # test -n "$old_archive_from_expsyms_cmds" - if test "$linkmode" = prog || test "$opt_mode" != relink; then + if test prog = "$linkmode" || test relink != "$opt_mode"; then add_shlibpath= add_dir= add= lib_linked=yes case $hardcode_action in immediate | unsupported) - if test "$hardcode_direct" = no; then - add="$dir/$linklib" + if test no = "$hardcode_direct"; then + add=$dir/$linklib case $host in - *-*-sco3.2v5.0.[024]*) add_dir="-L$dir" ;; - *-*-sysv4*uw2*) add_dir="-L$dir" ;; + *-*-sco3.2v5.0.[024]*) add_dir=-L$dir ;; + *-*-sysv4*uw2*) add_dir=-L$dir ;; *-*-sysv5OpenUNIX* | *-*-sysv5UnixWare7.[01].[10]* | \ - *-*-unixware7*) add_dir="-L$dir" ;; + *-*-unixware7*) add_dir=-L$dir ;; *-*-darwin* ) - # if the lib is a (non-dlopened) module then we can not + # if the lib is a (non-dlopened) module then we cannot # link against it, someone is ignoring the earlier warnings if /usr/bin/file -L $add 2> /dev/null | - $GREP ": [^:]* bundle" >/dev/null ; then + $GREP ": [^:]* bundle" >/dev/null; then if test "X$dlopenmodule" != "X$lib"; then $ECHO "*** Warning: lib $linklib is a module, not a shared library" - if test -z "$old_library" ; then + if test -z "$old_library"; then echo echo "*** And there doesn't seem to be a static archive available" echo "*** The link will probably fail, sorry" else - add="$dir/$old_library" + add=$dir/$old_library fi elif test -n "$old_library"; then - add="$dir/$old_library" + add=$dir/$old_library fi fi esac - elif test "$hardcode_minus_L" = no; then + elif test no = "$hardcode_minus_L"; then case $host in - *-*-sunos*) add_shlibpath="$dir" ;; + *-*-sunos*) add_shlibpath=$dir ;; esac - add_dir="-L$dir" - add="-l$name" - elif test "$hardcode_shlibpath_var" = no; then - add_shlibpath="$dir" - add="-l$name" + add_dir=-L$dir + add=-l$name + elif test no = "$hardcode_shlibpath_var"; then + add_shlibpath=$dir + add=-l$name else lib_linked=no fi ;; relink) - if test "$hardcode_direct" = yes && - test "$hardcode_direct_absolute" = no; then - add="$dir/$linklib" - elif test "$hardcode_minus_L" = yes; then - add_dir="-L$absdir" + if test yes = "$hardcode_direct" && + test no = "$hardcode_direct_absolute"; then + add=$dir/$linklib + elif test yes = "$hardcode_minus_L"; then + add_dir=-L$absdir # Try looking first in the location we're being installed to. if test -n "$inst_prefix_dir"; then case $libdir in @@ -6854,10 +8297,10 @@ func_mode_link () ;; esac fi - add="-l$name" - elif test "$hardcode_shlibpath_var" = yes; then - add_shlibpath="$dir" - add="-l$name" + add=-l$name + elif test yes = "$hardcode_shlibpath_var"; then + add_shlibpath=$dir + add=-l$name else lib_linked=no fi @@ -6865,7 +8308,7 @@ func_mode_link () *) lib_linked=no ;; esac - if test "$lib_linked" != yes; then + if test yes != "$lib_linked"; then func_fatal_configuration "unsupported hardcode properties" fi @@ -6875,15 +8318,15 @@ func_mode_link () *) func_append compile_shlibpath "$add_shlibpath:" ;; esac fi - if test "$linkmode" = prog; then + if test prog = "$linkmode"; then test -n "$add_dir" && compile_deplibs="$add_dir $compile_deplibs" test -n "$add" && compile_deplibs="$add $compile_deplibs" else test -n "$add_dir" && deplibs="$add_dir $deplibs" test -n "$add" && deplibs="$add $deplibs" - if test "$hardcode_direct" != yes && - test "$hardcode_minus_L" != yes && - test "$hardcode_shlibpath_var" = yes; then + if test yes != "$hardcode_direct" && + test yes != "$hardcode_minus_L" && + test yes = "$hardcode_shlibpath_var"; then case :$finalize_shlibpath: in *":$libdir:"*) ;; *) func_append finalize_shlibpath "$libdir:" ;; @@ -6892,33 +8335,33 @@ func_mode_link () fi fi - if test "$linkmode" = prog || test "$opt_mode" = relink; then + if test prog = "$linkmode" || test relink = "$opt_mode"; then add_shlibpath= add_dir= add= # Finalize command for both is simple: just hardcode it. - if test "$hardcode_direct" = yes && - test "$hardcode_direct_absolute" = no; then - add="$libdir/$linklib" - elif test "$hardcode_minus_L" = yes; then - add_dir="-L$libdir" - add="-l$name" - elif test "$hardcode_shlibpath_var" = yes; then + if test yes = "$hardcode_direct" && + test no = "$hardcode_direct_absolute"; then + add=$libdir/$linklib + elif test yes = "$hardcode_minus_L"; then + add_dir=-L$libdir + add=-l$name + elif test yes = "$hardcode_shlibpath_var"; then case :$finalize_shlibpath: in *":$libdir:"*) ;; *) func_append finalize_shlibpath "$libdir:" ;; esac - add="-l$name" - elif test "$hardcode_automatic" = yes; then + add=-l$name + elif test yes = "$hardcode_automatic"; then if test -n "$inst_prefix_dir" && - test -f "$inst_prefix_dir$libdir/$linklib" ; then - add="$inst_prefix_dir$libdir/$linklib" + test -f "$inst_prefix_dir$libdir/$linklib"; then + add=$inst_prefix_dir$libdir/$linklib else - add="$libdir/$linklib" + add=$libdir/$linklib fi else # We cannot seem to hardcode it, guess we'll fake it. - add_dir="-L$libdir" + add_dir=-L$libdir # Try looking first in the location we're being installed to. if test -n "$inst_prefix_dir"; then case $libdir in @@ -6927,10 +8370,10 @@ func_mode_link () ;; esac fi - add="-l$name" + add=-l$name fi - if test "$linkmode" = prog; then + if test prog = "$linkmode"; then test -n "$add_dir" && finalize_deplibs="$add_dir $finalize_deplibs" test -n "$add" && finalize_deplibs="$add $finalize_deplibs" else @@ -6938,43 +8381,43 @@ func_mode_link () test -n "$add" && deplibs="$add $deplibs" fi fi - elif test "$linkmode" = prog; then + elif test prog = "$linkmode"; then # Here we assume that one of hardcode_direct or hardcode_minus_L # is not unsupported. This is valid on all known static and # shared platforms. - if test "$hardcode_direct" != unsupported; then - test -n "$old_library" && linklib="$old_library" + if test unsupported != "$hardcode_direct"; then + test -n "$old_library" && linklib=$old_library compile_deplibs="$dir/$linklib $compile_deplibs" finalize_deplibs="$dir/$linklib $finalize_deplibs" else compile_deplibs="-l$name -L$dir $compile_deplibs" finalize_deplibs="-l$name -L$dir $finalize_deplibs" fi - elif test "$build_libtool_libs" = yes; then + elif test yes = "$build_libtool_libs"; then # Not a shared library - if test "$deplibs_check_method" != pass_all; then + if test pass_all != "$deplibs_check_method"; then # We're trying link a shared library against a static one # but the system doesn't support it. # Just print a warning and add the library to dependency_libs so # that the program can be linked against the static library. echo - $ECHO "*** Warning: This system can not link to static lib archive $lib." + $ECHO "*** Warning: This system cannot link to static lib archive $lib." echo "*** I have the capability to make that library automatically link in when" echo "*** you link to this library. But I can only do this if you have a" echo "*** shared version of the library, which you do not appear to have." - if test "$module" = yes; then + if test yes = "$module"; then echo "*** But as you try to build a module library, libtool will still create " echo "*** a static module, that should work as long as the dlopening application" echo "*** is linked with the -dlopen flag to resolve symbols at runtime." if test -z "$global_symbol_pipe"; then echo echo "*** However, this would only work if libtool was able to extract symbol" - echo "*** lists from a program, using \`nm' or equivalent, but libtool could" + echo "*** lists from a program, using 'nm' or equivalent, but libtool could" echo "*** not find such a program. So, this module is probably useless." - echo "*** \`nm' from GNU binutils and a full rebuild may help." + echo "*** 'nm' from GNU binutils and a full rebuild may help." fi - if test "$build_old_libs" = no; then + if test no = "$build_old_libs"; then build_libtool_libs=module build_old_libs=yes else @@ -6987,11 +8430,11 @@ func_mode_link () fi fi # link shared/static library? - if test "$linkmode" = lib; then + if test lib = "$linkmode"; then if test -n "$dependency_libs" && - { test "$hardcode_into_libs" != yes || - test "$build_old_libs" = yes || - test "$link_static" = yes; }; then + { test yes != "$hardcode_into_libs" || + test yes = "$build_old_libs" || + test yes = "$link_static"; }; then # Extract -R from dependency_libs temp_deplibs= for libdir in $dependency_libs; do @@ -7005,12 +8448,12 @@ func_mode_link () *) func_append temp_deplibs " $libdir";; esac done - dependency_libs="$temp_deplibs" + dependency_libs=$temp_deplibs fi func_append newlib_search_path " $absdir" # Link against this library - test "$link_static" = no && newdependency_libs="$abs_ladir/$laname $newdependency_libs" + test no = "$link_static" && newdependency_libs="$abs_ladir/$laname $newdependency_libs" # ... and its dependency_libs tmp_libs= for deplib in $dependency_libs; do @@ -7020,7 +8463,7 @@ func_mode_link () func_resolve_sysroot "$func_stripname_result";; *) func_resolve_sysroot "$deplib" ;; esac - if $opt_preserve_dup_deps ; then + if $opt_preserve_dup_deps; then case "$tmp_libs " in *" $func_resolve_sysroot_result "*) func_append specialdeplibs " $func_resolve_sysroot_result" ;; @@ -7029,12 +8472,12 @@ func_mode_link () func_append tmp_libs " $func_resolve_sysroot_result" done - if test "$link_all_deplibs" != no; then + if test no != "$link_all_deplibs"; then # Add the search paths of all dependency libraries for deplib in $dependency_libs; do path= case $deplib in - -L*) path="$deplib" ;; + -L*) path=$deplib ;; *.la) func_resolve_sysroot "$deplib" deplib=$func_resolve_sysroot_result @@ -7042,12 +8485,12 @@ func_mode_link () dir=$func_dirname_result # We need an absolute path. case $dir in - [\\/]* | [A-Za-z]:[\\/]*) absdir="$dir" ;; + [\\/]* | [A-Za-z]:[\\/]*) absdir=$dir ;; *) absdir=`cd "$dir" && pwd` if test -z "$absdir"; then - func_warning "cannot determine absolute directory name of \`$dir'" - absdir="$dir" + func_warning "cannot determine absolute directory name of '$dir'" + absdir=$dir fi ;; esac @@ -7055,35 +8498,35 @@ func_mode_link () case $host in *-*-darwin*) depdepl= - eval deplibrary_names=`${SED} -n -e 's/^library_names=\(.*\)$/\1/p' $deplib` - if test -n "$deplibrary_names" ; then - for tmp in $deplibrary_names ; do + eval deplibrary_names=`$SED -n -e 's/^library_names=\(.*\)$/\1/p' $deplib` + if test -n "$deplibrary_names"; then + for tmp in $deplibrary_names; do depdepl=$tmp done - if test -f "$absdir/$objdir/$depdepl" ; then - depdepl="$absdir/$objdir/$depdepl" - darwin_install_name=`${OTOOL} -L $depdepl | awk '{if (NR == 2) {print $1;exit}}'` + if test -f "$absdir/$objdir/$depdepl"; then + depdepl=$absdir/$objdir/$depdepl + darwin_install_name=`$OTOOL -L $depdepl | awk '{if (NR == 2) {print $1;exit}}'` if test -z "$darwin_install_name"; then - darwin_install_name=`${OTOOL64} -L $depdepl | awk '{if (NR == 2) {print $1;exit}}'` + darwin_install_name=`$OTOOL64 -L $depdepl | awk '{if (NR == 2) {print $1;exit}}'` fi - func_append compiler_flags " ${wl}-dylib_file ${wl}${darwin_install_name}:${depdepl}" - func_append linker_flags " -dylib_file ${darwin_install_name}:${depdepl}" + func_append compiler_flags " $wl-dylib_file $wl$darwin_install_name:$depdepl" + func_append linker_flags " -dylib_file $darwin_install_name:$depdepl" path= fi fi ;; *) - path="-L$absdir/$objdir" + path=-L$absdir/$objdir ;; esac else - eval libdir=`${SED} -n -e 's/^libdir=\(.*\)$/\1/p' $deplib` + eval libdir=`$SED -n -e 's/^libdir=\(.*\)$/\1/p' $deplib` test -z "$libdir" && \ - func_fatal_error "\`$deplib' is not a valid libtool archive" + func_fatal_error "'$deplib' is not a valid libtool archive" test "$absdir" != "$libdir" && \ - func_warning "\`$deplib' seems to be moved" + func_warning "'$deplib' seems to be moved" - path="-L$absdir" + path=-L$absdir fi ;; esac @@ -7095,23 +8538,23 @@ func_mode_link () fi # link_all_deplibs != no fi # linkmode = lib done # for deplib in $libs - if test "$pass" = link; then - if test "$linkmode" = "prog"; then + if test link = "$pass"; then + if test prog = "$linkmode"; then compile_deplibs="$new_inherited_linker_flags $compile_deplibs" finalize_deplibs="$new_inherited_linker_flags $finalize_deplibs" else compiler_flags="$compiler_flags "`$ECHO " $new_inherited_linker_flags" | $SED 's% \([^ $]*\).ltframework% -framework \1%g'` fi fi - dependency_libs="$newdependency_libs" - if test "$pass" = dlpreopen; then + dependency_libs=$newdependency_libs + if test dlpreopen = "$pass"; then # Link the dlpreopened libraries before other libraries for deplib in $save_deplibs; do deplibs="$deplib $deplibs" done fi - if test "$pass" != dlopen; then - if test "$pass" != conv; then + if test dlopen != "$pass"; then + test conv = "$pass" || { # Make sure lib_search_path contains only unique directories. lib_search_path= for dir in $newlib_search_path; do @@ -7121,12 +8564,12 @@ func_mode_link () esac done newlib_search_path= - fi + } - if test "$linkmode,$pass" != "prog,link"; then - vars="deplibs" - else + if test prog,link = "$linkmode,$pass"; then vars="compile_deplibs finalize_deplibs" + else + vars=deplibs fi for var in $vars dependency_libs; do # Add libraries to $var in reverse order @@ -7184,62 +8627,93 @@ func_mode_link () eval $var=\"$tmp_libs\" done # for var fi + + # Add Sun CC postdeps if required: + test CXX = "$tagname" && { + case $host_os in + linux*) + case `$CC -V 2>&1 | sed 5q` in + *Sun\ C*) # Sun C++ 5.9 + func_suncc_cstd_abi + + if test no != "$suncc_use_cstd_abi"; then + func_append postdeps ' -library=Cstd -library=Crun' + fi + ;; + esac + ;; + + solaris*) + func_cc_basename "$CC" + case $func_cc_basename_result in + CC* | sunCC*) + func_suncc_cstd_abi + + if test no != "$suncc_use_cstd_abi"; then + func_append postdeps ' -library=Cstd -library=Crun' + fi + ;; + esac + ;; + esac + } + # Last step: remove runtime libs from dependency_libs # (they stay in deplibs) tmp_libs= - for i in $dependency_libs ; do + for i in $dependency_libs; do case " $predeps $postdeps $compiler_lib_search_path " in *" $i "*) - i="" + i= ;; esac - if test -n "$i" ; then + if test -n "$i"; then func_append tmp_libs " $i" fi done dependency_libs=$tmp_libs done # for pass - if test "$linkmode" = prog; then - dlfiles="$newdlfiles" + if test prog = "$linkmode"; then + dlfiles=$newdlfiles fi - if test "$linkmode" = prog || test "$linkmode" = lib; then - dlprefiles="$newdlprefiles" + if test prog = "$linkmode" || test lib = "$linkmode"; then + dlprefiles=$newdlprefiles fi case $linkmode in oldlib) - if test -n "$dlfiles$dlprefiles" || test "$dlself" != no; then - func_warning "\`-dlopen' is ignored for archives" + if test -n "$dlfiles$dlprefiles" || test no != "$dlself"; then + func_warning "'-dlopen' is ignored for archives" fi case " $deplibs" in *\ -l* | *\ -L*) - func_warning "\`-l' and \`-L' are ignored for archives" ;; + func_warning "'-l' and '-L' are ignored for archives" ;; esac test -n "$rpath" && \ - func_warning "\`-rpath' is ignored for archives" + func_warning "'-rpath' is ignored for archives" test -n "$xrpath" && \ - func_warning "\`-R' is ignored for archives" + func_warning "'-R' is ignored for archives" test -n "$vinfo" && \ - func_warning "\`-version-info/-version-number' is ignored for archives" + func_warning "'-version-info/-version-number' is ignored for archives" test -n "$release" && \ - func_warning "\`-release' is ignored for archives" + func_warning "'-release' is ignored for archives" test -n "$export_symbols$export_symbols_regex" && \ - func_warning "\`-export-symbols' is ignored for archives" + func_warning "'-export-symbols' is ignored for archives" # Now set the variables for building old libraries. build_libtool_libs=no - oldlibs="$output" + oldlibs=$output func_append objs "$old_deplibs" ;; lib) - # Make sure we only generate libraries of the form `libNAME.la'. + # Make sure we only generate libraries of the form 'libNAME.la'. case $outputname in lib*) func_stripname 'lib' '.la' "$outputname" @@ -7248,10 +8722,10 @@ func_mode_link () eval libname=\"$libname_spec\" ;; *) - test "$module" = no && \ - func_fatal_help "libtool library \`$output' must begin with \`lib'" + test no = "$module" \ + && func_fatal_help "libtool library '$output' must begin with 'lib'" - if test "$need_lib_prefix" != no; then + if test no != "$need_lib_prefix"; then # Add the "lib" prefix for modules if required func_stripname '' '.la' "$outputname" name=$func_stripname_result @@ -7265,8 +8739,8 @@ func_mode_link () esac if test -n "$objs"; then - if test "$deplibs_check_method" != pass_all; then - func_fatal_error "cannot build libtool library \`$output' from non-libtool objects on this host:$objs" + if test pass_all != "$deplibs_check_method"; then + func_fatal_error "cannot build libtool library '$output' from non-libtool objects on this host:$objs" else echo $ECHO "*** Warning: Linking the shared library $output against the non-libtool" @@ -7275,21 +8749,21 @@ func_mode_link () fi fi - test "$dlself" != no && \ - func_warning "\`-dlopen self' is ignored for libtool libraries" + test no = "$dlself" \ + || func_warning "'-dlopen self' is ignored for libtool libraries" set dummy $rpath shift - test "$#" -gt 1 && \ - func_warning "ignoring multiple \`-rpath's for a libtool library" + test 1 -lt "$#" \ + && func_warning "ignoring multiple '-rpath's for a libtool library" - install_libdir="$1" + install_libdir=$1 oldlibs= if test -z "$rpath"; then - if test "$build_libtool_libs" = yes; then + if test yes = "$build_libtool_libs"; then # Building a libtool convenience library. - # Some compilers have problems with a `.al' extension so + # Some compilers have problems with a '.al' extension so # convenience libraries should have the same extension an # archive normally would. oldlibs="$output_objdir/$libname.$libext $oldlibs" @@ -7298,20 +8772,20 @@ func_mode_link () fi test -n "$vinfo" && \ - func_warning "\`-version-info/-version-number' is ignored for convenience libraries" + func_warning "'-version-info/-version-number' is ignored for convenience libraries" test -n "$release" && \ - func_warning "\`-release' is ignored for convenience libraries" + func_warning "'-release' is ignored for convenience libraries" else # Parse the version information argument. - save_ifs="$IFS"; IFS=':' + save_ifs=$IFS; IFS=: set dummy $vinfo 0 0 0 shift - IFS="$save_ifs" + IFS=$save_ifs test -n "$7" && \ - func_fatal_help "too many parameters to \`-version-info'" + func_fatal_help "too many parameters to '-version-info'" # convert absolute version numbers to libtool ages # this retains compatibility with .la files and attempts @@ -7319,42 +8793,42 @@ func_mode_link () case $vinfo_number in yes) - number_major="$1" - number_minor="$2" - number_revision="$3" + number_major=$1 + number_minor=$2 + number_revision=$3 # # There are really only two kinds -- those that # use the current revision as the major version # and those that subtract age and use age as # a minor version. But, then there is irix - # which has an extra 1 added just for fun + # that has an extra 1 added just for fun # case $version_type in # correct linux to gnu/linux during the next big refactor - darwin|linux|osf|windows|none) + darwin|freebsd-elf|linux|osf|windows|none) func_arith $number_major + $number_minor current=$func_arith_result - age="$number_minor" - revision="$number_revision" + age=$number_minor + revision=$number_revision ;; - freebsd-aout|freebsd-elf|qnx|sunos) - current="$number_major" - revision="$number_minor" - age="0" + freebsd-aout|qnx|sunos) + current=$number_major + revision=$number_minor + age=0 ;; irix|nonstopux) func_arith $number_major + $number_minor current=$func_arith_result - age="$number_minor" - revision="$number_minor" + age=$number_minor + revision=$number_minor lt_irix_increment=no ;; esac ;; no) - current="$1" - revision="$2" - age="$3" + current=$1 + revision=$2 + age=$3 ;; esac @@ -7362,30 +8836,30 @@ func_mode_link () case $current in 0|[1-9]|[1-9][0-9]|[1-9][0-9][0-9]|[1-9][0-9][0-9][0-9]|[1-9][0-9][0-9][0-9][0-9]) ;; *) - func_error "CURRENT \`$current' must be a nonnegative integer" - func_fatal_error "\`$vinfo' is not valid version information" + func_error "CURRENT '$current' must be a nonnegative integer" + func_fatal_error "'$vinfo' is not valid version information" ;; esac case $revision in 0|[1-9]|[1-9][0-9]|[1-9][0-9][0-9]|[1-9][0-9][0-9][0-9]|[1-9][0-9][0-9][0-9][0-9]) ;; *) - func_error "REVISION \`$revision' must be a nonnegative integer" - func_fatal_error "\`$vinfo' is not valid version information" + func_error "REVISION '$revision' must be a nonnegative integer" + func_fatal_error "'$vinfo' is not valid version information" ;; esac case $age in 0|[1-9]|[1-9][0-9]|[1-9][0-9][0-9]|[1-9][0-9][0-9][0-9]|[1-9][0-9][0-9][0-9][0-9]) ;; *) - func_error "AGE \`$age' must be a nonnegative integer" - func_fatal_error "\`$vinfo' is not valid version information" + func_error "AGE '$age' must be a nonnegative integer" + func_fatal_error "'$vinfo' is not valid version information" ;; esac if test "$age" -gt "$current"; then - func_error "AGE \`$age' is greater than the current interface number \`$current'" - func_fatal_error "\`$vinfo' is not valid version information" + func_error "AGE '$age' is greater than the current interface number '$current'" + func_fatal_error "'$vinfo' is not valid version information" fi # Calculate the version variables. @@ -7400,26 +8874,36 @@ func_mode_link () # verstring for coding it into the library header func_arith $current - $age major=.$func_arith_result - versuffix="$major.$age.$revision" + versuffix=$major.$age.$revision # Darwin ld doesn't like 0 for these options... func_arith $current + 1 minor_current=$func_arith_result - xlcverstring="${wl}-compatibility_version ${wl}$minor_current ${wl}-current_version ${wl}$minor_current.$revision" + xlcverstring="$wl-compatibility_version $wl$minor_current $wl-current_version $wl$minor_current.$revision" verstring="-compatibility_version $minor_current -current_version $minor_current.$revision" + # On Darwin other compilers + case $CC in + nagfor*) + verstring="$wl-compatibility_version $wl$minor_current $wl-current_version $wl$minor_current.$revision" + ;; + *) + verstring="-compatibility_version $minor_current -current_version $minor_current.$revision" + ;; + esac ;; freebsd-aout) - major=".$current" - versuffix=".$current.$revision"; + major=.$current + versuffix=.$current.$revision ;; freebsd-elf) - major=".$current" - versuffix=".$current" + func_arith $current - $age + major=.$func_arith_result + versuffix=$major.$age.$revision ;; irix | nonstopux) - if test "X$lt_irix_increment" = "Xno"; then + if test no = "$lt_irix_increment"; then func_arith $current - $age else func_arith $current - $age + 1 @@ -7430,69 +8914,74 @@ func_mode_link () nonstopux) verstring_prefix=nonstopux ;; *) verstring_prefix=sgi ;; esac - verstring="$verstring_prefix$major.$revision" + verstring=$verstring_prefix$major.$revision # Add in all the interfaces that we are compatible with. loop=$revision - while test "$loop" -ne 0; do + while test 0 -ne "$loop"; do func_arith $revision - $loop iface=$func_arith_result func_arith $loop - 1 loop=$func_arith_result - verstring="$verstring_prefix$major.$iface:$verstring" + verstring=$verstring_prefix$major.$iface:$verstring done - # Before this point, $major must not contain `.'. + # Before this point, $major must not contain '.'. major=.$major - versuffix="$major.$revision" + versuffix=$major.$revision ;; linux) # correct to gnu/linux during the next big refactor func_arith $current - $age major=.$func_arith_result - versuffix="$major.$age.$revision" + versuffix=$major.$age.$revision ;; osf) func_arith $current - $age major=.$func_arith_result - versuffix=".$current.$age.$revision" - verstring="$current.$age.$revision" + versuffix=.$current.$age.$revision + verstring=$current.$age.$revision # Add in all the interfaces that we are compatible with. loop=$age - while test "$loop" -ne 0; do + while test 0 -ne "$loop"; do func_arith $current - $loop iface=$func_arith_result func_arith $loop - 1 loop=$func_arith_result - verstring="$verstring:${iface}.0" + verstring=$verstring:$iface.0 done # Make executables depend on our current version. - func_append verstring ":${current}.0" + func_append verstring ":$current.0" ;; qnx) - major=".$current" - versuffix=".$current" + major=.$current + versuffix=.$current + ;; + + sco) + major=.$current + versuffix=.$current ;; sunos) - major=".$current" - versuffix=".$current.$revision" + major=.$current + versuffix=.$current.$revision ;; windows) # Use '-' rather than '.', since we only want one - # extension on DOS 8.3 filesystems. + # extension on DOS 8.3 file systems. func_arith $current - $age major=$func_arith_result - versuffix="-$major" + versuffix=-$major ;; *) - func_fatal_configuration "unknown library version type \`$version_type'" + func_fatal_configuration "unknown library version type '$version_type'" ;; esac @@ -7506,42 +8995,45 @@ func_mode_link () verstring= ;; *) - verstring="0.0" + verstring=0.0 ;; esac - if test "$need_version" = no; then + if test no = "$need_version"; then versuffix= else - versuffix=".0.0" + versuffix=.0.0 fi fi # Remove version info from name if versioning should be avoided - if test "$avoid_version" = yes && test "$need_version" = no; then + if test yes,no = "$avoid_version,$need_version"; then major= versuffix= - verstring="" + verstring= fi # Check to see if the archive will have undefined symbols. - if test "$allow_undefined" = yes; then - if test "$allow_undefined_flag" = unsupported; then - func_warning "undefined symbols not allowed in $host shared libraries" - build_libtool_libs=no - build_old_libs=yes + if test yes = "$allow_undefined"; then + if test unsupported = "$allow_undefined_flag"; then + if test yes = "$build_old_libs"; then + func_warning "undefined symbols not allowed in $host shared libraries; building static only" + build_libtool_libs=no + else + func_fatal_error "can't build $host shared library unless -no-undefined is specified" + fi fi else # Don't allow undefined symbols. - allow_undefined_flag="$no_undefined_flag" + allow_undefined_flag=$no_undefined_flag fi fi - func_generate_dlsyms "$libname" "$libname" "yes" + func_generate_dlsyms "$libname" "$libname" : func_append libobjs " $symfileobj" - test "X$libobjs" = "X " && libobjs= + test " " = "$libobjs" && libobjs= - if test "$opt_mode" != relink; then + if test relink != "$opt_mode"; then # Remove our outputs, but don't remove object files since they # may have been created when compiling PIC objects. removelist= @@ -7550,8 +9042,8 @@ func_mode_link () case $p in *.$objext | *.gcno) ;; - $output_objdir/$outputname | $output_objdir/$libname.* | $output_objdir/${libname}${release}.*) - if test "X$precious_files_regex" != "X"; then + $output_objdir/$outputname | $output_objdir/$libname.* | $output_objdir/$libname$release.*) + if test -n "$precious_files_regex"; then if $ECHO "$p" | $EGREP -e "$precious_files_regex" >/dev/null 2>&1 then continue @@ -7567,11 +9059,11 @@ func_mode_link () fi # Now set the variables for building old libraries. - if test "$build_old_libs" = yes && test "$build_libtool_libs" != convenience ; then + if test yes = "$build_old_libs" && test convenience != "$build_libtool_libs"; then func_append oldlibs " $output_objdir/$libname.$libext" # Transform .lo files to .o files. - oldobjs="$objs "`$ECHO "$libobjs" | $SP2NL | $SED "/\.${libext}$/d; $lo2o" | $NL2SP` + oldobjs="$objs "`$ECHO "$libobjs" | $SP2NL | $SED "/\.$libext$/d; $lo2o" | $NL2SP` fi # Eliminate all temporary directories. @@ -7592,13 +9084,13 @@ func_mode_link () *) func_append finalize_rpath " $libdir" ;; esac done - if test "$hardcode_into_libs" != yes || test "$build_old_libs" = yes; then + if test yes != "$hardcode_into_libs" || test yes = "$build_old_libs"; then dependency_libs="$temp_xrpath $dependency_libs" fi fi # Make sure dlfiles contains only unique files that won't be dlpreopened - old_dlfiles="$dlfiles" + old_dlfiles=$dlfiles dlfiles= for lib in $old_dlfiles; do case " $dlprefiles $dlfiles " in @@ -7608,7 +9100,7 @@ func_mode_link () done # Make sure dlprefiles contains only unique files - old_dlprefiles="$dlprefiles" + old_dlprefiles=$dlprefiles dlprefiles= for lib in $old_dlprefiles; do case "$dlprefiles " in @@ -7617,7 +9109,7 @@ func_mode_link () esac done - if test "$build_libtool_libs" = yes; then + if test yes = "$build_libtool_libs"; then if test -n "$rpath"; then case $host in *-*-cygwin* | *-*-mingw* | *-*-pw32* | *-*-os2* | *-*-beos* | *-cegcc* | *-*-haiku*) @@ -7641,7 +9133,7 @@ func_mode_link () ;; *) # Add libc to deplibs on all other systems if necessary. - if test "$build_libtool_need_lc" = "yes"; then + if test yes = "$build_libtool_need_lc"; then func_append deplibs " -lc" fi ;; @@ -7657,9 +9149,9 @@ func_mode_link () # I'm not sure if I'm treating the release correctly. I think # release should show up in the -l (ie -lgmp5) so we don't want to # add it in twice. Is that correct? - release="" - versuffix="" - major="" + release= + versuffix= + major= newdeplibs= droppeddeps=no case $deplibs_check_method in @@ -7688,20 +9180,20 @@ EOF -l*) func_stripname -l '' "$i" name=$func_stripname_result - if test "X$allow_libtool_libs_with_static_runtimes" = "Xyes" ; then + if test yes = "$allow_libtool_libs_with_static_runtimes"; then case " $predeps $postdeps " in *" $i "*) func_append newdeplibs " $i" - i="" + i= ;; esac fi - if test -n "$i" ; then + if test -n "$i"; then libname=`eval "\\$ECHO \"$libname_spec\""` deplib_matches=`eval "\\$ECHO \"$library_names_spec\""` set dummy $deplib_matches; shift deplib_match=$1 - if test `expr "$ldd_output" : ".*$deplib_match"` -ne 0 ; then + if test `expr "$ldd_output" : ".*$deplib_match"` -ne 0; then func_append newdeplibs " $i" else droppeddeps=yes @@ -7731,20 +9223,20 @@ EOF $opt_dry_run || $RM conftest if $LTCC $LTCFLAGS -o conftest conftest.c $i; then ldd_output=`ldd conftest` - if test "X$allow_libtool_libs_with_static_runtimes" = "Xyes" ; then + if test yes = "$allow_libtool_libs_with_static_runtimes"; then case " $predeps $postdeps " in *" $i "*) func_append newdeplibs " $i" - i="" + i= ;; esac fi - if test -n "$i" ; then + if test -n "$i"; then libname=`eval "\\$ECHO \"$libname_spec\""` deplib_matches=`eval "\\$ECHO \"$library_names_spec\""` set dummy $deplib_matches; shift deplib_match=$1 - if test `expr "$ldd_output" : ".*$deplib_match"` -ne 0 ; then + if test `expr "$ldd_output" : ".*$deplib_match"` -ne 0; then func_append newdeplibs " $i" else droppeddeps=yes @@ -7781,24 +9273,24 @@ EOF -l*) func_stripname -l '' "$a_deplib" name=$func_stripname_result - if test "X$allow_libtool_libs_with_static_runtimes" = "Xyes" ; then + if test yes = "$allow_libtool_libs_with_static_runtimes"; then case " $predeps $postdeps " in *" $a_deplib "*) func_append newdeplibs " $a_deplib" - a_deplib="" + a_deplib= ;; esac fi - if test -n "$a_deplib" ; then + if test -n "$a_deplib"; then libname=`eval "\\$ECHO \"$libname_spec\""` if test -n "$file_magic_glob"; then libnameglob=`func_echo_all "$libname" | $SED -e $file_magic_glob` else libnameglob=$libname fi - test "$want_nocaseglob" = yes && nocaseglob=`shopt -p nocaseglob` + test yes = "$want_nocaseglob" && nocaseglob=`shopt -p nocaseglob` for i in $lib_search_path $sys_lib_search_path $shlib_search_path; do - if test "$want_nocaseglob" = yes; then + if test yes = "$want_nocaseglob"; then shopt -s nocaseglob potential_libs=`ls $i/$libnameglob[.-]* 2>/dev/null` $nocaseglob @@ -7816,25 +9308,25 @@ EOF # We might still enter an endless loop, since a link # loop can be closed while we follow links, # but so what? - potlib="$potent_lib" + potlib=$potent_lib while test -h "$potlib" 2>/dev/null; do - potliblink=`ls -ld $potlib | ${SED} 's/.* -> //'` + potliblink=`ls -ld $potlib | $SED 's/.* -> //'` case $potliblink in - [\\/]* | [A-Za-z]:[\\/]*) potlib="$potliblink";; - *) potlib=`$ECHO "$potlib" | $SED 's,[^/]*$,,'`"$potliblink";; + [\\/]* | [A-Za-z]:[\\/]*) potlib=$potliblink;; + *) potlib=`$ECHO "$potlib" | $SED 's|[^/]*$||'`"$potliblink";; esac done if eval $file_magic_cmd \"\$potlib\" 2>/dev/null | $SED -e 10q | $EGREP "$file_magic_regex" > /dev/null; then func_append newdeplibs " $a_deplib" - a_deplib="" + a_deplib= break 2 fi done done fi - if test -n "$a_deplib" ; then + if test -n "$a_deplib"; then droppeddeps=yes echo $ECHO "*** Warning: linker path does not have real file for library $a_deplib." @@ -7842,7 +9334,7 @@ EOF echo "*** you link to this library. But I can only do this if you have a" echo "*** shared version of the library, which you do not appear to have" echo "*** because I did check the linker path looking for a file starting" - if test -z "$potlib" ; then + if test -z "$potlib"; then $ECHO "*** with $libname but no candidates were found. (...for file magic test)" else $ECHO "*** with $libname and none of the candidates passed a file format test" @@ -7865,30 +9357,30 @@ EOF -l*) func_stripname -l '' "$a_deplib" name=$func_stripname_result - if test "X$allow_libtool_libs_with_static_runtimes" = "Xyes" ; then + if test yes = "$allow_libtool_libs_with_static_runtimes"; then case " $predeps $postdeps " in *" $a_deplib "*) func_append newdeplibs " $a_deplib" - a_deplib="" + a_deplib= ;; esac fi - if test -n "$a_deplib" ; then + if test -n "$a_deplib"; then libname=`eval "\\$ECHO \"$libname_spec\""` for i in $lib_search_path $sys_lib_search_path $shlib_search_path; do potential_libs=`ls $i/$libname[.-]* 2>/dev/null` for potent_lib in $potential_libs; do - potlib="$potent_lib" # see symlink-check above in file_magic test + potlib=$potent_lib # see symlink-check above in file_magic test if eval "\$ECHO \"$potent_lib\"" 2>/dev/null | $SED 10q | \ $EGREP "$match_pattern_regex" > /dev/null; then func_append newdeplibs " $a_deplib" - a_deplib="" + a_deplib= break 2 fi done done fi - if test -n "$a_deplib" ; then + if test -n "$a_deplib"; then droppeddeps=yes echo $ECHO "*** Warning: linker path does not have real file for library $a_deplib." @@ -7896,7 +9388,7 @@ EOF echo "*** you link to this library. But I can only do this if you have a" echo "*** shared version of the library, which you do not appear to have" echo "*** because I did check the linker path looking for a file starting" - if test -z "$potlib" ; then + if test -z "$potlib"; then $ECHO "*** with $libname but no candidates were found. (...for regex pattern test)" else $ECHO "*** with $libname and none of the candidates passed a file format test" @@ -7912,18 +9404,18 @@ EOF done # Gone through all deplibs. ;; none | unknown | *) - newdeplibs="" + newdeplibs= tmp_deplibs=`$ECHO " $deplibs" | $SED 's/ -lc$//; s/ -[LR][^ ]*//g'` - if test "X$allow_libtool_libs_with_static_runtimes" = "Xyes" ; then - for i in $predeps $postdeps ; do + if test yes = "$allow_libtool_libs_with_static_runtimes"; then + for i in $predeps $postdeps; do # can't use Xsed below, because $i might contain '/' - tmp_deplibs=`$ECHO " $tmp_deplibs" | $SED "s,$i,,"` + tmp_deplibs=`$ECHO " $tmp_deplibs" | $SED "s|$i||"` done fi case $tmp_deplibs in *[!\ \ ]*) echo - if test "X$deplibs_check_method" = "Xnone"; then + if test none = "$deplibs_check_method"; then echo "*** Warning: inter-library dependencies are not supported in this platform." else echo "*** Warning: inter-library dependencies are not known to be supported." @@ -7947,8 +9439,8 @@ EOF ;; esac - if test "$droppeddeps" = yes; then - if test "$module" = yes; then + if test yes = "$droppeddeps"; then + if test yes = "$module"; then echo echo "*** Warning: libtool could not satisfy all declared inter-library" $ECHO "*** dependencies of module $libname. Therefore, libtool will create" @@ -7957,12 +9449,12 @@ EOF if test -z "$global_symbol_pipe"; then echo echo "*** However, this would only work if libtool was able to extract symbol" - echo "*** lists from a program, using \`nm' or equivalent, but libtool could" + echo "*** lists from a program, using 'nm' or equivalent, but libtool could" echo "*** not find such a program. So, this module is probably useless." - echo "*** \`nm' from GNU binutils and a full rebuild may help." + echo "*** 'nm' from GNU binutils and a full rebuild may help." fi - if test "$build_old_libs" = no; then - oldlibs="$output_objdir/$libname.$libext" + if test no = "$build_old_libs"; then + oldlibs=$output_objdir/$libname.$libext build_libtool_libs=module build_old_libs=yes else @@ -7973,14 +9465,14 @@ EOF echo "*** automatically added whenever a program is linked with this library" echo "*** or is declared to -dlopen it." - if test "$allow_undefined" = no; then + if test no = "$allow_undefined"; then echo echo "*** Since this library must not contain undefined symbols," echo "*** because either the platform does not support them or" echo "*** it was explicitly requested with -no-undefined," echo "*** libtool will only create a static version of it." - if test "$build_old_libs" = no; then - oldlibs="$output_objdir/$libname.$libext" + if test no = "$build_old_libs"; then + oldlibs=$output_objdir/$libname.$libext build_libtool_libs=module build_old_libs=yes else @@ -8026,7 +9518,7 @@ EOF *) func_append new_libs " $deplib" ;; esac done - deplibs="$new_libs" + deplibs=$new_libs # All the library-specific variables (install_libdir is set above). library_names= @@ -8034,25 +9526,25 @@ EOF dlname= # Test again, we may have decided not to build it any more - if test "$build_libtool_libs" = yes; then - # Remove ${wl} instances when linking with ld. + if test yes = "$build_libtool_libs"; then + # Remove $wl instances when linking with ld. # FIXME: should test the right _cmds variable. case $archive_cmds in *\$LD\ *) wl= ;; esac - if test "$hardcode_into_libs" = yes; then + if test yes = "$hardcode_into_libs"; then # Hardcode the library paths hardcode_libdirs= dep_rpath= - rpath="$finalize_rpath" - test "$opt_mode" != relink && rpath="$compile_rpath$rpath" + rpath=$finalize_rpath + test relink = "$opt_mode" || rpath=$compile_rpath$rpath for libdir in $rpath; do if test -n "$hardcode_libdir_flag_spec"; then if test -n "$hardcode_libdir_separator"; then func_replace_sysroot "$libdir" libdir=$func_replace_sysroot_result if test -z "$hardcode_libdirs"; then - hardcode_libdirs="$libdir" + hardcode_libdirs=$libdir else # Just accumulate the unique libdirs. case $hardcode_libdir_separator$hardcode_libdirs$hardcode_libdir_separator in @@ -8077,7 +9569,7 @@ EOF # Substitute the hardcoded libdirs into the rpath. if test -n "$hardcode_libdir_separator" && test -n "$hardcode_libdirs"; then - libdir="$hardcode_libdirs" + libdir=$hardcode_libdirs eval "dep_rpath=\"$hardcode_libdir_flag_spec\"" fi if test -n "$runpath_var" && test -n "$perm_rpath"; then @@ -8091,8 +9583,8 @@ EOF test -n "$dep_rpath" && deplibs="$dep_rpath $deplibs" fi - shlibpath="$finalize_shlibpath" - test "$opt_mode" != relink && shlibpath="$compile_shlibpath$shlibpath" + shlibpath=$finalize_shlibpath + test relink = "$opt_mode" || shlibpath=$compile_shlibpath$shlibpath if test -n "$shlibpath"; then eval "$shlibpath_var='$shlibpath\$$shlibpath_var'; export $shlibpath_var" fi @@ -8102,19 +9594,19 @@ EOF eval library_names=\"$library_names_spec\" set dummy $library_names shift - realname="$1" + realname=$1 shift if test -n "$soname_spec"; then eval soname=\"$soname_spec\" else - soname="$realname" + soname=$realname fi if test -z "$dlname"; then dlname=$soname fi - lib="$output_objdir/$realname" + lib=$output_objdir/$realname linknames= for link do @@ -8128,7 +9620,7 @@ EOF delfiles= if test -n "$export_symbols" && test -n "$include_expsyms"; then $opt_dry_run || cp "$export_symbols" "$output_objdir/$libname.uexp" - export_symbols="$output_objdir/$libname.uexp" + export_symbols=$output_objdir/$libname.uexp func_append delfiles " $export_symbols" fi @@ -8137,31 +9629,31 @@ EOF cygwin* | mingw* | cegcc*) if test -n "$export_symbols" && test -z "$export_symbols_regex"; then # exporting using user supplied symfile - if test "x`$SED 1q $export_symbols`" != xEXPORTS; then + func_dll_def_p "$export_symbols" || { # and it's NOT already a .def file. Must figure out # which of the given symbols are data symbols and tag # them as such. So, trigger use of export_symbols_cmds. # export_symbols gets reassigned inside the "prepare # the list of exported symbols" if statement, so the # include_expsyms logic still works. - orig_export_symbols="$export_symbols" + orig_export_symbols=$export_symbols export_symbols= always_export_symbols=yes - fi + } fi ;; esac # Prepare the list of exported symbols if test -z "$export_symbols"; then - if test "$always_export_symbols" = yes || test -n "$export_symbols_regex"; then - func_verbose "generating symbol list for \`$libname.la'" - export_symbols="$output_objdir/$libname.exp" + if test yes = "$always_export_symbols" || test -n "$export_symbols_regex"; then + func_verbose "generating symbol list for '$libname.la'" + export_symbols=$output_objdir/$libname.exp $opt_dry_run || $RM $export_symbols cmds=$export_symbols_cmds - save_ifs="$IFS"; IFS='~' + save_ifs=$IFS; IFS='~' for cmd1 in $cmds; do - IFS="$save_ifs" + IFS=$save_ifs # Take the normal branch if the nm_file_list_spec branch # doesn't work or if tool conversion is not needed. case $nm_file_list_spec~$to_tool_file_cmd in @@ -8175,7 +9667,7 @@ EOF try_normal_branch=no ;; esac - if test "$try_normal_branch" = yes \ + if test yes = "$try_normal_branch" \ && { test "$len" -lt "$max_cmd_len" \ || test "$max_cmd_len" -le -1; } then @@ -8186,7 +9678,7 @@ EOF output_la=$func_basename_result save_libobjs=$libobjs save_output=$output - output=${output_objdir}/${output_la}.nm + output=$output_objdir/$output_la.nm func_to_tool_file "$output" libobjs=$nm_file_list_spec$func_to_tool_file_result func_append delfiles " $output" @@ -8209,8 +9701,8 @@ EOF break fi done - IFS="$save_ifs" - if test -n "$export_symbols_regex" && test "X$skipped_export" != "X:"; then + IFS=$save_ifs + if test -n "$export_symbols_regex" && test : != "$skipped_export"; then func_show_eval '$EGREP -e "$export_symbols_regex" "$export_symbols" > "${export_symbols}T"' func_show_eval '$MV "${export_symbols}T" "$export_symbols"' fi @@ -8218,16 +9710,16 @@ EOF fi if test -n "$export_symbols" && test -n "$include_expsyms"; then - tmp_export_symbols="$export_symbols" - test -n "$orig_export_symbols" && tmp_export_symbols="$orig_export_symbols" + tmp_export_symbols=$export_symbols + test -n "$orig_export_symbols" && tmp_export_symbols=$orig_export_symbols $opt_dry_run || eval '$ECHO "$include_expsyms" | $SP2NL >> "$tmp_export_symbols"' fi - if test "X$skipped_export" != "X:" && test -n "$orig_export_symbols"; then + if test : != "$skipped_export" && test -n "$orig_export_symbols"; then # The given exports_symbols file has to be filtered, so filter it. - func_verbose "filter symbol list for \`$libname.la' to tag DATA exports" + func_verbose "filter symbol list for '$libname.la' to tag DATA exports" # FIXME: $output_objdir/$libname.filter potentially contains lots of - # 's' commands which not all seds can handle. GNU sed should be fine + # 's' commands, which not all seds can handle. GNU sed should be fine # though. Also, the filter scales superlinearly with the number of # global variables. join(1) would be nice here, but unfortunately # isn't a blessed tool. @@ -8246,11 +9738,11 @@ EOF ;; esac done - deplibs="$tmp_deplibs" + deplibs=$tmp_deplibs if test -n "$convenience"; then if test -n "$whole_archive_flag_spec" && - test "$compiler_needs_object" = yes && + test yes = "$compiler_needs_object" && test -z "$libobjs"; then # extract the archives, so we have objects to list. # TODO: could optimize this to just extract one archive. @@ -8261,7 +9753,7 @@ EOF eval libobjs=\"\$libobjs $whole_archive_flag_spec\" test "X$libobjs" = "X " && libobjs= else - gentop="$output_objdir/${outputname}x" + gentop=$output_objdir/${outputname}x func_append generated " $gentop" func_extract_archives $gentop $convenience @@ -8270,18 +9762,18 @@ EOF fi fi - if test "$thread_safe" = yes && test -n "$thread_safe_flag_spec"; then + if test yes = "$thread_safe" && test -n "$thread_safe_flag_spec"; then eval flag=\"$thread_safe_flag_spec\" func_append linker_flags " $flag" fi # Make a backup of the uninstalled library when relinking - if test "$opt_mode" = relink; then + if test relink = "$opt_mode"; then $opt_dry_run || eval '(cd $output_objdir && $RM ${realname}U && $MV $realname ${realname}U)' || exit $? fi # Do each of the archive commands. - if test "$module" = yes && test -n "$module_cmds" ; then + if test yes = "$module" && test -n "$module_cmds"; then if test -n "$export_symbols" && test -n "$module_expsym_cmds"; then eval test_cmds=\"$module_expsym_cmds\" cmds=$module_expsym_cmds @@ -8299,7 +9791,7 @@ EOF fi fi - if test "X$skipped_export" != "X:" && + if test : != "$skipped_export" && func_len " $test_cmds" && len=$func_len_result && test "$len" -lt "$max_cmd_len" || test "$max_cmd_len" -le -1; then @@ -8332,8 +9824,8 @@ EOF last_robj= k=1 - if test -n "$save_libobjs" && test "X$skipped_export" != "X:" && test "$with_gnu_ld" = yes; then - output=${output_objdir}/${output_la}.lnkscript + if test -n "$save_libobjs" && test : != "$skipped_export" && test yes = "$with_gnu_ld"; then + output=$output_objdir/$output_la.lnkscript func_verbose "creating GNU ld script: $output" echo 'INPUT (' > $output for obj in $save_libobjs @@ -8345,14 +9837,14 @@ EOF func_append delfiles " $output" func_to_tool_file "$output" output=$func_to_tool_file_result - elif test -n "$save_libobjs" && test "X$skipped_export" != "X:" && test "X$file_list_spec" != X; then - output=${output_objdir}/${output_la}.lnk + elif test -n "$save_libobjs" && test : != "$skipped_export" && test -n "$file_list_spec"; then + output=$output_objdir/$output_la.lnk func_verbose "creating linker input file list: $output" : > $output set x $save_libobjs shift firstobj= - if test "$compiler_needs_object" = yes; then + if test yes = "$compiler_needs_object"; then firstobj="$1 " shift fi @@ -8367,7 +9859,7 @@ EOF else if test -n "$save_libobjs"; then func_verbose "creating reloadable object files..." - output=$output_objdir/$output_la-${k}.$objext + output=$output_objdir/$output_la-$k.$objext eval test_cmds=\"$reload_cmds\" func_len " $test_cmds" len0=$func_len_result @@ -8379,13 +9871,13 @@ EOF func_len " $obj" func_arith $len + $func_len_result len=$func_arith_result - if test "X$objlist" = X || + if test -z "$objlist" || test "$len" -lt "$max_cmd_len"; then func_append objlist " $obj" else # The command $test_cmds is almost too long, add a # command to the queue. - if test "$k" -eq 1 ; then + if test 1 -eq "$k"; then # The first file doesn't have a previous command to add. reload_objs=$objlist eval concat_cmds=\"$reload_cmds\" @@ -8395,10 +9887,10 @@ EOF reload_objs="$objlist $last_robj" eval concat_cmds=\"\$concat_cmds~$reload_cmds~\$RM $last_robj\" fi - last_robj=$output_objdir/$output_la-${k}.$objext + last_robj=$output_objdir/$output_la-$k.$objext func_arith $k + 1 k=$func_arith_result - output=$output_objdir/$output_la-${k}.$objext + output=$output_objdir/$output_la-$k.$objext objlist=" $obj" func_len " $last_robj" func_arith $len0 + $func_len_result @@ -8410,9 +9902,9 @@ EOF # files will link in the last one created. test -z "$concat_cmds" || concat_cmds=$concat_cmds~ reload_objs="$objlist $last_robj" - eval concat_cmds=\"\${concat_cmds}$reload_cmds\" + eval concat_cmds=\"\$concat_cmds$reload_cmds\" if test -n "$last_robj"; then - eval concat_cmds=\"\${concat_cmds}~\$RM $last_robj\" + eval concat_cmds=\"\$concat_cmds~\$RM $last_robj\" fi func_append delfiles " $output" @@ -8420,9 +9912,9 @@ EOF output= fi - if ${skipped_export-false}; then - func_verbose "generating symbol list for \`$libname.la'" - export_symbols="$output_objdir/$libname.exp" + ${skipped_export-false} && { + func_verbose "generating symbol list for '$libname.la'" + export_symbols=$output_objdir/$libname.exp $opt_dry_run || $RM $export_symbols libobjs=$output # Append the command to create the export file. @@ -8431,16 +9923,16 @@ EOF if test -n "$last_robj"; then eval concat_cmds=\"\$concat_cmds~\$RM $last_robj\" fi - fi + } test -n "$save_libobjs" && func_verbose "creating a temporary reloadable object file: $output" # Loop through the commands generated above and execute them. - save_ifs="$IFS"; IFS='~' + save_ifs=$IFS; IFS='~' for cmd in $concat_cmds; do - IFS="$save_ifs" - $opt_silent || { + IFS=$save_ifs + $opt_quiet || { func_quote_for_expand "$cmd" eval "func_echo $func_quote_for_expand_result" } @@ -8448,7 +9940,7 @@ EOF lt_exit=$? # Restore the uninstalled library and exit - if test "$opt_mode" = relink; then + if test relink = "$opt_mode"; then ( cd "$output_objdir" && \ $RM "${realname}T" && \ $MV "${realname}U" "$realname" ) @@ -8457,7 +9949,7 @@ EOF exit $lt_exit } done - IFS="$save_ifs" + IFS=$save_ifs if test -n "$export_symbols_regex" && ${skipped_export-false}; then func_show_eval '$EGREP -e "$export_symbols_regex" "$export_symbols" > "${export_symbols}T"' @@ -8465,18 +9957,18 @@ EOF fi fi - if ${skipped_export-false}; then + ${skipped_export-false} && { if test -n "$export_symbols" && test -n "$include_expsyms"; then - tmp_export_symbols="$export_symbols" - test -n "$orig_export_symbols" && tmp_export_symbols="$orig_export_symbols" + tmp_export_symbols=$export_symbols + test -n "$orig_export_symbols" && tmp_export_symbols=$orig_export_symbols $opt_dry_run || eval '$ECHO "$include_expsyms" | $SP2NL >> "$tmp_export_symbols"' fi if test -n "$orig_export_symbols"; then # The given exports_symbols file has to be filtered, so filter it. - func_verbose "filter symbol list for \`$libname.la' to tag DATA exports" + func_verbose "filter symbol list for '$libname.la' to tag DATA exports" # FIXME: $output_objdir/$libname.filter potentially contains lots of - # 's' commands which not all seds can handle. GNU sed should be fine + # 's' commands, which not all seds can handle. GNU sed should be fine # though. Also, the filter scales superlinearly with the number of # global variables. join(1) would be nice here, but unfortunately # isn't a blessed tool. @@ -8485,7 +9977,7 @@ EOF export_symbols=$output_objdir/$libname.def $opt_dry_run || $SED -f $output_objdir/$libname.filter < $orig_export_symbols > $export_symbols fi - fi + } libobjs=$output # Restore the value of output. @@ -8499,7 +9991,7 @@ EOF # value of $libobjs for piecewise linking. # Do each of the archive commands. - if test "$module" = yes && test -n "$module_cmds" ; then + if test yes = "$module" && test -n "$module_cmds"; then if test -n "$export_symbols" && test -n "$module_expsym_cmds"; then cmds=$module_expsym_cmds else @@ -8521,7 +10013,7 @@ EOF # Add any objects from preloaded convenience libraries if test -n "$dlprefiles"; then - gentop="$output_objdir/${outputname}x" + gentop=$output_objdir/${outputname}x func_append generated " $gentop" func_extract_archives $gentop $dlprefiles @@ -8529,11 +10021,12 @@ EOF test "X$libobjs" = "X " && libobjs= fi - save_ifs="$IFS"; IFS='~' + save_ifs=$IFS; IFS='~' for cmd in $cmds; do - IFS="$save_ifs" + IFS=$sp$nl eval cmd=\"$cmd\" - $opt_silent || { + IFS=$save_ifs + $opt_quiet || { func_quote_for_expand "$cmd" eval "func_echo $func_quote_for_expand_result" } @@ -8541,7 +10034,7 @@ EOF lt_exit=$? # Restore the uninstalled library and exit - if test "$opt_mode" = relink; then + if test relink = "$opt_mode"; then ( cd "$output_objdir" && \ $RM "${realname}T" && \ $MV "${realname}U" "$realname" ) @@ -8550,10 +10043,10 @@ EOF exit $lt_exit } done - IFS="$save_ifs" + IFS=$save_ifs # Restore the uninstalled library and exit - if test "$opt_mode" = relink; then + if test relink = "$opt_mode"; then $opt_dry_run || eval '(cd $output_objdir && $RM ${realname}T && $MV $realname ${realname}T && $MV ${realname}U $realname)' || exit $? if test -n "$convenience"; then @@ -8573,39 +10066,39 @@ EOF done # If -module or -export-dynamic was specified, set the dlname. - if test "$module" = yes || test "$export_dynamic" = yes; then + if test yes = "$module" || test yes = "$export_dynamic"; then # On all known operating systems, these are identical. - dlname="$soname" + dlname=$soname fi fi ;; obj) - if test -n "$dlfiles$dlprefiles" || test "$dlself" != no; then - func_warning "\`-dlopen' is ignored for objects" + if test -n "$dlfiles$dlprefiles" || test no != "$dlself"; then + func_warning "'-dlopen' is ignored for objects" fi case " $deplibs" in *\ -l* | *\ -L*) - func_warning "\`-l' and \`-L' are ignored for objects" ;; + func_warning "'-l' and '-L' are ignored for objects" ;; esac test -n "$rpath" && \ - func_warning "\`-rpath' is ignored for objects" + func_warning "'-rpath' is ignored for objects" test -n "$xrpath" && \ - func_warning "\`-R' is ignored for objects" + func_warning "'-R' is ignored for objects" test -n "$vinfo" && \ - func_warning "\`-version-info' is ignored for objects" + func_warning "'-version-info' is ignored for objects" test -n "$release" && \ - func_warning "\`-release' is ignored for objects" + func_warning "'-release' is ignored for objects" case $output in *.lo) test -n "$objs$old_deplibs" && \ - func_fatal_error "cannot build library object \`$output' from non-libtool objects" + func_fatal_error "cannot build library object '$output' from non-libtool objects" libobj=$output func_lo2o "$libobj" @@ -8613,7 +10106,7 @@ EOF ;; *) libobj= - obj="$output" + obj=$output ;; esac @@ -8626,17 +10119,19 @@ EOF # the extraction. reload_conv_objs= gentop= - # reload_cmds runs $LD directly, so let us get rid of - # -Wl from whole_archive_flag_spec and hope we can get by with - # turning comma into space.. - wl= - + # if reload_cmds runs $LD directly, get rid of -Wl from + # whole_archive_flag_spec and hope we can get by with turning comma + # into space. + case $reload_cmds in + *\$LD[\ \$]*) wl= ;; + esac if test -n "$convenience"; then if test -n "$whole_archive_flag_spec"; then eval tmp_whole_archive_flags=\"$whole_archive_flag_spec\" - reload_conv_objs=$reload_objs\ `$ECHO "$tmp_whole_archive_flags" | $SED 's|,| |g'` + test -n "$wl" || tmp_whole_archive_flags=`$ECHO "$tmp_whole_archive_flags" | $SED 's|,| |g'` + reload_conv_objs=$reload_objs\ $tmp_whole_archive_flags else - gentop="$output_objdir/${obj}x" + gentop=$output_objdir/${obj}x func_append generated " $gentop" func_extract_archives $gentop $convenience @@ -8645,12 +10140,12 @@ EOF fi # If we're not building shared, we need to use non_pic_objs - test "$build_libtool_libs" != yes && libobjs="$non_pic_objects" + test yes = "$build_libtool_libs" || libobjs=$non_pic_objects # Create the old-style object. - reload_objs="$objs$old_deplibs "`$ECHO "$libobjs" | $SP2NL | $SED "/\.${libext}$/d; /\.lib$/d; $lo2o" | $NL2SP`" $reload_conv_objs" ### testsuite: skip nested quoting test + reload_objs=$objs$old_deplibs' '`$ECHO "$libobjs" | $SP2NL | $SED "/\.$libext$/d; /\.lib$/d; $lo2o" | $NL2SP`' '$reload_conv_objs - output="$obj" + output=$obj func_execute_cmds "$reload_cmds" 'exit $?' # Exit if we aren't doing a library object file. @@ -8662,7 +10157,7 @@ EOF exit $EXIT_SUCCESS fi - if test "$build_libtool_libs" != yes; then + test yes = "$build_libtool_libs" || { if test -n "$gentop"; then func_show_eval '${RM}r "$gentop"' fi @@ -8672,12 +10167,12 @@ EOF # $show "echo timestamp > $libobj" # $opt_dry_run || eval "echo timestamp > $libobj" || exit $? exit $EXIT_SUCCESS - fi + } - if test -n "$pic_flag" || test "$pic_mode" != default; then + if test -n "$pic_flag" || test default != "$pic_mode"; then # Only do commands if we really have different PIC objects. reload_objs="$libobjs $reload_conv_objs" - output="$libobj" + output=$libobj func_execute_cmds "$reload_cmds" 'exit $?' fi @@ -8694,16 +10189,14 @@ EOF output=$func_stripname_result.exe;; esac test -n "$vinfo" && \ - func_warning "\`-version-info' is ignored for programs" + func_warning "'-version-info' is ignored for programs" test -n "$release" && \ - func_warning "\`-release' is ignored for programs" + func_warning "'-release' is ignored for programs" - test "$preload" = yes \ - && test "$dlopen_support" = unknown \ - && test "$dlopen_self" = unknown \ - && test "$dlopen_self_static" = unknown && \ - func_warning "\`LT_INIT([dlopen])' not used. Assuming no dlopen support." + $preload \ + && test unknown,unknown,unknown = "$dlopen_support,$dlopen_self,$dlopen_self_static" \ + && func_warning "'LT_INIT([dlopen])' not used. Assuming no dlopen support." case $host in *-*-rhapsody* | *-*-darwin1.[012]) @@ -8717,11 +10210,11 @@ EOF *-*-darwin*) # Don't allow lazy linking, it breaks C++ global constructors # But is supposedly fixed on 10.4 or later (yay!). - if test "$tagname" = CXX ; then + if test CXX = "$tagname"; then case ${MACOSX_DEPLOYMENT_TARGET-10.0} in 10.[0123]) - func_append compile_command " ${wl}-bind_at_load" - func_append finalize_command " ${wl}-bind_at_load" + func_append compile_command " $wl-bind_at_load" + func_append finalize_command " $wl-bind_at_load" ;; esac fi @@ -8757,7 +10250,7 @@ EOF *) func_append new_libs " $deplib" ;; esac done - compile_deplibs="$new_libs" + compile_deplibs=$new_libs func_append compile_command " $compile_deplibs" @@ -8781,7 +10274,7 @@ EOF if test -n "$hardcode_libdir_flag_spec"; then if test -n "$hardcode_libdir_separator"; then if test -z "$hardcode_libdirs"; then - hardcode_libdirs="$libdir" + hardcode_libdirs=$libdir else # Just accumulate the unique libdirs. case $hardcode_libdir_separator$hardcode_libdirs$hardcode_libdir_separator in @@ -8804,7 +10297,7 @@ EOF fi case $host in *-*-cygwin* | *-*-mingw* | *-*-pw32* | *-*-os2* | *-cegcc*) - testbindir=`${ECHO} "$libdir" | ${SED} -e 's*/lib$*/bin*'` + testbindir=`$ECHO "$libdir" | $SED -e 's*/lib$*/bin*'` case :$dllsearchpath: in *":$libdir:"*) ;; ::) dllsearchpath=$libdir;; @@ -8821,10 +10314,10 @@ EOF # Substitute the hardcoded libdirs into the rpath. if test -n "$hardcode_libdir_separator" && test -n "$hardcode_libdirs"; then - libdir="$hardcode_libdirs" + libdir=$hardcode_libdirs eval rpath=\" $hardcode_libdir_flag_spec\" fi - compile_rpath="$rpath" + compile_rpath=$rpath rpath= hardcode_libdirs= @@ -8832,7 +10325,7 @@ EOF if test -n "$hardcode_libdir_flag_spec"; then if test -n "$hardcode_libdir_separator"; then if test -z "$hardcode_libdirs"; then - hardcode_libdirs="$libdir" + hardcode_libdirs=$libdir else # Just accumulate the unique libdirs. case $hardcode_libdir_separator$hardcode_libdirs$hardcode_libdir_separator in @@ -8857,45 +10350,43 @@ EOF # Substitute the hardcoded libdirs into the rpath. if test -n "$hardcode_libdir_separator" && test -n "$hardcode_libdirs"; then - libdir="$hardcode_libdirs" + libdir=$hardcode_libdirs eval rpath=\" $hardcode_libdir_flag_spec\" fi - finalize_rpath="$rpath" + finalize_rpath=$rpath - if test -n "$libobjs" && test "$build_old_libs" = yes; then + if test -n "$libobjs" && test yes = "$build_old_libs"; then # Transform all the library objects into standard objects. compile_command=`$ECHO "$compile_command" | $SP2NL | $SED "$lo2o" | $NL2SP` finalize_command=`$ECHO "$finalize_command" | $SP2NL | $SED "$lo2o" | $NL2SP` fi - func_generate_dlsyms "$outputname" "@PROGRAM@" "no" + func_generate_dlsyms "$outputname" "@PROGRAM@" false # template prelinking step if test -n "$prelink_cmds"; then func_execute_cmds "$prelink_cmds" 'exit $?' fi - wrappers_required=yes + wrappers_required=: case $host in *cegcc* | *mingw32ce*) # Disable wrappers for cegcc and mingw32ce hosts, we are cross compiling anyway. - wrappers_required=no + wrappers_required=false ;; *cygwin* | *mingw* ) - if test "$build_libtool_libs" != yes; then - wrappers_required=no - fi + test yes = "$build_libtool_libs" || wrappers_required=false ;; *) - if test "$need_relink" = no || test "$build_libtool_libs" != yes; then - wrappers_required=no + if test no = "$need_relink" || test yes != "$build_libtool_libs"; then + wrappers_required=false fi ;; esac - if test "$wrappers_required" = no; then + $wrappers_required || { # Replace the output file specification. compile_command=`$ECHO "$compile_command" | $SED 's%@OUTPUT@%'"$output"'%g'` - link_command="$compile_command$compile_rpath" + link_command=$compile_command$compile_rpath # We have no uninstalled library dependencies, so finalize right now. exit_status=0 @@ -8908,12 +10399,12 @@ EOF fi # Delete the generated files. - if test -f "$output_objdir/${outputname}S.${objext}"; then - func_show_eval '$RM "$output_objdir/${outputname}S.${objext}"' + if test -f "$output_objdir/${outputname}S.$objext"; then + func_show_eval '$RM "$output_objdir/${outputname}S.$objext"' fi exit $exit_status - fi + } if test -n "$compile_shlibpath$finalize_shlibpath"; then compile_command="$shlibpath_var=\"$compile_shlibpath$finalize_shlibpath\$$shlibpath_var\" $compile_command" @@ -8943,9 +10434,9 @@ EOF fi fi - if test "$no_install" = yes; then + if test yes = "$no_install"; then # We don't need to create a wrapper script. - link_command="$compile_var$compile_command$compile_rpath" + link_command=$compile_var$compile_command$compile_rpath # Replace the output file specification. link_command=`$ECHO "$link_command" | $SED 's%@OUTPUT@%'"$output"'%g'` # Delete the old output file. @@ -8962,27 +10453,28 @@ EOF exit $EXIT_SUCCESS fi - if test "$hardcode_action" = relink; then - # Fast installation is not supported - link_command="$compile_var$compile_command$compile_rpath" - relink_command="$finalize_var$finalize_command$finalize_rpath" + case $hardcode_action,$fast_install in + relink,*) + # Fast installation is not supported + link_command=$compile_var$compile_command$compile_rpath + relink_command=$finalize_var$finalize_command$finalize_rpath - func_warning "this platform does not like uninstalled shared libraries" - func_warning "\`$output' will be relinked during installation" - else - if test "$fast_install" != no; then - link_command="$finalize_var$compile_command$finalize_rpath" - if test "$fast_install" = yes; then - relink_command=`$ECHO "$compile_var$compile_command$compile_rpath" | $SED 's%@OUTPUT@%\$progdir/\$file%g'` - else - # fast_install is set to needless - relink_command= - fi - else - link_command="$compile_var$compile_command$compile_rpath" - relink_command="$finalize_var$finalize_command$finalize_rpath" - fi - fi + func_warning "this platform does not like uninstalled shared libraries" + func_warning "'$output' will be relinked during installation" + ;; + *,yes) + link_command=$finalize_var$compile_command$finalize_rpath + relink_command=`$ECHO "$compile_var$compile_command$compile_rpath" | $SED 's%@OUTPUT@%\$progdir/\$file%g'` + ;; + *,no) + link_command=$compile_var$compile_command$compile_rpath + relink_command=$finalize_var$finalize_command$finalize_rpath + ;; + *,needless) + link_command=$finalize_var$compile_command$finalize_rpath + relink_command= + ;; + esac # Replace the output file specification. link_command=`$ECHO "$link_command" | $SED 's%@OUTPUT@%'"$output_objdir/$outputname"'%g'` @@ -9039,8 +10531,8 @@ EOF func_dirname_and_basename "$output" "" "." output_name=$func_basename_result output_path=$func_dirname_result - cwrappersource="$output_path/$objdir/lt-$output_name.c" - cwrapper="$output_path/$output_name.exe" + cwrappersource=$output_path/$objdir/lt-$output_name.c + cwrapper=$output_path/$output_name.exe $RM $cwrappersource $cwrapper trap "$RM $cwrappersource $cwrapper; exit $EXIT_FAILURE" 1 2 15 @@ -9061,7 +10553,7 @@ EOF trap "$RM $func_ltwrapper_scriptname_result; exit $EXIT_FAILURE" 1 2 15 $opt_dry_run || { # note: this script will not be executed, so do not chmod. - if test "x$build" = "x$host" ; then + if test "x$build" = "x$host"; then $cwrapper --lt-dump-script > $func_ltwrapper_scriptname_result else func_emit_wrapper no > $func_ltwrapper_scriptname_result @@ -9084,25 +10576,27 @@ EOF # See if we need to build an old-fashioned archive. for oldlib in $oldlibs; do - if test "$build_libtool_libs" = convenience; then - oldobjs="$libobjs_save $symfileobj" - addlibs="$convenience" - build_libtool_libs=no - else - if test "$build_libtool_libs" = module; then - oldobjs="$libobjs_save" + case $build_libtool_libs in + convenience) + oldobjs="$libobjs_save $symfileobj" + addlibs=$convenience build_libtool_libs=no - else + ;; + module) + oldobjs=$libobjs_save + addlibs=$old_convenience + build_libtool_libs=no + ;; + *) oldobjs="$old_deplibs $non_pic_objects" - if test "$preload" = yes && test -f "$symfileobj"; then - func_append oldobjs " $symfileobj" - fi - fi - addlibs="$old_convenience" - fi + $preload && test -f "$symfileobj" \ + && func_append oldobjs " $symfileobj" + addlibs=$old_convenience + ;; + esac if test -n "$addlibs"; then - gentop="$output_objdir/${outputname}x" + gentop=$output_objdir/${outputname}x func_append generated " $gentop" func_extract_archives $gentop $addlibs @@ -9110,13 +10604,13 @@ EOF fi # Do each command in the archive commands. - if test -n "$old_archive_from_new_cmds" && test "$build_libtool_libs" = yes; then + if test -n "$old_archive_from_new_cmds" && test yes = "$build_libtool_libs"; then cmds=$old_archive_from_new_cmds else # Add any objects from preloaded convenience libraries if test -n "$dlprefiles"; then - gentop="$output_objdir/${outputname}x" + gentop=$output_objdir/${outputname}x func_append generated " $gentop" func_extract_archives $gentop $dlprefiles @@ -9137,7 +10631,7 @@ EOF : else echo "copying selected object files to avoid basename conflicts..." - gentop="$output_objdir/${outputname}x" + gentop=$output_objdir/${outputname}x func_append generated " $gentop" func_mkdir_p "$gentop" save_oldobjs=$oldobjs @@ -9146,7 +10640,7 @@ EOF for obj in $save_oldobjs do func_basename "$obj" - objbase="$func_basename_result" + objbase=$func_basename_result case " $oldobjs " in " ") oldobjs=$obj ;; *[\ /]"$objbase "*) @@ -9215,18 +10709,18 @@ EOF else # the above command should be used before it gets too long oldobjs=$objlist - if test "$obj" = "$last_oldobj" ; then + if test "$obj" = "$last_oldobj"; then RANLIB=$save_RANLIB fi test -z "$concat_cmds" || concat_cmds=$concat_cmds~ - eval concat_cmds=\"\${concat_cmds}$old_archive_cmds\" + eval concat_cmds=\"\$concat_cmds$old_archive_cmds\" objlist= len=$len0 fi done RANLIB=$save_RANLIB oldobjs=$objlist - if test "X$oldobjs" = "X" ; then + if test -z "$oldobjs"; then eval cmds=\"\$concat_cmds\" else eval cmds=\"\$concat_cmds~\$old_archive_cmds\" @@ -9243,7 +10737,7 @@ EOF case $output in *.la) old_library= - test "$build_old_libs" = yes && old_library="$libname.$libext" + test yes = "$build_old_libs" && old_library=$libname.$libext func_verbose "creating $output" # Preserve any variables that may affect compiler behavior @@ -9258,31 +10752,31 @@ EOF fi done # Quote the link command for shipping. - relink_command="(cd `pwd`; $SHELL $progpath $preserve_args --mode=relink $libtool_args @inst_prefix_dir@)" + relink_command="(cd `pwd`; $SHELL \"$progpath\" $preserve_args --mode=relink $libtool_args @inst_prefix_dir@)" relink_command=`$ECHO "$relink_command" | $SED "$sed_quote_subst"` - if test "$hardcode_automatic" = yes ; then + if test yes = "$hardcode_automatic"; then relink_command= fi # Only create the output if not a dry run. $opt_dry_run || { for installed in no yes; do - if test "$installed" = yes; then + if test yes = "$installed"; then if test -z "$install_libdir"; then break fi - output="$output_objdir/$outputname"i + output=$output_objdir/${outputname}i # Replace all uninstalled libtool libraries with the installed ones newdependency_libs= for deplib in $dependency_libs; do case $deplib in *.la) func_basename "$deplib" - name="$func_basename_result" + name=$func_basename_result func_resolve_sysroot "$deplib" - eval libdir=`${SED} -n -e 's/^libdir=\(.*\)$/\1/p' $func_resolve_sysroot_result` + eval libdir=`$SED -n -e 's/^libdir=\(.*\)$/\1/p' $func_resolve_sysroot_result` test -z "$libdir" && \ - func_fatal_error "\`$deplib' is not a valid libtool archive" + func_fatal_error "'$deplib' is not a valid libtool archive" func_append newdependency_libs " ${lt_sysroot:+=}$libdir/$name" ;; -L*) @@ -9298,23 +10792,23 @@ EOF *) func_append newdependency_libs " $deplib" ;; esac done - dependency_libs="$newdependency_libs" + dependency_libs=$newdependency_libs newdlfiles= for lib in $dlfiles; do case $lib in *.la) func_basename "$lib" - name="$func_basename_result" - eval libdir=`${SED} -n -e 's/^libdir=\(.*\)$/\1/p' $lib` + name=$func_basename_result + eval libdir=`$SED -n -e 's/^libdir=\(.*\)$/\1/p' $lib` test -z "$libdir" && \ - func_fatal_error "\`$lib' is not a valid libtool archive" + func_fatal_error "'$lib' is not a valid libtool archive" func_append newdlfiles " ${lt_sysroot:+=}$libdir/$name" ;; *) func_append newdlfiles " $lib" ;; esac done - dlfiles="$newdlfiles" + dlfiles=$newdlfiles newdlprefiles= for lib in $dlprefiles; do case $lib in @@ -9324,34 +10818,34 @@ EOF # didn't already link the preopened objects directly into # the library: func_basename "$lib" - name="$func_basename_result" - eval libdir=`${SED} -n -e 's/^libdir=\(.*\)$/\1/p' $lib` + name=$func_basename_result + eval libdir=`$SED -n -e 's/^libdir=\(.*\)$/\1/p' $lib` test -z "$libdir" && \ - func_fatal_error "\`$lib' is not a valid libtool archive" + func_fatal_error "'$lib' is not a valid libtool archive" func_append newdlprefiles " ${lt_sysroot:+=}$libdir/$name" ;; esac done - dlprefiles="$newdlprefiles" + dlprefiles=$newdlprefiles else newdlfiles= for lib in $dlfiles; do case $lib in - [\\/]* | [A-Za-z]:[\\/]*) abs="$lib" ;; + [\\/]* | [A-Za-z]:[\\/]*) abs=$lib ;; *) abs=`pwd`"/$lib" ;; esac func_append newdlfiles " $abs" done - dlfiles="$newdlfiles" + dlfiles=$newdlfiles newdlprefiles= for lib in $dlprefiles; do case $lib in - [\\/]* | [A-Za-z]:[\\/]*) abs="$lib" ;; + [\\/]* | [A-Za-z]:[\\/]*) abs=$lib ;; *) abs=`pwd`"/$lib" ;; esac func_append newdlprefiles " $abs" done - dlprefiles="$newdlprefiles" + dlprefiles=$newdlprefiles fi $RM $output # place dlname in correct position for cygwin @@ -9367,10 +10861,9 @@ EOF case $host,$output,$installed,$module,$dlname in *cygwin*,*lai,yes,no,*.dll | *mingw*,*lai,yes,no,*.dll | *cegcc*,*lai,yes,no,*.dll) # If a -bindir argument was supplied, place the dll there. - if test "x$bindir" != x ; - then + if test -n "$bindir"; then func_relative_path "$install_libdir" "$bindir" - tdlname=$func_relative_path_result$dlname + tdlname=$func_relative_path_result/$dlname else # Otherwise fall back on heuristic. tdlname=../bin/$dlname @@ -9379,7 +10872,7 @@ EOF esac $ECHO > $output "\ # $outputname - a libtool library file -# Generated by $PROGRAM (GNU $PACKAGE$TIMESTAMP) $VERSION +# Generated by $PROGRAM (GNU $PACKAGE) $VERSION # # Please DO NOT delete this file! # It is necessary for linking the library. @@ -9393,7 +10886,7 @@ library_names='$library_names' # The name of the static archive. old_library='$old_library' -# Linker flags that can not go in dependency_libs. +# Linker flags that cannot go in dependency_libs. inherited_linker_flags='$new_inherited_linker_flags' # Libraries that this one depends upon. @@ -9419,7 +10912,7 @@ dlpreopen='$dlprefiles' # Directory that this library needs to be installed in: libdir='$install_libdir'" - if test "$installed" = no && test "$need_relink" = yes; then + if test no,yes = "$installed,$need_relink"; then $ECHO >> $output "\ relink_command=\"$relink_command\"" fi @@ -9434,27 +10927,29 @@ relink_command=\"$relink_command\"" exit $EXIT_SUCCESS } -{ test "$opt_mode" = link || test "$opt_mode" = relink; } && - func_mode_link ${1+"$@"} +if test link = "$opt_mode" || test relink = "$opt_mode"; then + func_mode_link ${1+"$@"} +fi # func_mode_uninstall arg... func_mode_uninstall () { - $opt_debug - RM="$nonopt" + $debug_cmd + + RM=$nonopt files= - rmforce= + rmforce=false exit_status=0 # This variable tells wrapper scripts just to set variables rather # than running their programs. - libtool_install_magic="$magic" + libtool_install_magic=$magic for arg do case $arg in - -f) func_append RM " $arg"; rmforce=yes ;; + -f) func_append RM " $arg"; rmforce=: ;; -*) func_append RM " $arg" ;; *) func_append files " $arg" ;; esac @@ -9467,18 +10962,18 @@ func_mode_uninstall () for file in $files; do func_dirname "$file" "" "." - dir="$func_dirname_result" - if test "X$dir" = X.; then - odir="$objdir" + dir=$func_dirname_result + if test . = "$dir"; then + odir=$objdir else - odir="$dir/$objdir" + odir=$dir/$objdir fi func_basename "$file" - name="$func_basename_result" - test "$opt_mode" = uninstall && odir="$dir" + name=$func_basename_result + test uninstall = "$opt_mode" && odir=$dir # Remember odir for removal later, being careful to avoid duplicates - if test "$opt_mode" = clean; then + if test clean = "$opt_mode"; then case " $rmdirs " in *" $odir "*) ;; *) func_append rmdirs " $odir" ;; @@ -9493,11 +10988,11 @@ func_mode_uninstall () elif test -d "$file"; then exit_status=1 continue - elif test "$rmforce" = yes; then + elif $rmforce; then continue fi - rmfiles="$file" + rmfiles=$file case $name in *.la) @@ -9511,7 +11006,7 @@ func_mode_uninstall () done test -n "$old_library" && func_append rmfiles " $odir/$old_library" - case "$opt_mode" in + case $opt_mode in clean) case " $library_names " in *" $dlname "*) ;; @@ -9522,12 +11017,12 @@ func_mode_uninstall () uninstall) if test -n "$library_names"; then # Do each command in the postuninstall commands. - func_execute_cmds "$postuninstall_cmds" 'test "$rmforce" = yes || exit_status=1' + func_execute_cmds "$postuninstall_cmds" '$rmforce || exit_status=1' fi if test -n "$old_library"; then # Do each command in the old_postuninstall commands. - func_execute_cmds "$old_postuninstall_cmds" 'test "$rmforce" = yes || exit_status=1' + func_execute_cmds "$old_postuninstall_cmds" '$rmforce || exit_status=1' fi # FIXME: should reinstall the best remaining shared library. ;; @@ -9543,21 +11038,19 @@ func_mode_uninstall () func_source $dir/$name # Add PIC object to the list of files to remove. - if test -n "$pic_object" && - test "$pic_object" != none; then + if test -n "$pic_object" && test none != "$pic_object"; then func_append rmfiles " $dir/$pic_object" fi # Add non-PIC object to the list of files to remove. - if test -n "$non_pic_object" && - test "$non_pic_object" != none; then + if test -n "$non_pic_object" && test none != "$non_pic_object"; then func_append rmfiles " $dir/$non_pic_object" fi fi ;; *) - if test "$opt_mode" = clean ; then + if test clean = "$opt_mode"; then noexename=$name case $file in *.exe) @@ -9584,12 +11077,12 @@ func_mode_uninstall () # note $name still contains .exe if it was in $file originally # as does the version of $file that was added into $rmfiles - func_append rmfiles " $odir/$name $odir/${name}S.${objext}" - if test "$fast_install" = yes && test -n "$relink_command"; then + func_append rmfiles " $odir/$name $odir/${name}S.$objext" + if test yes = "$fast_install" && test -n "$relink_command"; then func_append rmfiles " $odir/lt-$name" fi - if test "X$noexename" != "X$name" ; then - func_append rmfiles " $odir/lt-${noexename}.c" + if test "X$noexename" != "X$name"; then + func_append rmfiles " $odir/lt-$noexename.c" fi fi fi @@ -9598,7 +11091,7 @@ func_mode_uninstall () func_show_eval "$RM $rmfiles" 'exit_status=1' done - # Try to remove the ${objdir}s in the directories where we deleted files + # Try to remove the $objdir's in the directories where we deleted files for dir in $rmdirs; do if test -d "$dir"; then func_show_eval "rmdir $dir >/dev/null 2>&1" @@ -9608,16 +11101,17 @@ func_mode_uninstall () exit $exit_status } -{ test "$opt_mode" = uninstall || test "$opt_mode" = clean; } && - func_mode_uninstall ${1+"$@"} +if test uninstall = "$opt_mode" || test clean = "$opt_mode"; then + func_mode_uninstall ${1+"$@"} +fi test -z "$opt_mode" && { - help="$generic_help" + help=$generic_help func_fatal_help "you must specify a MODE" } test -z "$exec_cmd" && \ - func_fatal_help "invalid operation mode \`$opt_mode'" + func_fatal_help "invalid operation mode '$opt_mode'" if test -n "$exec_cmd"; then eval exec "$exec_cmd" @@ -9628,7 +11122,7 @@ exit $exit_status # The TAGs below are defined such that we never get into a situation -# in which we disable both kinds of libraries. Given conflicting +# where we disable both kinds of libraries. Given conflicting # choices, we go for a static library, that is the most portable, # since we can't tell whether shared libraries were disabled because # the user asked for that or because the platform doesn't support @@ -9651,5 +11145,3 @@ build_old_libs=`case $build_libtool_libs in yes) echo no;; *) echo yes;; esac` # mode:shell-script # sh-indentation:2 # End: -# vi:sw=2 - diff --git a/gtsam/3rdparty/GeographicLib/m4/libtool.m4 b/gtsam/3rdparty/GeographicLib/m4/libtool.m4 index 56666f0ec..a644432f4 100644 --- a/gtsam/3rdparty/GeographicLib/m4/libtool.m4 +++ b/gtsam/3rdparty/GeographicLib/m4/libtool.m4 @@ -1,8 +1,6 @@ # libtool.m4 - Configure libtool for the host system. -*-Autoconf-*- # -# Copyright (C) 1996, 1997, 1998, 1999, 2000, 2001, 2003, 2004, 2005, -# 2006, 2007, 2008, 2009, 2010, 2011 Free Software -# Foundation, Inc. +# Copyright (C) 1996-2001, 2003-2015 Free Software Foundation, Inc. # Written by Gordon Matzigkeit, 1996 # # This file is free software; the Free Software Foundation gives @@ -10,36 +8,30 @@ # modifications, as long as this notice is preserved. m4_define([_LT_COPYING], [dnl -# Copyright (C) 1996, 1997, 1998, 1999, 2000, 2001, 2003, 2004, 2005, -# 2006, 2007, 2008, 2009, 2010, 2011 Free Software -# Foundation, Inc. -# Written by Gordon Matzigkeit, 1996 +# Copyright (C) 2014 Free Software Foundation, Inc. +# This is free software; see the source for copying conditions. There is NO +# warranty; not even for MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + +# GNU Libtool 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 2 of of the License, or +# (at your option) any later version. # -# This file is part of GNU Libtool. +# As a special exception to the GNU General Public License, if you +# distribute this file as part of a program or library that is built +# using GNU Libtool, you may include this file under the same +# distribution terms that you use for the rest of that program. # -# GNU Libtool 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 2 of -# the License, or (at your option) any later version. -# -# As a special exception to the GNU General Public License, -# if you distribute this file as part of a program or library that -# is built using GNU Libtool, you may include this file under the -# same distribution terms that you use for the rest of that program. -# -# GNU Libtool is distributed in the hope that it will be useful, -# but WITHOUT ANY WARRANTY; without even the implied warranty of +# GNU Libtool 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 GNU Libtool; see the file COPYING. If not, a copy -# can be downloaded from http://www.gnu.org/licenses/gpl.html, or -# obtained by writing to the Free Software Foundation, Inc., -# 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301, USA. +# along with this program. If not, see . ]) -# serial 57 LT_INIT +# serial 58 LT_INIT # LT_PREREQ(VERSION) @@ -67,7 +59,7 @@ esac # LT_INIT([OPTIONS]) # ------------------ AC_DEFUN([LT_INIT], -[AC_PREREQ([2.58])dnl We use AC_INCLUDES_DEFAULT +[AC_PREREQ([2.62])dnl We use AC_PATH_PROGS_FEATURE_CHECK AC_REQUIRE([AC_CONFIG_AUX_DIR_DEFAULT])dnl AC_BEFORE([$0], [LT_LANG])dnl AC_BEFORE([$0], [LT_OUTPUT])dnl @@ -91,7 +83,7 @@ dnl Parse OPTIONS _LT_SET_OPTIONS([$0], [$1]) # This can be used to rebuild libtool when needed -LIBTOOL_DEPS="$ltmain" +LIBTOOL_DEPS=$ltmain # Always use our own libtool. LIBTOOL='$(SHELL) $(top_builddir)/libtool' @@ -111,26 +103,43 @@ dnl AC_DEFUN([AC_PROG_LIBTOOL], []) dnl AC_DEFUN([AM_PROG_LIBTOOL], []) +# _LT_PREPARE_CC_BASENAME +# ----------------------- +m4_defun([_LT_PREPARE_CC_BASENAME], [ +# Calculate cc_basename. Skip known compiler wrappers and cross-prefix. +func_cc_basename () +{ + for cc_temp in @S|@*""; do + case $cc_temp in + compile | *[[\\/]]compile | ccache | *[[\\/]]ccache ) ;; + distcc | *[[\\/]]distcc | purify | *[[\\/]]purify ) ;; + \-*) ;; + *) break;; + esac + done + func_cc_basename_result=`$ECHO "$cc_temp" | $SED "s%.*/%%; s%^$host_alias-%%"` +} +])# _LT_PREPARE_CC_BASENAME + + # _LT_CC_BASENAME(CC) # ------------------- -# Calculate cc_basename. Skip known compiler wrappers and cross-prefix. +# It would be clearer to call AC_REQUIREs from _LT_PREPARE_CC_BASENAME, +# but that macro is also expanded into generated libtool script, which +# arranges for $SED and $ECHO to be set by different means. m4_defun([_LT_CC_BASENAME], -[for cc_temp in $1""; do - case $cc_temp in - compile | *[[\\/]]compile | ccache | *[[\\/]]ccache ) ;; - distcc | *[[\\/]]distcc | purify | *[[\\/]]purify ) ;; - \-*) ;; - *) break;; - esac -done -cc_basename=`$ECHO "$cc_temp" | $SED "s%.*/%%; s%^$host_alias-%%"` +[m4_require([_LT_PREPARE_CC_BASENAME])dnl +AC_REQUIRE([_LT_DECL_SED])dnl +AC_REQUIRE([_LT_PROG_ECHO_BACKSLASH])dnl +func_cc_basename $1 +cc_basename=$func_cc_basename_result ]) # _LT_FILEUTILS_DEFAULTS # ---------------------- # It is okay to use these file commands and assume they have been set -# sensibly after `m4_require([_LT_FILEUTILS_DEFAULTS])'. +# sensibly after 'm4_require([_LT_FILEUTILS_DEFAULTS])'. m4_defun([_LT_FILEUTILS_DEFAULTS], [: ${CP="cp -f"} : ${MV="mv -f"} @@ -177,15 +186,16 @@ m4_require([_LT_CHECK_SHAREDLIB_FROM_LINKLIB])dnl m4_require([_LT_CMD_OLD_ARCHIVE])dnl m4_require([_LT_CMD_GLOBAL_SYMBOLS])dnl m4_require([_LT_WITH_SYSROOT])dnl +m4_require([_LT_CMD_TRUNCATE])dnl _LT_CONFIG_LIBTOOL_INIT([ -# See if we are running on zsh, and set the options which allow our +# See if we are running on zsh, and set the options that allow our # commands through without removal of \ escapes INIT. -if test -n "\${ZSH_VERSION+set}" ; then +if test -n "\${ZSH_VERSION+set}"; then setopt NO_GLOB_SUBST fi ]) -if test -n "${ZSH_VERSION+set}" ; then +if test -n "${ZSH_VERSION+set}"; then setopt NO_GLOB_SUBST fi @@ -198,7 +208,7 @@ aix3*) # AIX sometimes has problems with the GCC collect2 program. For some # reason, if we set the COLLECT_NAMES environment variable, the problems # vanish in a puff of smoke. - if test "X${COLLECT_NAMES+set}" != Xset; then + if test set != "${COLLECT_NAMES+set}"; then COLLECT_NAMES= export COLLECT_NAMES fi @@ -209,14 +219,14 @@ esac ofile=libtool can_build_shared=yes -# All known linkers require a `.a' archive for static linking (except MSVC, +# All known linkers require a '.a' archive for static linking (except MSVC, # which needs '.lib'). libext=a -with_gnu_ld="$lt_cv_prog_gnu_ld" +with_gnu_ld=$lt_cv_prog_gnu_ld -old_CC="$CC" -old_CFLAGS="$CFLAGS" +old_CC=$CC +old_CFLAGS=$CFLAGS # Set sane defaults for various variables test -z "$CC" && CC=cc @@ -269,14 +279,14 @@ no_glob_subst='s/\*/\\\*/g' # _LT_PROG_LTMAIN # --------------- -# Note that this code is called both from `configure', and `config.status' +# Note that this code is called both from 'configure', and 'config.status' # now that we use AC_CONFIG_COMMANDS to generate libtool. Notably, -# `config.status' has no value for ac_aux_dir unless we are using Automake, +# 'config.status' has no value for ac_aux_dir unless we are using Automake, # so we pass a copy along to make sure it has a sensible value anyway. m4_defun([_LT_PROG_LTMAIN], [m4_ifdef([AC_REQUIRE_AUX_FILE], [AC_REQUIRE_AUX_FILE([ltmain.sh])])dnl _LT_CONFIG_LIBTOOL_INIT([ac_aux_dir='$ac_aux_dir']) -ltmain="$ac_aux_dir/ltmain.sh" +ltmain=$ac_aux_dir/ltmain.sh ])# _LT_PROG_LTMAIN @@ -286,7 +296,7 @@ ltmain="$ac_aux_dir/ltmain.sh" # So that we can recreate a full libtool script including additional # tags, we accumulate the chunks of code to send to AC_CONFIG_COMMANDS -# in macros and then make a single call at the end using the `libtool' +# in macros and then make a single call at the end using the 'libtool' # label. @@ -421,8 +431,8 @@ m4_define([_lt_decl_all_varnames], # _LT_CONFIG_STATUS_DECLARE([VARNAME]) # ------------------------------------ -# Quote a variable value, and forward it to `config.status' so that its -# declaration there will have the same value as in `configure'. VARNAME +# Quote a variable value, and forward it to 'config.status' so that its +# declaration there will have the same value as in 'configure'. VARNAME # must have a single quote delimited value for this to work. m4_define([_LT_CONFIG_STATUS_DECLARE], [$1='`$ECHO "$][$1" | $SED "$delay_single_quote_subst"`']) @@ -446,7 +456,7 @@ m4_defun([_LT_CONFIG_STATUS_DECLARATIONS], # Output comment and list of tags supported by the script m4_defun([_LT_LIBTOOL_TAGS], [_LT_FORMAT_COMMENT([The names of the tagged configurations supported by this script])dnl -available_tags="_LT_TAGS"dnl +available_tags='_LT_TAGS'dnl ]) @@ -474,7 +484,7 @@ m4_ifval([$2], [_$2])[]m4_popdef([_libtool_name])[]dnl # _LT_LIBTOOL_CONFIG_VARS # ----------------------- # Produce commented declarations of non-tagged libtool config variables -# suitable for insertion in the LIBTOOL CONFIG section of the `libtool' +# suitable for insertion in the LIBTOOL CONFIG section of the 'libtool' # script. Tagged libtool config variables (even for the LIBTOOL CONFIG # section) are produced by _LT_LIBTOOL_TAG_VARS. m4_defun([_LT_LIBTOOL_CONFIG_VARS], @@ -500,8 +510,8 @@ m4_define([_LT_TAGVAR], [m4_ifval([$2], [$1_$2], [$1])]) # Send accumulated output to $CONFIG_STATUS. Thanks to the lists of # variables for single and double quote escaping we saved from calls # to _LT_DECL, we can put quote escaped variables declarations -# into `config.status', and then the shell code to quote escape them in -# for loops in `config.status'. Finally, any additional code accumulated +# into 'config.status', and then the shell code to quote escape them in +# for loops in 'config.status'. Finally, any additional code accumulated # from calls to _LT_CONFIG_LIBTOOL_INIT is expanded. m4_defun([_LT_CONFIG_COMMANDS], [AC_PROVIDE_IFELSE([LT_OUTPUT], @@ -547,7 +557,7 @@ for var in lt_decl_all_varnames([[ \ ]], lt_decl_quote_varnames); do case \`eval \\\\\$ECHO \\\\""\\\\\$\$var"\\\\"\` in *[[\\\\\\\`\\"\\\$]]*) - eval "lt_\$var=\\\\\\"\\\`\\\$ECHO \\"\\\$\$var\\" | \\\$SED \\"\\\$sed_quote_subst\\"\\\`\\\\\\"" + eval "lt_\$var=\\\\\\"\\\`\\\$ECHO \\"\\\$\$var\\" | \\\$SED \\"\\\$sed_quote_subst\\"\\\`\\\\\\"" ## exclude from sc_prohibit_nested_quotes ;; *) eval "lt_\$var=\\\\\\"\\\$\$var\\\\\\"" @@ -560,7 +570,7 @@ for var in lt_decl_all_varnames([[ \ ]], lt_decl_dquote_varnames); do case \`eval \\\\\$ECHO \\\\""\\\\\$\$var"\\\\"\` in *[[\\\\\\\`\\"\\\$]]*) - eval "lt_\$var=\\\\\\"\\\`\\\$ECHO \\"\\\$\$var\\" | \\\$SED -e \\"\\\$double_quote_subst\\" -e \\"\\\$sed_quote_subst\\" -e \\"\\\$delay_variable_subst\\"\\\`\\\\\\"" + eval "lt_\$var=\\\\\\"\\\`\\\$ECHO \\"\\\$\$var\\" | \\\$SED -e \\"\\\$double_quote_subst\\" -e \\"\\\$sed_quote_subst\\" -e \\"\\\$delay_variable_subst\\"\\\`\\\\\\"" ## exclude from sc_prohibit_nested_quotes ;; *) eval "lt_\$var=\\\\\\"\\\$\$var\\\\\\"" @@ -576,7 +586,7 @@ _LT_OUTPUT_LIBTOOL_INIT # Generate a child script FILE with all initialization necessary to # reuse the environment learned by the parent script, and make the # file executable. If COMMENT is supplied, it is inserted after the -# `#!' sequence but before initialization text begins. After this +# '#!' sequence but before initialization text begins. After this # macro, additional text can be appended to FILE to form the body of # the child script. The macro ends with non-zero status if the # file could not be fully written (such as if the disk is full). @@ -598,7 +608,7 @@ AS_SHELL_SANITIZE _AS_PREPARE exec AS_MESSAGE_FD>&1 _ASEOF -test $lt_write_fail = 0 && chmod +x $1[]dnl +test 0 = "$lt_write_fail" && chmod +x $1[]dnl m4_popdef([AS_MESSAGE_LOG_FD])])])# _LT_GENERATED_FILE_INIT # LT_OUTPUT @@ -621,7 +631,7 @@ exec AS_MESSAGE_LOG_FD>>config.log } >&AS_MESSAGE_LOG_FD lt_cl_help="\ -\`$as_me' creates a local libtool stub from the current configuration, +'$as_me' creates a local libtool stub from the current configuration, for use in further configure time tests before the real libtool is generated. @@ -643,7 +653,7 @@ Copyright (C) 2011 Free Software Foundation, Inc. This config.lt script is free software; the Free Software Foundation gives unlimited permision to copy, distribute and modify it." -while test $[#] != 0 +while test 0 != $[#] do case $[1] in --version | --v* | -V ) @@ -656,10 +666,10 @@ do lt_cl_silent=: ;; -*) AC_MSG_ERROR([unrecognized option: $[1] -Try \`$[0] --help' for more information.]) ;; +Try '$[0] --help' for more information.]) ;; *) AC_MSG_ERROR([unrecognized argument: $[1] -Try \`$[0] --help' for more information.]) ;; +Try '$[0] --help' for more information.]) ;; esac shift done @@ -685,7 +695,7 @@ chmod +x "$CONFIG_LT" # open by configure. Here we exec the FD to /dev/null, effectively closing # config.log, so it can be properly (re)opened and appended to by config.lt. lt_cl_success=: -test "$silent" = yes && +test yes = "$silent" && lt_config_lt_args="$lt_config_lt_args --quiet" exec AS_MESSAGE_LOG_FD>/dev/null $SHELL "$CONFIG_LT" $lt_config_lt_args || lt_cl_success=false @@ -705,32 +715,47 @@ m4_defun([_LT_CONFIG], _LT_CONFIG_SAVE_COMMANDS([ m4_define([_LT_TAG], m4_if([$1], [], [C], [$1]))dnl m4_if(_LT_TAG, [C], [ - # See if we are running on zsh, and set the options which allow our + # See if we are running on zsh, and set the options that allow our # commands through without removal of \ escapes. - if test -n "${ZSH_VERSION+set}" ; then + if test -n "${ZSH_VERSION+set}"; then setopt NO_GLOB_SUBST fi - cfgfile="${ofile}T" + cfgfile=${ofile}T trap "$RM \"$cfgfile\"; exit 1" 1 2 15 $RM "$cfgfile" cat <<_LT_EOF >> "$cfgfile" #! $SHELL - -# `$ECHO "$ofile" | sed 's%^.*/%%'` - Provide generalized library-building support services. -# Generated automatically by $as_me ($PACKAGE$TIMESTAMP) $VERSION +# Generated automatically by $as_me ($PACKAGE) $VERSION # Libtool was configured on host `(hostname || uname -n) 2>/dev/null | sed 1q`: # NOTE: Changes made to this file will be lost: look at ltmain.sh. -# + +# Provide generalized library-building support services. +# Written by Gordon Matzigkeit, 1996 + _LT_COPYING _LT_LIBTOOL_TAGS +# Configured defaults for sys_lib_dlsearch_path munging. +: \${LT_SYS_LIBRARY_PATH="$configure_time_lt_sys_library_path"} + # ### BEGIN LIBTOOL CONFIG _LT_LIBTOOL_CONFIG_VARS _LT_LIBTOOL_TAG_VARS # ### END LIBTOOL CONFIG +_LT_EOF + + cat <<'_LT_EOF' >> "$cfgfile" + +# ### BEGIN FUNCTIONS SHARED WITH CONFIGURE + +_LT_PREPARE_MUNGE_PATH_LIST +_LT_PREPARE_CC_BASENAME + +# ### END FUNCTIONS SHARED WITH CONFIGURE + _LT_EOF case $host_os in @@ -739,7 +764,7 @@ _LT_EOF # AIX sometimes has problems with the GCC collect2 program. For some # reason, if we set the COLLECT_NAMES environment variable, the problems # vanish in a puff of smoke. -if test "X${COLLECT_NAMES+set}" != Xset; then +if test set != "${COLLECT_NAMES+set}"; then COLLECT_NAMES= export COLLECT_NAMES fi @@ -756,8 +781,6 @@ _LT_EOF sed '$q' "$ltmain" >> "$cfgfile" \ || (rm -f "$cfgfile"; exit 1) - _LT_PROG_REPLACE_SHELLFNS - mv -f "$cfgfile" "$ofile" || (rm -f "$ofile" && cp "$cfgfile" "$ofile" && rm -f "$cfgfile") chmod +x "$ofile" @@ -775,7 +798,6 @@ _LT_EOF [m4_if([$1], [], [ PACKAGE='$PACKAGE' VERSION='$VERSION' - TIMESTAMP='$TIMESTAMP' RM='$RM' ofile='$ofile'], []) ])dnl /_LT_CONFIG_SAVE_COMMANDS @@ -974,7 +996,7 @@ m4_defun_once([_LT_REQUIRED_DARWIN_CHECKS],[ AC_CACHE_CHECK([for -single_module linker flag],[lt_cv_apple_cc_single_mod], [lt_cv_apple_cc_single_mod=no - if test -z "${LT_MULTI_MODULE}"; then + if test -z "$LT_MULTI_MODULE"; then # By default we will add the -single_module flag. You can override # by either setting the environment variable LT_MULTI_MODULE # non-empty at configure time, or by adding -multi_module to the @@ -992,7 +1014,7 @@ m4_defun_once([_LT_REQUIRED_DARWIN_CHECKS],[ cat conftest.err >&AS_MESSAGE_LOG_FD # Otherwise, if the output was created with a 0 exit code from # the compiler, it worked. - elif test -f libconftest.dylib && test $_lt_result -eq 0; then + elif test -f libconftest.dylib && test 0 = "$_lt_result"; then lt_cv_apple_cc_single_mod=yes else cat conftest.err >&AS_MESSAGE_LOG_FD @@ -1010,7 +1032,7 @@ m4_defun_once([_LT_REQUIRED_DARWIN_CHECKS],[ AC_LINK_IFELSE([AC_LANG_PROGRAM([],[])], [lt_cv_ld_exported_symbols_list=yes], [lt_cv_ld_exported_symbols_list=no]) - LDFLAGS="$save_LDFLAGS" + LDFLAGS=$save_LDFLAGS ]) AC_CACHE_CHECK([for -force_load linker flag],[lt_cv_ld_force_load], @@ -1032,7 +1054,7 @@ _LT_EOF _lt_result=$? if test -s conftest.err && $GREP force_load conftest.err; then cat conftest.err >&AS_MESSAGE_LOG_FD - elif test -f conftest && test $_lt_result -eq 0 && $GREP forced_load conftest >/dev/null 2>&1 ; then + elif test -f conftest && test 0 = "$_lt_result" && $GREP forced_load conftest >/dev/null 2>&1; then lt_cv_ld_force_load=yes else cat conftest.err >&AS_MESSAGE_LOG_FD @@ -1042,32 +1064,32 @@ _LT_EOF ]) case $host_os in rhapsody* | darwin1.[[012]]) - _lt_dar_allow_undefined='${wl}-undefined ${wl}suppress' ;; + _lt_dar_allow_undefined='$wl-undefined ${wl}suppress' ;; darwin1.*) - _lt_dar_allow_undefined='${wl}-flat_namespace ${wl}-undefined ${wl}suppress' ;; + _lt_dar_allow_undefined='$wl-flat_namespace $wl-undefined ${wl}suppress' ;; darwin*) # darwin 5.x on # if running on 10.5 or later, the deployment target defaults # to the OS version, if on x86, and 10.4, the deployment # target defaults to 10.4. Don't you love it? case ${MACOSX_DEPLOYMENT_TARGET-10.0},$host in 10.0,*86*-darwin8*|10.0,*-darwin[[91]]*) - _lt_dar_allow_undefined='${wl}-undefined ${wl}dynamic_lookup' ;; - 10.[[012]]*) - _lt_dar_allow_undefined='${wl}-flat_namespace ${wl}-undefined ${wl}suppress' ;; + _lt_dar_allow_undefined='$wl-undefined ${wl}dynamic_lookup' ;; + 10.[[012]][[,.]]*) + _lt_dar_allow_undefined='$wl-flat_namespace $wl-undefined ${wl}suppress' ;; 10.*) - _lt_dar_allow_undefined='${wl}-undefined ${wl}dynamic_lookup' ;; + _lt_dar_allow_undefined='$wl-undefined ${wl}dynamic_lookup' ;; esac ;; esac - if test "$lt_cv_apple_cc_single_mod" = "yes"; then + if test yes = "$lt_cv_apple_cc_single_mod"; then _lt_dar_single_mod='$single_module' fi - if test "$lt_cv_ld_exported_symbols_list" = "yes"; then - _lt_dar_export_syms=' ${wl}-exported_symbols_list,$output_objdir/${libname}-symbols.expsym' + if test yes = "$lt_cv_ld_exported_symbols_list"; then + _lt_dar_export_syms=' $wl-exported_symbols_list,$output_objdir/$libname-symbols.expsym' else - _lt_dar_export_syms='~$NMEDIT -s $output_objdir/${libname}-symbols.expsym ${lib}' + _lt_dar_export_syms='~$NMEDIT -s $output_objdir/$libname-symbols.expsym $lib' fi - if test "$DSYMUTIL" != ":" && test "$lt_cv_ld_force_load" = "no"; then + if test : != "$DSYMUTIL" && test no = "$lt_cv_ld_force_load"; then _lt_dsymutil='~$DSYMUTIL $lib || :' else _lt_dsymutil= @@ -1087,29 +1109,29 @@ m4_defun([_LT_DARWIN_LINKER_FEATURES], _LT_TAGVAR(hardcode_direct, $1)=no _LT_TAGVAR(hardcode_automatic, $1)=yes _LT_TAGVAR(hardcode_shlibpath_var, $1)=unsupported - if test "$lt_cv_ld_force_load" = "yes"; then - _LT_TAGVAR(whole_archive_flag_spec, $1)='`for conv in $convenience\"\"; do test -n \"$conv\" && new_convenience=\"$new_convenience ${wl}-force_load,$conv\"; done; func_echo_all \"$new_convenience\"`' + if test yes = "$lt_cv_ld_force_load"; then + _LT_TAGVAR(whole_archive_flag_spec, $1)='`for conv in $convenience\"\"; do test -n \"$conv\" && new_convenience=\"$new_convenience $wl-force_load,$conv\"; done; func_echo_all \"$new_convenience\"`' m4_case([$1], [F77], [_LT_TAGVAR(compiler_needs_object, $1)=yes], [FC], [_LT_TAGVAR(compiler_needs_object, $1)=yes]) else _LT_TAGVAR(whole_archive_flag_spec, $1)='' fi _LT_TAGVAR(link_all_deplibs, $1)=yes - _LT_TAGVAR(allow_undefined_flag, $1)="$_lt_dar_allow_undefined" + _LT_TAGVAR(allow_undefined_flag, $1)=$_lt_dar_allow_undefined case $cc_basename in - ifort*) _lt_dar_can_shared=yes ;; + ifort*|nagfor*) _lt_dar_can_shared=yes ;; *) _lt_dar_can_shared=$GCC ;; esac - if test "$_lt_dar_can_shared" = "yes"; then + if test yes = "$_lt_dar_can_shared"; then output_verbose_link_cmd=func_echo_all - _LT_TAGVAR(archive_cmds, $1)="\$CC -dynamiclib \$allow_undefined_flag -o \$lib \$libobjs \$deplibs \$compiler_flags -install_name \$rpath/\$soname \$verstring $_lt_dar_single_mod${_lt_dsymutil}" - _LT_TAGVAR(module_cmds, $1)="\$CC \$allow_undefined_flag -o \$lib -bundle \$libobjs \$deplibs \$compiler_flags${_lt_dsymutil}" - _LT_TAGVAR(archive_expsym_cmds, $1)="sed 's,^,_,' < \$export_symbols > \$output_objdir/\${libname}-symbols.expsym~\$CC -dynamiclib \$allow_undefined_flag -o \$lib \$libobjs \$deplibs \$compiler_flags -install_name \$rpath/\$soname \$verstring ${_lt_dar_single_mod}${_lt_dar_export_syms}${_lt_dsymutil}" - _LT_TAGVAR(module_expsym_cmds, $1)="sed -e 's,^,_,' < \$export_symbols > \$output_objdir/\${libname}-symbols.expsym~\$CC \$allow_undefined_flag -o \$lib -bundle \$libobjs \$deplibs \$compiler_flags${_lt_dar_export_syms}${_lt_dsymutil}" + _LT_TAGVAR(archive_cmds, $1)="\$CC -dynamiclib \$allow_undefined_flag -o \$lib \$libobjs \$deplibs \$compiler_flags -install_name \$rpath/\$soname \$verstring $_lt_dar_single_mod$_lt_dsymutil" + _LT_TAGVAR(module_cmds, $1)="\$CC \$allow_undefined_flag -o \$lib -bundle \$libobjs \$deplibs \$compiler_flags$_lt_dsymutil" + _LT_TAGVAR(archive_expsym_cmds, $1)="sed 's|^|_|' < \$export_symbols > \$output_objdir/\$libname-symbols.expsym~\$CC -dynamiclib \$allow_undefined_flag -o \$lib \$libobjs \$deplibs \$compiler_flags -install_name \$rpath/\$soname \$verstring $_lt_dar_single_mod$_lt_dar_export_syms$_lt_dsymutil" + _LT_TAGVAR(module_expsym_cmds, $1)="sed -e 's|^|_|' < \$export_symbols > \$output_objdir/\$libname-symbols.expsym~\$CC \$allow_undefined_flag -o \$lib -bundle \$libobjs \$deplibs \$compiler_flags$_lt_dar_export_syms$_lt_dsymutil" m4_if([$1], [CXX], -[ if test "$lt_cv_apple_cc_single_mod" != "yes"; then - _LT_TAGVAR(archive_cmds, $1)="\$CC -r -keep_private_externs -nostdlib -o \${lib}-master.o \$libobjs~\$CC -dynamiclib \$allow_undefined_flag -o \$lib \${lib}-master.o \$deplibs \$compiler_flags -install_name \$rpath/\$soname \$verstring${_lt_dsymutil}" - _LT_TAGVAR(archive_expsym_cmds, $1)="sed 's,^,_,' < \$export_symbols > \$output_objdir/\${libname}-symbols.expsym~\$CC -r -keep_private_externs -nostdlib -o \${lib}-master.o \$libobjs~\$CC -dynamiclib \$allow_undefined_flag -o \$lib \${lib}-master.o \$deplibs \$compiler_flags -install_name \$rpath/\$soname \$verstring${_lt_dar_export_syms}${_lt_dsymutil}" +[ if test yes != "$lt_cv_apple_cc_single_mod"; then + _LT_TAGVAR(archive_cmds, $1)="\$CC -r -keep_private_externs -nostdlib -o \$lib-master.o \$libobjs~\$CC -dynamiclib \$allow_undefined_flag -o \$lib \$lib-master.o \$deplibs \$compiler_flags -install_name \$rpath/\$soname \$verstring$_lt_dsymutil" + _LT_TAGVAR(archive_expsym_cmds, $1)="sed 's|^|_|' < \$export_symbols > \$output_objdir/\$libname-symbols.expsym~\$CC -r -keep_private_externs -nostdlib -o \$lib-master.o \$libobjs~\$CC -dynamiclib \$allow_undefined_flag -o \$lib \$lib-master.o \$deplibs \$compiler_flags -install_name \$rpath/\$soname \$verstring$_lt_dar_export_syms$_lt_dsymutil" fi ],[]) else @@ -1129,7 +1151,7 @@ m4_defun([_LT_DARWIN_LINKER_FEATURES], # Allow to override them for all tags through lt_cv_aix_libpath. m4_defun([_LT_SYS_MODULE_PATH_AIX], [m4_require([_LT_DECL_SED])dnl -if test "${lt_cv_aix_libpath+set}" = set; then +if test set = "${lt_cv_aix_libpath+set}"; then aix_libpath=$lt_cv_aix_libpath else AC_CACHE_VAL([_LT_TAGVAR([lt_cv_aix_libpath_], [$1])], @@ -1147,7 +1169,7 @@ else _LT_TAGVAR([lt_cv_aix_libpath_], [$1])=`dump -HX64 conftest$ac_exeext 2>/dev/null | $SED -n -e "$lt_aix_libpath_sed"` fi],[]) if test -z "$_LT_TAGVAR([lt_cv_aix_libpath_], [$1])"; then - _LT_TAGVAR([lt_cv_aix_libpath_], [$1])="/usr/lib:/lib" + _LT_TAGVAR([lt_cv_aix_libpath_], [$1])=/usr/lib:/lib fi ]) aix_libpath=$_LT_TAGVAR([lt_cv_aix_libpath_], [$1]) @@ -1167,8 +1189,8 @@ m4_define([_LT_SHELL_INIT], # ----------------------- # Find how we can fake an echo command that does not interpret backslash. # In particular, with Autoconf 2.60 or later we add some code to the start -# of the generated configure script which will find a shell with a builtin -# printf (which we can use as an echo command). +# of the generated configure script that will find a shell with a builtin +# printf (that we can use as an echo command). m4_defun([_LT_PROG_ECHO_BACKSLASH], [ECHO='\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\' ECHO=$ECHO$ECHO$ECHO$ECHO$ECHO @@ -1196,10 +1218,10 @@ fi # Invoke $ECHO with all args, space-separated. func_echo_all () { - $ECHO "$*" + $ECHO "$*" } -case "$ECHO" in +case $ECHO in printf*) AC_MSG_RESULT([printf]) ;; print*) AC_MSG_RESULT([print -r]) ;; *) AC_MSG_RESULT([cat]) ;; @@ -1225,16 +1247,17 @@ _LT_DECL([], [ECHO], [1], [An echo program that protects backslashes]) AC_DEFUN([_LT_WITH_SYSROOT], [AC_MSG_CHECKING([for sysroot]) AC_ARG_WITH([sysroot], -[ --with-sysroot[=DIR] Search for dependent libraries within DIR - (or the compiler's sysroot if not specified).], +[AS_HELP_STRING([--with-sysroot@<:@=DIR@:>@], + [Search for dependent libraries within DIR (or the compiler's sysroot + if not specified).])], [], [with_sysroot=no]) dnl lt_sysroot will always be passed unquoted. We quote it here dnl in case the user passed a directory name. lt_sysroot= -case ${with_sysroot} in #( +case $with_sysroot in #( yes) - if test "$GCC" = yes; then + if test yes = "$GCC"; then lt_sysroot=`$CC --print-sysroot 2>/dev/null` fi ;; #( @@ -1244,14 +1267,14 @@ case ${with_sysroot} in #( no|'') ;; #( *) - AC_MSG_RESULT([${with_sysroot}]) + AC_MSG_RESULT([$with_sysroot]) AC_MSG_ERROR([The sysroot must be an absolute path.]) ;; esac AC_MSG_RESULT([${lt_sysroot:-no}]) _LT_DECL([], [lt_sysroot], [0], [The root where to search for ]dnl -[dependent libraries, and in which our libraries should be installed.])]) +[dependent libraries, and where our libraries should be installed.])]) # _LT_ENABLE_LOCK # --------------- @@ -1259,31 +1282,33 @@ m4_defun([_LT_ENABLE_LOCK], [AC_ARG_ENABLE([libtool-lock], [AS_HELP_STRING([--disable-libtool-lock], [avoid locking (might break parallel builds)])]) -test "x$enable_libtool_lock" != xno && enable_libtool_lock=yes +test no = "$enable_libtool_lock" || enable_libtool_lock=yes # Some flags need to be propagated to the compiler or linker for good # libtool support. case $host in ia64-*-hpux*) - # Find out which ABI we are using. + # Find out what ABI is being produced by ac_compile, and set mode + # options accordingly. echo 'int i;' > conftest.$ac_ext if AC_TRY_EVAL(ac_compile); then case `/usr/bin/file conftest.$ac_objext` in *ELF-32*) - HPUX_IA64_MODE="32" + HPUX_IA64_MODE=32 ;; *ELF-64*) - HPUX_IA64_MODE="64" + HPUX_IA64_MODE=64 ;; esac fi rm -rf conftest* ;; *-*-irix6*) - # Find out which ABI we are using. + # Find out what ABI is being produced by ac_compile, and set linker + # options accordingly. echo '[#]line '$LINENO' "configure"' > conftest.$ac_ext if AC_TRY_EVAL(ac_compile); then - if test "$lt_cv_prog_gnu_ld" = yes; then + if test yes = "$lt_cv_prog_gnu_ld"; then case `/usr/bin/file conftest.$ac_objext` in *32-bit*) LD="${LD-ld} -melf32bsmip" @@ -1312,9 +1337,46 @@ ia64-*-hpux*) rm -rf conftest* ;; -x86_64-*kfreebsd*-gnu|x86_64-*linux*|ppc*-*linux*|powerpc*-*linux*| \ +mips64*-*linux*) + # Find out what ABI is being produced by ac_compile, and set linker + # options accordingly. + echo '[#]line '$LINENO' "configure"' > conftest.$ac_ext + if AC_TRY_EVAL(ac_compile); then + emul=elf + case `/usr/bin/file conftest.$ac_objext` in + *32-bit*) + emul="${emul}32" + ;; + *64-bit*) + emul="${emul}64" + ;; + esac + case `/usr/bin/file conftest.$ac_objext` in + *MSB*) + emul="${emul}btsmip" + ;; + *LSB*) + emul="${emul}ltsmip" + ;; + esac + case `/usr/bin/file conftest.$ac_objext` in + *N32*) + emul="${emul}n32" + ;; + esac + LD="${LD-ld} -m $emul" + fi + rm -rf conftest* + ;; + +x86_64-*kfreebsd*-gnu|x86_64-*linux*|powerpc*-*linux*| \ s390*-*linux*|s390*-*tpf*|sparc*-*linux*) - # Find out which ABI we are using. + # Find out what ABI is being produced by ac_compile, and set linker + # options accordingly. Note that the listed cases only cover the + # situations where additional linker options are needed (such as when + # doing 32-bit compilation for a host where ld defaults to 64-bit, or + # vice versa); the common cases where no linker options are needed do + # not appear in the list. echo 'int i;' > conftest.$ac_ext if AC_TRY_EVAL(ac_compile); then case `/usr/bin/file conftest.o` in @@ -1324,9 +1386,19 @@ s390*-*linux*|s390*-*tpf*|sparc*-*linux*) LD="${LD-ld} -m elf_i386_fbsd" ;; x86_64-*linux*) - LD="${LD-ld} -m elf_i386" + case `/usr/bin/file conftest.o` in + *x86-64*) + LD="${LD-ld} -m elf32_x86_64" + ;; + *) + LD="${LD-ld} -m elf_i386" + ;; + esac ;; - ppc64-*linux*|powerpc64-*linux*) + powerpc64le-*linux*) + LD="${LD-ld} -m elf32lppclinux" + ;; + powerpc64-*linux*) LD="${LD-ld} -m elf32ppclinux" ;; s390x-*linux*) @@ -1345,7 +1417,10 @@ s390*-*linux*|s390*-*tpf*|sparc*-*linux*) x86_64-*linux*) LD="${LD-ld} -m elf_x86_64" ;; - ppc*-*linux*|powerpc*-*linux*) + powerpcle-*linux*) + LD="${LD-ld} -m elf64lppc" + ;; + powerpc-*linux*) LD="${LD-ld} -m elf64ppc" ;; s390*-*linux*|s390*-*tpf*) @@ -1363,19 +1438,20 @@ s390*-*linux*|s390*-*tpf*|sparc*-*linux*) *-*-sco3.2v5*) # On SCO OpenServer 5, we need -belf to get full-featured binaries. - SAVE_CFLAGS="$CFLAGS" + SAVE_CFLAGS=$CFLAGS CFLAGS="$CFLAGS -belf" AC_CACHE_CHECK([whether the C compiler needs -belf], lt_cv_cc_needs_belf, [AC_LANG_PUSH(C) AC_LINK_IFELSE([AC_LANG_PROGRAM([[]],[[]])],[lt_cv_cc_needs_belf=yes],[lt_cv_cc_needs_belf=no]) AC_LANG_POP]) - if test x"$lt_cv_cc_needs_belf" != x"yes"; then + if test yes != "$lt_cv_cc_needs_belf"; then # this is probably gcc 2.8.0, egcs 1.0 or newer; no need for -belf - CFLAGS="$SAVE_CFLAGS" + CFLAGS=$SAVE_CFLAGS fi ;; *-*solaris*) - # Find out which ABI we are using. + # Find out what ABI is being produced by ac_compile, and set linker + # options accordingly. echo 'int i;' > conftest.$ac_ext if AC_TRY_EVAL(ac_compile); then case `/usr/bin/file conftest.o` in @@ -1383,7 +1459,7 @@ s390*-*linux*|s390*-*tpf*|sparc*-*linux*) case $lt_cv_prog_gnu_ld in yes*) case $host in - i?86-*-solaris*) + i?86-*-solaris*|x86_64-*-solaris*) LD="${LD-ld} -m elf_x86_64" ;; sparc*-*-solaris*) @@ -1392,7 +1468,7 @@ s390*-*linux*|s390*-*tpf*|sparc*-*linux*) esac # GNU ld 2.21 introduced _sol2 emulations. Use them if available. if ${LD-ld} -V | grep _sol2 >/dev/null 2>&1; then - LD="${LD-ld}_sol2" + LD=${LD-ld}_sol2 fi ;; *) @@ -1408,7 +1484,7 @@ s390*-*linux*|s390*-*tpf*|sparc*-*linux*) ;; esac -need_locks="$enable_libtool_lock" +need_locks=$enable_libtool_lock ])# _LT_ENABLE_LOCK @@ -1427,11 +1503,11 @@ AC_CACHE_CHECK([for archiver @FILE support], [lt_cv_ar_at_file], [echo conftest.$ac_objext > conftest.lst lt_ar_try='$AR $AR_FLAGS libconftest.a @conftest.lst >&AS_MESSAGE_LOG_FD' AC_TRY_EVAL([lt_ar_try]) - if test "$ac_status" -eq 0; then + if test 0 -eq "$ac_status"; then # Ensure the archiver fails upon bogus file names. rm -f conftest.$ac_objext libconftest.a AC_TRY_EVAL([lt_ar_try]) - if test "$ac_status" -ne 0; then + if test 0 -ne "$ac_status"; then lt_cv_ar_at_file=@ fi fi @@ -1439,7 +1515,7 @@ AC_CACHE_CHECK([for archiver @FILE support], [lt_cv_ar_at_file], ]) ]) -if test "x$lt_cv_ar_at_file" = xno; then +if test no = "$lt_cv_ar_at_file"; then archiver_list_spec= else archiver_list_spec=$lt_cv_ar_at_file @@ -1470,7 +1546,7 @@ old_postuninstall_cmds= if test -n "$RANLIB"; then case $host_os in - openbsd*) + bitrig* | openbsd*) old_postinstall_cmds="$old_postinstall_cmds~\$RANLIB -t \$tool_oldlib" ;; *) @@ -1506,7 +1582,7 @@ AC_CACHE_CHECK([$1], [$2], [$2=no m4_if([$4], , [ac_outfile=conftest.$ac_objext], [ac_outfile=$4]) echo "$lt_simple_compile_test_code" > conftest.$ac_ext - lt_compiler_flag="$3" + lt_compiler_flag="$3" ## exclude from sc_useless_quotes_in_assignment # Insert the option either (1) after the last *FLAGS variable, or # (2) before a word containing "conftest.", or (3) at the end. # Note that $ac_compile itself does not contain backslashes and begins @@ -1533,7 +1609,7 @@ AC_CACHE_CHECK([$1], [$2], $RM conftest* ]) -if test x"[$]$2" = xyes; then +if test yes = "[$]$2"; then m4_if([$5], , :, [$5]) else m4_if([$6], , :, [$6]) @@ -1555,7 +1631,7 @@ AC_DEFUN([_LT_LINKER_OPTION], m4_require([_LT_DECL_SED])dnl AC_CACHE_CHECK([$1], [$2], [$2=no - save_LDFLAGS="$LDFLAGS" + save_LDFLAGS=$LDFLAGS LDFLAGS="$LDFLAGS $3" echo "$lt_simple_link_test_code" > conftest.$ac_ext if (eval $ac_link 2>conftest.err) && test -s conftest$ac_exeext; then @@ -1574,10 +1650,10 @@ AC_CACHE_CHECK([$1], [$2], fi fi $RM -r conftest* - LDFLAGS="$save_LDFLAGS" + LDFLAGS=$save_LDFLAGS ]) -if test x"[$]$2" = xyes; then +if test yes = "[$]$2"; then m4_if([$4], , :, [$4]) else m4_if([$5], , :, [$5]) @@ -1598,7 +1674,7 @@ AC_DEFUN([LT_CMD_MAX_LEN], AC_MSG_CHECKING([the maximum length of command line arguments]) AC_CACHE_VAL([lt_cv_sys_max_cmd_len], [dnl i=0 - teststring="ABCD" + teststring=ABCD case $build_os in msdosdjgpp*) @@ -1638,7 +1714,7 @@ AC_CACHE_VAL([lt_cv_sys_max_cmd_len], [dnl lt_cv_sys_max_cmd_len=8192; ;; - netbsd* | freebsd* | openbsd* | darwin* | dragonfly*) + bitrig* | darwin* | dragonfly* | freebsd* | netbsd* | openbsd*) # This has been around since 386BSD, at least. Likely further. if test -x /sbin/sysctl; then lt_cv_sys_max_cmd_len=`/sbin/sysctl -n kern.argmax` @@ -1688,22 +1764,23 @@ AC_CACHE_VAL([lt_cv_sys_max_cmd_len], [dnl ;; *) lt_cv_sys_max_cmd_len=`(getconf ARG_MAX) 2> /dev/null` - if test -n "$lt_cv_sys_max_cmd_len"; then + if test -n "$lt_cv_sys_max_cmd_len" && \ + test undefined != "$lt_cv_sys_max_cmd_len"; then lt_cv_sys_max_cmd_len=`expr $lt_cv_sys_max_cmd_len \/ 4` lt_cv_sys_max_cmd_len=`expr $lt_cv_sys_max_cmd_len \* 3` else # Make teststring a little bigger before we do anything with it. # a 1K string should be a reasonable start. - for i in 1 2 3 4 5 6 7 8 ; do + for i in 1 2 3 4 5 6 7 8; do teststring=$teststring$teststring done SHELL=${SHELL-${CONFIG_SHELL-/bin/sh}} # If test is not a shell built-in, we'll probably end up computing a # maximum length that is only half of the actual maximum length, but # we can't tell. - while { test "X"`env echo "$teststring$teststring" 2>/dev/null` \ + while { test X`env echo "$teststring$teststring" 2>/dev/null` \ = "X$teststring$teststring"; } >/dev/null 2>&1 && - test $i != 17 # 1/2 MB should be enough + test 17 != "$i" # 1/2 MB should be enough do i=`expr $i + 1` teststring=$teststring$teststring @@ -1719,7 +1796,7 @@ AC_CACHE_VAL([lt_cv_sys_max_cmd_len], [dnl ;; esac ]) -if test -n $lt_cv_sys_max_cmd_len ; then +if test -n "$lt_cv_sys_max_cmd_len"; then AC_MSG_RESULT($lt_cv_sys_max_cmd_len) else AC_MSG_RESULT(none) @@ -1747,7 +1824,7 @@ m4_defun([_LT_HEADER_DLFCN], # ---------------------------------------------------------------- m4_defun([_LT_TRY_DLOPEN_SELF], [m4_require([_LT_HEADER_DLFCN])dnl -if test "$cross_compiling" = yes; then : +if test yes = "$cross_compiling"; then : [$4] else lt_dlunknown=0; lt_dlno_uscore=1; lt_dlneed_uscore=2 @@ -1794,9 +1871,9 @@ else # endif #endif -/* When -fvisbility=hidden is used, assume the code has been annotated +/* When -fvisibility=hidden is used, assume the code has been annotated correspondingly for the symbols needed. */ -#if defined(__GNUC__) && (((__GNUC__ == 3) && (__GNUC_MINOR__ >= 3)) || (__GNUC__ > 3)) +#if defined __GNUC__ && (((__GNUC__ == 3) && (__GNUC_MINOR__ >= 3)) || (__GNUC__ > 3)) int fnord () __attribute__((visibility("default"))); #endif @@ -1822,7 +1899,7 @@ int main () return status; }] _LT_EOF - if AC_TRY_EVAL(ac_link) && test -s conftest${ac_exeext} 2>/dev/null; then + if AC_TRY_EVAL(ac_link) && test -s "conftest$ac_exeext" 2>/dev/null; then (./conftest; exit; ) >&AS_MESSAGE_LOG_FD 2>/dev/null lt_status=$? case x$lt_status in @@ -1843,7 +1920,7 @@ rm -fr conftest* # ------------------ AC_DEFUN([LT_SYS_DLOPEN_SELF], [m4_require([_LT_HEADER_DLFCN])dnl -if test "x$enable_dlopen" != xyes; then +if test yes != "$enable_dlopen"; then enable_dlopen=unknown enable_dlopen_self=unknown enable_dlopen_self_static=unknown @@ -1853,44 +1930,52 @@ else case $host_os in beos*) - lt_cv_dlopen="load_add_on" + lt_cv_dlopen=load_add_on lt_cv_dlopen_libs= lt_cv_dlopen_self=yes ;; mingw* | pw32* | cegcc*) - lt_cv_dlopen="LoadLibrary" + lt_cv_dlopen=LoadLibrary lt_cv_dlopen_libs= ;; cygwin*) - lt_cv_dlopen="dlopen" + lt_cv_dlopen=dlopen lt_cv_dlopen_libs= ;; darwin*) - # if libdl is installed we need to link against it + # if libdl is installed we need to link against it AC_CHECK_LIB([dl], [dlopen], - [lt_cv_dlopen="dlopen" lt_cv_dlopen_libs="-ldl"],[ - lt_cv_dlopen="dyld" + [lt_cv_dlopen=dlopen lt_cv_dlopen_libs=-ldl],[ + lt_cv_dlopen=dyld lt_cv_dlopen_libs= lt_cv_dlopen_self=yes ]) ;; + tpf*) + # Don't try to run any link tests for TPF. We know it's impossible + # because TPF is a cross-compiler, and we know how we open DSOs. + lt_cv_dlopen=dlopen + lt_cv_dlopen_libs= + lt_cv_dlopen_self=no + ;; + *) AC_CHECK_FUNC([shl_load], - [lt_cv_dlopen="shl_load"], + [lt_cv_dlopen=shl_load], [AC_CHECK_LIB([dld], [shl_load], - [lt_cv_dlopen="shl_load" lt_cv_dlopen_libs="-ldld"], + [lt_cv_dlopen=shl_load lt_cv_dlopen_libs=-ldld], [AC_CHECK_FUNC([dlopen], - [lt_cv_dlopen="dlopen"], + [lt_cv_dlopen=dlopen], [AC_CHECK_LIB([dl], [dlopen], - [lt_cv_dlopen="dlopen" lt_cv_dlopen_libs="-ldl"], + [lt_cv_dlopen=dlopen lt_cv_dlopen_libs=-ldl], [AC_CHECK_LIB([svld], [dlopen], - [lt_cv_dlopen="dlopen" lt_cv_dlopen_libs="-lsvld"], + [lt_cv_dlopen=dlopen lt_cv_dlopen_libs=-lsvld], [AC_CHECK_LIB([dld], [dld_link], - [lt_cv_dlopen="dld_link" lt_cv_dlopen_libs="-ldld"]) + [lt_cv_dlopen=dld_link lt_cv_dlopen_libs=-ldld]) ]) ]) ]) @@ -1899,21 +1984,21 @@ else ;; esac - if test "x$lt_cv_dlopen" != xno; then - enable_dlopen=yes - else + if test no = "$lt_cv_dlopen"; then enable_dlopen=no + else + enable_dlopen=yes fi case $lt_cv_dlopen in dlopen) - save_CPPFLAGS="$CPPFLAGS" - test "x$ac_cv_header_dlfcn_h" = xyes && CPPFLAGS="$CPPFLAGS -DHAVE_DLFCN_H" + save_CPPFLAGS=$CPPFLAGS + test yes = "$ac_cv_header_dlfcn_h" && CPPFLAGS="$CPPFLAGS -DHAVE_DLFCN_H" - save_LDFLAGS="$LDFLAGS" + save_LDFLAGS=$LDFLAGS wl=$lt_prog_compiler_wl eval LDFLAGS=\"\$LDFLAGS $export_dynamic_flag_spec\" - save_LIBS="$LIBS" + save_LIBS=$LIBS LIBS="$lt_cv_dlopen_libs $LIBS" AC_CACHE_CHECK([whether a program can dlopen itself], @@ -1923,7 +2008,7 @@ else lt_cv_dlopen_self=no, lt_cv_dlopen_self=cross) ]) - if test "x$lt_cv_dlopen_self" = xyes; then + if test yes = "$lt_cv_dlopen_self"; then wl=$lt_prog_compiler_wl eval LDFLAGS=\"\$LDFLAGS $lt_prog_compiler_static\" AC_CACHE_CHECK([whether a statically linked program can dlopen itself], lt_cv_dlopen_self_static, [dnl @@ -1933,9 +2018,9 @@ else ]) fi - CPPFLAGS="$save_CPPFLAGS" - LDFLAGS="$save_LDFLAGS" - LIBS="$save_LIBS" + CPPFLAGS=$save_CPPFLAGS + LDFLAGS=$save_LDFLAGS + LIBS=$save_LIBS ;; esac @@ -2027,8 +2112,8 @@ m4_defun([_LT_COMPILER_FILE_LOCKS], m4_require([_LT_FILEUTILS_DEFAULTS])dnl _LT_COMPILER_C_O([$1]) -hard_links="nottested" -if test "$_LT_TAGVAR(lt_cv_prog_compiler_c_o, $1)" = no && test "$need_locks" != no; then +hard_links=nottested +if test no = "$_LT_TAGVAR(lt_cv_prog_compiler_c_o, $1)" && test no != "$need_locks"; then # do not overwrite the value of need_locks provided by the user AC_MSG_CHECKING([if we can lock with hard links]) hard_links=yes @@ -2038,8 +2123,8 @@ if test "$_LT_TAGVAR(lt_cv_prog_compiler_c_o, $1)" = no && test "$need_locks" != ln conftest.a conftest.b 2>&5 || hard_links=no ln conftest.a conftest.b 2>/dev/null && hard_links=no AC_MSG_RESULT([$hard_links]) - if test "$hard_links" = no; then - AC_MSG_WARN([`$CC' does not support `-c -o', so `make -j' may be unsafe]) + if test no = "$hard_links"; then + AC_MSG_WARN(['$CC' does not support '-c -o', so 'make -j' may be unsafe]) need_locks=warn fi else @@ -2066,8 +2151,8 @@ objdir=$lt_cv_objdir _LT_DECL([], [objdir], [0], [The name of the directory that contains temporary libtool files])dnl m4_pattern_allow([LT_OBJDIR])dnl -AC_DEFINE_UNQUOTED(LT_OBJDIR, "$lt_cv_objdir/", - [Define to the sub-directory in which libtool stores uninstalled libraries.]) +AC_DEFINE_UNQUOTED([LT_OBJDIR], "$lt_cv_objdir/", + [Define to the sub-directory where libtool stores uninstalled libraries.]) ])# _LT_CHECK_OBJDIR @@ -2079,15 +2164,15 @@ m4_defun([_LT_LINKER_HARDCODE_LIBPATH], _LT_TAGVAR(hardcode_action, $1)= if test -n "$_LT_TAGVAR(hardcode_libdir_flag_spec, $1)" || test -n "$_LT_TAGVAR(runpath_var, $1)" || - test "X$_LT_TAGVAR(hardcode_automatic, $1)" = "Xyes" ; then + test yes = "$_LT_TAGVAR(hardcode_automatic, $1)"; then # We can hardcode non-existent directories. - if test "$_LT_TAGVAR(hardcode_direct, $1)" != no && + if test no != "$_LT_TAGVAR(hardcode_direct, $1)" && # If the only mechanism to avoid hardcoding is shlibpath_var, we # have to relink, otherwise we might link with an installed library # when we should be linking with a yet-to-be-installed one - ## test "$_LT_TAGVAR(hardcode_shlibpath_var, $1)" != no && - test "$_LT_TAGVAR(hardcode_minus_L, $1)" != no; then + ## test no != "$_LT_TAGVAR(hardcode_shlibpath_var, $1)" && + test no != "$_LT_TAGVAR(hardcode_minus_L, $1)"; then # Linking always hardcodes the temporary library directory. _LT_TAGVAR(hardcode_action, $1)=relink else @@ -2101,12 +2186,12 @@ else fi AC_MSG_RESULT([$_LT_TAGVAR(hardcode_action, $1)]) -if test "$_LT_TAGVAR(hardcode_action, $1)" = relink || - test "$_LT_TAGVAR(inherit_rpath, $1)" = yes; then +if test relink = "$_LT_TAGVAR(hardcode_action, $1)" || + test yes = "$_LT_TAGVAR(inherit_rpath, $1)"; then # Fast installation is not supported enable_fast_install=no -elif test "$shlibpath_overrides_runpath" = yes || - test "$enable_shared" = no; then +elif test yes = "$shlibpath_overrides_runpath" || + test no = "$enable_shared"; then # Fast installation is not necessary enable_fast_install=needless fi @@ -2130,7 +2215,7 @@ else # FIXME - insert some real tests, host_os isn't really good enough case $host_os in darwin*) - if test -n "$STRIP" ; then + if test -n "$STRIP"; then striplib="$STRIP -x" old_striplib="$STRIP -S" AC_MSG_RESULT([yes]) @@ -2148,6 +2233,47 @@ _LT_DECL([], [striplib], [1]) ])# _LT_CMD_STRIPLIB +# _LT_PREPARE_MUNGE_PATH_LIST +# --------------------------- +# Make sure func_munge_path_list() is defined correctly. +m4_defun([_LT_PREPARE_MUNGE_PATH_LIST], +[[# func_munge_path_list VARIABLE PATH +# ----------------------------------- +# VARIABLE is name of variable containing _space_ separated list of +# directories to be munged by the contents of PATH, which is string +# having a format: +# "DIR[:DIR]:" +# string "DIR[ DIR]" will be prepended to VARIABLE +# ":DIR[:DIR]" +# string "DIR[ DIR]" will be appended to VARIABLE +# "DIRP[:DIRP]::[DIRA:]DIRA" +# string "DIRP[ DIRP]" will be prepended to VARIABLE and string +# "DIRA[ DIRA]" will be appended to VARIABLE +# "DIR[:DIR]" +# VARIABLE will be replaced by "DIR[ DIR]" +func_munge_path_list () +{ + case x@S|@2 in + x) + ;; + *:) + eval @S|@1=\"`$ECHO @S|@2 | $SED 's/:/ /g'` \@S|@@S|@1\" + ;; + x:*) + eval @S|@1=\"\@S|@@S|@1 `$ECHO @S|@2 | $SED 's/:/ /g'`\" + ;; + *::*) + eval @S|@1=\"\@S|@@S|@1\ `$ECHO @S|@2 | $SED -e 's/.*:://' -e 's/:/ /g'`\" + eval @S|@1=\"`$ECHO @S|@2 | $SED -e 's/::.*//' -e 's/:/ /g'`\ \@S|@@S|@1\" + ;; + *) + eval @S|@1=\"`$ECHO @S|@2 | $SED 's/:/ /g'`\" + ;; + esac +} +]])# _LT_PREPARE_PATH_LIST + + # _LT_SYS_DYNAMIC_LINKER([TAG]) # ----------------------------- # PORTME Fill in your ld.so characteristics @@ -2158,17 +2284,18 @@ m4_require([_LT_FILEUTILS_DEFAULTS])dnl m4_require([_LT_DECL_OBJDUMP])dnl m4_require([_LT_DECL_SED])dnl m4_require([_LT_CHECK_SHELL_FEATURES])dnl +m4_require([_LT_PREPARE_MUNGE_PATH_LIST])dnl AC_MSG_CHECKING([dynamic linker characteristics]) m4_if([$1], [], [ -if test "$GCC" = yes; then +if test yes = "$GCC"; then case $host_os in - darwin*) lt_awk_arg="/^libraries:/,/LR/" ;; - *) lt_awk_arg="/^libraries:/" ;; + darwin*) lt_awk_arg='/^libraries:/,/LR/' ;; + *) lt_awk_arg='/^libraries:/' ;; esac case $host_os in - mingw* | cegcc*) lt_sed_strip_eq="s,=\([[A-Za-z]]:\),\1,g" ;; - *) lt_sed_strip_eq="s,=/,/,g" ;; + mingw* | cegcc*) lt_sed_strip_eq='s|=\([[A-Za-z]]:\)|\1|g' ;; + *) lt_sed_strip_eq='s|=/|/|g' ;; esac lt_search_path_spec=`$CC -print-search-dirs | awk $lt_awk_arg | $SED -e "s/^libraries://" -e $lt_sed_strip_eq` case $lt_search_path_spec in @@ -2184,28 +2311,35 @@ if test "$GCC" = yes; then ;; esac # Ok, now we have the path, separated by spaces, we can step through it - # and add multilib dir if necessary. + # and add multilib dir if necessary... lt_tmp_lt_search_path_spec= - lt_multi_os_dir=`$CC $CPPFLAGS $CFLAGS $LDFLAGS -print-multi-os-directory 2>/dev/null` + lt_multi_os_dir=/`$CC $CPPFLAGS $CFLAGS $LDFLAGS -print-multi-os-directory 2>/dev/null` + # ...but if some path component already ends with the multilib dir we assume + # that all is fine and trust -print-search-dirs as is (GCC 4.2? or newer). + case "$lt_multi_os_dir; $lt_search_path_spec " in + "/; "* | "/.; "* | "/./; "* | *"$lt_multi_os_dir "* | *"$lt_multi_os_dir/ "*) + lt_multi_os_dir= + ;; + esac for lt_sys_path in $lt_search_path_spec; do - if test -d "$lt_sys_path/$lt_multi_os_dir"; then - lt_tmp_lt_search_path_spec="$lt_tmp_lt_search_path_spec $lt_sys_path/$lt_multi_os_dir" - else + if test -d "$lt_sys_path$lt_multi_os_dir"; then + lt_tmp_lt_search_path_spec="$lt_tmp_lt_search_path_spec $lt_sys_path$lt_multi_os_dir" + elif test -n "$lt_multi_os_dir"; then test -d "$lt_sys_path" && \ lt_tmp_lt_search_path_spec="$lt_tmp_lt_search_path_spec $lt_sys_path" fi done lt_search_path_spec=`$ECHO "$lt_tmp_lt_search_path_spec" | awk ' -BEGIN {RS=" "; FS="/|\n";} { - lt_foo=""; - lt_count=0; +BEGIN {RS = " "; FS = "/|\n";} { + lt_foo = ""; + lt_count = 0; for (lt_i = NF; lt_i > 0; lt_i--) { if ($lt_i != "" && $lt_i != ".") { if ($lt_i == "..") { lt_count++; } else { if (lt_count == 0) { - lt_foo="/" $lt_i lt_foo; + lt_foo = "/" $lt_i lt_foo; } else { lt_count--; } @@ -2219,7 +2353,7 @@ BEGIN {RS=" "; FS="/|\n";} { # for these hosts. case $host_os in mingw* | cegcc*) lt_search_path_spec=`$ECHO "$lt_search_path_spec" |\ - $SED 's,/\([[A-Za-z]]:\),\1,g'` ;; + $SED 's|/\([[A-Za-z]]:\)|\1|g'` ;; esac sys_lib_search_path_spec=`$ECHO "$lt_search_path_spec" | $lt_NL2SP` else @@ -2228,7 +2362,7 @@ fi]) library_names_spec= libname_spec='lib$name' soname_spec= -shrext_cmds=".so" +shrext_cmds=.so postinstall_cmds= postuninstall_cmds= finish_cmds= @@ -2245,14 +2379,17 @@ hardcode_into_libs=no # flags to be left without arguments need_version=unknown +AC_ARG_VAR([LT_SYS_LIBRARY_PATH], +[User-defined run-time library search path.]) + case $host_os in aix3*) version_type=linux # correct to gnu/linux during the next big refactor - library_names_spec='${libname}${release}${shared_ext}$versuffix $libname.a' + library_names_spec='$libname$release$shared_ext$versuffix $libname.a' shlibpath_var=LIBPATH # AIX 3 has no versioning support, so we append a major version to the name. - soname_spec='${libname}${release}${shared_ext}$major' + soname_spec='$libname$release$shared_ext$major' ;; aix[[4-9]]*) @@ -2260,41 +2397,91 @@ aix[[4-9]]*) need_lib_prefix=no need_version=no hardcode_into_libs=yes - if test "$host_cpu" = ia64; then + if test ia64 = "$host_cpu"; then # AIX 5 supports IA64 - library_names_spec='${libname}${release}${shared_ext}$major ${libname}${release}${shared_ext}$versuffix $libname${shared_ext}' + library_names_spec='$libname$release$shared_ext$major $libname$release$shared_ext$versuffix $libname$shared_ext' shlibpath_var=LD_LIBRARY_PATH else # With GCC up to 2.95.x, collect2 would create an import file # for dependence libraries. The import file would start with - # the line `#! .'. This would cause the generated library to - # depend on `.', always an invalid library. This was fixed in + # the line '#! .'. This would cause the generated library to + # depend on '.', always an invalid library. This was fixed in # development snapshots of GCC prior to 3.0. case $host_os in aix4 | aix4.[[01]] | aix4.[[01]].*) if { echo '#if __GNUC__ > 2 || (__GNUC__ == 2 && __GNUC_MINOR__ >= 97)' echo ' yes ' - echo '#endif'; } | ${CC} -E - | $GREP yes > /dev/null; then + echo '#endif'; } | $CC -E - | $GREP yes > /dev/null; then : else can_build_shared=no fi ;; esac - # AIX (on Power*) has no versioning support, so currently we can not hardcode correct + # Using Import Files as archive members, it is possible to support + # filename-based versioning of shared library archives on AIX. While + # this would work for both with and without runtime linking, it will + # prevent static linking of such archives. So we do filename-based + # shared library versioning with .so extension only, which is used + # when both runtime linking and shared linking is enabled. + # Unfortunately, runtime linking may impact performance, so we do + # not want this to be the default eventually. Also, we use the + # versioned .so libs for executables only if there is the -brtl + # linker flag in LDFLAGS as well, or --with-aix-soname=svr4 only. + # To allow for filename-based versioning support, we need to create + # libNAME.so.V as an archive file, containing: + # *) an Import File, referring to the versioned filename of the + # archive as well as the shared archive member, telling the + # bitwidth (32 or 64) of that shared object, and providing the + # list of exported symbols of that shared object, eventually + # decorated with the 'weak' keyword + # *) the shared object with the F_LOADONLY flag set, to really avoid + # it being seen by the linker. + # At run time we better use the real file rather than another symlink, + # but for link time we create the symlink libNAME.so -> libNAME.so.V + + case $with_aix_soname,$aix_use_runtimelinking in + # AIX (on Power*) has no versioning support, so currently we cannot hardcode correct # soname into executable. Probably we can add versioning support to # collect2, so additional links can be useful in future. - if test "$aix_use_runtimelinking" = yes; then + aix,yes) # traditional libtool + dynamic_linker='AIX unversionable lib.so' # If using run time linking (on AIX 4.2 or later) use lib.so # instead of lib.a to let people know that these are not # typical AIX shared libraries. - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' - else + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$shared_ext' + ;; + aix,no) # traditional AIX only + dynamic_linker='AIX lib.a[(]lib.so.V[)]' # We preserve .a as extension for shared libraries through AIX4.2 # and later when we are not doing run time linking. - library_names_spec='${libname}${release}.a $libname.a' - soname_spec='${libname}${release}${shared_ext}$major' - fi + library_names_spec='$libname$release.a $libname.a' + soname_spec='$libname$release$shared_ext$major' + ;; + svr4,*) # full svr4 only + dynamic_linker="AIX lib.so.V[(]$shared_archive_member_spec.o[)]" + library_names_spec='$libname$release$shared_ext$major $libname$shared_ext' + # We do not specify a path in Import Files, so LIBPATH fires. + shlibpath_overrides_runpath=yes + ;; + *,yes) # both, prefer svr4 + dynamic_linker="AIX lib.so.V[(]$shared_archive_member_spec.o[)], lib.a[(]lib.so.V[)]" + library_names_spec='$libname$release$shared_ext$major $libname$shared_ext' + # unpreferred sharedlib libNAME.a needs extra handling + postinstall_cmds='test -n "$linkname" || linkname="$realname"~func_stripname "" ".so" "$linkname"~$install_shared_prog "$dir/$func_stripname_result.$libext" "$destdir/$func_stripname_result.$libext"~test -z "$tstripme" || test -z "$striplib" || $striplib "$destdir/$func_stripname_result.$libext"' + postuninstall_cmds='for n in $library_names $old_library; do :; done~func_stripname "" ".so" "$n"~test "$func_stripname_result" = "$n" || func_append rmfiles " $odir/$func_stripname_result.$libext"' + # We do not specify a path in Import Files, so LIBPATH fires. + shlibpath_overrides_runpath=yes + ;; + *,no) # both, prefer aix + dynamic_linker="AIX lib.a[(]lib.so.V[)], lib.so.V[(]$shared_archive_member_spec.o[)]" + library_names_spec='$libname$release.a $libname.a' + soname_spec='$libname$release$shared_ext$major' + # unpreferred sharedlib libNAME.so.V and symlink libNAME.so need extra handling + postinstall_cmds='test -z "$dlname" || $install_shared_prog $dir/$dlname $destdir/$dlname~test -z "$tstripme" || test -z "$striplib" || $striplib $destdir/$dlname~test -n "$linkname" || linkname=$realname~func_stripname "" ".a" "$linkname"~(cd "$destdir" && $LN_S -f $dlname $func_stripname_result.so)' + postuninstall_cmds='test -z "$dlname" || func_append rmfiles " $odir/$dlname"~for n in $old_library $library_names; do :; done~func_stripname "" ".a" "$n"~func_append rmfiles " $odir/$func_stripname_result.so"' + ;; + esac shlibpath_var=LIBPATH fi ;; @@ -2304,18 +2491,18 @@ amigaos*) powerpc) # Since July 2007 AmigaOS4 officially supports .so libraries. # When compiling the executable, add -use-dynld -Lsobjs: to the compileline. - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$shared_ext' ;; m68k) library_names_spec='$libname.ixlibrary $libname.a' # Create ${libname}_ixlibrary.a entries in /sys/libs. - finish_eval='for lib in `ls $libdir/*.ixlibrary 2>/dev/null`; do libname=`func_echo_all "$lib" | $SED '\''s%^.*/\([[^/]]*\)\.ixlibrary$%\1%'\''`; test $RM /sys/libs/${libname}_ixlibrary.a; $show "cd /sys/libs && $LN_S $lib ${libname}_ixlibrary.a"; cd /sys/libs && $LN_S $lib ${libname}_ixlibrary.a || exit 1; done' + finish_eval='for lib in `ls $libdir/*.ixlibrary 2>/dev/null`; do libname=`func_echo_all "$lib" | $SED '\''s%^.*/\([[^/]]*\)\.ixlibrary$%\1%'\''`; $RM /sys/libs/${libname}_ixlibrary.a; $show "cd /sys/libs && $LN_S $lib ${libname}_ixlibrary.a"; cd /sys/libs && $LN_S $lib ${libname}_ixlibrary.a || exit 1; done' ;; esac ;; beos*) - library_names_spec='${libname}${shared_ext}' + library_names_spec='$libname$shared_ext' dynamic_linker="$host_os ld.so" shlibpath_var=LIBRARY_PATH ;; @@ -2323,8 +2510,8 @@ beos*) bsdi[[45]]*) version_type=linux # correct to gnu/linux during the next big refactor need_version=no - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' - soname_spec='${libname}${release}${shared_ext}$major' + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$shared_ext' + soname_spec='$libname$release$shared_ext$major' finish_cmds='PATH="\$PATH:/sbin" ldconfig $libdir' shlibpath_var=LD_LIBRARY_PATH sys_lib_search_path_spec="/shlib /usr/lib /usr/X11/lib /usr/contrib/lib /lib /usr/local/lib" @@ -2336,7 +2523,7 @@ bsdi[[45]]*) cygwin* | mingw* | pw32* | cegcc*) version_type=windows - shrext_cmds=".dll" + shrext_cmds=.dll need_version=no need_lib_prefix=no @@ -2345,8 +2532,8 @@ cygwin* | mingw* | pw32* | cegcc*) # gcc library_names_spec='$libname.dll.a' # DLL is installed to $(libdir)/../bin by postinstall_cmds - postinstall_cmds='base_file=`basename \${file}`~ - dlpath=`$SHELL 2>&1 -c '\''. $dir/'\''\${base_file}'\''i; echo \$dlname'\''`~ + postinstall_cmds='base_file=`basename \$file`~ + dlpath=`$SHELL 2>&1 -c '\''. $dir/'\''\$base_file'\''i; echo \$dlname'\''`~ dldir=$destdir/`dirname \$dlpath`~ test -d \$dldir || mkdir -p \$dldir~ $install_prog $dir/$dlname \$dldir/$dlname~ @@ -2362,17 +2549,17 @@ cygwin* | mingw* | pw32* | cegcc*) case $host_os in cygwin*) # Cygwin DLLs use 'cyg' prefix rather than 'lib' - soname_spec='`echo ${libname} | sed -e 's/^lib/cyg/'``echo ${release} | $SED -e 's/[[.]]/-/g'`${versuffix}${shared_ext}' + soname_spec='`echo $libname | sed -e 's/^lib/cyg/'``echo $release | $SED -e 's/[[.]]/-/g'`$versuffix$shared_ext' m4_if([$1], [],[ sys_lib_search_path_spec="$sys_lib_search_path_spec /usr/lib/w32api"]) ;; mingw* | cegcc*) # MinGW DLLs use traditional 'lib' prefix - soname_spec='${libname}`echo ${release} | $SED -e 's/[[.]]/-/g'`${versuffix}${shared_ext}' + soname_spec='$libname`echo $release | $SED -e 's/[[.]]/-/g'`$versuffix$shared_ext' ;; pw32*) # pw32 DLLs use 'pw' prefix rather than 'lib' - library_names_spec='`echo ${libname} | sed -e 's/^lib/pw/'``echo ${release} | $SED -e 's/[[.]]/-/g'`${versuffix}${shared_ext}' + library_names_spec='`echo $libname | sed -e 's/^lib/pw/'``echo $release | $SED -e 's/[[.]]/-/g'`$versuffix$shared_ext' ;; esac dynamic_linker='Win32 ld.exe' @@ -2381,8 +2568,8 @@ m4_if([$1], [],[ *,cl*) # Native MSVC libname_spec='$name' - soname_spec='${libname}`echo ${release} | $SED -e 's/[[.]]/-/g'`${versuffix}${shared_ext}' - library_names_spec='${libname}.dll.lib' + soname_spec='$libname`echo $release | $SED -e 's/[[.]]/-/g'`$versuffix$shared_ext' + library_names_spec='$libname.dll.lib' case $build_os in mingw*) @@ -2409,7 +2596,7 @@ m4_if([$1], [],[ sys_lib_search_path_spec=`cygpath --path --unix "$sys_lib_search_path_spec" | $SED -e "s/$PATH_SEPARATOR/ /g"` ;; *) - sys_lib_search_path_spec="$LIB" + sys_lib_search_path_spec=$LIB if $ECHO "$sys_lib_search_path_spec" | [$GREP ';[c-zC-Z]:/' >/dev/null]; then # It is most probably a Windows format PATH. sys_lib_search_path_spec=`$ECHO "$sys_lib_search_path_spec" | $SED -e 's/;/ /g'` @@ -2422,8 +2609,8 @@ m4_if([$1], [],[ esac # DLL is installed to $(libdir)/../bin by postinstall_cmds - postinstall_cmds='base_file=`basename \${file}`~ - dlpath=`$SHELL 2>&1 -c '\''. $dir/'\''\${base_file}'\''i; echo \$dlname'\''`~ + postinstall_cmds='base_file=`basename \$file`~ + dlpath=`$SHELL 2>&1 -c '\''. $dir/'\''\$base_file'\''i; echo \$dlname'\''`~ dldir=$destdir/`dirname \$dlpath`~ test -d \$dldir || mkdir -p \$dldir~ $install_prog $dir/$dlname \$dldir/$dlname' @@ -2436,7 +2623,7 @@ m4_if([$1], [],[ *) # Assume MSVC wrapper - library_names_spec='${libname}`echo ${release} | $SED -e 's/[[.]]/-/g'`${versuffix}${shared_ext} $libname.lib' + library_names_spec='$libname`echo $release | $SED -e 's/[[.]]/-/g'`$versuffix$shared_ext $libname.lib' dynamic_linker='Win32 ld.exe' ;; esac @@ -2449,8 +2636,8 @@ darwin* | rhapsody*) version_type=darwin need_lib_prefix=no need_version=no - library_names_spec='${libname}${release}${major}$shared_ext ${libname}$shared_ext' - soname_spec='${libname}${release}${major}$shared_ext' + library_names_spec='$libname$release$major$shared_ext $libname$shared_ext' + soname_spec='$libname$release$major$shared_ext' shlibpath_overrides_runpath=yes shlibpath_var=DYLD_LIBRARY_PATH shrext_cmds='`test .$module = .yes && echo .so || echo .dylib`' @@ -2463,8 +2650,8 @@ dgux*) version_type=linux # correct to gnu/linux during the next big refactor need_lib_prefix=no need_version=no - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname$shared_ext' - soname_spec='${libname}${release}${shared_ext}$major' + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$shared_ext' + soname_spec='$libname$release$shared_ext$major' shlibpath_var=LD_LIBRARY_PATH ;; @@ -2482,12 +2669,13 @@ freebsd* | dragonfly*) version_type=freebsd-$objformat case $version_type in freebsd-elf*) - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext} $libname${shared_ext}' + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$shared_ext' + soname_spec='$libname$release$shared_ext$major' need_version=no need_lib_prefix=no ;; freebsd-*) - library_names_spec='${libname}${release}${shared_ext}$versuffix $libname${shared_ext}$versuffix' + library_names_spec='$libname$release$shared_ext$versuffix $libname$shared_ext$versuffix' need_version=yes ;; esac @@ -2512,26 +2700,15 @@ freebsd* | dragonfly*) esac ;; -gnu*) - version_type=linux # correct to gnu/linux during the next big refactor - need_lib_prefix=no - need_version=no - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}${major} ${libname}${shared_ext}' - soname_spec='${libname}${release}${shared_ext}$major' - shlibpath_var=LD_LIBRARY_PATH - shlibpath_overrides_runpath=no - hardcode_into_libs=yes - ;; - haiku*) version_type=linux # correct to gnu/linux during the next big refactor need_lib_prefix=no need_version=no dynamic_linker="$host_os runtime_loader" - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}${major} ${libname}${shared_ext}' - soname_spec='${libname}${release}${shared_ext}$major' + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$shared_ext' + soname_spec='$libname$release$shared_ext$major' shlibpath_var=LIBRARY_PATH - shlibpath_overrides_runpath=yes + shlibpath_overrides_runpath=no sys_lib_dlsearch_path_spec='/boot/home/config/lib /boot/common/lib /boot/system/lib' hardcode_into_libs=yes ;; @@ -2549,14 +2726,15 @@ hpux9* | hpux10* | hpux11*) dynamic_linker="$host_os dld.so" shlibpath_var=LD_LIBRARY_PATH shlibpath_overrides_runpath=yes # Unless +noenvvar is specified. - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' - soname_spec='${libname}${release}${shared_ext}$major' - if test "X$HPUX_IA64_MODE" = X32; then + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$shared_ext' + soname_spec='$libname$release$shared_ext$major' + if test 32 = "$HPUX_IA64_MODE"; then sys_lib_search_path_spec="/usr/lib/hpux32 /usr/local/lib/hpux32 /usr/local/lib" + sys_lib_dlsearch_path_spec=/usr/lib/hpux32 else sys_lib_search_path_spec="/usr/lib/hpux64 /usr/local/lib/hpux64" + sys_lib_dlsearch_path_spec=/usr/lib/hpux64 fi - sys_lib_dlsearch_path_spec=$sys_lib_search_path_spec ;; hppa*64*) shrext_cmds='.sl' @@ -2564,8 +2742,8 @@ hpux9* | hpux10* | hpux11*) dynamic_linker="$host_os dld.sl" shlibpath_var=LD_LIBRARY_PATH # How should we handle SHLIB_PATH shlibpath_overrides_runpath=yes # Unless +noenvvar is specified. - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' - soname_spec='${libname}${release}${shared_ext}$major' + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$shared_ext' + soname_spec='$libname$release$shared_ext$major' sys_lib_search_path_spec="/usr/lib/pa20_64 /usr/ccs/lib/pa20_64" sys_lib_dlsearch_path_spec=$sys_lib_search_path_spec ;; @@ -2574,8 +2752,8 @@ hpux9* | hpux10* | hpux11*) dynamic_linker="$host_os dld.sl" shlibpath_var=SHLIB_PATH shlibpath_overrides_runpath=no # +s is required to enable SHLIB_PATH - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' - soname_spec='${libname}${release}${shared_ext}$major' + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$shared_ext' + soname_spec='$libname$release$shared_ext$major' ;; esac # HP-UX runs *really* slowly unless shared libraries are mode 555, ... @@ -2588,8 +2766,8 @@ interix[[3-9]]*) version_type=linux # correct to gnu/linux during the next big refactor need_lib_prefix=no need_version=no - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major ${libname}${shared_ext}' - soname_spec='${libname}${release}${shared_ext}$major' + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$shared_ext' + soname_spec='$libname$release$shared_ext$major' dynamic_linker='Interix 3.x ld.so.1 (PE, like ELF)' shlibpath_var=LD_LIBRARY_PATH shlibpath_overrides_runpath=no @@ -2600,7 +2778,7 @@ irix5* | irix6* | nonstopux*) case $host_os in nonstopux*) version_type=nonstopux ;; *) - if test "$lt_cv_prog_gnu_ld" = yes; then + if test yes = "$lt_cv_prog_gnu_ld"; then version_type=linux # correct to gnu/linux during the next big refactor else version_type=irix @@ -2608,8 +2786,8 @@ irix5* | irix6* | nonstopux*) esac need_lib_prefix=no need_version=no - soname_spec='${libname}${release}${shared_ext}$major' - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major ${libname}${release}${shared_ext} $libname${shared_ext}' + soname_spec='$libname$release$shared_ext$major' + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$release$shared_ext $libname$shared_ext' case $host_os in irix5* | nonstopux*) libsuff= shlibsuff= @@ -2628,8 +2806,8 @@ irix5* | irix6* | nonstopux*) esac shlibpath_var=LD_LIBRARY${shlibsuff}_PATH shlibpath_overrides_runpath=no - sys_lib_search_path_spec="/usr/lib${libsuff} /lib${libsuff} /usr/local/lib${libsuff}" - sys_lib_dlsearch_path_spec="/usr/lib${libsuff} /lib${libsuff}" + sys_lib_search_path_spec="/usr/lib$libsuff /lib$libsuff /usr/local/lib$libsuff" + sys_lib_dlsearch_path_spec="/usr/lib$libsuff /lib$libsuff" hardcode_into_libs=yes ;; @@ -2638,13 +2816,33 @@ linux*oldld* | linux*aout* | linux*coff*) dynamic_linker=no ;; +linux*android*) + version_type=none # Android doesn't support versioned libraries. + need_lib_prefix=no + need_version=no + library_names_spec='$libname$release$shared_ext' + soname_spec='$libname$release$shared_ext' + finish_cmds= + shlibpath_var=LD_LIBRARY_PATH + shlibpath_overrides_runpath=yes + + # This implies no fast_install, which is unacceptable. + # Some rework will be needed to allow for fast_install + # before this can be enabled. + hardcode_into_libs=yes + + dynamic_linker='Android linker' + # Don't embed -rpath directories since the linker doesn't support them. + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='-L$libdir' + ;; + # This must be glibc/ELF. -linux* | k*bsd*-gnu | kopensolaris*-gnu) +linux* | k*bsd*-gnu | kopensolaris*-gnu | gnu*) version_type=linux # correct to gnu/linux during the next big refactor need_lib_prefix=no need_version=no - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' - soname_spec='${libname}${release}${shared_ext}$major' + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$shared_ext' + soname_spec='$libname$release$shared_ext$major' finish_cmds='PATH="\$PATH:/sbin" ldconfig -n $libdir' shlibpath_var=LD_LIBRARY_PATH shlibpath_overrides_runpath=no @@ -2672,11 +2870,15 @@ linux* | k*bsd*-gnu | kopensolaris*-gnu) # Add ABI-specific directories to the system library path. sys_lib_dlsearch_path_spec="/lib64 /usr/lib64 /lib /usr/lib" - # Append ld.so.conf contents to the search path + # Ideally, we could use ldconfig to report *all* directores which are + # searched for libraries, however this is still not possible. Aside from not + # being certain /sbin/ldconfig is available, command + # 'ldconfig -N -X -v | grep ^/' on 64bit Fedora does not report /usr/lib64, + # even though it is searched at run-time. Try to do the best guess by + # appending ld.so.conf contents (and includes) to the search path. if test -f /etc/ld.so.conf; then lt_ld_extra=`awk '/^include / { system(sprintf("cd /etc; cat %s 2>/dev/null", \[$]2)); skip = 1; } { if (!skip) print \[$]0; skip = 0; }' < /etc/ld.so.conf | $SED -e 's/#.*//;/^[ ]*hwcap[ ]/d;s/[:, ]/ /g;s/=[^=]*$//;s/=[^= ]* / /g;s/"//g;/^$/d' | tr '\n' ' '` sys_lib_dlsearch_path_spec="$sys_lib_dlsearch_path_spec $lt_ld_extra" - fi # We used to test for /lib/ld.so.1 and disable shared libraries on @@ -2693,12 +2895,12 @@ netbsd*) need_lib_prefix=no need_version=no if echo __ELF__ | $CC -E - | $GREP __ELF__ >/dev/null; then - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${shared_ext}$versuffix' + library_names_spec='$libname$release$shared_ext$versuffix $libname$shared_ext$versuffix' finish_cmds='PATH="\$PATH:/sbin" ldconfig -m $libdir' dynamic_linker='NetBSD (a.out) ld.so' else - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major ${libname}${shared_ext}' - soname_spec='${libname}${release}${shared_ext}$major' + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$shared_ext' + soname_spec='$libname$release$shared_ext$major' dynamic_linker='NetBSD ld.elf_so' fi shlibpath_var=LD_LIBRARY_PATH @@ -2708,7 +2910,7 @@ netbsd*) newsos6) version_type=linux # correct to gnu/linux during the next big refactor - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$shared_ext' shlibpath_var=LD_LIBRARY_PATH shlibpath_overrides_runpath=yes ;; @@ -2717,58 +2919,68 @@ newsos6) version_type=qnx need_lib_prefix=no need_version=no - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' - soname_spec='${libname}${release}${shared_ext}$major' + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$shared_ext' + soname_spec='$libname$release$shared_ext$major' shlibpath_var=LD_LIBRARY_PATH shlibpath_overrides_runpath=no hardcode_into_libs=yes dynamic_linker='ldqnx.so' ;; -openbsd*) +openbsd* | bitrig*) version_type=sunos - sys_lib_dlsearch_path_spec="/usr/lib" + sys_lib_dlsearch_path_spec=/usr/lib need_lib_prefix=no - # Some older versions of OpenBSD (3.3 at least) *do* need versioned libs. - case $host_os in - openbsd3.3 | openbsd3.3.*) need_version=yes ;; - *) need_version=no ;; - esac - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${shared_ext}$versuffix' + if test -z "`echo __ELF__ | $CC -E - | $GREP __ELF__`"; then + need_version=no + else + need_version=yes + fi + library_names_spec='$libname$release$shared_ext$versuffix $libname$shared_ext$versuffix' finish_cmds='PATH="\$PATH:/sbin" ldconfig -m $libdir' shlibpath_var=LD_LIBRARY_PATH - if test -z "`echo __ELF__ | $CC -E - | $GREP __ELF__`" || test "$host_os-$host_cpu" = "openbsd2.8-powerpc"; then - case $host_os in - openbsd2.[[89]] | openbsd2.[[89]].*) - shlibpath_overrides_runpath=no - ;; - *) - shlibpath_overrides_runpath=yes - ;; - esac - else - shlibpath_overrides_runpath=yes - fi + shlibpath_overrides_runpath=yes ;; os2*) libname_spec='$name' - shrext_cmds=".dll" + version_type=windows + shrext_cmds=.dll + need_version=no need_lib_prefix=no - library_names_spec='$libname${shared_ext} $libname.a' + # OS/2 can only load a DLL with a base name of 8 characters or less. + soname_spec='`test -n "$os2dllname" && libname="$os2dllname"; + v=$($ECHO $release$versuffix | tr -d .-); + n=$($ECHO $libname | cut -b -$((8 - ${#v})) | tr . _); + $ECHO $n$v`$shared_ext' + library_names_spec='${libname}_dll.$libext' dynamic_linker='OS/2 ld.exe' - shlibpath_var=LIBPATH + shlibpath_var=BEGINLIBPATH + sys_lib_search_path_spec="/lib /usr/lib /usr/local/lib" + sys_lib_dlsearch_path_spec=$sys_lib_search_path_spec + postinstall_cmds='base_file=`basename \$file`~ + dlpath=`$SHELL 2>&1 -c '\''. $dir/'\''\$base_file'\''i; $ECHO \$dlname'\''`~ + dldir=$destdir/`dirname \$dlpath`~ + test -d \$dldir || mkdir -p \$dldir~ + $install_prog $dir/$dlname \$dldir/$dlname~ + chmod a+x \$dldir/$dlname~ + if test -n '\''$stripme'\'' && test -n '\''$striplib'\''; then + eval '\''$striplib \$dldir/$dlname'\'' || exit \$?; + fi' + postuninstall_cmds='dldll=`$SHELL 2>&1 -c '\''. $file; $ECHO \$dlname'\''`~ + dlpath=$dir/\$dldll~ + $RM \$dlpath' ;; osf3* | osf4* | osf5*) version_type=osf need_lib_prefix=no need_version=no - soname_spec='${libname}${release}${shared_ext}$major' - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' + soname_spec='$libname$release$shared_ext$major' + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$shared_ext' shlibpath_var=LD_LIBRARY_PATH sys_lib_search_path_spec="/usr/shlib /usr/ccs/lib /usr/lib/cmplrs/cc /usr/lib /usr/local/lib /var/shlib" - sys_lib_dlsearch_path_spec="$sys_lib_search_path_spec" + sys_lib_dlsearch_path_spec=$sys_lib_search_path_spec ;; rdos*) @@ -2779,8 +2991,8 @@ solaris*) version_type=linux # correct to gnu/linux during the next big refactor need_lib_prefix=no need_version=no - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' - soname_spec='${libname}${release}${shared_ext}$major' + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$shared_ext' + soname_spec='$libname$release$shared_ext$major' shlibpath_var=LD_LIBRARY_PATH shlibpath_overrides_runpath=yes hardcode_into_libs=yes @@ -2790,11 +3002,11 @@ solaris*) sunos4*) version_type=sunos - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${shared_ext}$versuffix' + library_names_spec='$libname$release$shared_ext$versuffix $libname$shared_ext$versuffix' finish_cmds='PATH="\$PATH:/usr/etc" ldconfig $libdir' shlibpath_var=LD_LIBRARY_PATH shlibpath_overrides_runpath=yes - if test "$with_gnu_ld" = yes; then + if test yes = "$with_gnu_ld"; then need_lib_prefix=no fi need_version=yes @@ -2802,8 +3014,8 @@ sunos4*) sysv4 | sysv4.3*) version_type=linux # correct to gnu/linux during the next big refactor - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' - soname_spec='${libname}${release}${shared_ext}$major' + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$shared_ext' + soname_spec='$libname$release$shared_ext$major' shlibpath_var=LD_LIBRARY_PATH case $host_vendor in sni) @@ -2824,24 +3036,24 @@ sysv4 | sysv4.3*) ;; sysv4*MP*) - if test -d /usr/nec ;then + if test -d /usr/nec; then version_type=linux # correct to gnu/linux during the next big refactor - library_names_spec='$libname${shared_ext}.$versuffix $libname${shared_ext}.$major $libname${shared_ext}' - soname_spec='$libname${shared_ext}.$major' + library_names_spec='$libname$shared_ext.$versuffix $libname$shared_ext.$major $libname$shared_ext' + soname_spec='$libname$shared_ext.$major' shlibpath_var=LD_LIBRARY_PATH fi ;; sysv5* | sco3.2v5* | sco5v6* | unixware* | OpenUNIX* | sysv4*uw2*) - version_type=freebsd-elf + version_type=sco need_lib_prefix=no need_version=no - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext} $libname${shared_ext}' - soname_spec='${libname}${release}${shared_ext}$major' + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext $libname$shared_ext' + soname_spec='$libname$release$shared_ext$major' shlibpath_var=LD_LIBRARY_PATH shlibpath_overrides_runpath=yes hardcode_into_libs=yes - if test "$with_gnu_ld" = yes; then + if test yes = "$with_gnu_ld"; then sys_lib_search_path_spec='/usr/local/lib /usr/gnu/lib /usr/ccs/lib /usr/lib /lib' else sys_lib_search_path_spec='/usr/ccs/lib /usr/lib' @@ -2859,7 +3071,7 @@ tpf*) version_type=linux # correct to gnu/linux during the next big refactor need_lib_prefix=no need_version=no - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$shared_ext' shlibpath_var=LD_LIBRARY_PATH shlibpath_overrides_runpath=no hardcode_into_libs=yes @@ -2867,8 +3079,8 @@ tpf*) uts4*) version_type=linux # correct to gnu/linux during the next big refactor - library_names_spec='${libname}${release}${shared_ext}$versuffix ${libname}${release}${shared_ext}$major $libname${shared_ext}' - soname_spec='${libname}${release}${shared_ext}$major' + library_names_spec='$libname$release$shared_ext$versuffix $libname$release$shared_ext$major $libname$shared_ext' + soname_spec='$libname$release$shared_ext$major' shlibpath_var=LD_LIBRARY_PATH ;; @@ -2877,20 +3089,30 @@ uts4*) ;; esac AC_MSG_RESULT([$dynamic_linker]) -test "$dynamic_linker" = no && can_build_shared=no +test no = "$dynamic_linker" && can_build_shared=no variables_saved_for_relink="PATH $shlibpath_var $runpath_var" -if test "$GCC" = yes; then +if test yes = "$GCC"; then variables_saved_for_relink="$variables_saved_for_relink GCC_EXEC_PREFIX COMPILER_PATH LIBRARY_PATH" fi -if test "${lt_cv_sys_lib_search_path_spec+set}" = set; then - sys_lib_search_path_spec="$lt_cv_sys_lib_search_path_spec" +if test set = "${lt_cv_sys_lib_search_path_spec+set}"; then + sys_lib_search_path_spec=$lt_cv_sys_lib_search_path_spec fi -if test "${lt_cv_sys_lib_dlsearch_path_spec+set}" = set; then - sys_lib_dlsearch_path_spec="$lt_cv_sys_lib_dlsearch_path_spec" + +if test set = "${lt_cv_sys_lib_dlsearch_path_spec+set}"; then + sys_lib_dlsearch_path_spec=$lt_cv_sys_lib_dlsearch_path_spec fi +# remember unaugmented sys_lib_dlsearch_path content for libtool script decls... +configure_time_dlsearch_path=$sys_lib_dlsearch_path_spec + +# ... but it needs LT_SYS_LIBRARY_PATH munging for other configure-time code +func_munge_path_list sys_lib_dlsearch_path_spec "$LT_SYS_LIBRARY_PATH" + +# to be used as default LT_SYS_LIBRARY_PATH value in generated libtool +configure_time_lt_sys_library_path=$LT_SYS_LIBRARY_PATH + _LT_DECL([], [variables_saved_for_relink], [1], [Variables whose values should be saved in libtool wrapper scripts and restored at link time]) @@ -2923,39 +3145,41 @@ _LT_DECL([], [hardcode_into_libs], [0], [Whether we should hardcode library paths into libraries]) _LT_DECL([], [sys_lib_search_path_spec], [2], [Compile-time system search path for libraries]) -_LT_DECL([], [sys_lib_dlsearch_path_spec], [2], - [Run-time system search path for libraries]) +_LT_DECL([sys_lib_dlsearch_path_spec], [configure_time_dlsearch_path], [2], + [Detected run-time system search path for libraries]) +_LT_DECL([], [configure_time_lt_sys_library_path], [2], + [Explicit LT_SYS_LIBRARY_PATH set during ./configure time]) ])# _LT_SYS_DYNAMIC_LINKER # _LT_PATH_TOOL_PREFIX(TOOL) # -------------------------- -# find a file program which can recognize shared library +# find a file program that can recognize shared library AC_DEFUN([_LT_PATH_TOOL_PREFIX], [m4_require([_LT_DECL_EGREP])dnl AC_MSG_CHECKING([for $1]) AC_CACHE_VAL(lt_cv_path_MAGIC_CMD, [case $MAGIC_CMD in [[\\/*] | ?:[\\/]*]) - lt_cv_path_MAGIC_CMD="$MAGIC_CMD" # Let the user override the test with a path. + lt_cv_path_MAGIC_CMD=$MAGIC_CMD # Let the user override the test with a path. ;; *) - lt_save_MAGIC_CMD="$MAGIC_CMD" - lt_save_ifs="$IFS"; IFS=$PATH_SEPARATOR + lt_save_MAGIC_CMD=$MAGIC_CMD + lt_save_ifs=$IFS; IFS=$PATH_SEPARATOR dnl $ac_dummy forces splitting on constant user-supplied paths. dnl POSIX.2 word splitting is done only on the output of word expansions, dnl not every word. This closes a longstanding sh security hole. ac_dummy="m4_if([$2], , $PATH, [$2])" for ac_dir in $ac_dummy; do - IFS="$lt_save_ifs" + IFS=$lt_save_ifs test -z "$ac_dir" && ac_dir=. - if test -f $ac_dir/$1; then - lt_cv_path_MAGIC_CMD="$ac_dir/$1" + if test -f "$ac_dir/$1"; then + lt_cv_path_MAGIC_CMD=$ac_dir/"$1" if test -n "$file_magic_test_file"; then case $deplibs_check_method in "file_magic "*) file_magic_regex=`expr "$deplibs_check_method" : "file_magic \(.*\)"` - MAGIC_CMD="$lt_cv_path_MAGIC_CMD" + MAGIC_CMD=$lt_cv_path_MAGIC_CMD if eval $file_magic_cmd \$file_magic_test_file 2> /dev/null | $EGREP "$file_magic_regex" > /dev/null; then : @@ -2978,11 +3202,11 @@ _LT_EOF break fi done - IFS="$lt_save_ifs" - MAGIC_CMD="$lt_save_MAGIC_CMD" + IFS=$lt_save_ifs + MAGIC_CMD=$lt_save_MAGIC_CMD ;; esac]) -MAGIC_CMD="$lt_cv_path_MAGIC_CMD" +MAGIC_CMD=$lt_cv_path_MAGIC_CMD if test -n "$MAGIC_CMD"; then AC_MSG_RESULT($MAGIC_CMD) else @@ -3000,7 +3224,7 @@ dnl AC_DEFUN([AC_PATH_TOOL_PREFIX], []) # _LT_PATH_MAGIC # -------------- -# find a file program which can recognize a shared library +# find a file program that can recognize a shared library m4_defun([_LT_PATH_MAGIC], [_LT_PATH_TOOL_PREFIX(${ac_tool_prefix}file, /usr/bin$PATH_SEPARATOR$PATH) if test -z "$lt_cv_path_MAGIC_CMD"; then @@ -3027,16 +3251,16 @@ m4_require([_LT_PROG_ECHO_BACKSLASH])dnl AC_ARG_WITH([gnu-ld], [AS_HELP_STRING([--with-gnu-ld], [assume the C compiler uses GNU ld @<:@default=no@:>@])], - [test "$withval" = no || with_gnu_ld=yes], + [test no = "$withval" || with_gnu_ld=yes], [with_gnu_ld=no])dnl ac_prog=ld -if test "$GCC" = yes; then +if test yes = "$GCC"; then # Check if gcc -print-prog-name=ld gives a path. AC_MSG_CHECKING([for ld used by $CC]) case $host in *-*-mingw*) - # gcc leaves a trailing carriage return which upsets mingw + # gcc leaves a trailing carriage return, which upsets mingw ac_prog=`($CC -print-prog-name=ld) 2>&5 | tr -d '\015'` ;; *) ac_prog=`($CC -print-prog-name=ld) 2>&5` ;; @@ -3050,7 +3274,7 @@ if test "$GCC" = yes; then while $ECHO "$ac_prog" | $GREP "$re_direlt" > /dev/null 2>&1; do ac_prog=`$ECHO $ac_prog| $SED "s%$re_direlt%/%"` done - test -z "$LD" && LD="$ac_prog" + test -z "$LD" && LD=$ac_prog ;; "") # If it fails, then pretend we aren't using GCC. @@ -3061,37 +3285,37 @@ if test "$GCC" = yes; then with_gnu_ld=unknown ;; esac -elif test "$with_gnu_ld" = yes; then +elif test yes = "$with_gnu_ld"; then AC_MSG_CHECKING([for GNU ld]) else AC_MSG_CHECKING([for non-GNU ld]) fi AC_CACHE_VAL(lt_cv_path_LD, [if test -z "$LD"; then - lt_save_ifs="$IFS"; IFS=$PATH_SEPARATOR + lt_save_ifs=$IFS; IFS=$PATH_SEPARATOR for ac_dir in $PATH; do - IFS="$lt_save_ifs" + IFS=$lt_save_ifs test -z "$ac_dir" && ac_dir=. if test -f "$ac_dir/$ac_prog" || test -f "$ac_dir/$ac_prog$ac_exeext"; then - lt_cv_path_LD="$ac_dir/$ac_prog" + lt_cv_path_LD=$ac_dir/$ac_prog # Check to see if the program is GNU ld. I'd rather use --version, # but apparently some variants of GNU ld only accept -v. # Break only if it was the GNU/non-GNU ld that we prefer. case `"$lt_cv_path_LD" -v 2>&1 conftest.i +cat conftest.i conftest.i >conftest2.i +: ${lt_DD:=$DD} +AC_PATH_PROGS_FEATURE_CHECK([lt_DD], [dd], +[if "$ac_path_lt_DD" bs=32 count=1 conftest.out 2>/dev/null; then + cmp -s conftest.i conftest.out \ + && ac_cv_path_lt_DD="$ac_path_lt_DD" ac_path_lt_DD_found=: +fi]) +rm -f conftest.i conftest2.i conftest.out]) +])# _LT_PATH_DD + + +# _LT_CMD_TRUNCATE +# ---------------- +# find command to truncate a binary pipe +m4_defun([_LT_CMD_TRUNCATE], +[m4_require([_LT_PATH_DD]) +AC_CACHE_CHECK([how to truncate binary pipes], [lt_cv_truncate_bin], +[printf 0123456789abcdef0123456789abcdef >conftest.i +cat conftest.i conftest.i >conftest2.i +lt_cv_truncate_bin= +if "$ac_cv_path_lt_DD" bs=32 count=1 conftest.out 2>/dev/null; then + cmp -s conftest.i conftest.out \ + && lt_cv_truncate_bin="$ac_cv_path_lt_DD bs=4096 count=1" +fi +rm -f conftest.i conftest2.i conftest.out +test -z "$lt_cv_truncate_bin" && lt_cv_truncate_bin="$SED -e 4q"]) +_LT_DECL([lt_truncate_bin], [lt_cv_truncate_bin], [1], + [Command to truncate a binary pipe]) +])# _LT_CMD_TRUNCATE + + # _LT_CHECK_MAGIC_METHOD # ---------------------- # how to check for library dependencies @@ -3177,13 +3438,13 @@ lt_cv_deplibs_check_method='unknown' # Need to set the preceding variable on all platforms that support # interlibrary dependencies. # 'none' -- dependencies not supported. -# `unknown' -- same as none, but documents that we really don't know. +# 'unknown' -- same as none, but documents that we really don't know. # 'pass_all' -- all dependencies passed with no checks. # 'test_compile' -- check by making test program. # 'file_magic [[regex]]' -- check by looking for files in library path -# which responds to the $file_magic_cmd with a given extended regex. -# If you have `file' or equivalent on your system and you're not sure -# whether `pass_all' will *always* work, you probably want this one. +# that responds to the $file_magic_cmd with a given extended regex. +# If you have 'file' or equivalent on your system and you're not sure +# whether 'pass_all' will *always* work, you probably want this one. case $host_os in aix[[4-9]]*) @@ -3210,8 +3471,7 @@ mingw* | pw32*) # Base MSYS/MinGW do not provide the 'file' command needed by # func_win32_libid shell function, so use a weaker test based on 'objdump', # unless we find 'file', for example because we are cross-compiling. - # func_win32_libid assumes BSD nm, so disallow it if using MS dumpbin. - if ( test "$lt_cv_nm_interface" = "BSD nm" && file / ) >/dev/null 2>&1; then + if ( file / ) >/dev/null 2>&1; then lt_cv_deplibs_check_method='file_magic ^x86 archive import|^x86 DLL' lt_cv_file_magic_cmd='func_win32_libid' else @@ -3247,10 +3507,6 @@ freebsd* | dragonfly*) fi ;; -gnu*) - lt_cv_deplibs_check_method=pass_all - ;; - haiku*) lt_cv_deplibs_check_method=pass_all ;; @@ -3289,7 +3545,7 @@ irix5* | irix6* | nonstopux*) ;; # This must be glibc/ELF. -linux* | k*bsd*-gnu | kopensolaris*-gnu) +linux* | k*bsd*-gnu | kopensolaris*-gnu | gnu*) lt_cv_deplibs_check_method=pass_all ;; @@ -3311,8 +3567,8 @@ newos6*) lt_cv_deplibs_check_method=pass_all ;; -openbsd*) - if test -z "`echo __ELF__ | $CC -E - | $GREP __ELF__`" || test "$host_os-$host_cpu" = "openbsd2.8-powerpc"; then +openbsd* | bitrig*) + if test -z "`echo __ELF__ | $CC -E - | $GREP __ELF__`"; then lt_cv_deplibs_check_method='match_pattern /lib[[^/]]+(\.so\.[[0-9]]+\.[[0-9]]+|\.so|_pic\.a)$' else lt_cv_deplibs_check_method='match_pattern /lib[[^/]]+(\.so\.[[0-9]]+\.[[0-9]]+|_pic\.a)$' @@ -3365,6 +3621,9 @@ sysv4 | sysv4.3*) tpf*) lt_cv_deplibs_check_method=pass_all ;; +os2*) + lt_cv_deplibs_check_method=pass_all + ;; esac ]) @@ -3405,33 +3664,38 @@ AC_DEFUN([LT_PATH_NM], AC_CACHE_CHECK([for BSD- or MS-compatible name lister (nm)], lt_cv_path_NM, [if test -n "$NM"; then # Let the user override the test. - lt_cv_path_NM="$NM" + lt_cv_path_NM=$NM else - lt_nm_to_check="${ac_tool_prefix}nm" + lt_nm_to_check=${ac_tool_prefix}nm if test -n "$ac_tool_prefix" && test "$build" = "$host"; then lt_nm_to_check="$lt_nm_to_check nm" fi for lt_tmp_nm in $lt_nm_to_check; do - lt_save_ifs="$IFS"; IFS=$PATH_SEPARATOR + lt_save_ifs=$IFS; IFS=$PATH_SEPARATOR for ac_dir in $PATH /usr/ccs/bin/elf /usr/ccs/bin /usr/ucb /bin; do - IFS="$lt_save_ifs" + IFS=$lt_save_ifs test -z "$ac_dir" && ac_dir=. - tmp_nm="$ac_dir/$lt_tmp_nm" - if test -f "$tmp_nm" || test -f "$tmp_nm$ac_exeext" ; then + tmp_nm=$ac_dir/$lt_tmp_nm + if test -f "$tmp_nm" || test -f "$tmp_nm$ac_exeext"; then # Check to see if the nm accepts a BSD-compat flag. - # Adding the `sed 1q' prevents false positives on HP-UX, which says: + # Adding the 'sed 1q' prevents false positives on HP-UX, which says: # nm: unknown option "B" ignored # Tru64's nm complains that /dev/null is an invalid object file - case `"$tmp_nm" -B /dev/null 2>&1 | sed '1q'` in - */dev/null* | *'Invalid file or object type'*) + # MSYS converts /dev/null to NUL, MinGW nm treats NUL as empty + case $build_os in + mingw*) lt_bad_file=conftest.nm/nofile ;; + *) lt_bad_file=/dev/null ;; + esac + case `"$tmp_nm" -B $lt_bad_file 2>&1 | sed '1q'` in + *$lt_bad_file* | *'Invalid file or object type'*) lt_cv_path_NM="$tmp_nm -B" - break + break 2 ;; *) case `"$tmp_nm" -p /dev/null 2>&1 | sed '1q'` in */dev/null*) lt_cv_path_NM="$tmp_nm -p" - break + break 2 ;; *) lt_cv_path_NM=${lt_cv_path_NM="$tmp_nm"} # keep the first match, but @@ -3442,21 +3706,21 @@ else esac fi done - IFS="$lt_save_ifs" + IFS=$lt_save_ifs done : ${lt_cv_path_NM=no} fi]) -if test "$lt_cv_path_NM" != "no"; then - NM="$lt_cv_path_NM" +if test no != "$lt_cv_path_NM"; then + NM=$lt_cv_path_NM else # Didn't find any BSD compatible name lister, look for dumpbin. if test -n "$DUMPBIN"; then : # Let the user override the test. else AC_CHECK_TOOLS(DUMPBIN, [dumpbin "link -dump"], :) - case `$DUMPBIN -symbols /dev/null 2>&1 | sed '1q'` in + case `$DUMPBIN -symbols -headers /dev/null 2>&1 | sed '1q'` in *COFF*) - DUMPBIN="$DUMPBIN -symbols" + DUMPBIN="$DUMPBIN -symbols -headers" ;; *) DUMPBIN=: @@ -3464,8 +3728,8 @@ else esac fi AC_SUBST([DUMPBIN]) - if test "$DUMPBIN" != ":"; then - NM="$DUMPBIN" + if test : != "$DUMPBIN"; then + NM=$DUMPBIN fi fi test -z "$NM" && NM=nm @@ -3511,8 +3775,8 @@ lt_cv_sharedlib_from_linklib_cmd, case $host_os in cygwin* | mingw* | pw32* | cegcc*) - # two different shell functions defined in ltmain.sh - # decide which to use based on capabilities of $DLLTOOL + # two different shell functions defined in ltmain.sh; + # decide which one to use based on capabilities of $DLLTOOL case `$DLLTOOL --help 2>&1` in *--identify-strict*) lt_cv_sharedlib_from_linklib_cmd=func_cygming_dll_for_implib @@ -3524,7 +3788,7 @@ cygwin* | mingw* | pw32* | cegcc*) ;; *) # fallback: assume linklib IS sharedlib - lt_cv_sharedlib_from_linklib_cmd="$ECHO" + lt_cv_sharedlib_from_linklib_cmd=$ECHO ;; esac ]) @@ -3551,13 +3815,28 @@ AC_CACHE_CHECK([if $MANIFEST_TOOL is a manifest tool], [lt_cv_path_mainfest_tool lt_cv_path_mainfest_tool=yes fi rm -f conftest*]) -if test "x$lt_cv_path_mainfest_tool" != xyes; then +if test yes != "$lt_cv_path_mainfest_tool"; then MANIFEST_TOOL=: fi _LT_DECL([], [MANIFEST_TOOL], [1], [Manifest tool])dnl ])# _LT_PATH_MANIFEST_TOOL +# _LT_DLL_DEF_P([FILE]) +# --------------------- +# True iff FILE is a Windows DLL '.def' file. +# Keep in sync with func_dll_def_p in the libtool script +AC_DEFUN([_LT_DLL_DEF_P], +[dnl + test DEF = "`$SED -n dnl + -e '\''s/^[[ ]]*//'\'' dnl Strip leading whitespace + -e '\''/^\(;.*\)*$/d'\'' dnl Delete empty lines and comments + -e '\''s/^\(EXPORTS\|LIBRARY\)\([[ ]].*\)*$/DEF/p'\'' dnl + -e q dnl Only consider the first "real" line + $1`" dnl +])# _LT_DLL_DEF_P + + # LT_LIB_M # -------- # check for math library @@ -3569,11 +3848,11 @@ case $host in # These system don't have libm, or don't need it ;; *-ncr-sysv4.3*) - AC_CHECK_LIB(mw, _mwvalidcheckl, LIBM="-lmw") + AC_CHECK_LIB(mw, _mwvalidcheckl, LIBM=-lmw) AC_CHECK_LIB(m, cos, LIBM="$LIBM -lm") ;; *) - AC_CHECK_LIB(m, cos, LIBM="-lm") + AC_CHECK_LIB(m, cos, LIBM=-lm) ;; esac AC_SUBST([LIBM]) @@ -3592,7 +3871,7 @@ m4_defun([_LT_COMPILER_NO_RTTI], _LT_TAGVAR(lt_prog_compiler_no_builtin_flag, $1)= -if test "$GCC" = yes; then +if test yes = "$GCC"; then case $cc_basename in nvcc*) _LT_TAGVAR(lt_prog_compiler_no_builtin_flag, $1)=' -Xcompiler -fno-builtin' ;; @@ -3644,7 +3923,7 @@ cygwin* | mingw* | pw32* | cegcc*) symcode='[[ABCDGISTW]]' ;; hpux*) - if test "$host_cpu" = ia64; then + if test ia64 = "$host_cpu"; then symcode='[[ABCDEGRST]]' fi ;; @@ -3677,14 +3956,44 @@ case `$NM -V 2>&1` in symcode='[[ABCDGIRSTW]]' ;; esac +if test "$lt_cv_nm_interface" = "MS dumpbin"; then + # Gets list of data symbols to import. + lt_cv_sys_global_symbol_to_import="sed -n -e 's/^I .* \(.*\)$/\1/p'" + # Adjust the below global symbol transforms to fixup imported variables. + lt_cdecl_hook=" -e 's/^I .* \(.*\)$/extern __declspec(dllimport) char \1;/p'" + lt_c_name_hook=" -e 's/^I .* \(.*\)$/ {\"\1\", (void *) 0},/p'" + lt_c_name_lib_hook="\ + -e 's/^I .* \(lib.*\)$/ {\"\1\", (void *) 0},/p'\ + -e 's/^I .* \(.*\)$/ {\"lib\1\", (void *) 0},/p'" +else + # Disable hooks by default. + lt_cv_sys_global_symbol_to_import= + lt_cdecl_hook= + lt_c_name_hook= + lt_c_name_lib_hook= +fi + # Transform an extracted symbol line into a proper C declaration. # Some systems (esp. on ia64) link data and code symbols differently, # so use this general approach. -lt_cv_sys_global_symbol_to_cdecl="sed -n -e 's/^T .* \(.*\)$/extern int \1();/p' -e 's/^$symcode* .* \(.*\)$/extern char \1;/p'" +lt_cv_sys_global_symbol_to_cdecl="sed -n"\ +$lt_cdecl_hook\ +" -e 's/^T .* \(.*\)$/extern int \1();/p'"\ +" -e 's/^$symcode$symcode* .* \(.*\)$/extern char \1;/p'" # Transform an extracted symbol line into symbol name and symbol address -lt_cv_sys_global_symbol_to_c_name_address="sed -n -e 's/^: \([[^ ]]*\)[[ ]]*$/ {\\\"\1\\\", (void *) 0},/p' -e 's/^$symcode* \([[^ ]]*\) \([[^ ]]*\)$/ {\"\2\", (void *) \&\2},/p'" -lt_cv_sys_global_symbol_to_c_name_address_lib_prefix="sed -n -e 's/^: \([[^ ]]*\)[[ ]]*$/ {\\\"\1\\\", (void *) 0},/p' -e 's/^$symcode* \([[^ ]]*\) \(lib[[^ ]]*\)$/ {\"\2\", (void *) \&\2},/p' -e 's/^$symcode* \([[^ ]]*\) \([[^ ]]*\)$/ {\"lib\2\", (void *) \&\2},/p'" +lt_cv_sys_global_symbol_to_c_name_address="sed -n"\ +$lt_c_name_hook\ +" -e 's/^: \(.*\) .*$/ {\"\1\", (void *) 0},/p'"\ +" -e 's/^$symcode$symcode* .* \(.*\)$/ {\"\1\", (void *) \&\1},/p'" + +# Transform an extracted symbol line into symbol name with lib prefix and +# symbol address. +lt_cv_sys_global_symbol_to_c_name_address_lib_prefix="sed -n"\ +$lt_c_name_lib_hook\ +" -e 's/^: \(.*\) .*$/ {\"\1\", (void *) 0},/p'"\ +" -e 's/^$symcode$symcode* .* \(lib.*\)$/ {\"\1\", (void *) \&\1},/p'"\ +" -e 's/^$symcode$symcode* .* \(.*\)$/ {\"lib\1\", (void *) \&\1},/p'" # Handle CRLF in mingw tool chain opt_cr= @@ -3702,21 +4011,24 @@ for ac_symprfx in "" "_"; do # Write the raw and C identifiers. if test "$lt_cv_nm_interface" = "MS dumpbin"; then - # Fake it for dumpbin and say T for any non-static function - # and D for any global variable. + # Fake it for dumpbin and say T for any non-static function, + # D for any global variable and I for any imported variable. # Also find C++ and __fastcall symbols from MSVC++, # which start with @ or ?. lt_cv_sys_global_symbol_pipe="$AWK ['"\ " {last_section=section; section=\$ 3};"\ " /^COFF SYMBOL TABLE/{for(i in hide) delete hide[i]};"\ " /Section length .*#relocs.*(pick any)/{hide[last_section]=1};"\ +" /^ *Symbol name *: /{split(\$ 0,sn,\":\"); si=substr(sn[2],2)};"\ +" /^ *Type *: code/{print \"T\",si,substr(si,length(prfx))};"\ +" /^ *Type *: data/{print \"I\",si,substr(si,length(prfx))};"\ " \$ 0!~/External *\|/{next};"\ " / 0+ UNDEF /{next}; / UNDEF \([^|]\)*()/{next};"\ " {if(hide[section]) next};"\ -" {f=0}; \$ 0~/\(\).*\|/{f=1}; {printf f ? \"T \" : \"D \"};"\ -" {split(\$ 0, a, /\||\r/); split(a[2], s)};"\ -" s[1]~/^[@?]/{print s[1], s[1]; next};"\ -" s[1]~prfx {split(s[1],t,\"@\"); print t[1], substr(t[1],length(prfx))}"\ +" {f=\"D\"}; \$ 0~/\(\).*\|/{f=\"T\"};"\ +" {split(\$ 0,a,/\||\r/); split(a[2],s)};"\ +" s[1]~/^[@?]/{print f,s[1],s[1]; next};"\ +" s[1]~prfx {split(s[1],t,\"@\"); print f,t[1],substr(t[1],length(prfx))}"\ " ' prfx=^$ac_symprfx]" else lt_cv_sys_global_symbol_pipe="sed -n -e 's/^.*[[ ]]\($symcode$symcode*\)[[ ]][[ ]]*$ac_symprfx$sympat$opt_cr$/$symxfrm/p'" @@ -3756,11 +4068,11 @@ _LT_EOF if $GREP ' nm_test_func$' "$nlist" >/dev/null; then cat <<_LT_EOF > conftest.$ac_ext /* Keep this code in sync between libtool.m4, ltmain, lt_system.h, and tests. */ -#if defined(_WIN32) || defined(__CYGWIN__) || defined(_WIN32_WCE) -/* DATA imports from DLLs on WIN32 con't be const, because runtime +#if defined _WIN32 || defined __CYGWIN__ || defined _WIN32_WCE +/* DATA imports from DLLs on WIN32 can't be const, because runtime relocations are performed -- see ld's documentation on pseudo-relocs. */ # define LT@&t@_DLSYM_CONST -#elif defined(__osf__) +#elif defined __osf__ /* This system does not cope well with relocations in const data. */ # define LT@&t@_DLSYM_CONST #else @@ -3786,7 +4098,7 @@ lt__PROGRAM__LTX_preloaded_symbols[[]] = { { "@PROGRAM@", (void *) 0 }, _LT_EOF - $SED "s/^$symcode$symcode* \(.*\) \(.*\)$/ {\"\2\", (void *) \&\2},/" < "$nlist" | $GREP -v main >> conftest.$ac_ext + $SED "s/^$symcode$symcode* .* \(.*\)$/ {\"\1\", (void *) \&\1},/" < "$nlist" | $GREP -v main >> conftest.$ac_ext cat <<\_LT_EOF >> conftest.$ac_ext {0, (void *) 0} }; @@ -3806,9 +4118,9 @@ _LT_EOF mv conftest.$ac_objext conftstm.$ac_objext lt_globsym_save_LIBS=$LIBS lt_globsym_save_CFLAGS=$CFLAGS - LIBS="conftstm.$ac_objext" + LIBS=conftstm.$ac_objext CFLAGS="$CFLAGS$_LT_TAGVAR(lt_prog_compiler_no_builtin_flag, $1)" - if AC_TRY_EVAL(ac_link) && test -s conftest${ac_exeext}; then + if AC_TRY_EVAL(ac_link) && test -s conftest$ac_exeext; then pipe_works=yes fi LIBS=$lt_globsym_save_LIBS @@ -3829,7 +4141,7 @@ _LT_EOF rm -rf conftest* conftst* # Do not use the global_symbol_pipe unless it works. - if test "$pipe_works" = yes; then + if test yes = "$pipe_works"; then break else lt_cv_sys_global_symbol_pipe= @@ -3856,12 +4168,16 @@ _LT_DECL([global_symbol_pipe], [lt_cv_sys_global_symbol_pipe], [1], [Take the output of nm and produce a listing of raw symbols and C names]) _LT_DECL([global_symbol_to_cdecl], [lt_cv_sys_global_symbol_to_cdecl], [1], [Transform the output of nm in a proper C declaration]) +_LT_DECL([global_symbol_to_import], [lt_cv_sys_global_symbol_to_import], [1], + [Transform the output of nm into a list of symbols to manually relocate]) _LT_DECL([global_symbol_to_c_name_address], [lt_cv_sys_global_symbol_to_c_name_address], [1], [Transform the output of nm in a C name address pair]) _LT_DECL([global_symbol_to_c_name_address_lib_prefix], [lt_cv_sys_global_symbol_to_c_name_address_lib_prefix], [1], [Transform the output of nm in a C name address pair when lib prefix is needed]) +_LT_DECL([nm_interface], [lt_cv_nm_interface], [1], + [The name lister interface]) _LT_DECL([], [nm_file_list_spec], [1], [Specify filename containing input files for $NM]) ]) # _LT_CMD_GLOBAL_SYMBOLS @@ -3877,17 +4193,18 @@ _LT_TAGVAR(lt_prog_compiler_static, $1)= m4_if([$1], [CXX], [ # C++ specific cases for pic, static, wl, etc. - if test "$GXX" = yes; then + if test yes = "$GXX"; then _LT_TAGVAR(lt_prog_compiler_wl, $1)='-Wl,' _LT_TAGVAR(lt_prog_compiler_static, $1)='-static' case $host_os in aix*) # All AIX code is PIC. - if test "$host_cpu" = ia64; then + if test ia64 = "$host_cpu"; then # AIX 5 now supports IA64 processor _LT_TAGVAR(lt_prog_compiler_static, $1)='-Bstatic' fi + _LT_TAGVAR(lt_prog_compiler_pic, $1)='-fPIC' ;; amigaos*) @@ -3898,8 +4215,8 @@ m4_if([$1], [CXX], [ ;; m68k) # FIXME: we need at least 68020 code to build shared libraries, but - # adding the `-m68020' flag to GCC prevents building anything better, - # like `-m68040'. + # adding the '-m68020' flag to GCC prevents building anything better, + # like '-m68040'. _LT_TAGVAR(lt_prog_compiler_pic, $1)='-m68020 -resident32 -malways-restore-a4' ;; esac @@ -3915,6 +4232,11 @@ m4_if([$1], [CXX], [ # (--disable-auto-import) libraries m4_if([$1], [GCJ], [], [_LT_TAGVAR(lt_prog_compiler_pic, $1)='-DDLL_EXPORT']) + case $host_os in + os2*) + _LT_TAGVAR(lt_prog_compiler_static, $1)='$wl-static' + ;; + esac ;; darwin* | rhapsody*) # PIC is the default on this platform @@ -3964,7 +4286,7 @@ m4_if([$1], [CXX], [ case $host_os in aix[[4-9]]*) # All AIX code is PIC. - if test "$host_cpu" = ia64; then + if test ia64 = "$host_cpu"; then # AIX 5 now supports IA64 processor _LT_TAGVAR(lt_prog_compiler_static, $1)='-Bstatic' else @@ -4005,14 +4327,14 @@ m4_if([$1], [CXX], [ case $cc_basename in CC*) _LT_TAGVAR(lt_prog_compiler_wl, $1)='-Wl,' - _LT_TAGVAR(lt_prog_compiler_static, $1)='${wl}-a ${wl}archive' - if test "$host_cpu" != ia64; then + _LT_TAGVAR(lt_prog_compiler_static, $1)='$wl-a ${wl}archive' + if test ia64 != "$host_cpu"; then _LT_TAGVAR(lt_prog_compiler_pic, $1)='+Z' fi ;; aCC*) _LT_TAGVAR(lt_prog_compiler_wl, $1)='-Wl,' - _LT_TAGVAR(lt_prog_compiler_static, $1)='${wl}-a ${wl}archive' + _LT_TAGVAR(lt_prog_compiler_static, $1)='$wl-a ${wl}archive' case $host_cpu in hppa*64*|ia64*) # +Z the default @@ -4041,7 +4363,7 @@ m4_if([$1], [CXX], [ ;; esac ;; - linux* | k*bsd*-gnu | kopensolaris*-gnu) + linux* | k*bsd*-gnu | kopensolaris*-gnu | gnu*) case $cc_basename in KCC*) # KAI C++ Compiler @@ -4049,7 +4371,7 @@ m4_if([$1], [CXX], [ _LT_TAGVAR(lt_prog_compiler_pic, $1)='-fPIC' ;; ecpc* ) - # old Intel C++ for x86_64 which still supported -KPIC. + # old Intel C++ for x86_64, which still supported -KPIC. _LT_TAGVAR(lt_prog_compiler_wl, $1)='-Wl,' _LT_TAGVAR(lt_prog_compiler_pic, $1)='-KPIC' _LT_TAGVAR(lt_prog_compiler_static, $1)='-static' @@ -4194,17 +4516,18 @@ m4_if([$1], [CXX], [ fi ], [ - if test "$GCC" = yes; then + if test yes = "$GCC"; then _LT_TAGVAR(lt_prog_compiler_wl, $1)='-Wl,' _LT_TAGVAR(lt_prog_compiler_static, $1)='-static' case $host_os in aix*) # All AIX code is PIC. - if test "$host_cpu" = ia64; then + if test ia64 = "$host_cpu"; then # AIX 5 now supports IA64 processor _LT_TAGVAR(lt_prog_compiler_static, $1)='-Bstatic' fi + _LT_TAGVAR(lt_prog_compiler_pic, $1)='-fPIC' ;; amigaos*) @@ -4215,8 +4538,8 @@ m4_if([$1], [CXX], [ ;; m68k) # FIXME: we need at least 68020 code to build shared libraries, but - # adding the `-m68020' flag to GCC prevents building anything better, - # like `-m68040'. + # adding the '-m68020' flag to GCC prevents building anything better, + # like '-m68040'. _LT_TAGVAR(lt_prog_compiler_pic, $1)='-m68020 -resident32 -malways-restore-a4' ;; esac @@ -4233,6 +4556,11 @@ m4_if([$1], [CXX], [ # (--disable-auto-import) libraries m4_if([$1], [GCJ], [], [_LT_TAGVAR(lt_prog_compiler_pic, $1)='-DDLL_EXPORT']) + case $host_os in + os2*) + _LT_TAGVAR(lt_prog_compiler_static, $1)='$wl-static' + ;; + esac ;; darwin* | rhapsody*) @@ -4303,7 +4631,7 @@ m4_if([$1], [CXX], [ case $host_os in aix*) _LT_TAGVAR(lt_prog_compiler_wl, $1)='-Wl,' - if test "$host_cpu" = ia64; then + if test ia64 = "$host_cpu"; then # AIX 5 now supports IA64 processor _LT_TAGVAR(lt_prog_compiler_static, $1)='-Bstatic' else @@ -4311,11 +4639,30 @@ m4_if([$1], [CXX], [ fi ;; + darwin* | rhapsody*) + # PIC is the default on this platform + # Common symbols not allowed in MH_DYLIB files + _LT_TAGVAR(lt_prog_compiler_pic, $1)='-fno-common' + case $cc_basename in + nagfor*) + # NAG Fortran compiler + _LT_TAGVAR(lt_prog_compiler_wl, $1)='-Wl,-Wl,,' + _LT_TAGVAR(lt_prog_compiler_pic, $1)='-PIC' + _LT_TAGVAR(lt_prog_compiler_static, $1)='-Bstatic' + ;; + esac + ;; + mingw* | cygwin* | pw32* | os2* | cegcc*) # This hack is so that the source file can tell whether it is being # built for inclusion in a dll (and should export symbols for example). m4_if([$1], [GCJ], [], [_LT_TAGVAR(lt_prog_compiler_pic, $1)='-DDLL_EXPORT']) + case $host_os in + os2*) + _LT_TAGVAR(lt_prog_compiler_static, $1)='$wl-static' + ;; + esac ;; hpux9* | hpux10* | hpux11*) @@ -4331,7 +4678,7 @@ m4_if([$1], [CXX], [ ;; esac # Is there a better lt_prog_compiler_static that works with the bundled CC? - _LT_TAGVAR(lt_prog_compiler_static, $1)='${wl}-a ${wl}archive' + _LT_TAGVAR(lt_prog_compiler_static, $1)='$wl-a ${wl}archive' ;; irix5* | irix6* | nonstopux*) @@ -4340,9 +4687,9 @@ m4_if([$1], [CXX], [ _LT_TAGVAR(lt_prog_compiler_static, $1)='-non_shared' ;; - linux* | k*bsd*-gnu | kopensolaris*-gnu) + linux* | k*bsd*-gnu | kopensolaris*-gnu | gnu*) case $cc_basename in - # old Intel for x86_64 which still supported -KPIC. + # old Intel for x86_64, which still supported -KPIC. ecc*) _LT_TAGVAR(lt_prog_compiler_wl, $1)='-Wl,' _LT_TAGVAR(lt_prog_compiler_pic, $1)='-KPIC' @@ -4367,6 +4714,12 @@ m4_if([$1], [CXX], [ _LT_TAGVAR(lt_prog_compiler_pic, $1)='-PIC' _LT_TAGVAR(lt_prog_compiler_static, $1)='-Bstatic' ;; + tcc*) + # Fabrice Bellard et al's Tiny C Compiler + _LT_TAGVAR(lt_prog_compiler_wl, $1)='-Wl,' + _LT_TAGVAR(lt_prog_compiler_pic, $1)='-fPIC' + _LT_TAGVAR(lt_prog_compiler_static, $1)='-static' + ;; pgcc* | pgf77* | pgf90* | pgf95* | pgfortran*) # Portland Group compilers (*not* the Pentium gcc compiler, # which looks to be a dead project) @@ -4464,7 +4817,7 @@ m4_if([$1], [CXX], [ ;; sysv4*MP*) - if test -d /usr/nec ;then + if test -d /usr/nec; then _LT_TAGVAR(lt_prog_compiler_pic, $1)='-Kconform_pic' _LT_TAGVAR(lt_prog_compiler_static, $1)='-Bstatic' fi @@ -4493,7 +4846,7 @@ m4_if([$1], [CXX], [ fi ]) case $host_os in - # For platforms which do not support PIC, -DPIC is meaningless: + # For platforms that do not support PIC, -DPIC is meaningless: *djgpp*) _LT_TAGVAR(lt_prog_compiler_pic, $1)= ;; @@ -4559,17 +4912,21 @@ m4_if([$1], [CXX], [ case $host_os in aix[[4-9]]*) # If we're using GNU nm, then we don't want the "-C" option. - # -C means demangle to AIX nm, but means don't demangle with GNU nm - # Also, AIX nm treats weak defined symbols like other global defined - # symbols, whereas GNU nm marks them as "W". + # -C means demangle to GNU nm, but means don't demangle to AIX nm. + # Without the "-l" option, or with the "-B" option, AIX nm treats + # weak defined symbols like other global defined symbols, whereas + # GNU nm marks them as "W". + # While the 'weak' keyword is ignored in the Export File, we need + # it in the Import File for the 'aix-soname' feature, so we have + # to replace the "-B" option with "-P" for AIX nm. if $NM -V 2>&1 | $GREP 'GNU' > /dev/null; then - _LT_TAGVAR(export_symbols_cmds, $1)='$NM -Bpg $libobjs $convenience | awk '\''{ if (((\$ 2 == "T") || (\$ 2 == "D") || (\$ 2 == "B") || (\$ 2 == "W")) && ([substr](\$ 3,1,1) != ".")) { print \$ 3 } }'\'' | sort -u > $export_symbols' + _LT_TAGVAR(export_symbols_cmds, $1)='$NM -Bpg $libobjs $convenience | awk '\''{ if (((\$ 2 == "T") || (\$ 2 == "D") || (\$ 2 == "B") || (\$ 2 == "W")) && ([substr](\$ 3,1,1) != ".")) { if (\$ 2 == "W") { print \$ 3 " weak" } else { print \$ 3 } } }'\'' | sort -u > $export_symbols' else - _LT_TAGVAR(export_symbols_cmds, $1)='$NM -BCpg $libobjs $convenience | awk '\''{ if (((\$ 2 == "T") || (\$ 2 == "D") || (\$ 2 == "B")) && ([substr](\$ 3,1,1) != ".")) { print \$ 3 } }'\'' | sort -u > $export_symbols' + _LT_TAGVAR(export_symbols_cmds, $1)='`func_echo_all $NM | $SED -e '\''s/B\([[^B]]*\)$/P\1/'\''` -PCpgl $libobjs $convenience | awk '\''{ if (((\$ 2 == "T") || (\$ 2 == "D") || (\$ 2 == "B") || (\$ 2 == "W") || (\$ 2 == "V") || (\$ 2 == "Z")) && ([substr](\$ 1,1,1) != ".")) { if ((\$ 2 == "W") || (\$ 2 == "V") || (\$ 2 == "Z")) { print \$ 1 " weak" } else { print \$ 1 } } }'\'' | sort -u > $export_symbols' fi ;; pw32*) - _LT_TAGVAR(export_symbols_cmds, $1)="$ltdll_cmds" + _LT_TAGVAR(export_symbols_cmds, $1)=$ltdll_cmds ;; cygwin* | mingw* | cegcc*) case $cc_basename in @@ -4615,9 +4972,9 @@ m4_if([$1], [CXX], [ # included in the symbol list _LT_TAGVAR(include_expsyms, $1)= # exclude_expsyms can be an extended regexp of symbols to exclude - # it will be wrapped by ` (' and `)$', so one must not match beginning or - # end of line. Example: `a|bc|.*d.*' will exclude the symbols `a' and `bc', - # as well as any symbol that contains `d'. + # it will be wrapped by ' (' and ')$', so one must not match beginning or + # end of line. Example: 'a|bc|.*d.*' will exclude the symbols 'a' and 'bc', + # as well as any symbol that contains 'd'. _LT_TAGVAR(exclude_expsyms, $1)=['_GLOBAL_OFFSET_TABLE_|_GLOBAL__F[ID]_.*'] # Although _GLOBAL_OFFSET_TABLE_ is a valid symbol C name, most a.out # platforms (ab)use it in PIC code, but their linkers get confused if @@ -4633,7 +4990,7 @@ dnl Note also adjust exclude_expsyms for C++ above. # FIXME: the MSVC++ port hasn't been tested in a loooong time # When not using gcc, we currently assume that we are using # Microsoft Visual C++. - if test "$GCC" != yes; then + if test yes != "$GCC"; then with_gnu_ld=no fi ;; @@ -4641,7 +4998,7 @@ dnl Note also adjust exclude_expsyms for C++ above. # we just hope/assume this is gcc and not c89 (= MSVC++) with_gnu_ld=yes ;; - openbsd*) + openbsd* | bitrig*) with_gnu_ld=no ;; esac @@ -4651,7 +5008,7 @@ dnl Note also adjust exclude_expsyms for C++ above. # On some targets, GNU ld is compatible enough with the native linker # that we're better off using the native interface for both. lt_use_gnu_ld_interface=no - if test "$with_gnu_ld" = yes; then + if test yes = "$with_gnu_ld"; then case $host_os in aix*) # The AIX port of GNU ld has always aspired to compatibility @@ -4673,24 +5030,24 @@ dnl Note also adjust exclude_expsyms for C++ above. esac fi - if test "$lt_use_gnu_ld_interface" = yes; then + if test yes = "$lt_use_gnu_ld_interface"; then # If archive_cmds runs LD, not CC, wlarc should be empty - wlarc='${wl}' + wlarc='$wl' # Set some defaults for GNU ld with shared library support. These # are reset later if shared libraries are not supported. Putting them # here allows them to be overridden if necessary. runpath_var=LD_RUN_PATH - _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}-rpath ${wl}$libdir' - _LT_TAGVAR(export_dynamic_flag_spec, $1)='${wl}--export-dynamic' + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='$wl-rpath $wl$libdir' + _LT_TAGVAR(export_dynamic_flag_spec, $1)='$wl--export-dynamic' # ancient GNU ld didn't support --whole-archive et. al. if $LD --help 2>&1 | $GREP 'no-whole-archive' > /dev/null; then - _LT_TAGVAR(whole_archive_flag_spec, $1)="$wlarc"'--whole-archive$convenience '"$wlarc"'--no-whole-archive' + _LT_TAGVAR(whole_archive_flag_spec, $1)=$wlarc'--whole-archive$convenience '$wlarc'--no-whole-archive' else _LT_TAGVAR(whole_archive_flag_spec, $1)= fi supports_anon_versioning=no - case `$LD -v 2>&1` in + case `$LD -v | $SED -e 's/([^)]\+)\s\+//' 2>&1` in *GNU\ gold*) supports_anon_versioning=yes ;; *\ [[01]].* | *\ 2.[[0-9]].* | *\ 2.10.*) ;; # catch versions < 2.11 *\ 2.11.93.0.2\ *) supports_anon_versioning=yes ;; # RH7.3 ... @@ -4703,7 +5060,7 @@ dnl Note also adjust exclude_expsyms for C++ above. case $host_os in aix[[3-9]]*) # On AIX/PPC, the GNU linker is very broken - if test "$host_cpu" != ia64; then + if test ia64 != "$host_cpu"; then _LT_TAGVAR(ld_shlibs, $1)=no cat <<_LT_EOF 1>&2 @@ -4722,7 +5079,7 @@ _LT_EOF case $host_cpu in powerpc) # see comment about AmigaOS4 .so support - _LT_TAGVAR(archive_cmds, $1)='$CC -shared $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname -o $lib' + _LT_TAGVAR(archive_cmds, $1)='$CC -shared $libobjs $deplibs $compiler_flags $wl-soname $wl$soname -o $lib' _LT_TAGVAR(archive_expsym_cmds, $1)='' ;; m68k) @@ -4738,7 +5095,7 @@ _LT_EOF _LT_TAGVAR(allow_undefined_flag, $1)=unsupported # Joseph Beckenbach says some releases of gcc # support --undefined. This deserves some investigation. FIXME - _LT_TAGVAR(archive_cmds, $1)='$CC -nostart $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname -o $lib' + _LT_TAGVAR(archive_cmds, $1)='$CC -nostart $libobjs $deplibs $compiler_flags $wl-soname $wl$soname -o $lib' else _LT_TAGVAR(ld_shlibs, $1)=no fi @@ -4748,7 +5105,7 @@ _LT_EOF # _LT_TAGVAR(hardcode_libdir_flag_spec, $1) is actually meaningless, # as there is no search path for DLLs. _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='-L$libdir' - _LT_TAGVAR(export_dynamic_flag_spec, $1)='${wl}--export-all-symbols' + _LT_TAGVAR(export_dynamic_flag_spec, $1)='$wl--export-all-symbols' _LT_TAGVAR(allow_undefined_flag, $1)=unsupported _LT_TAGVAR(always_export_symbols, $1)=no _LT_TAGVAR(enable_shared_with_static_runtimes, $1)=yes @@ -4756,61 +5113,89 @@ _LT_EOF _LT_TAGVAR(exclude_expsyms, $1)=['[_]+GLOBAL_OFFSET_TABLE_|[_]+GLOBAL__[FID]_.*|[_]+head_[A-Za-z0-9_]+_dll|[A-Za-z0-9_]+_dll_iname'] if $LD --help 2>&1 | $GREP 'auto-import' > /dev/null; then - _LT_TAGVAR(archive_cmds, $1)='$CC -shared $libobjs $deplibs $compiler_flags -o $output_objdir/$soname ${wl}--enable-auto-image-base -Xlinker --out-implib -Xlinker $lib' - # If the export-symbols file already is a .def file (1st line - # is EXPORTS), use it as is; otherwise, prepend... - _LT_TAGVAR(archive_expsym_cmds, $1)='if test "x`$SED 1q $export_symbols`" = xEXPORTS; then - cp $export_symbols $output_objdir/$soname.def; - else - echo EXPORTS > $output_objdir/$soname.def; - cat $export_symbols >> $output_objdir/$soname.def; - fi~ - $CC -shared $output_objdir/$soname.def $libobjs $deplibs $compiler_flags -o $output_objdir/$soname ${wl}--enable-auto-image-base -Xlinker --out-implib -Xlinker $lib' + _LT_TAGVAR(archive_cmds, $1)='$CC -shared $libobjs $deplibs $compiler_flags -o $output_objdir/$soname $wl--enable-auto-image-base -Xlinker --out-implib -Xlinker $lib' + # If the export-symbols file already is a .def file, use it as + # is; otherwise, prepend EXPORTS... + _LT_TAGVAR(archive_expsym_cmds, $1)='if _LT_DLL_DEF_P([$export_symbols]); then + cp $export_symbols $output_objdir/$soname.def; + else + echo EXPORTS > $output_objdir/$soname.def; + cat $export_symbols >> $output_objdir/$soname.def; + fi~ + $CC -shared $output_objdir/$soname.def $libobjs $deplibs $compiler_flags -o $output_objdir/$soname $wl--enable-auto-image-base -Xlinker --out-implib -Xlinker $lib' else _LT_TAGVAR(ld_shlibs, $1)=no fi ;; haiku*) - _LT_TAGVAR(archive_cmds, $1)='$CC -shared $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname -o $lib' + _LT_TAGVAR(archive_cmds, $1)='$CC -shared $libobjs $deplibs $compiler_flags $wl-soname $wl$soname -o $lib' _LT_TAGVAR(link_all_deplibs, $1)=yes ;; + os2*) + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='-L$libdir' + _LT_TAGVAR(hardcode_minus_L, $1)=yes + _LT_TAGVAR(allow_undefined_flag, $1)=unsupported + shrext_cmds=.dll + _LT_TAGVAR(archive_cmds, $1)='$ECHO "LIBRARY ${soname%$shared_ext} INITINSTANCE TERMINSTANCE" > $output_objdir/$libname.def~ + $ECHO "DESCRIPTION \"$libname\"" >> $output_objdir/$libname.def~ + $ECHO "DATA MULTIPLE NONSHARED" >> $output_objdir/$libname.def~ + $ECHO EXPORTS >> $output_objdir/$libname.def~ + emxexp $libobjs | $SED /"_DLL_InitTerm"/d >> $output_objdir/$libname.def~ + $CC -Zdll -Zcrtdll -o $output_objdir/$soname $libobjs $deplibs $compiler_flags $output_objdir/$libname.def~ + emximp -o $lib $output_objdir/$libname.def' + _LT_TAGVAR(archive_expsym_cmds, $1)='$ECHO "LIBRARY ${soname%$shared_ext} INITINSTANCE TERMINSTANCE" > $output_objdir/$libname.def~ + $ECHO "DESCRIPTION \"$libname\"" >> $output_objdir/$libname.def~ + $ECHO "DATA MULTIPLE NONSHARED" >> $output_objdir/$libname.def~ + $ECHO EXPORTS >> $output_objdir/$libname.def~ + prefix_cmds="$SED"~ + if test EXPORTS = "`$SED 1q $export_symbols`"; then + prefix_cmds="$prefix_cmds -e 1d"; + fi~ + prefix_cmds="$prefix_cmds -e \"s/^\(.*\)$/_\1/g\""~ + cat $export_symbols | $prefix_cmds >> $output_objdir/$libname.def~ + $CC -Zdll -Zcrtdll -o $output_objdir/$soname $libobjs $deplibs $compiler_flags $output_objdir/$libname.def~ + emximp -o $lib $output_objdir/$libname.def' + _LT_TAGVAR(old_archive_From_new_cmds, $1)='emximp -o $output_objdir/${libname}_dll.a $output_objdir/$libname.def' + _LT_TAGVAR(enable_shared_with_static_runtimes, $1)=yes + ;; + interix[[3-9]]*) _LT_TAGVAR(hardcode_direct, $1)=no _LT_TAGVAR(hardcode_shlibpath_var, $1)=no - _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}-rpath,$libdir' - _LT_TAGVAR(export_dynamic_flag_spec, $1)='${wl}-E' + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='$wl-rpath,$libdir' + _LT_TAGVAR(export_dynamic_flag_spec, $1)='$wl-E' # Hack: On Interix 3.x, we cannot compile PIC because of a broken gcc. # Instead, shared libraries are loaded at an image base (0x10000000 by # default) and relocated if they conflict, which is a slow very memory # consuming and fragmenting process. To avoid this, we pick a random, # 256 KiB-aligned image base between 0x50000000 and 0x6FFC0000 at link # time. Moving up from 0x10000000 also allows more sbrk(2) space. - _LT_TAGVAR(archive_cmds, $1)='$CC -shared $pic_flag $libobjs $deplibs $compiler_flags ${wl}-h,$soname ${wl}--image-base,`expr ${RANDOM-$$} % 4096 / 2 \* 262144 + 1342177280` -o $lib' - _LT_TAGVAR(archive_expsym_cmds, $1)='sed "s,^,_," $export_symbols >$output_objdir/$soname.expsym~$CC -shared $pic_flag $libobjs $deplibs $compiler_flags ${wl}-h,$soname ${wl}--retain-symbols-file,$output_objdir/$soname.expsym ${wl}--image-base,`expr ${RANDOM-$$} % 4096 / 2 \* 262144 + 1342177280` -o $lib' + _LT_TAGVAR(archive_cmds, $1)='$CC -shared $pic_flag $libobjs $deplibs $compiler_flags $wl-h,$soname $wl--image-base,`expr ${RANDOM-$$} % 4096 / 2 \* 262144 + 1342177280` -o $lib' + _LT_TAGVAR(archive_expsym_cmds, $1)='sed "s|^|_|" $export_symbols >$output_objdir/$soname.expsym~$CC -shared $pic_flag $libobjs $deplibs $compiler_flags $wl-h,$soname $wl--retain-symbols-file,$output_objdir/$soname.expsym $wl--image-base,`expr ${RANDOM-$$} % 4096 / 2 \* 262144 + 1342177280` -o $lib' ;; gnu* | linux* | tpf* | k*bsd*-gnu | kopensolaris*-gnu) tmp_diet=no - if test "$host_os" = linux-dietlibc; then + if test linux-dietlibc = "$host_os"; then case $cc_basename in diet\ *) tmp_diet=yes;; # linux-dietlibc with static linking (!diet-dyn) esac fi if $LD --help 2>&1 | $EGREP ': supported targets:.* elf' > /dev/null \ - && test "$tmp_diet" = no + && test no = "$tmp_diet" then tmp_addflag=' $pic_flag' tmp_sharedflag='-shared' case $cc_basename,$host_cpu in pgcc*) # Portland Group C compiler - _LT_TAGVAR(whole_archive_flag_spec, $1)='${wl}--whole-archive`for conv in $convenience\"\"; do test -n \"$conv\" && new_convenience=\"$new_convenience,$conv\"; done; func_echo_all \"$new_convenience\"` ${wl}--no-whole-archive' + _LT_TAGVAR(whole_archive_flag_spec, $1)='$wl--whole-archive`for conv in $convenience\"\"; do test -n \"$conv\" && new_convenience=\"$new_convenience,$conv\"; done; func_echo_all \"$new_convenience\"` $wl--no-whole-archive' tmp_addflag=' $pic_flag' ;; pgf77* | pgf90* | pgf95* | pgfortran*) # Portland Group f77 and f90 compilers - _LT_TAGVAR(whole_archive_flag_spec, $1)='${wl}--whole-archive`for conv in $convenience\"\"; do test -n \"$conv\" && new_convenience=\"$new_convenience,$conv\"; done; func_echo_all \"$new_convenience\"` ${wl}--no-whole-archive' + _LT_TAGVAR(whole_archive_flag_spec, $1)='$wl--whole-archive`for conv in $convenience\"\"; do test -n \"$conv\" && new_convenience=\"$new_convenience,$conv\"; done; func_echo_all \"$new_convenience\"` $wl--no-whole-archive' tmp_addflag=' $pic_flag -Mnomain' ;; ecc*,ia64* | icc*,ia64*) # Intel C compiler on ia64 tmp_addflag=' -i_dynamic' ;; @@ -4821,42 +5206,47 @@ _LT_EOF lf95*) # Lahey Fortran 8.1 _LT_TAGVAR(whole_archive_flag_spec, $1)= tmp_sharedflag='--shared' ;; + nagfor*) # NAGFOR 5.3 + tmp_sharedflag='-Wl,-shared' ;; xl[[cC]]* | bgxl[[cC]]* | mpixl[[cC]]*) # IBM XL C 8.0 on PPC (deal with xlf below) tmp_sharedflag='-qmkshrobj' tmp_addflag= ;; nvcc*) # Cuda Compiler Driver 2.2 - _LT_TAGVAR(whole_archive_flag_spec, $1)='${wl}--whole-archive`for conv in $convenience\"\"; do test -n \"$conv\" && new_convenience=\"$new_convenience,$conv\"; done; func_echo_all \"$new_convenience\"` ${wl}--no-whole-archive' + _LT_TAGVAR(whole_archive_flag_spec, $1)='$wl--whole-archive`for conv in $convenience\"\"; do test -n \"$conv\" && new_convenience=\"$new_convenience,$conv\"; done; func_echo_all \"$new_convenience\"` $wl--no-whole-archive' _LT_TAGVAR(compiler_needs_object, $1)=yes ;; esac case `$CC -V 2>&1 | sed 5q` in *Sun\ C*) # Sun C 5.9 - _LT_TAGVAR(whole_archive_flag_spec, $1)='${wl}--whole-archive`new_convenience=; for conv in $convenience\"\"; do test -z \"$conv\" || new_convenience=\"$new_convenience,$conv\"; done; func_echo_all \"$new_convenience\"` ${wl}--no-whole-archive' + _LT_TAGVAR(whole_archive_flag_spec, $1)='$wl--whole-archive`new_convenience=; for conv in $convenience\"\"; do test -z \"$conv\" || new_convenience=\"$new_convenience,$conv\"; done; func_echo_all \"$new_convenience\"` $wl--no-whole-archive' _LT_TAGVAR(compiler_needs_object, $1)=yes tmp_sharedflag='-G' ;; *Sun\ F*) # Sun Fortran 8.3 tmp_sharedflag='-G' ;; esac - _LT_TAGVAR(archive_cmds, $1)='$CC '"$tmp_sharedflag""$tmp_addflag"' $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname -o $lib' + _LT_TAGVAR(archive_cmds, $1)='$CC '"$tmp_sharedflag""$tmp_addflag"' $libobjs $deplibs $compiler_flags $wl-soname $wl$soname -o $lib' - if test "x$supports_anon_versioning" = xyes; then + if test yes = "$supports_anon_versioning"; then _LT_TAGVAR(archive_expsym_cmds, $1)='echo "{ global:" > $output_objdir/$libname.ver~ - cat $export_symbols | sed -e "s/\(.*\)/\1;/" >> $output_objdir/$libname.ver~ - echo "local: *; };" >> $output_objdir/$libname.ver~ - $CC '"$tmp_sharedflag""$tmp_addflag"' $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname ${wl}-version-script ${wl}$output_objdir/$libname.ver -o $lib' + cat $export_symbols | sed -e "s/\(.*\)/\1;/" >> $output_objdir/$libname.ver~ + echo "local: *; };" >> $output_objdir/$libname.ver~ + $CC '"$tmp_sharedflag""$tmp_addflag"' $libobjs $deplibs $compiler_flags $wl-soname $wl$soname $wl-version-script $wl$output_objdir/$libname.ver -o $lib' fi case $cc_basename in + tcc*) + _LT_TAGVAR(export_dynamic_flag_spec, $1)='-rdynamic' + ;; xlf* | bgf* | bgxlf* | mpixlf*) # IBM XL Fortran 10.1 on PPC cannot create shared libs itself _LT_TAGVAR(whole_archive_flag_spec, $1)='--whole-archive$convenience --no-whole-archive' - _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}-rpath ${wl}$libdir' + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='$wl-rpath $wl$libdir' _LT_TAGVAR(archive_cmds, $1)='$LD -shared $libobjs $deplibs $linker_flags -soname $soname -o $lib' - if test "x$supports_anon_versioning" = xyes; then + if test yes = "$supports_anon_versioning"; then _LT_TAGVAR(archive_expsym_cmds, $1)='echo "{ global:" > $output_objdir/$libname.ver~ - cat $export_symbols | sed -e "s/\(.*\)/\1;/" >> $output_objdir/$libname.ver~ - echo "local: *; };" >> $output_objdir/$libname.ver~ - $LD -shared $libobjs $deplibs $linker_flags -soname $soname -version-script $output_objdir/$libname.ver -o $lib' + cat $export_symbols | sed -e "s/\(.*\)/\1;/" >> $output_objdir/$libname.ver~ + echo "local: *; };" >> $output_objdir/$libname.ver~ + $LD -shared $libobjs $deplibs $linker_flags -soname $soname -version-script $output_objdir/$libname.ver -o $lib' fi ;; esac @@ -4870,8 +5260,8 @@ _LT_EOF _LT_TAGVAR(archive_cmds, $1)='$LD -Bshareable $libobjs $deplibs $linker_flags -o $lib' wlarc= else - _LT_TAGVAR(archive_cmds, $1)='$CC -shared $pic_flag $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname -o $lib' - _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -shared $pic_flag $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname ${wl}-retain-symbols-file $wl$export_symbols -o $lib' + _LT_TAGVAR(archive_cmds, $1)='$CC -shared $pic_flag $libobjs $deplibs $compiler_flags $wl-soname $wl$soname -o $lib' + _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -shared $pic_flag $libobjs $deplibs $compiler_flags $wl-soname $wl$soname $wl-retain-symbols-file $wl$export_symbols -o $lib' fi ;; @@ -4889,8 +5279,8 @@ _LT_EOF _LT_EOF elif $LD --help 2>&1 | $GREP ': supported targets:.* elf' > /dev/null; then - _LT_TAGVAR(archive_cmds, $1)='$CC -shared $pic_flag $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname -o $lib' - _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -shared $pic_flag $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname ${wl}-retain-symbols-file $wl$export_symbols -o $lib' + _LT_TAGVAR(archive_cmds, $1)='$CC -shared $pic_flag $libobjs $deplibs $compiler_flags $wl-soname $wl$soname -o $lib' + _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -shared $pic_flag $libobjs $deplibs $compiler_flags $wl-soname $wl$soname $wl-retain-symbols-file $wl$export_symbols -o $lib' else _LT_TAGVAR(ld_shlibs, $1)=no fi @@ -4902,7 +5292,7 @@ _LT_EOF _LT_TAGVAR(ld_shlibs, $1)=no cat <<_LT_EOF 1>&2 -*** Warning: Releases of the GNU linker prior to 2.16.91.0.3 can not +*** Warning: Releases of the GNU linker prior to 2.16.91.0.3 cannot *** reliably create shared libraries on SCO systems. Therefore, libtool *** is disabling shared libraries support. We urge you to upgrade GNU *** binutils to release 2.16.91.0.3 or newer. Another option is to modify @@ -4917,9 +5307,9 @@ _LT_EOF # DT_RUNPATH tag from executables and libraries. But doing so # requires that you compile everything twice, which is a pain. if $LD --help 2>&1 | $GREP ': supported targets:.* elf' > /dev/null; then - _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}-rpath ${wl}$libdir' - _LT_TAGVAR(archive_cmds, $1)='$CC -shared $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname -o $lib' - _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -shared $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname ${wl}-retain-symbols-file $wl$export_symbols -o $lib' + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='$wl-rpath $wl$libdir' + _LT_TAGVAR(archive_cmds, $1)='$CC -shared $libobjs $deplibs $compiler_flags $wl-soname $wl$soname -o $lib' + _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -shared $libobjs $deplibs $compiler_flags $wl-soname $wl$soname $wl-retain-symbols-file $wl$export_symbols -o $lib' else _LT_TAGVAR(ld_shlibs, $1)=no fi @@ -4936,15 +5326,15 @@ _LT_EOF *) if $LD --help 2>&1 | $GREP ': supported targets:.* elf' > /dev/null; then - _LT_TAGVAR(archive_cmds, $1)='$CC -shared $pic_flag $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname -o $lib' - _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -shared $pic_flag $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname ${wl}-retain-symbols-file $wl$export_symbols -o $lib' + _LT_TAGVAR(archive_cmds, $1)='$CC -shared $pic_flag $libobjs $deplibs $compiler_flags $wl-soname $wl$soname -o $lib' + _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -shared $pic_flag $libobjs $deplibs $compiler_flags $wl-soname $wl$soname $wl-retain-symbols-file $wl$export_symbols -o $lib' else _LT_TAGVAR(ld_shlibs, $1)=no fi ;; esac - if test "$_LT_TAGVAR(ld_shlibs, $1)" = no; then + if test no = "$_LT_TAGVAR(ld_shlibs, $1)"; then runpath_var= _LT_TAGVAR(hardcode_libdir_flag_spec, $1)= _LT_TAGVAR(export_dynamic_flag_spec, $1)= @@ -4960,7 +5350,7 @@ _LT_EOF # Note: this linker hardcodes the directories in LIBPATH if there # are no directories specified by -L. _LT_TAGVAR(hardcode_minus_L, $1)=yes - if test "$GCC" = yes && test -z "$lt_prog_compiler_static"; then + if test yes = "$GCC" && test -z "$lt_prog_compiler_static"; then # Neither direct hardcoding nor static linking is supported with a # broken collect2. _LT_TAGVAR(hardcode_direct, $1)=unsupported @@ -4968,34 +5358,57 @@ _LT_EOF ;; aix[[4-9]]*) - if test "$host_cpu" = ia64; then + if test ia64 = "$host_cpu"; then # On IA64, the linker does run time linking by default, so we don't # have to do anything special. aix_use_runtimelinking=no exp_sym_flag='-Bexport' - no_entry_flag="" + no_entry_flag= else # If we're using GNU nm, then we don't want the "-C" option. - # -C means demangle to AIX nm, but means don't demangle with GNU nm - # Also, AIX nm treats weak defined symbols like other global - # defined symbols, whereas GNU nm marks them as "W". + # -C means demangle to GNU nm, but means don't demangle to AIX nm. + # Without the "-l" option, or with the "-B" option, AIX nm treats + # weak defined symbols like other global defined symbols, whereas + # GNU nm marks them as "W". + # While the 'weak' keyword is ignored in the Export File, we need + # it in the Import File for the 'aix-soname' feature, so we have + # to replace the "-B" option with "-P" for AIX nm. if $NM -V 2>&1 | $GREP 'GNU' > /dev/null; then - _LT_TAGVAR(export_symbols_cmds, $1)='$NM -Bpg $libobjs $convenience | awk '\''{ if (((\$ 2 == "T") || (\$ 2 == "D") || (\$ 2 == "B") || (\$ 2 == "W")) && ([substr](\$ 3,1,1) != ".")) { print \$ 3 } }'\'' | sort -u > $export_symbols' + _LT_TAGVAR(export_symbols_cmds, $1)='$NM -Bpg $libobjs $convenience | awk '\''{ if (((\$ 2 == "T") || (\$ 2 == "D") || (\$ 2 == "B") || (\$ 2 == "W")) && ([substr](\$ 3,1,1) != ".")) { if (\$ 2 == "W") { print \$ 3 " weak" } else { print \$ 3 } } }'\'' | sort -u > $export_symbols' else - _LT_TAGVAR(export_symbols_cmds, $1)='$NM -BCpg $libobjs $convenience | awk '\''{ if (((\$ 2 == "T") || (\$ 2 == "D") || (\$ 2 == "B")) && ([substr](\$ 3,1,1) != ".")) { print \$ 3 } }'\'' | sort -u > $export_symbols' + _LT_TAGVAR(export_symbols_cmds, $1)='`func_echo_all $NM | $SED -e '\''s/B\([[^B]]*\)$/P\1/'\''` -PCpgl $libobjs $convenience | awk '\''{ if (((\$ 2 == "T") || (\$ 2 == "D") || (\$ 2 == "B") || (\$ 2 == "W") || (\$ 2 == "V") || (\$ 2 == "Z")) && ([substr](\$ 1,1,1) != ".")) { if ((\$ 2 == "W") || (\$ 2 == "V") || (\$ 2 == "Z")) { print \$ 1 " weak" } else { print \$ 1 } } }'\'' | sort -u > $export_symbols' fi aix_use_runtimelinking=no # Test if we are trying to use run time linking or normal # AIX style linking. If -brtl is somewhere in LDFLAGS, we - # need to do runtime linking. + # have runtime linking enabled, and use it for executables. + # For shared libraries, we enable/disable runtime linking + # depending on the kind of the shared library created - + # when "with_aix_soname,aix_use_runtimelinking" is: + # "aix,no" lib.a(lib.so.V) shared, rtl:no, for executables + # "aix,yes" lib.so shared, rtl:yes, for executables + # lib.a static archive + # "both,no" lib.so.V(shr.o) shared, rtl:yes + # lib.a(lib.so.V) shared, rtl:no, for executables + # "both,yes" lib.so.V(shr.o) shared, rtl:yes, for executables + # lib.a(lib.so.V) shared, rtl:no + # "svr4,*" lib.so.V(shr.o) shared, rtl:yes, for executables + # lib.a static archive case $host_os in aix4.[[23]]|aix4.[[23]].*|aix[[5-9]]*) for ld_flag in $LDFLAGS; do - if (test $ld_flag = "-brtl" || test $ld_flag = "-Wl,-brtl"); then + if (test x-brtl = "x$ld_flag" || test x-Wl,-brtl = "x$ld_flag"); then aix_use_runtimelinking=yes break fi done + if test svr4,no = "$with_aix_soname,$aix_use_runtimelinking"; then + # With aix-soname=svr4, we create the lib.so.V shared archives only, + # so we don't have lib.a shared libs to link our executables. + # We have to force runtime linking in this case. + aix_use_runtimelinking=yes + LDFLAGS="$LDFLAGS -Wl,-brtl" + fi ;; esac @@ -5014,13 +5427,21 @@ _LT_EOF _LT_TAGVAR(hardcode_direct_absolute, $1)=yes _LT_TAGVAR(hardcode_libdir_separator, $1)=':' _LT_TAGVAR(link_all_deplibs, $1)=yes - _LT_TAGVAR(file_list_spec, $1)='${wl}-f,' + _LT_TAGVAR(file_list_spec, $1)='$wl-f,' + case $with_aix_soname,$aix_use_runtimelinking in + aix,*) ;; # traditional, no import file + svr4,* | *,yes) # use import file + # The Import File defines what to hardcode. + _LT_TAGVAR(hardcode_direct, $1)=no + _LT_TAGVAR(hardcode_direct_absolute, $1)=no + ;; + esac - if test "$GCC" = yes; then + if test yes = "$GCC"; then case $host_os in aix4.[[012]]|aix4.[[012]].*) # We only want to do this on AIX 4.2 and lower, the check # below for broken collect2 doesn't work under 4.3+ - collect2name=`${CC} -print-prog-name=collect2` + collect2name=`$CC -print-prog-name=collect2` if test -f "$collect2name" && strings "$collect2name" | $GREP resolve_lib_name >/dev/null then @@ -5039,61 +5460,80 @@ _LT_EOF ;; esac shared_flag='-shared' - if test "$aix_use_runtimelinking" = yes; then - shared_flag="$shared_flag "'${wl}-G' + if test yes = "$aix_use_runtimelinking"; then + shared_flag="$shared_flag "'$wl-G' fi + # Need to ensure runtime linking is disabled for the traditional + # shared library, or the linker may eventually find shared libraries + # /with/ Import File - we do not want to mix them. + shared_flag_aix='-shared' + shared_flag_svr4='-shared $wl-G' else # not using gcc - if test "$host_cpu" = ia64; then + if test ia64 = "$host_cpu"; then # VisualAge C++, Version 5.5 for AIX 5L for IA-64, Beta 3 Release # chokes on -Wl,-G. The following line is correct: shared_flag='-G' else - if test "$aix_use_runtimelinking" = yes; then - shared_flag='${wl}-G' + if test yes = "$aix_use_runtimelinking"; then + shared_flag='$wl-G' else - shared_flag='${wl}-bM:SRE' + shared_flag='$wl-bM:SRE' fi + shared_flag_aix='$wl-bM:SRE' + shared_flag_svr4='$wl-G' fi fi - _LT_TAGVAR(export_dynamic_flag_spec, $1)='${wl}-bexpall' + _LT_TAGVAR(export_dynamic_flag_spec, $1)='$wl-bexpall' # It seems that -bexpall does not export symbols beginning with # underscore (_), so it is better to generate a list of symbols to export. _LT_TAGVAR(always_export_symbols, $1)=yes - if test "$aix_use_runtimelinking" = yes; then + if test aix,yes = "$with_aix_soname,$aix_use_runtimelinking"; then # Warning - without using the other runtime loading flags (-brtl), # -berok will link without error, but may produce a broken library. _LT_TAGVAR(allow_undefined_flag, $1)='-berok' # Determine the default libpath from the value encoded in an # empty executable. _LT_SYS_MODULE_PATH_AIX([$1]) - _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}-blibpath:$libdir:'"$aix_libpath" - _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -o $output_objdir/$soname $libobjs $deplibs '"\${wl}$no_entry_flag"' $compiler_flags `if test "x${allow_undefined_flag}" != "x"; then func_echo_all "${wl}${allow_undefined_flag}"; else :; fi` '"\${wl}$exp_sym_flag:\$export_symbols $shared_flag" + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='$wl-blibpath:$libdir:'"$aix_libpath" + _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -o $output_objdir/$soname $libobjs $deplibs $wl'$no_entry_flag' $compiler_flags `if test -n "$allow_undefined_flag"; then func_echo_all "$wl$allow_undefined_flag"; else :; fi` $wl'$exp_sym_flag:\$export_symbols' '$shared_flag else - if test "$host_cpu" = ia64; then - _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}-R $libdir:/usr/lib:/lib' + if test ia64 = "$host_cpu"; then + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='$wl-R $libdir:/usr/lib:/lib' _LT_TAGVAR(allow_undefined_flag, $1)="-z nodefs" - _LT_TAGVAR(archive_expsym_cmds, $1)="\$CC $shared_flag"' -o $output_objdir/$soname $libobjs $deplibs '"\${wl}$no_entry_flag"' $compiler_flags ${wl}${allow_undefined_flag} '"\${wl}$exp_sym_flag:\$export_symbols" + _LT_TAGVAR(archive_expsym_cmds, $1)="\$CC $shared_flag"' -o $output_objdir/$soname $libobjs $deplibs '"\$wl$no_entry_flag"' $compiler_flags $wl$allow_undefined_flag '"\$wl$exp_sym_flag:\$export_symbols" else # Determine the default libpath from the value encoded in an # empty executable. _LT_SYS_MODULE_PATH_AIX([$1]) - _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}-blibpath:$libdir:'"$aix_libpath" + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='$wl-blibpath:$libdir:'"$aix_libpath" # Warning - without using the other run time loading flags, # -berok will link without error, but may produce a broken library. - _LT_TAGVAR(no_undefined_flag, $1)=' ${wl}-bernotok' - _LT_TAGVAR(allow_undefined_flag, $1)=' ${wl}-berok' - if test "$with_gnu_ld" = yes; then + _LT_TAGVAR(no_undefined_flag, $1)=' $wl-bernotok' + _LT_TAGVAR(allow_undefined_flag, $1)=' $wl-berok' + if test yes = "$with_gnu_ld"; then # We only use this code for GNU lds that support --whole-archive. - _LT_TAGVAR(whole_archive_flag_spec, $1)='${wl}--whole-archive$convenience ${wl}--no-whole-archive' + _LT_TAGVAR(whole_archive_flag_spec, $1)='$wl--whole-archive$convenience $wl--no-whole-archive' else # Exported symbols can be pulled into shared objects from archives _LT_TAGVAR(whole_archive_flag_spec, $1)='$convenience' fi _LT_TAGVAR(archive_cmds_need_lc, $1)=yes - # This is similar to how AIX traditionally builds its shared libraries. - _LT_TAGVAR(archive_expsym_cmds, $1)="\$CC $shared_flag"' -o $output_objdir/$soname $libobjs $deplibs ${wl}-bnoentry $compiler_flags ${wl}-bE:$export_symbols${allow_undefined_flag}~$AR $AR_FLAGS $output_objdir/$libname$release.a $output_objdir/$soname' + _LT_TAGVAR(archive_expsym_cmds, $1)='$RM -r $output_objdir/$realname.d~$MKDIR $output_objdir/$realname.d' + # -brtl affects multiple linker settings, -berok does not and is overridden later + compiler_flags_filtered='`func_echo_all "$compiler_flags " | $SED -e "s%-brtl\\([[, ]]\\)%-berok\\1%g"`' + if test svr4 != "$with_aix_soname"; then + # This is similar to how AIX traditionally builds its shared libraries. + _LT_TAGVAR(archive_expsym_cmds, $1)="$_LT_TAGVAR(archive_expsym_cmds, $1)"'~$CC '$shared_flag_aix' -o $output_objdir/$realname.d/$soname $libobjs $deplibs $wl-bnoentry '$compiler_flags_filtered'$wl-bE:$export_symbols$allow_undefined_flag~$AR $AR_FLAGS $output_objdir/$libname$release.a $output_objdir/$realname.d/$soname' + fi + if test aix != "$with_aix_soname"; then + _LT_TAGVAR(archive_expsym_cmds, $1)="$_LT_TAGVAR(archive_expsym_cmds, $1)"'~$CC '$shared_flag_svr4' -o $output_objdir/$realname.d/$shared_archive_member_spec.o $libobjs $deplibs $wl-bnoentry '$compiler_flags_filtered'$wl-bE:$export_symbols$allow_undefined_flag~$STRIP -e $output_objdir/$realname.d/$shared_archive_member_spec.o~( func_echo_all "#! $soname($shared_archive_member_spec.o)"; if test shr_64 = "$shared_archive_member_spec"; then func_echo_all "# 64"; else func_echo_all "# 32"; fi; cat $export_symbols ) > $output_objdir/$realname.d/$shared_archive_member_spec.imp~$AR $AR_FLAGS $output_objdir/$soname $output_objdir/$realname.d/$shared_archive_member_spec.o $output_objdir/$realname.d/$shared_archive_member_spec.imp' + else + # used by -dlpreopen to get the symbols + _LT_TAGVAR(archive_expsym_cmds, $1)="$_LT_TAGVAR(archive_expsym_cmds, $1)"'~$MV $output_objdir/$realname.d/$soname $output_objdir' + fi + _LT_TAGVAR(archive_expsym_cmds, $1)="$_LT_TAGVAR(archive_expsym_cmds, $1)"'~$RM -r $output_objdir/$realname.d' fi fi ;; @@ -5102,7 +5542,7 @@ _LT_EOF case $host_cpu in powerpc) # see comment about AmigaOS4 .so support - _LT_TAGVAR(archive_cmds, $1)='$CC -shared $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname -o $lib' + _LT_TAGVAR(archive_cmds, $1)='$CC -shared $libobjs $deplibs $compiler_flags $wl-soname $wl$soname -o $lib' _LT_TAGVAR(archive_expsym_cmds, $1)='' ;; m68k) @@ -5132,16 +5572,17 @@ _LT_EOF # Tell ltmain to make .lib files, not .a files. libext=lib # Tell ltmain to make .dll files, not .so files. - shrext_cmds=".dll" + shrext_cmds=.dll # FIXME: Setting linknames here is a bad hack. - _LT_TAGVAR(archive_cmds, $1)='$CC -o $output_objdir/$soname $libobjs $compiler_flags $deplibs -Wl,-dll~linknames=' - _LT_TAGVAR(archive_expsym_cmds, $1)='if test "x`$SED 1q $export_symbols`" = xEXPORTS; then - sed -n -e 's/\\\\\\\(.*\\\\\\\)/-link\\\ -EXPORT:\\\\\\\1/' -e '1\\\!p' < $export_symbols > $output_objdir/$soname.exp; - else - sed -e 's/\\\\\\\(.*\\\\\\\)/-link\\\ -EXPORT:\\\\\\\1/' < $export_symbols > $output_objdir/$soname.exp; - fi~ - $CC -o $tool_output_objdir$soname $libobjs $compiler_flags $deplibs "@$tool_output_objdir$soname.exp" -Wl,-DLL,-IMPLIB:"$tool_output_objdir$libname.dll.lib"~ - linknames=' + _LT_TAGVAR(archive_cmds, $1)='$CC -o $output_objdir/$soname $libobjs $compiler_flags $deplibs -Wl,-DLL,-IMPLIB:"$tool_output_objdir$libname.dll.lib"~linknames=' + _LT_TAGVAR(archive_expsym_cmds, $1)='if _LT_DLL_DEF_P([$export_symbols]); then + cp "$export_symbols" "$output_objdir/$soname.def"; + echo "$tool_output_objdir$soname.def" > "$output_objdir/$soname.exp"; + else + $SED -e '\''s/^/-link -EXPORT:/'\'' < $export_symbols > $output_objdir/$soname.exp; + fi~ + $CC -o $tool_output_objdir$soname $libobjs $compiler_flags $deplibs "@$tool_output_objdir$soname.exp" -Wl,-DLL,-IMPLIB:"$tool_output_objdir$libname.dll.lib"~ + linknames=' # The linker will not automatically build a static lib if we build a DLL. # _LT_TAGVAR(old_archive_from_new_cmds, $1)='true' _LT_TAGVAR(enable_shared_with_static_runtimes, $1)=yes @@ -5150,18 +5591,18 @@ _LT_EOF # Don't use ranlib _LT_TAGVAR(old_postinstall_cmds, $1)='chmod 644 $oldlib' _LT_TAGVAR(postlink_cmds, $1)='lt_outputfile="@OUTPUT@"~ - lt_tool_outputfile="@TOOL_OUTPUT@"~ - case $lt_outputfile in - *.exe|*.EXE) ;; - *) - lt_outputfile="$lt_outputfile.exe" - lt_tool_outputfile="$lt_tool_outputfile.exe" - ;; - esac~ - if test "$MANIFEST_TOOL" != ":" && test -f "$lt_outputfile.manifest"; then - $MANIFEST_TOOL -manifest "$lt_tool_outputfile.manifest" -outputresource:"$lt_tool_outputfile" || exit 1; - $RM "$lt_outputfile.manifest"; - fi' + lt_tool_outputfile="@TOOL_OUTPUT@"~ + case $lt_outputfile in + *.exe|*.EXE) ;; + *) + lt_outputfile=$lt_outputfile.exe + lt_tool_outputfile=$lt_tool_outputfile.exe + ;; + esac~ + if test : != "$MANIFEST_TOOL" && test -f "$lt_outputfile.manifest"; then + $MANIFEST_TOOL -manifest "$lt_tool_outputfile.manifest" -outputresource:"$lt_tool_outputfile" || exit 1; + $RM "$lt_outputfile.manifest"; + fi' ;; *) # Assume MSVC wrapper @@ -5170,7 +5611,7 @@ _LT_EOF # Tell ltmain to make .lib files, not .a files. libext=lib # Tell ltmain to make .dll files, not .so files. - shrext_cmds=".dll" + shrext_cmds=.dll # FIXME: Setting linknames here is a bad hack. _LT_TAGVAR(archive_cmds, $1)='$CC -o $lib $libobjs $compiler_flags `func_echo_all "$deplibs" | $SED '\''s/ -lc$//'\''` -link -dll~linknames=' # The linker will automatically build a .lib file if we build a DLL. @@ -5220,33 +5661,33 @@ _LT_EOF ;; hpux9*) - if test "$GCC" = yes; then - _LT_TAGVAR(archive_cmds, $1)='$RM $output_objdir/$soname~$CC -shared $pic_flag ${wl}+b ${wl}$install_libdir -o $output_objdir/$soname $libobjs $deplibs $compiler_flags~test $output_objdir/$soname = $lib || mv $output_objdir/$soname $lib' + if test yes = "$GCC"; then + _LT_TAGVAR(archive_cmds, $1)='$RM $output_objdir/$soname~$CC -shared $pic_flag $wl+b $wl$install_libdir -o $output_objdir/$soname $libobjs $deplibs $compiler_flags~test "x$output_objdir/$soname" = "x$lib" || mv $output_objdir/$soname $lib' else - _LT_TAGVAR(archive_cmds, $1)='$RM $output_objdir/$soname~$LD -b +b $install_libdir -o $output_objdir/$soname $libobjs $deplibs $linker_flags~test $output_objdir/$soname = $lib || mv $output_objdir/$soname $lib' + _LT_TAGVAR(archive_cmds, $1)='$RM $output_objdir/$soname~$LD -b +b $install_libdir -o $output_objdir/$soname $libobjs $deplibs $linker_flags~test "x$output_objdir/$soname" = "x$lib" || mv $output_objdir/$soname $lib' fi - _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}+b ${wl}$libdir' + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='$wl+b $wl$libdir' _LT_TAGVAR(hardcode_libdir_separator, $1)=: _LT_TAGVAR(hardcode_direct, $1)=yes # hardcode_minus_L: Not really in the search PATH, # but as the default location of the library. _LT_TAGVAR(hardcode_minus_L, $1)=yes - _LT_TAGVAR(export_dynamic_flag_spec, $1)='${wl}-E' + _LT_TAGVAR(export_dynamic_flag_spec, $1)='$wl-E' ;; hpux10*) - if test "$GCC" = yes && test "$with_gnu_ld" = no; then - _LT_TAGVAR(archive_cmds, $1)='$CC -shared $pic_flag ${wl}+h ${wl}$soname ${wl}+b ${wl}$install_libdir -o $lib $libobjs $deplibs $compiler_flags' + if test yes,no = "$GCC,$with_gnu_ld"; then + _LT_TAGVAR(archive_cmds, $1)='$CC -shared $pic_flag $wl+h $wl$soname $wl+b $wl$install_libdir -o $lib $libobjs $deplibs $compiler_flags' else _LT_TAGVAR(archive_cmds, $1)='$LD -b +h $soname +b $install_libdir -o $lib $libobjs $deplibs $linker_flags' fi - if test "$with_gnu_ld" = no; then - _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}+b ${wl}$libdir' + if test no = "$with_gnu_ld"; then + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='$wl+b $wl$libdir' _LT_TAGVAR(hardcode_libdir_separator, $1)=: _LT_TAGVAR(hardcode_direct, $1)=yes _LT_TAGVAR(hardcode_direct_absolute, $1)=yes - _LT_TAGVAR(export_dynamic_flag_spec, $1)='${wl}-E' + _LT_TAGVAR(export_dynamic_flag_spec, $1)='$wl-E' # hardcode_minus_L: Not really in the search PATH, # but as the default location of the library. _LT_TAGVAR(hardcode_minus_L, $1)=yes @@ -5254,25 +5695,25 @@ _LT_EOF ;; hpux11*) - if test "$GCC" = yes && test "$with_gnu_ld" = no; then + if test yes,no = "$GCC,$with_gnu_ld"; then case $host_cpu in hppa*64*) - _LT_TAGVAR(archive_cmds, $1)='$CC -shared ${wl}+h ${wl}$soname -o $lib $libobjs $deplibs $compiler_flags' + _LT_TAGVAR(archive_cmds, $1)='$CC -shared $wl+h $wl$soname -o $lib $libobjs $deplibs $compiler_flags' ;; ia64*) - _LT_TAGVAR(archive_cmds, $1)='$CC -shared $pic_flag ${wl}+h ${wl}$soname ${wl}+nodefaultrpath -o $lib $libobjs $deplibs $compiler_flags' + _LT_TAGVAR(archive_cmds, $1)='$CC -shared $pic_flag $wl+h $wl$soname $wl+nodefaultrpath -o $lib $libobjs $deplibs $compiler_flags' ;; *) - _LT_TAGVAR(archive_cmds, $1)='$CC -shared $pic_flag ${wl}+h ${wl}$soname ${wl}+b ${wl}$install_libdir -o $lib $libobjs $deplibs $compiler_flags' + _LT_TAGVAR(archive_cmds, $1)='$CC -shared $pic_flag $wl+h $wl$soname $wl+b $wl$install_libdir -o $lib $libobjs $deplibs $compiler_flags' ;; esac else case $host_cpu in hppa*64*) - _LT_TAGVAR(archive_cmds, $1)='$CC -b ${wl}+h ${wl}$soname -o $lib $libobjs $deplibs $compiler_flags' + _LT_TAGVAR(archive_cmds, $1)='$CC -b $wl+h $wl$soname -o $lib $libobjs $deplibs $compiler_flags' ;; ia64*) - _LT_TAGVAR(archive_cmds, $1)='$CC -b ${wl}+h ${wl}$soname ${wl}+nodefaultrpath -o $lib $libobjs $deplibs $compiler_flags' + _LT_TAGVAR(archive_cmds, $1)='$CC -b $wl+h $wl$soname $wl+nodefaultrpath -o $lib $libobjs $deplibs $compiler_flags' ;; *) m4_if($1, [], [ @@ -5280,14 +5721,14 @@ _LT_EOF # (HP92453-01 A.11.01.20 doesn't, HP92453-01 B.11.X.35175-35176.GP does) _LT_LINKER_OPTION([if $CC understands -b], _LT_TAGVAR(lt_cv_prog_compiler__b, $1), [-b], - [_LT_TAGVAR(archive_cmds, $1)='$CC -b ${wl}+h ${wl}$soname ${wl}+b ${wl}$install_libdir -o $lib $libobjs $deplibs $compiler_flags'], + [_LT_TAGVAR(archive_cmds, $1)='$CC -b $wl+h $wl$soname $wl+b $wl$install_libdir -o $lib $libobjs $deplibs $compiler_flags'], [_LT_TAGVAR(archive_cmds, $1)='$LD -b +h $soname +b $install_libdir -o $lib $libobjs $deplibs $linker_flags'])], - [_LT_TAGVAR(archive_cmds, $1)='$CC -b ${wl}+h ${wl}$soname ${wl}+b ${wl}$install_libdir -o $lib $libobjs $deplibs $compiler_flags']) + [_LT_TAGVAR(archive_cmds, $1)='$CC -b $wl+h $wl$soname $wl+b $wl$install_libdir -o $lib $libobjs $deplibs $compiler_flags']) ;; esac fi - if test "$with_gnu_ld" = no; then - _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}+b ${wl}$libdir' + if test no = "$with_gnu_ld"; then + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='$wl+b $wl$libdir' _LT_TAGVAR(hardcode_libdir_separator, $1)=: case $host_cpu in @@ -5298,7 +5739,7 @@ _LT_EOF *) _LT_TAGVAR(hardcode_direct, $1)=yes _LT_TAGVAR(hardcode_direct_absolute, $1)=yes - _LT_TAGVAR(export_dynamic_flag_spec, $1)='${wl}-E' + _LT_TAGVAR(export_dynamic_flag_spec, $1)='$wl-E' # hardcode_minus_L: Not really in the search PATH, # but as the default location of the library. @@ -5309,16 +5750,16 @@ _LT_EOF ;; irix5* | irix6* | nonstopux*) - if test "$GCC" = yes; then - _LT_TAGVAR(archive_cmds, $1)='$CC -shared $pic_flag $libobjs $deplibs $compiler_flags ${wl}-soname ${wl}$soname `test -n "$verstring" && func_echo_all "${wl}-set_version ${wl}$verstring"` ${wl}-update_registry ${wl}${output_objdir}/so_locations -o $lib' + if test yes = "$GCC"; then + _LT_TAGVAR(archive_cmds, $1)='$CC -shared $pic_flag $libobjs $deplibs $compiler_flags $wl-soname $wl$soname `test -n "$verstring" && func_echo_all "$wl-set_version $wl$verstring"` $wl-update_registry $wl$output_objdir/so_locations -o $lib' # Try to use the -exported_symbol ld option, if it does not # work, assume that -exports_file does not work either and # implicitly export all symbols. # This should be the same for all languages, so no per-tag cache variable. AC_CACHE_CHECK([whether the $host_os linker accepts -exported_symbol], [lt_cv_irix_exported_symbol], - [save_LDFLAGS="$LDFLAGS" - LDFLAGS="$LDFLAGS -shared ${wl}-exported_symbol ${wl}foo ${wl}-update_registry ${wl}/dev/null" + [save_LDFLAGS=$LDFLAGS + LDFLAGS="$LDFLAGS -shared $wl-exported_symbol ${wl}foo $wl-update_registry $wl/dev/null" AC_LINK_IFELSE( [AC_LANG_SOURCE( [AC_LANG_CASE([C], [[int foo (void) { return 0; }]], @@ -5331,21 +5772,31 @@ _LT_EOF end]])])], [lt_cv_irix_exported_symbol=yes], [lt_cv_irix_exported_symbol=no]) - LDFLAGS="$save_LDFLAGS"]) - if test "$lt_cv_irix_exported_symbol" = yes; then - _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -shared $pic_flag $libobjs $deplibs $compiler_flags ${wl}-soname ${wl}$soname `test -n "$verstring" && func_echo_all "${wl}-set_version ${wl}$verstring"` ${wl}-update_registry ${wl}${output_objdir}/so_locations ${wl}-exports_file ${wl}$export_symbols -o $lib' + LDFLAGS=$save_LDFLAGS]) + if test yes = "$lt_cv_irix_exported_symbol"; then + _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -shared $pic_flag $libobjs $deplibs $compiler_flags $wl-soname $wl$soname `test -n "$verstring" && func_echo_all "$wl-set_version $wl$verstring"` $wl-update_registry $wl$output_objdir/so_locations $wl-exports_file $wl$export_symbols -o $lib' fi else - _LT_TAGVAR(archive_cmds, $1)='$CC -shared $libobjs $deplibs $compiler_flags -soname $soname `test -n "$verstring" && func_echo_all "-set_version $verstring"` -update_registry ${output_objdir}/so_locations -o $lib' - _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -shared $libobjs $deplibs $compiler_flags -soname $soname `test -n "$verstring" && func_echo_all "-set_version $verstring"` -update_registry ${output_objdir}/so_locations -exports_file $export_symbols -o $lib' + _LT_TAGVAR(archive_cmds, $1)='$CC -shared $libobjs $deplibs $compiler_flags -soname $soname `test -n "$verstring" && func_echo_all "-set_version $verstring"` -update_registry $output_objdir/so_locations -o $lib' + _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -shared $libobjs $deplibs $compiler_flags -soname $soname `test -n "$verstring" && func_echo_all "-set_version $verstring"` -update_registry $output_objdir/so_locations -exports_file $export_symbols -o $lib' fi _LT_TAGVAR(archive_cmds_need_lc, $1)='no' - _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}-rpath ${wl}$libdir' + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='$wl-rpath $wl$libdir' _LT_TAGVAR(hardcode_libdir_separator, $1)=: _LT_TAGVAR(inherit_rpath, $1)=yes _LT_TAGVAR(link_all_deplibs, $1)=yes ;; + linux*) + case $cc_basename in + tcc*) + # Fabrice Bellard et al's Tiny C Compiler + _LT_TAGVAR(ld_shlibs, $1)=yes + _LT_TAGVAR(archive_cmds, $1)='$CC -shared $pic_flag -o $lib $libobjs $deplibs $compiler_flags' + ;; + esac + ;; + netbsd*) if echo __ELF__ | $CC -E - | $GREP __ELF__ >/dev/null; then _LT_TAGVAR(archive_cmds, $1)='$LD -Bshareable -o $lib $libobjs $deplibs $linker_flags' # a.out @@ -5360,7 +5811,7 @@ _LT_EOF newsos6) _LT_TAGVAR(archive_cmds, $1)='$LD -G -h $soname -o $lib $libobjs $deplibs $linker_flags' _LT_TAGVAR(hardcode_direct, $1)=yes - _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}-rpath ${wl}$libdir' + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='$wl-rpath $wl$libdir' _LT_TAGVAR(hardcode_libdir_separator, $1)=: _LT_TAGVAR(hardcode_shlibpath_var, $1)=no ;; @@ -5368,27 +5819,19 @@ _LT_EOF *nto* | *qnx*) ;; - openbsd*) + openbsd* | bitrig*) if test -f /usr/libexec/ld.so; then _LT_TAGVAR(hardcode_direct, $1)=yes _LT_TAGVAR(hardcode_shlibpath_var, $1)=no _LT_TAGVAR(hardcode_direct_absolute, $1)=yes - if test -z "`echo __ELF__ | $CC -E - | $GREP __ELF__`" || test "$host_os-$host_cpu" = "openbsd2.8-powerpc"; then + if test -z "`echo __ELF__ | $CC -E - | $GREP __ELF__`"; then _LT_TAGVAR(archive_cmds, $1)='$CC -shared $pic_flag -o $lib $libobjs $deplibs $compiler_flags' - _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -shared $pic_flag -o $lib $libobjs $deplibs $compiler_flags ${wl}-retain-symbols-file,$export_symbols' - _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}-rpath,$libdir' - _LT_TAGVAR(export_dynamic_flag_spec, $1)='${wl}-E' + _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -shared $pic_flag -o $lib $libobjs $deplibs $compiler_flags $wl-retain-symbols-file,$export_symbols' + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='$wl-rpath,$libdir' + _LT_TAGVAR(export_dynamic_flag_spec, $1)='$wl-E' else - case $host_os in - openbsd[[01]].* | openbsd2.[[0-7]] | openbsd2.[[0-7]].*) - _LT_TAGVAR(archive_cmds, $1)='$LD -Bshareable -o $lib $libobjs $deplibs $linker_flags' - _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='-R$libdir' - ;; - *) - _LT_TAGVAR(archive_cmds, $1)='$CC -shared $pic_flag -o $lib $libobjs $deplibs $compiler_flags' - _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}-rpath,$libdir' - ;; - esac + _LT_TAGVAR(archive_cmds, $1)='$CC -shared $pic_flag -o $lib $libobjs $deplibs $compiler_flags' + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='$wl-rpath,$libdir' fi else _LT_TAGVAR(ld_shlibs, $1)=no @@ -5399,33 +5842,53 @@ _LT_EOF _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='-L$libdir' _LT_TAGVAR(hardcode_minus_L, $1)=yes _LT_TAGVAR(allow_undefined_flag, $1)=unsupported - _LT_TAGVAR(archive_cmds, $1)='$ECHO "LIBRARY $libname INITINSTANCE" > $output_objdir/$libname.def~$ECHO "DESCRIPTION \"$libname\"" >> $output_objdir/$libname.def~echo DATA >> $output_objdir/$libname.def~echo " SINGLE NONSHARED" >> $output_objdir/$libname.def~echo EXPORTS >> $output_objdir/$libname.def~emxexp $libobjs >> $output_objdir/$libname.def~$CC -Zdll -Zcrtdll -o $lib $libobjs $deplibs $compiler_flags $output_objdir/$libname.def' - _LT_TAGVAR(old_archive_from_new_cmds, $1)='emximp -o $output_objdir/$libname.a $output_objdir/$libname.def' + shrext_cmds=.dll + _LT_TAGVAR(archive_cmds, $1)='$ECHO "LIBRARY ${soname%$shared_ext} INITINSTANCE TERMINSTANCE" > $output_objdir/$libname.def~ + $ECHO "DESCRIPTION \"$libname\"" >> $output_objdir/$libname.def~ + $ECHO "DATA MULTIPLE NONSHARED" >> $output_objdir/$libname.def~ + $ECHO EXPORTS >> $output_objdir/$libname.def~ + emxexp $libobjs | $SED /"_DLL_InitTerm"/d >> $output_objdir/$libname.def~ + $CC -Zdll -Zcrtdll -o $output_objdir/$soname $libobjs $deplibs $compiler_flags $output_objdir/$libname.def~ + emximp -o $lib $output_objdir/$libname.def' + _LT_TAGVAR(archive_expsym_cmds, $1)='$ECHO "LIBRARY ${soname%$shared_ext} INITINSTANCE TERMINSTANCE" > $output_objdir/$libname.def~ + $ECHO "DESCRIPTION \"$libname\"" >> $output_objdir/$libname.def~ + $ECHO "DATA MULTIPLE NONSHARED" >> $output_objdir/$libname.def~ + $ECHO EXPORTS >> $output_objdir/$libname.def~ + prefix_cmds="$SED"~ + if test EXPORTS = "`$SED 1q $export_symbols`"; then + prefix_cmds="$prefix_cmds -e 1d"; + fi~ + prefix_cmds="$prefix_cmds -e \"s/^\(.*\)$/_\1/g\""~ + cat $export_symbols | $prefix_cmds >> $output_objdir/$libname.def~ + $CC -Zdll -Zcrtdll -o $output_objdir/$soname $libobjs $deplibs $compiler_flags $output_objdir/$libname.def~ + emximp -o $lib $output_objdir/$libname.def' + _LT_TAGVAR(old_archive_From_new_cmds, $1)='emximp -o $output_objdir/${libname}_dll.a $output_objdir/$libname.def' + _LT_TAGVAR(enable_shared_with_static_runtimes, $1)=yes ;; osf3*) - if test "$GCC" = yes; then - _LT_TAGVAR(allow_undefined_flag, $1)=' ${wl}-expect_unresolved ${wl}\*' - _LT_TAGVAR(archive_cmds, $1)='$CC -shared${allow_undefined_flag} $libobjs $deplibs $compiler_flags ${wl}-soname ${wl}$soname `test -n "$verstring" && func_echo_all "${wl}-set_version ${wl}$verstring"` ${wl}-update_registry ${wl}${output_objdir}/so_locations -o $lib' + if test yes = "$GCC"; then + _LT_TAGVAR(allow_undefined_flag, $1)=' $wl-expect_unresolved $wl\*' + _LT_TAGVAR(archive_cmds, $1)='$CC -shared$allow_undefined_flag $libobjs $deplibs $compiler_flags $wl-soname $wl$soname `test -n "$verstring" && func_echo_all "$wl-set_version $wl$verstring"` $wl-update_registry $wl$output_objdir/so_locations -o $lib' else _LT_TAGVAR(allow_undefined_flag, $1)=' -expect_unresolved \*' - _LT_TAGVAR(archive_cmds, $1)='$CC -shared${allow_undefined_flag} $libobjs $deplibs $compiler_flags -soname $soname `test -n "$verstring" && func_echo_all "-set_version $verstring"` -update_registry ${output_objdir}/so_locations -o $lib' + _LT_TAGVAR(archive_cmds, $1)='$CC -shared$allow_undefined_flag $libobjs $deplibs $compiler_flags -soname $soname `test -n "$verstring" && func_echo_all "-set_version $verstring"` -update_registry $output_objdir/so_locations -o $lib' fi _LT_TAGVAR(archive_cmds_need_lc, $1)='no' - _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}-rpath ${wl}$libdir' + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='$wl-rpath $wl$libdir' _LT_TAGVAR(hardcode_libdir_separator, $1)=: ;; osf4* | osf5*) # as osf3* with the addition of -msym flag - if test "$GCC" = yes; then - _LT_TAGVAR(allow_undefined_flag, $1)=' ${wl}-expect_unresolved ${wl}\*' - _LT_TAGVAR(archive_cmds, $1)='$CC -shared${allow_undefined_flag} $pic_flag $libobjs $deplibs $compiler_flags ${wl}-msym ${wl}-soname ${wl}$soname `test -n "$verstring" && func_echo_all "${wl}-set_version ${wl}$verstring"` ${wl}-update_registry ${wl}${output_objdir}/so_locations -o $lib' - _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}-rpath ${wl}$libdir' + if test yes = "$GCC"; then + _LT_TAGVAR(allow_undefined_flag, $1)=' $wl-expect_unresolved $wl\*' + _LT_TAGVAR(archive_cmds, $1)='$CC -shared$allow_undefined_flag $pic_flag $libobjs $deplibs $compiler_flags $wl-msym $wl-soname $wl$soname `test -n "$verstring" && func_echo_all "$wl-set_version $wl$verstring"` $wl-update_registry $wl$output_objdir/so_locations -o $lib' + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='$wl-rpath $wl$libdir' else _LT_TAGVAR(allow_undefined_flag, $1)=' -expect_unresolved \*' - _LT_TAGVAR(archive_cmds, $1)='$CC -shared${allow_undefined_flag} $libobjs $deplibs $compiler_flags -msym -soname $soname `test -n "$verstring" && func_echo_all "-set_version $verstring"` -update_registry ${output_objdir}/so_locations -o $lib' + _LT_TAGVAR(archive_cmds, $1)='$CC -shared$allow_undefined_flag $libobjs $deplibs $compiler_flags -msym -soname $soname `test -n "$verstring" && func_echo_all "-set_version $verstring"` -update_registry $output_objdir/so_locations -o $lib' _LT_TAGVAR(archive_expsym_cmds, $1)='for i in `cat $export_symbols`; do printf "%s %s\\n" -exported_symbol "\$i" >> $lib.exp; done; printf "%s\\n" "-hidden">> $lib.exp~ - $CC -shared${allow_undefined_flag} ${wl}-input ${wl}$lib.exp $compiler_flags $libobjs $deplibs -soname $soname `test -n "$verstring" && $ECHO "-set_version $verstring"` -update_registry ${output_objdir}/so_locations -o $lib~$RM $lib.exp' + $CC -shared$allow_undefined_flag $wl-input $wl$lib.exp $compiler_flags $libobjs $deplibs -soname $soname `test -n "$verstring" && $ECHO "-set_version $verstring"` -update_registry $output_objdir/so_locations -o $lib~$RM $lib.exp' # Both c and cxx compiler support -rpath directly _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='-rpath $libdir' @@ -5436,24 +5899,24 @@ _LT_EOF solaris*) _LT_TAGVAR(no_undefined_flag, $1)=' -z defs' - if test "$GCC" = yes; then - wlarc='${wl}' - _LT_TAGVAR(archive_cmds, $1)='$CC -shared $pic_flag ${wl}-z ${wl}text ${wl}-h ${wl}$soname -o $lib $libobjs $deplibs $compiler_flags' + if test yes = "$GCC"; then + wlarc='$wl' + _LT_TAGVAR(archive_cmds, $1)='$CC -shared $pic_flag $wl-z ${wl}text $wl-h $wl$soname -o $lib $libobjs $deplibs $compiler_flags' _LT_TAGVAR(archive_expsym_cmds, $1)='echo "{ global:" > $lib.exp~cat $export_symbols | $SED -e "s/\(.*\)/\1;/" >> $lib.exp~echo "local: *; };" >> $lib.exp~ - $CC -shared $pic_flag ${wl}-z ${wl}text ${wl}-M ${wl}$lib.exp ${wl}-h ${wl}$soname -o $lib $libobjs $deplibs $compiler_flags~$RM $lib.exp' + $CC -shared $pic_flag $wl-z ${wl}text $wl-M $wl$lib.exp $wl-h $wl$soname -o $lib $libobjs $deplibs $compiler_flags~$RM $lib.exp' else case `$CC -V 2>&1` in *"Compilers 5.0"*) wlarc='' - _LT_TAGVAR(archive_cmds, $1)='$LD -G${allow_undefined_flag} -h $soname -o $lib $libobjs $deplibs $linker_flags' + _LT_TAGVAR(archive_cmds, $1)='$LD -G$allow_undefined_flag -h $soname -o $lib $libobjs $deplibs $linker_flags' _LT_TAGVAR(archive_expsym_cmds, $1)='echo "{ global:" > $lib.exp~cat $export_symbols | $SED -e "s/\(.*\)/\1;/" >> $lib.exp~echo "local: *; };" >> $lib.exp~ - $LD -G${allow_undefined_flag} -M $lib.exp -h $soname -o $lib $libobjs $deplibs $linker_flags~$RM $lib.exp' + $LD -G$allow_undefined_flag -M $lib.exp -h $soname -o $lib $libobjs $deplibs $linker_flags~$RM $lib.exp' ;; *) - wlarc='${wl}' - _LT_TAGVAR(archive_cmds, $1)='$CC -G${allow_undefined_flag} -h $soname -o $lib $libobjs $deplibs $compiler_flags' + wlarc='$wl' + _LT_TAGVAR(archive_cmds, $1)='$CC -G$allow_undefined_flag -h $soname -o $lib $libobjs $deplibs $compiler_flags' _LT_TAGVAR(archive_expsym_cmds, $1)='echo "{ global:" > $lib.exp~cat $export_symbols | $SED -e "s/\(.*\)/\1;/" >> $lib.exp~echo "local: *; };" >> $lib.exp~ - $CC -G${allow_undefined_flag} -M $lib.exp -h $soname -o $lib $libobjs $deplibs $compiler_flags~$RM $lib.exp' + $CC -G$allow_undefined_flag -M $lib.exp -h $soname -o $lib $libobjs $deplibs $compiler_flags~$RM $lib.exp' ;; esac fi @@ -5463,11 +5926,11 @@ _LT_EOF solaris2.[[0-5]] | solaris2.[[0-5]].*) ;; *) # The compiler driver will combine and reorder linker options, - # but understands `-z linker_flag'. GCC discards it without `$wl', + # but understands '-z linker_flag'. GCC discards it without '$wl', # but is careful enough not to reorder. # Supported since Solaris 2.6 (maybe 2.5.1?) - if test "$GCC" = yes; then - _LT_TAGVAR(whole_archive_flag_spec, $1)='${wl}-z ${wl}allextract$convenience ${wl}-z ${wl}defaultextract' + if test yes = "$GCC"; then + _LT_TAGVAR(whole_archive_flag_spec, $1)='$wl-z ${wl}allextract$convenience $wl-z ${wl}defaultextract' else _LT_TAGVAR(whole_archive_flag_spec, $1)='-z allextract$convenience -z defaultextract' fi @@ -5477,10 +5940,10 @@ _LT_EOF ;; sunos4*) - if test "x$host_vendor" = xsequent; then + if test sequent = "$host_vendor"; then # Use $CC to link under sequent, because it throws in some extra .o # files that make .init and .fini sections work. - _LT_TAGVAR(archive_cmds, $1)='$CC -G ${wl}-h $soname -o $lib $libobjs $deplibs $compiler_flags' + _LT_TAGVAR(archive_cmds, $1)='$CC -G $wl-h $soname -o $lib $libobjs $deplibs $compiler_flags' else _LT_TAGVAR(archive_cmds, $1)='$LD -assert pure-text -Bstatic -o $lib $libobjs $deplibs $linker_flags' fi @@ -5529,43 +5992,43 @@ _LT_EOF ;; sysv4*uw2* | sysv5OpenUNIX* | sysv5UnixWare7.[[01]].[[10]]* | unixware7* | sco3.2v5.0.[[024]]*) - _LT_TAGVAR(no_undefined_flag, $1)='${wl}-z,text' + _LT_TAGVAR(no_undefined_flag, $1)='$wl-z,text' _LT_TAGVAR(archive_cmds_need_lc, $1)=no _LT_TAGVAR(hardcode_shlibpath_var, $1)=no runpath_var='LD_RUN_PATH' - if test "$GCC" = yes; then - _LT_TAGVAR(archive_cmds, $1)='$CC -shared ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' - _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -shared ${wl}-Bexport:$export_symbols ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + if test yes = "$GCC"; then + _LT_TAGVAR(archive_cmds, $1)='$CC -shared $wl-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -shared $wl-Bexport:$export_symbols $wl-h,$soname -o $lib $libobjs $deplibs $compiler_flags' else - _LT_TAGVAR(archive_cmds, $1)='$CC -G ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' - _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -G ${wl}-Bexport:$export_symbols ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + _LT_TAGVAR(archive_cmds, $1)='$CC -G $wl-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -G $wl-Bexport:$export_symbols $wl-h,$soname -o $lib $libobjs $deplibs $compiler_flags' fi ;; sysv5* | sco3.2v5* | sco5v6*) - # Note: We can NOT use -z defs as we might desire, because we do not + # Note: We CANNOT use -z defs as we might desire, because we do not # link with -lc, and that would cause any symbols used from libc to # always be unresolved, which means just about no library would # ever link correctly. If we're not using GNU ld we use -z text # though, which does catch some bad symbols but isn't as heavy-handed # as -z defs. - _LT_TAGVAR(no_undefined_flag, $1)='${wl}-z,text' - _LT_TAGVAR(allow_undefined_flag, $1)='${wl}-z,nodefs' + _LT_TAGVAR(no_undefined_flag, $1)='$wl-z,text' + _LT_TAGVAR(allow_undefined_flag, $1)='$wl-z,nodefs' _LT_TAGVAR(archive_cmds_need_lc, $1)=no _LT_TAGVAR(hardcode_shlibpath_var, $1)=no - _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}-R,$libdir' + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='$wl-R,$libdir' _LT_TAGVAR(hardcode_libdir_separator, $1)=':' _LT_TAGVAR(link_all_deplibs, $1)=yes - _LT_TAGVAR(export_dynamic_flag_spec, $1)='${wl}-Bexport' + _LT_TAGVAR(export_dynamic_flag_spec, $1)='$wl-Bexport' runpath_var='LD_RUN_PATH' - if test "$GCC" = yes; then - _LT_TAGVAR(archive_cmds, $1)='$CC -shared ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' - _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -shared ${wl}-Bexport:$export_symbols ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + if test yes = "$GCC"; then + _LT_TAGVAR(archive_cmds, $1)='$CC -shared $wl-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -shared $wl-Bexport:$export_symbols $wl-h,$soname -o $lib $libobjs $deplibs $compiler_flags' else - _LT_TAGVAR(archive_cmds, $1)='$CC -G ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' - _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -G ${wl}-Bexport:$export_symbols ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + _LT_TAGVAR(archive_cmds, $1)='$CC -G $wl-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -G $wl-Bexport:$export_symbols $wl-h,$soname -o $lib $libobjs $deplibs $compiler_flags' fi ;; @@ -5580,17 +6043,17 @@ _LT_EOF ;; esac - if test x$host_vendor = xsni; then + if test sni = "$host_vendor"; then case $host in sysv4 | sysv4.2uw2* | sysv4.3* | sysv5*) - _LT_TAGVAR(export_dynamic_flag_spec, $1)='${wl}-Blargedynsym' + _LT_TAGVAR(export_dynamic_flag_spec, $1)='$wl-Blargedynsym' ;; esac fi fi ]) AC_MSG_RESULT([$_LT_TAGVAR(ld_shlibs, $1)]) -test "$_LT_TAGVAR(ld_shlibs, $1)" = no && can_build_shared=no +test no = "$_LT_TAGVAR(ld_shlibs, $1)" && can_build_shared=no _LT_TAGVAR(with_gnu_ld, $1)=$with_gnu_ld @@ -5607,7 +6070,7 @@ x|xyes) # Assume -lc should be added _LT_TAGVAR(archive_cmds_need_lc, $1)=yes - if test "$enable_shared" = yes && test "$GCC" = yes; then + if test yes,yes = "$GCC,$enable_shared"; then case $_LT_TAGVAR(archive_cmds, $1) in *'~'*) # FIXME: we may have to deal with multi-command sequences. @@ -5687,12 +6150,12 @@ _LT_TAGDECL([], [hardcode_libdir_flag_spec], [1], _LT_TAGDECL([], [hardcode_libdir_separator], [1], [Whether we need a single "-rpath" flag with a separated argument]) _LT_TAGDECL([], [hardcode_direct], [0], - [Set to "yes" if using DIR/libNAME${shared_ext} during linking hardcodes + [Set to "yes" if using DIR/libNAME$shared_ext during linking hardcodes DIR into the resulting binary]) _LT_TAGDECL([], [hardcode_direct_absolute], [0], - [Set to "yes" if using DIR/libNAME${shared_ext} during linking hardcodes + [Set to "yes" if using DIR/libNAME$shared_ext during linking hardcodes DIR into the resulting binary and the resulting library dependency is - "absolute", i.e impossible to change by setting ${shlibpath_var} if the + "absolute", i.e impossible to change by setting $shlibpath_var if the library is relocated]) _LT_TAGDECL([], [hardcode_minus_L], [0], [Set to "yes" if using the -LDIR flag during linking hardcodes DIR @@ -5733,10 +6196,10 @@ dnl [Compiler flag to generate thread safe objects]) # ------------------------ # Ensure that the configuration variables for a C compiler are suitably # defined. These variables are subsequently used by _LT_CONFIG to write -# the compiler configuration to `libtool'. +# the compiler configuration to 'libtool'. m4_defun([_LT_LANG_C_CONFIG], [m4_require([_LT_DECL_EGREP])dnl -lt_save_CC="$CC" +lt_save_CC=$CC AC_LANG_PUSH(C) # Source file extension for C test sources. @@ -5776,18 +6239,18 @@ if test -n "$compiler"; then LT_SYS_DLOPEN_SELF _LT_CMD_STRIPLIB - # Report which library types will actually be built + # Report what library types will actually be built AC_MSG_CHECKING([if libtool supports shared libraries]) AC_MSG_RESULT([$can_build_shared]) AC_MSG_CHECKING([whether to build shared libraries]) - test "$can_build_shared" = "no" && enable_shared=no + test no = "$can_build_shared" && enable_shared=no # On AIX, shared libraries and static libraries use the same namespace, and # are all built from PIC. case $host_os in aix3*) - test "$enable_shared" = yes && enable_static=no + test yes = "$enable_shared" && enable_static=no if test -n "$RANLIB"; then archive_cmds="$archive_cmds~\$RANLIB \$lib" postinstall_cmds='$RANLIB $lib' @@ -5795,8 +6258,12 @@ if test -n "$compiler"; then ;; aix[[4-9]]*) - if test "$host_cpu" != ia64 && test "$aix_use_runtimelinking" = no ; then - test "$enable_shared" = yes && enable_static=no + if test ia64 != "$host_cpu"; then + case $enable_shared,$with_aix_soname,$aix_use_runtimelinking in + yes,aix,yes) ;; # shared object as lib.so file only + yes,svr4,*) ;; # shared object as lib.so archive member only + yes,*) enable_static=no ;; # shared object in lib.a archive as well + esac fi ;; esac @@ -5804,13 +6271,13 @@ if test -n "$compiler"; then AC_MSG_CHECKING([whether to build static libraries]) # Make sure either enable_shared or enable_static is yes. - test "$enable_shared" = yes || enable_static=yes + test yes = "$enable_shared" || enable_static=yes AC_MSG_RESULT([$enable_static]) _LT_CONFIG($1) fi AC_LANG_POP -CC="$lt_save_CC" +CC=$lt_save_CC ])# _LT_LANG_C_CONFIG @@ -5818,14 +6285,14 @@ CC="$lt_save_CC" # -------------------------- # Ensure that the configuration variables for a C++ compiler are suitably # defined. These variables are subsequently used by _LT_CONFIG to write -# the compiler configuration to `libtool'. +# the compiler configuration to 'libtool'. m4_defun([_LT_LANG_CXX_CONFIG], [m4_require([_LT_FILEUTILS_DEFAULTS])dnl m4_require([_LT_DECL_EGREP])dnl m4_require([_LT_PATH_MANIFEST_TOOL])dnl -if test -n "$CXX" && ( test "X$CXX" != "Xno" && - ( (test "X$CXX" = "Xg++" && `g++ -v >/dev/null 2>&1` ) || - (test "X$CXX" != "Xg++"))) ; then +if test -n "$CXX" && ( test no != "$CXX" && + ( (test g++ = "$CXX" && `g++ -v >/dev/null 2>&1` ) || + (test g++ != "$CXX"))); then AC_PROG_CXXCPP else _lt_caught_CXX_error=yes @@ -5867,7 +6334,7 @@ _LT_TAGVAR(objext, $1)=$objext # the CXX compiler isn't working. Some variables (like enable_shared) # are currently assumed to apply to all compilers on this platform, # and will be corrupted by setting them based on a non-working compiler. -if test "$_lt_caught_CXX_error" != yes; then +if test yes != "$_lt_caught_CXX_error"; then # Code to be used in simple compile tests lt_simple_compile_test_code="int some_variable = 0;" @@ -5909,35 +6376,35 @@ if test "$_lt_caught_CXX_error" != yes; then if test -n "$compiler"; then # We don't want -fno-exception when compiling C++ code, so set the # no_builtin_flag separately - if test "$GXX" = yes; then + if test yes = "$GXX"; then _LT_TAGVAR(lt_prog_compiler_no_builtin_flag, $1)=' -fno-builtin' else _LT_TAGVAR(lt_prog_compiler_no_builtin_flag, $1)= fi - if test "$GXX" = yes; then + if test yes = "$GXX"; then # Set up default GNU C++ configuration LT_PATH_LD # Check if GNU C++ uses GNU ld as the underlying linker, since the # archiving commands below assume that GNU ld is being used. - if test "$with_gnu_ld" = yes; then - _LT_TAGVAR(archive_cmds, $1)='$CC $pic_flag -shared -nostdlib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-soname $wl$soname -o $lib' - _LT_TAGVAR(archive_expsym_cmds, $1)='$CC $pic_flag -shared -nostdlib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-soname $wl$soname ${wl}-retain-symbols-file $wl$export_symbols -o $lib' + if test yes = "$with_gnu_ld"; then + _LT_TAGVAR(archive_cmds, $1)='$CC $pic_flag -shared -nostdlib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags $wl-soname $wl$soname -o $lib' + _LT_TAGVAR(archive_expsym_cmds, $1)='$CC $pic_flag -shared -nostdlib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags $wl-soname $wl$soname $wl-retain-symbols-file $wl$export_symbols -o $lib' - _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}-rpath ${wl}$libdir' - _LT_TAGVAR(export_dynamic_flag_spec, $1)='${wl}--export-dynamic' + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='$wl-rpath $wl$libdir' + _LT_TAGVAR(export_dynamic_flag_spec, $1)='$wl--export-dynamic' # If archive_cmds runs LD, not CC, wlarc should be empty # XXX I think wlarc can be eliminated in ltcf-cxx, but I need to # investigate it a little bit more. (MM) - wlarc='${wl}' + wlarc='$wl' # ancient GNU ld didn't support --whole-archive et. al. if eval "`$CC -print-prog-name=ld` --help 2>&1" | $GREP 'no-whole-archive' > /dev/null; then - _LT_TAGVAR(whole_archive_flag_spec, $1)="$wlarc"'--whole-archive$convenience '"$wlarc"'--no-whole-archive' + _LT_TAGVAR(whole_archive_flag_spec, $1)=$wlarc'--whole-archive$convenience '$wlarc'--no-whole-archive' else _LT_TAGVAR(whole_archive_flag_spec, $1)= fi @@ -5973,18 +6440,30 @@ if test "$_lt_caught_CXX_error" != yes; then _LT_TAGVAR(ld_shlibs, $1)=no ;; aix[[4-9]]*) - if test "$host_cpu" = ia64; then + if test ia64 = "$host_cpu"; then # On IA64, the linker does run time linking by default, so we don't # have to do anything special. aix_use_runtimelinking=no exp_sym_flag='-Bexport' - no_entry_flag="" + no_entry_flag= else aix_use_runtimelinking=no # Test if we are trying to use run time linking or normal # AIX style linking. If -brtl is somewhere in LDFLAGS, we - # need to do runtime linking. + # have runtime linking enabled, and use it for executables. + # For shared libraries, we enable/disable runtime linking + # depending on the kind of the shared library created - + # when "with_aix_soname,aix_use_runtimelinking" is: + # "aix,no" lib.a(lib.so.V) shared, rtl:no, for executables + # "aix,yes" lib.so shared, rtl:yes, for executables + # lib.a static archive + # "both,no" lib.so.V(shr.o) shared, rtl:yes + # lib.a(lib.so.V) shared, rtl:no, for executables + # "both,yes" lib.so.V(shr.o) shared, rtl:yes, for executables + # lib.a(lib.so.V) shared, rtl:no + # "svr4,*" lib.so.V(shr.o) shared, rtl:yes, for executables + # lib.a static archive case $host_os in aix4.[[23]]|aix4.[[23]].*|aix[[5-9]]*) for ld_flag in $LDFLAGS; do case $ld_flag in @@ -5994,6 +6473,13 @@ if test "$_lt_caught_CXX_error" != yes; then ;; esac done + if test svr4,no = "$with_aix_soname,$aix_use_runtimelinking"; then + # With aix-soname=svr4, we create the lib.so.V shared archives only, + # so we don't have lib.a shared libs to link our executables. + # We have to force runtime linking in this case. + aix_use_runtimelinking=yes + LDFLAGS="$LDFLAGS -Wl,-brtl" + fi ;; esac @@ -6012,13 +6498,21 @@ if test "$_lt_caught_CXX_error" != yes; then _LT_TAGVAR(hardcode_direct_absolute, $1)=yes _LT_TAGVAR(hardcode_libdir_separator, $1)=':' _LT_TAGVAR(link_all_deplibs, $1)=yes - _LT_TAGVAR(file_list_spec, $1)='${wl}-f,' + _LT_TAGVAR(file_list_spec, $1)='$wl-f,' + case $with_aix_soname,$aix_use_runtimelinking in + aix,*) ;; # no import file + svr4,* | *,yes) # use import file + # The Import File defines what to hardcode. + _LT_TAGVAR(hardcode_direct, $1)=no + _LT_TAGVAR(hardcode_direct_absolute, $1)=no + ;; + esac - if test "$GXX" = yes; then + if test yes = "$GXX"; then case $host_os in aix4.[[012]]|aix4.[[012]].*) # We only want to do this on AIX 4.2 and lower, the check # below for broken collect2 doesn't work under 4.3+ - collect2name=`${CC} -print-prog-name=collect2` + collect2name=`$CC -print-prog-name=collect2` if test -f "$collect2name" && strings "$collect2name" | $GREP resolve_lib_name >/dev/null then @@ -6036,64 +6530,84 @@ if test "$_lt_caught_CXX_error" != yes; then fi esac shared_flag='-shared' - if test "$aix_use_runtimelinking" = yes; then - shared_flag="$shared_flag "'${wl}-G' + if test yes = "$aix_use_runtimelinking"; then + shared_flag=$shared_flag' $wl-G' fi + # Need to ensure runtime linking is disabled for the traditional + # shared library, or the linker may eventually find shared libraries + # /with/ Import File - we do not want to mix them. + shared_flag_aix='-shared' + shared_flag_svr4='-shared $wl-G' else # not using gcc - if test "$host_cpu" = ia64; then + if test ia64 = "$host_cpu"; then # VisualAge C++, Version 5.5 for AIX 5L for IA-64, Beta 3 Release # chokes on -Wl,-G. The following line is correct: shared_flag='-G' else - if test "$aix_use_runtimelinking" = yes; then - shared_flag='${wl}-G' + if test yes = "$aix_use_runtimelinking"; then + shared_flag='$wl-G' else - shared_flag='${wl}-bM:SRE' + shared_flag='$wl-bM:SRE' fi + shared_flag_aix='$wl-bM:SRE' + shared_flag_svr4='$wl-G' fi fi - _LT_TAGVAR(export_dynamic_flag_spec, $1)='${wl}-bexpall' + _LT_TAGVAR(export_dynamic_flag_spec, $1)='$wl-bexpall' # It seems that -bexpall does not export symbols beginning with # underscore (_), so it is better to generate a list of symbols to # export. _LT_TAGVAR(always_export_symbols, $1)=yes - if test "$aix_use_runtimelinking" = yes; then + if test aix,yes = "$with_aix_soname,$aix_use_runtimelinking"; then # Warning - without using the other runtime loading flags (-brtl), # -berok will link without error, but may produce a broken library. - _LT_TAGVAR(allow_undefined_flag, $1)='-berok' + # The "-G" linker flag allows undefined symbols. + _LT_TAGVAR(no_undefined_flag, $1)='-bernotok' # Determine the default libpath from the value encoded in an empty # executable. _LT_SYS_MODULE_PATH_AIX([$1]) - _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}-blibpath:$libdir:'"$aix_libpath" + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='$wl-blibpath:$libdir:'"$aix_libpath" - _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -o $output_objdir/$soname $libobjs $deplibs '"\${wl}$no_entry_flag"' $compiler_flags `if test "x${allow_undefined_flag}" != "x"; then func_echo_all "${wl}${allow_undefined_flag}"; else :; fi` '"\${wl}$exp_sym_flag:\$export_symbols $shared_flag" + _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -o $output_objdir/$soname $libobjs $deplibs $wl'$no_entry_flag' $compiler_flags `if test -n "$allow_undefined_flag"; then func_echo_all "$wl$allow_undefined_flag"; else :; fi` $wl'$exp_sym_flag:\$export_symbols' '$shared_flag else - if test "$host_cpu" = ia64; then - _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}-R $libdir:/usr/lib:/lib' + if test ia64 = "$host_cpu"; then + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='$wl-R $libdir:/usr/lib:/lib' _LT_TAGVAR(allow_undefined_flag, $1)="-z nodefs" - _LT_TAGVAR(archive_expsym_cmds, $1)="\$CC $shared_flag"' -o $output_objdir/$soname $libobjs $deplibs '"\${wl}$no_entry_flag"' $compiler_flags ${wl}${allow_undefined_flag} '"\${wl}$exp_sym_flag:\$export_symbols" + _LT_TAGVAR(archive_expsym_cmds, $1)="\$CC $shared_flag"' -o $output_objdir/$soname $libobjs $deplibs '"\$wl$no_entry_flag"' $compiler_flags $wl$allow_undefined_flag '"\$wl$exp_sym_flag:\$export_symbols" else # Determine the default libpath from the value encoded in an # empty executable. _LT_SYS_MODULE_PATH_AIX([$1]) - _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}-blibpath:$libdir:'"$aix_libpath" + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='$wl-blibpath:$libdir:'"$aix_libpath" # Warning - without using the other run time loading flags, # -berok will link without error, but may produce a broken library. - _LT_TAGVAR(no_undefined_flag, $1)=' ${wl}-bernotok' - _LT_TAGVAR(allow_undefined_flag, $1)=' ${wl}-berok' - if test "$with_gnu_ld" = yes; then + _LT_TAGVAR(no_undefined_flag, $1)=' $wl-bernotok' + _LT_TAGVAR(allow_undefined_flag, $1)=' $wl-berok' + if test yes = "$with_gnu_ld"; then # We only use this code for GNU lds that support --whole-archive. - _LT_TAGVAR(whole_archive_flag_spec, $1)='${wl}--whole-archive$convenience ${wl}--no-whole-archive' + _LT_TAGVAR(whole_archive_flag_spec, $1)='$wl--whole-archive$convenience $wl--no-whole-archive' else # Exported symbols can be pulled into shared objects from archives _LT_TAGVAR(whole_archive_flag_spec, $1)='$convenience' fi _LT_TAGVAR(archive_cmds_need_lc, $1)=yes - # This is similar to how AIX traditionally builds its shared - # libraries. - _LT_TAGVAR(archive_expsym_cmds, $1)="\$CC $shared_flag"' -o $output_objdir/$soname $libobjs $deplibs ${wl}-bnoentry $compiler_flags ${wl}-bE:$export_symbols${allow_undefined_flag}~$AR $AR_FLAGS $output_objdir/$libname$release.a $output_objdir/$soname' + _LT_TAGVAR(archive_expsym_cmds, $1)='$RM -r $output_objdir/$realname.d~$MKDIR $output_objdir/$realname.d' + # -brtl affects multiple linker settings, -berok does not and is overridden later + compiler_flags_filtered='`func_echo_all "$compiler_flags " | $SED -e "s%-brtl\\([[, ]]\\)%-berok\\1%g"`' + if test svr4 != "$with_aix_soname"; then + # This is similar to how AIX traditionally builds its shared + # libraries. Need -bnortl late, we may have -brtl in LDFLAGS. + _LT_TAGVAR(archive_expsym_cmds, $1)="$_LT_TAGVAR(archive_expsym_cmds, $1)"'~$CC '$shared_flag_aix' -o $output_objdir/$realname.d/$soname $libobjs $deplibs $wl-bnoentry '$compiler_flags_filtered'$wl-bE:$export_symbols$allow_undefined_flag~$AR $AR_FLAGS $output_objdir/$libname$release.a $output_objdir/$realname.d/$soname' + fi + if test aix != "$with_aix_soname"; then + _LT_TAGVAR(archive_expsym_cmds, $1)="$_LT_TAGVAR(archive_expsym_cmds, $1)"'~$CC '$shared_flag_svr4' -o $output_objdir/$realname.d/$shared_archive_member_spec.o $libobjs $deplibs $wl-bnoentry '$compiler_flags_filtered'$wl-bE:$export_symbols$allow_undefined_flag~$STRIP -e $output_objdir/$realname.d/$shared_archive_member_spec.o~( func_echo_all "#! $soname($shared_archive_member_spec.o)"; if test shr_64 = "$shared_archive_member_spec"; then func_echo_all "# 64"; else func_echo_all "# 32"; fi; cat $export_symbols ) > $output_objdir/$realname.d/$shared_archive_member_spec.imp~$AR $AR_FLAGS $output_objdir/$soname $output_objdir/$realname.d/$shared_archive_member_spec.o $output_objdir/$realname.d/$shared_archive_member_spec.imp' + else + # used by -dlpreopen to get the symbols + _LT_TAGVAR(archive_expsym_cmds, $1)="$_LT_TAGVAR(archive_expsym_cmds, $1)"'~$MV $output_objdir/$realname.d/$soname $output_objdir' + fi + _LT_TAGVAR(archive_expsym_cmds, $1)="$_LT_TAGVAR(archive_expsym_cmds, $1)"'~$RM -r $output_objdir/$realname.d' fi fi ;; @@ -6103,7 +6617,7 @@ if test "$_lt_caught_CXX_error" != yes; then _LT_TAGVAR(allow_undefined_flag, $1)=unsupported # Joseph Beckenbach says some releases of gcc # support --undefined. This deserves some investigation. FIXME - _LT_TAGVAR(archive_cmds, $1)='$CC -nostart $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname -o $lib' + _LT_TAGVAR(archive_cmds, $1)='$CC -nostart $libobjs $deplibs $compiler_flags $wl-soname $wl$soname -o $lib' else _LT_TAGVAR(ld_shlibs, $1)=no fi @@ -6131,57 +6645,58 @@ if test "$_lt_caught_CXX_error" != yes; then # Tell ltmain to make .lib files, not .a files. libext=lib # Tell ltmain to make .dll files, not .so files. - shrext_cmds=".dll" + shrext_cmds=.dll # FIXME: Setting linknames here is a bad hack. - _LT_TAGVAR(archive_cmds, $1)='$CC -o $output_objdir/$soname $libobjs $compiler_flags $deplibs -Wl,-dll~linknames=' - _LT_TAGVAR(archive_expsym_cmds, $1)='if test "x`$SED 1q $export_symbols`" = xEXPORTS; then - $SED -n -e 's/\\\\\\\(.*\\\\\\\)/-link\\\ -EXPORT:\\\\\\\1/' -e '1\\\!p' < $export_symbols > $output_objdir/$soname.exp; - else - $SED -e 's/\\\\\\\(.*\\\\\\\)/-link\\\ -EXPORT:\\\\\\\1/' < $export_symbols > $output_objdir/$soname.exp; - fi~ - $CC -o $tool_output_objdir$soname $libobjs $compiler_flags $deplibs "@$tool_output_objdir$soname.exp" -Wl,-DLL,-IMPLIB:"$tool_output_objdir$libname.dll.lib"~ - linknames=' + _LT_TAGVAR(archive_cmds, $1)='$CC -o $output_objdir/$soname $libobjs $compiler_flags $deplibs -Wl,-DLL,-IMPLIB:"$tool_output_objdir$libname.dll.lib"~linknames=' + _LT_TAGVAR(archive_expsym_cmds, $1)='if _LT_DLL_DEF_P([$export_symbols]); then + cp "$export_symbols" "$output_objdir/$soname.def"; + echo "$tool_output_objdir$soname.def" > "$output_objdir/$soname.exp"; + else + $SED -e '\''s/^/-link -EXPORT:/'\'' < $export_symbols > $output_objdir/$soname.exp; + fi~ + $CC -o $tool_output_objdir$soname $libobjs $compiler_flags $deplibs "@$tool_output_objdir$soname.exp" -Wl,-DLL,-IMPLIB:"$tool_output_objdir$libname.dll.lib"~ + linknames=' # The linker will not automatically build a static lib if we build a DLL. # _LT_TAGVAR(old_archive_from_new_cmds, $1)='true' _LT_TAGVAR(enable_shared_with_static_runtimes, $1)=yes # Don't use ranlib _LT_TAGVAR(old_postinstall_cmds, $1)='chmod 644 $oldlib' _LT_TAGVAR(postlink_cmds, $1)='lt_outputfile="@OUTPUT@"~ - lt_tool_outputfile="@TOOL_OUTPUT@"~ - case $lt_outputfile in - *.exe|*.EXE) ;; - *) - lt_outputfile="$lt_outputfile.exe" - lt_tool_outputfile="$lt_tool_outputfile.exe" - ;; - esac~ - func_to_tool_file "$lt_outputfile"~ - if test "$MANIFEST_TOOL" != ":" && test -f "$lt_outputfile.manifest"; then - $MANIFEST_TOOL -manifest "$lt_tool_outputfile.manifest" -outputresource:"$lt_tool_outputfile" || exit 1; - $RM "$lt_outputfile.manifest"; - fi' + lt_tool_outputfile="@TOOL_OUTPUT@"~ + case $lt_outputfile in + *.exe|*.EXE) ;; + *) + lt_outputfile=$lt_outputfile.exe + lt_tool_outputfile=$lt_tool_outputfile.exe + ;; + esac~ + func_to_tool_file "$lt_outputfile"~ + if test : != "$MANIFEST_TOOL" && test -f "$lt_outputfile.manifest"; then + $MANIFEST_TOOL -manifest "$lt_tool_outputfile.manifest" -outputresource:"$lt_tool_outputfile" || exit 1; + $RM "$lt_outputfile.manifest"; + fi' ;; *) # g++ # _LT_TAGVAR(hardcode_libdir_flag_spec, $1) is actually meaningless, # as there is no search path for DLLs. _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='-L$libdir' - _LT_TAGVAR(export_dynamic_flag_spec, $1)='${wl}--export-all-symbols' + _LT_TAGVAR(export_dynamic_flag_spec, $1)='$wl--export-all-symbols' _LT_TAGVAR(allow_undefined_flag, $1)=unsupported _LT_TAGVAR(always_export_symbols, $1)=no _LT_TAGVAR(enable_shared_with_static_runtimes, $1)=yes if $LD --help 2>&1 | $GREP 'auto-import' > /dev/null; then - _LT_TAGVAR(archive_cmds, $1)='$CC -shared -nostdlib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags -o $output_objdir/$soname ${wl}--enable-auto-image-base -Xlinker --out-implib -Xlinker $lib' - # If the export-symbols file already is a .def file (1st line - # is EXPORTS), use it as is; otherwise, prepend... - _LT_TAGVAR(archive_expsym_cmds, $1)='if test "x`$SED 1q $export_symbols`" = xEXPORTS; then - cp $export_symbols $output_objdir/$soname.def; - else - echo EXPORTS > $output_objdir/$soname.def; - cat $export_symbols >> $output_objdir/$soname.def; - fi~ - $CC -shared -nostdlib $output_objdir/$soname.def $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags -o $output_objdir/$soname ${wl}--enable-auto-image-base -Xlinker --out-implib -Xlinker $lib' + _LT_TAGVAR(archive_cmds, $1)='$CC -shared -nostdlib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags -o $output_objdir/$soname $wl--enable-auto-image-base -Xlinker --out-implib -Xlinker $lib' + # If the export-symbols file already is a .def file, use it as + # is; otherwise, prepend EXPORTS... + _LT_TAGVAR(archive_expsym_cmds, $1)='if _LT_DLL_DEF_P([$export_symbols]); then + cp $export_symbols $output_objdir/$soname.def; + else + echo EXPORTS > $output_objdir/$soname.def; + cat $export_symbols >> $output_objdir/$soname.def; + fi~ + $CC -shared -nostdlib $output_objdir/$soname.def $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags -o $output_objdir/$soname $wl--enable-auto-image-base -Xlinker --out-implib -Xlinker $lib' else _LT_TAGVAR(ld_shlibs, $1)=no fi @@ -6192,6 +6707,34 @@ if test "$_lt_caught_CXX_error" != yes; then _LT_DARWIN_LINKER_FEATURES($1) ;; + os2*) + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='-L$libdir' + _LT_TAGVAR(hardcode_minus_L, $1)=yes + _LT_TAGVAR(allow_undefined_flag, $1)=unsupported + shrext_cmds=.dll + _LT_TAGVAR(archive_cmds, $1)='$ECHO "LIBRARY ${soname%$shared_ext} INITINSTANCE TERMINSTANCE" > $output_objdir/$libname.def~ + $ECHO "DESCRIPTION \"$libname\"" >> $output_objdir/$libname.def~ + $ECHO "DATA MULTIPLE NONSHARED" >> $output_objdir/$libname.def~ + $ECHO EXPORTS >> $output_objdir/$libname.def~ + emxexp $libobjs | $SED /"_DLL_InitTerm"/d >> $output_objdir/$libname.def~ + $CC -Zdll -Zcrtdll -o $output_objdir/$soname $libobjs $deplibs $compiler_flags $output_objdir/$libname.def~ + emximp -o $lib $output_objdir/$libname.def' + _LT_TAGVAR(archive_expsym_cmds, $1)='$ECHO "LIBRARY ${soname%$shared_ext} INITINSTANCE TERMINSTANCE" > $output_objdir/$libname.def~ + $ECHO "DESCRIPTION \"$libname\"" >> $output_objdir/$libname.def~ + $ECHO "DATA MULTIPLE NONSHARED" >> $output_objdir/$libname.def~ + $ECHO EXPORTS >> $output_objdir/$libname.def~ + prefix_cmds="$SED"~ + if test EXPORTS = "`$SED 1q $export_symbols`"; then + prefix_cmds="$prefix_cmds -e 1d"; + fi~ + prefix_cmds="$prefix_cmds -e \"s/^\(.*\)$/_\1/g\""~ + cat $export_symbols | $prefix_cmds >> $output_objdir/$libname.def~ + $CC -Zdll -Zcrtdll -o $output_objdir/$soname $libobjs $deplibs $compiler_flags $output_objdir/$libname.def~ + emximp -o $lib $output_objdir/$libname.def' + _LT_TAGVAR(old_archive_From_new_cmds, $1)='emximp -o $output_objdir/${libname}_dll.a $output_objdir/$libname.def' + _LT_TAGVAR(enable_shared_with_static_runtimes, $1)=yes + ;; + dgux*) case $cc_basename in ec++*) @@ -6226,18 +6769,15 @@ if test "$_lt_caught_CXX_error" != yes; then _LT_TAGVAR(ld_shlibs, $1)=yes ;; - gnu*) - ;; - haiku*) - _LT_TAGVAR(archive_cmds, $1)='$CC -shared $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname -o $lib' + _LT_TAGVAR(archive_cmds, $1)='$CC -shared $libobjs $deplibs $compiler_flags $wl-soname $wl$soname -o $lib' _LT_TAGVAR(link_all_deplibs, $1)=yes ;; hpux9*) - _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}+b ${wl}$libdir' + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='$wl+b $wl$libdir' _LT_TAGVAR(hardcode_libdir_separator, $1)=: - _LT_TAGVAR(export_dynamic_flag_spec, $1)='${wl}-E' + _LT_TAGVAR(export_dynamic_flag_spec, $1)='$wl-E' _LT_TAGVAR(hardcode_direct, $1)=yes _LT_TAGVAR(hardcode_minus_L, $1)=yes # Not in the search PATH, # but as the default @@ -6249,7 +6789,7 @@ if test "$_lt_caught_CXX_error" != yes; then _LT_TAGVAR(ld_shlibs, $1)=no ;; aCC*) - _LT_TAGVAR(archive_cmds, $1)='$RM $output_objdir/$soname~$CC -b ${wl}+b ${wl}$install_libdir -o $output_objdir/$soname $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags~test $output_objdir/$soname = $lib || mv $output_objdir/$soname $lib' + _LT_TAGVAR(archive_cmds, $1)='$RM $output_objdir/$soname~$CC -b $wl+b $wl$install_libdir -o $output_objdir/$soname $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags~test "x$output_objdir/$soname" = "x$lib" || mv $output_objdir/$soname $lib' # Commands to make compiler produce verbose output that lists # what "hidden" libraries, object files and flags are used when # linking a shared library. @@ -6258,11 +6798,11 @@ if test "$_lt_caught_CXX_error" != yes; then # explicitly linking system object files so we need to strip them # from the output so that they don't get included in the library # dependencies. - output_verbose_link_cmd='templist=`($CC -b $CFLAGS -v conftest.$objext 2>&1) | $EGREP "\-L"`; list=""; for z in $templist; do case $z in conftest.$objext) list="$list $z";; *.$objext);; *) list="$list $z";;esac; done; func_echo_all "$list"' + output_verbose_link_cmd='templist=`($CC -b $CFLAGS -v conftest.$objext 2>&1) | $EGREP "\-L"`; list= ; for z in $templist; do case $z in conftest.$objext) list="$list $z";; *.$objext);; *) list="$list $z";;esac; done; func_echo_all "$list"' ;; *) - if test "$GXX" = yes; then - _LT_TAGVAR(archive_cmds, $1)='$RM $output_objdir/$soname~$CC -shared -nostdlib $pic_flag ${wl}+b ${wl}$install_libdir -o $output_objdir/$soname $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags~test $output_objdir/$soname = $lib || mv $output_objdir/$soname $lib' + if test yes = "$GXX"; then + _LT_TAGVAR(archive_cmds, $1)='$RM $output_objdir/$soname~$CC -shared -nostdlib $pic_flag $wl+b $wl$install_libdir -o $output_objdir/$soname $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags~test "x$output_objdir/$soname" = "x$lib" || mv $output_objdir/$soname $lib' else # FIXME: insert proper C++ library support _LT_TAGVAR(ld_shlibs, $1)=no @@ -6272,15 +6812,15 @@ if test "$_lt_caught_CXX_error" != yes; then ;; hpux10*|hpux11*) - if test $with_gnu_ld = no; then - _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}+b ${wl}$libdir' + if test no = "$with_gnu_ld"; then + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='$wl+b $wl$libdir' _LT_TAGVAR(hardcode_libdir_separator, $1)=: case $host_cpu in hppa*64*|ia64*) ;; *) - _LT_TAGVAR(export_dynamic_flag_spec, $1)='${wl}-E' + _LT_TAGVAR(export_dynamic_flag_spec, $1)='$wl-E' ;; esac fi @@ -6306,13 +6846,13 @@ if test "$_lt_caught_CXX_error" != yes; then aCC*) case $host_cpu in hppa*64*) - _LT_TAGVAR(archive_cmds, $1)='$CC -b ${wl}+h ${wl}$soname -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags' + _LT_TAGVAR(archive_cmds, $1)='$CC -b $wl+h $wl$soname -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags' ;; ia64*) - _LT_TAGVAR(archive_cmds, $1)='$CC -b ${wl}+h ${wl}$soname ${wl}+nodefaultrpath -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags' + _LT_TAGVAR(archive_cmds, $1)='$CC -b $wl+h $wl$soname $wl+nodefaultrpath -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags' ;; *) - _LT_TAGVAR(archive_cmds, $1)='$CC -b ${wl}+h ${wl}$soname ${wl}+b ${wl}$install_libdir -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags' + _LT_TAGVAR(archive_cmds, $1)='$CC -b $wl+h $wl$soname $wl+b $wl$install_libdir -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags' ;; esac # Commands to make compiler produce verbose output that lists @@ -6323,20 +6863,20 @@ if test "$_lt_caught_CXX_error" != yes; then # explicitly linking system object files so we need to strip them # from the output so that they don't get included in the library # dependencies. - output_verbose_link_cmd='templist=`($CC -b $CFLAGS -v conftest.$objext 2>&1) | $GREP "\-L"`; list=""; for z in $templist; do case $z in conftest.$objext) list="$list $z";; *.$objext);; *) list="$list $z";;esac; done; func_echo_all "$list"' + output_verbose_link_cmd='templist=`($CC -b $CFLAGS -v conftest.$objext 2>&1) | $GREP "\-L"`; list= ; for z in $templist; do case $z in conftest.$objext) list="$list $z";; *.$objext);; *) list="$list $z";;esac; done; func_echo_all "$list"' ;; *) - if test "$GXX" = yes; then - if test $with_gnu_ld = no; then + if test yes = "$GXX"; then + if test no = "$with_gnu_ld"; then case $host_cpu in hppa*64*) - _LT_TAGVAR(archive_cmds, $1)='$CC -shared -nostdlib -fPIC ${wl}+h ${wl}$soname -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags' + _LT_TAGVAR(archive_cmds, $1)='$CC -shared -nostdlib -fPIC $wl+h $wl$soname -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags' ;; ia64*) - _LT_TAGVAR(archive_cmds, $1)='$CC -shared -nostdlib $pic_flag ${wl}+h ${wl}$soname ${wl}+nodefaultrpath -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags' + _LT_TAGVAR(archive_cmds, $1)='$CC -shared -nostdlib $pic_flag $wl+h $wl$soname $wl+nodefaultrpath -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags' ;; *) - _LT_TAGVAR(archive_cmds, $1)='$CC -shared -nostdlib $pic_flag ${wl}+h ${wl}$soname ${wl}+b ${wl}$install_libdir -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags' + _LT_TAGVAR(archive_cmds, $1)='$CC -shared -nostdlib $pic_flag $wl+h $wl$soname $wl+b $wl$install_libdir -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags' ;; esac fi @@ -6351,22 +6891,22 @@ if test "$_lt_caught_CXX_error" != yes; then interix[[3-9]]*) _LT_TAGVAR(hardcode_direct, $1)=no _LT_TAGVAR(hardcode_shlibpath_var, $1)=no - _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}-rpath,$libdir' - _LT_TAGVAR(export_dynamic_flag_spec, $1)='${wl}-E' + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='$wl-rpath,$libdir' + _LT_TAGVAR(export_dynamic_flag_spec, $1)='$wl-E' # Hack: On Interix 3.x, we cannot compile PIC because of a broken gcc. # Instead, shared libraries are loaded at an image base (0x10000000 by # default) and relocated if they conflict, which is a slow very memory # consuming and fragmenting process. To avoid this, we pick a random, # 256 KiB-aligned image base between 0x50000000 and 0x6FFC0000 at link # time. Moving up from 0x10000000 also allows more sbrk(2) space. - _LT_TAGVAR(archive_cmds, $1)='$CC -shared $pic_flag $libobjs $deplibs $compiler_flags ${wl}-h,$soname ${wl}--image-base,`expr ${RANDOM-$$} % 4096 / 2 \* 262144 + 1342177280` -o $lib' - _LT_TAGVAR(archive_expsym_cmds, $1)='sed "s,^,_," $export_symbols >$output_objdir/$soname.expsym~$CC -shared $pic_flag $libobjs $deplibs $compiler_flags ${wl}-h,$soname ${wl}--retain-symbols-file,$output_objdir/$soname.expsym ${wl}--image-base,`expr ${RANDOM-$$} % 4096 / 2 \* 262144 + 1342177280` -o $lib' + _LT_TAGVAR(archive_cmds, $1)='$CC -shared $pic_flag $libobjs $deplibs $compiler_flags $wl-h,$soname $wl--image-base,`expr ${RANDOM-$$} % 4096 / 2 \* 262144 + 1342177280` -o $lib' + _LT_TAGVAR(archive_expsym_cmds, $1)='sed "s|^|_|" $export_symbols >$output_objdir/$soname.expsym~$CC -shared $pic_flag $libobjs $deplibs $compiler_flags $wl-h,$soname $wl--retain-symbols-file,$output_objdir/$soname.expsym $wl--image-base,`expr ${RANDOM-$$} % 4096 / 2 \* 262144 + 1342177280` -o $lib' ;; irix5* | irix6*) case $cc_basename in CC*) # SGI C++ - _LT_TAGVAR(archive_cmds, $1)='$CC -shared -all -multigot $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags -soname $soname `test -n "$verstring" && func_echo_all "-set_version $verstring"` -update_registry ${output_objdir}/so_locations -o $lib' + _LT_TAGVAR(archive_cmds, $1)='$CC -shared -all -multigot $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags -soname $soname `test -n "$verstring" && func_echo_all "-set_version $verstring"` -update_registry $output_objdir/so_locations -o $lib' # Archives containing C++ object files must be created using # "CC -ar", where "CC" is the IRIX C++ compiler. This is @@ -6375,22 +6915,22 @@ if test "$_lt_caught_CXX_error" != yes; then _LT_TAGVAR(old_archive_cmds, $1)='$CC -ar -WR,-u -o $oldlib $oldobjs' ;; *) - if test "$GXX" = yes; then - if test "$with_gnu_ld" = no; then - _LT_TAGVAR(archive_cmds, $1)='$CC -shared $pic_flag -nostdlib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-soname ${wl}$soname `test -n "$verstring" && func_echo_all "${wl}-set_version ${wl}$verstring"` ${wl}-update_registry ${wl}${output_objdir}/so_locations -o $lib' + if test yes = "$GXX"; then + if test no = "$with_gnu_ld"; then + _LT_TAGVAR(archive_cmds, $1)='$CC -shared $pic_flag -nostdlib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags $wl-soname $wl$soname `test -n "$verstring" && func_echo_all "$wl-set_version $wl$verstring"` $wl-update_registry $wl$output_objdir/so_locations -o $lib' else - _LT_TAGVAR(archive_cmds, $1)='$CC -shared $pic_flag -nostdlib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-soname ${wl}$soname `test -n "$verstring" && func_echo_all "${wl}-set_version ${wl}$verstring"` -o $lib' + _LT_TAGVAR(archive_cmds, $1)='$CC -shared $pic_flag -nostdlib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags $wl-soname $wl$soname `test -n "$verstring" && func_echo_all "$wl-set_version $wl$verstring"` -o $lib' fi fi _LT_TAGVAR(link_all_deplibs, $1)=yes ;; esac - _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}-rpath ${wl}$libdir' + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='$wl-rpath $wl$libdir' _LT_TAGVAR(hardcode_libdir_separator, $1)=: _LT_TAGVAR(inherit_rpath, $1)=yes ;; - linux* | k*bsd*-gnu | kopensolaris*-gnu) + linux* | k*bsd*-gnu | kopensolaris*-gnu | gnu*) case $cc_basename in KCC*) # Kuck and Associates, Inc. (KAI) C++ Compiler @@ -6398,8 +6938,8 @@ if test "$_lt_caught_CXX_error" != yes; then # KCC will only create a shared library if the output file # ends with ".so" (or ".sl" for HP-UX), so rename the library # to its proper name (with version) after linking. - _LT_TAGVAR(archive_cmds, $1)='tempext=`echo $shared_ext | $SED -e '\''s/\([[^()0-9A-Za-z{}]]\)/\\\\\1/g'\''`; templib=`echo $lib | $SED -e "s/\${tempext}\..*/.so/"`; $CC $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags --soname $soname -o \$templib; mv \$templib $lib' - _LT_TAGVAR(archive_expsym_cmds, $1)='tempext=`echo $shared_ext | $SED -e '\''s/\([[^()0-9A-Za-z{}]]\)/\\\\\1/g'\''`; templib=`echo $lib | $SED -e "s/\${tempext}\..*/.so/"`; $CC $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags --soname $soname -o \$templib ${wl}-retain-symbols-file,$export_symbols; mv \$templib $lib' + _LT_TAGVAR(archive_cmds, $1)='tempext=`echo $shared_ext | $SED -e '\''s/\([[^()0-9A-Za-z{}]]\)/\\\\\1/g'\''`; templib=`echo $lib | $SED -e "s/\$tempext\..*/.so/"`; $CC $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags --soname $soname -o \$templib; mv \$templib $lib' + _LT_TAGVAR(archive_expsym_cmds, $1)='tempext=`echo $shared_ext | $SED -e '\''s/\([[^()0-9A-Za-z{}]]\)/\\\\\1/g'\''`; templib=`echo $lib | $SED -e "s/\$tempext\..*/.so/"`; $CC $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags --soname $soname -o \$templib $wl-retain-symbols-file,$export_symbols; mv \$templib $lib' # Commands to make compiler produce verbose output that lists # what "hidden" libraries, object files and flags are used when # linking a shared library. @@ -6408,10 +6948,10 @@ if test "$_lt_caught_CXX_error" != yes; then # explicitly linking system object files so we need to strip them # from the output so that they don't get included in the library # dependencies. - output_verbose_link_cmd='templist=`$CC $CFLAGS -v conftest.$objext -o libconftest$shared_ext 2>&1 | $GREP "ld"`; rm -f libconftest$shared_ext; list=""; for z in $templist; do case $z in conftest.$objext) list="$list $z";; *.$objext);; *) list="$list $z";;esac; done; func_echo_all "$list"' + output_verbose_link_cmd='templist=`$CC $CFLAGS -v conftest.$objext -o libconftest$shared_ext 2>&1 | $GREP "ld"`; rm -f libconftest$shared_ext; list= ; for z in $templist; do case $z in conftest.$objext) list="$list $z";; *.$objext);; *) list="$list $z";;esac; done; func_echo_all "$list"' - _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}-rpath,$libdir' - _LT_TAGVAR(export_dynamic_flag_spec, $1)='${wl}--export-dynamic' + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='$wl-rpath,$libdir' + _LT_TAGVAR(export_dynamic_flag_spec, $1)='$wl--export-dynamic' # Archives containing C++ object files must be created using # "CC -Bstatic", where "CC" is the KAI C++ compiler. @@ -6425,59 +6965,59 @@ if test "$_lt_caught_CXX_error" != yes; then # earlier do not add the objects themselves. case `$CC -V 2>&1` in *"Version 7."*) - _LT_TAGVAR(archive_cmds, $1)='$CC -shared $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-soname $wl$soname -o $lib' - _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -shared $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-soname $wl$soname ${wl}-retain-symbols-file $wl$export_symbols -o $lib' + _LT_TAGVAR(archive_cmds, $1)='$CC -shared $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags $wl-soname $wl$soname -o $lib' + _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -shared $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags $wl-soname $wl$soname $wl-retain-symbols-file $wl$export_symbols -o $lib' ;; *) # Version 8.0 or newer tmp_idyn= case $host_cpu in ia64*) tmp_idyn=' -i_dynamic';; esac - _LT_TAGVAR(archive_cmds, $1)='$CC -shared'"$tmp_idyn"' $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname -o $lib' - _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -shared'"$tmp_idyn"' $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname ${wl}-retain-symbols-file $wl$export_symbols -o $lib' + _LT_TAGVAR(archive_cmds, $1)='$CC -shared'"$tmp_idyn"' $libobjs $deplibs $compiler_flags $wl-soname $wl$soname -o $lib' + _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -shared'"$tmp_idyn"' $libobjs $deplibs $compiler_flags $wl-soname $wl$soname $wl-retain-symbols-file $wl$export_symbols -o $lib' ;; esac _LT_TAGVAR(archive_cmds_need_lc, $1)=no - _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}-rpath,$libdir' - _LT_TAGVAR(export_dynamic_flag_spec, $1)='${wl}--export-dynamic' - _LT_TAGVAR(whole_archive_flag_spec, $1)='${wl}--whole-archive$convenience ${wl}--no-whole-archive' + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='$wl-rpath,$libdir' + _LT_TAGVAR(export_dynamic_flag_spec, $1)='$wl--export-dynamic' + _LT_TAGVAR(whole_archive_flag_spec, $1)='$wl--whole-archive$convenience $wl--no-whole-archive' ;; pgCC* | pgcpp*) # Portland Group C++ compiler case `$CC -V` in *pgCC\ [[1-5]].* | *pgcpp\ [[1-5]].*) _LT_TAGVAR(prelink_cmds, $1)='tpldir=Template.dir~ - rm -rf $tpldir~ - $CC --prelink_objects --instantiation_dir $tpldir $objs $libobjs $compile_deplibs~ - compile_command="$compile_command `find $tpldir -name \*.o | sort | $NL2SP`"' + rm -rf $tpldir~ + $CC --prelink_objects --instantiation_dir $tpldir $objs $libobjs $compile_deplibs~ + compile_command="$compile_command `find $tpldir -name \*.o | sort | $NL2SP`"' _LT_TAGVAR(old_archive_cmds, $1)='tpldir=Template.dir~ - rm -rf $tpldir~ - $CC --prelink_objects --instantiation_dir $tpldir $oldobjs$old_deplibs~ - $AR $AR_FLAGS $oldlib$oldobjs$old_deplibs `find $tpldir -name \*.o | sort | $NL2SP`~ - $RANLIB $oldlib' + rm -rf $tpldir~ + $CC --prelink_objects --instantiation_dir $tpldir $oldobjs$old_deplibs~ + $AR $AR_FLAGS $oldlib$oldobjs$old_deplibs `find $tpldir -name \*.o | sort | $NL2SP`~ + $RANLIB $oldlib' _LT_TAGVAR(archive_cmds, $1)='tpldir=Template.dir~ - rm -rf $tpldir~ - $CC --prelink_objects --instantiation_dir $tpldir $predep_objects $libobjs $deplibs $convenience $postdep_objects~ - $CC -shared $pic_flag $predep_objects $libobjs $deplibs `find $tpldir -name \*.o | sort | $NL2SP` $postdep_objects $compiler_flags ${wl}-soname ${wl}$soname -o $lib' + rm -rf $tpldir~ + $CC --prelink_objects --instantiation_dir $tpldir $predep_objects $libobjs $deplibs $convenience $postdep_objects~ + $CC -shared $pic_flag $predep_objects $libobjs $deplibs `find $tpldir -name \*.o | sort | $NL2SP` $postdep_objects $compiler_flags $wl-soname $wl$soname -o $lib' _LT_TAGVAR(archive_expsym_cmds, $1)='tpldir=Template.dir~ - rm -rf $tpldir~ - $CC --prelink_objects --instantiation_dir $tpldir $predep_objects $libobjs $deplibs $convenience $postdep_objects~ - $CC -shared $pic_flag $predep_objects $libobjs $deplibs `find $tpldir -name \*.o | sort | $NL2SP` $postdep_objects $compiler_flags ${wl}-soname ${wl}$soname ${wl}-retain-symbols-file ${wl}$export_symbols -o $lib' + rm -rf $tpldir~ + $CC --prelink_objects --instantiation_dir $tpldir $predep_objects $libobjs $deplibs $convenience $postdep_objects~ + $CC -shared $pic_flag $predep_objects $libobjs $deplibs `find $tpldir -name \*.o | sort | $NL2SP` $postdep_objects $compiler_flags $wl-soname $wl$soname $wl-retain-symbols-file $wl$export_symbols -o $lib' ;; *) # Version 6 and above use weak symbols - _LT_TAGVAR(archive_cmds, $1)='$CC -shared $pic_flag $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-soname ${wl}$soname -o $lib' - _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -shared $pic_flag $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-soname ${wl}$soname ${wl}-retain-symbols-file ${wl}$export_symbols -o $lib' + _LT_TAGVAR(archive_cmds, $1)='$CC -shared $pic_flag $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags $wl-soname $wl$soname -o $lib' + _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -shared $pic_flag $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags $wl-soname $wl$soname $wl-retain-symbols-file $wl$export_symbols -o $lib' ;; esac - _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}--rpath ${wl}$libdir' - _LT_TAGVAR(export_dynamic_flag_spec, $1)='${wl}--export-dynamic' - _LT_TAGVAR(whole_archive_flag_spec, $1)='${wl}--whole-archive`for conv in $convenience\"\"; do test -n \"$conv\" && new_convenience=\"$new_convenience,$conv\"; done; func_echo_all \"$new_convenience\"` ${wl}--no-whole-archive' + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='$wl--rpath $wl$libdir' + _LT_TAGVAR(export_dynamic_flag_spec, $1)='$wl--export-dynamic' + _LT_TAGVAR(whole_archive_flag_spec, $1)='$wl--whole-archive`for conv in $convenience\"\"; do test -n \"$conv\" && new_convenience=\"$new_convenience,$conv\"; done; func_echo_all \"$new_convenience\"` $wl--no-whole-archive' ;; cxx*) # Compaq C++ - _LT_TAGVAR(archive_cmds, $1)='$CC -shared $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-soname $wl$soname -o $lib' - _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -shared $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-soname $wl$soname -o $lib ${wl}-retain-symbols-file $wl$export_symbols' + _LT_TAGVAR(archive_cmds, $1)='$CC -shared $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags $wl-soname $wl$soname -o $lib' + _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -shared $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags $wl-soname $wl$soname -o $lib $wl-retain-symbols-file $wl$export_symbols' runpath_var=LD_RUN_PATH _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='-rpath $libdir' @@ -6491,18 +7031,18 @@ if test "$_lt_caught_CXX_error" != yes; then # explicitly linking system object files so we need to strip them # from the output so that they don't get included in the library # dependencies. - output_verbose_link_cmd='templist=`$CC -shared $CFLAGS -v conftest.$objext 2>&1 | $GREP "ld"`; templist=`func_echo_all "$templist" | $SED "s/\(^.*ld.*\)\( .*ld .*$\)/\1/"`; list=""; for z in $templist; do case $z in conftest.$objext) list="$list $z";; *.$objext);; *) list="$list $z";;esac; done; func_echo_all "X$list" | $Xsed' + output_verbose_link_cmd='templist=`$CC -shared $CFLAGS -v conftest.$objext 2>&1 | $GREP "ld"`; templist=`func_echo_all "$templist" | $SED "s/\(^.*ld.*\)\( .*ld .*$\)/\1/"`; list= ; for z in $templist; do case $z in conftest.$objext) list="$list $z";; *.$objext);; *) list="$list $z";;esac; done; func_echo_all "X$list" | $Xsed' ;; xl* | mpixl* | bgxl*) # IBM XL 8.0 on PPC, with GNU ld - _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}-rpath ${wl}$libdir' - _LT_TAGVAR(export_dynamic_flag_spec, $1)='${wl}--export-dynamic' - _LT_TAGVAR(archive_cmds, $1)='$CC -qmkshrobj $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname -o $lib' - if test "x$supports_anon_versioning" = xyes; then + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='$wl-rpath $wl$libdir' + _LT_TAGVAR(export_dynamic_flag_spec, $1)='$wl--export-dynamic' + _LT_TAGVAR(archive_cmds, $1)='$CC -qmkshrobj $libobjs $deplibs $compiler_flags $wl-soname $wl$soname -o $lib' + if test yes = "$supports_anon_versioning"; then _LT_TAGVAR(archive_expsym_cmds, $1)='echo "{ global:" > $output_objdir/$libname.ver~ - cat $export_symbols | sed -e "s/\(.*\)/\1;/" >> $output_objdir/$libname.ver~ - echo "local: *; };" >> $output_objdir/$libname.ver~ - $CC -qmkshrobj $libobjs $deplibs $compiler_flags ${wl}-soname $wl$soname ${wl}-version-script ${wl}$output_objdir/$libname.ver -o $lib' + cat $export_symbols | sed -e "s/\(.*\)/\1;/" >> $output_objdir/$libname.ver~ + echo "local: *; };" >> $output_objdir/$libname.ver~ + $CC -qmkshrobj $libobjs $deplibs $compiler_flags $wl-soname $wl$soname $wl-version-script $wl$output_objdir/$libname.ver -o $lib' fi ;; *) @@ -6510,10 +7050,10 @@ if test "$_lt_caught_CXX_error" != yes; then *Sun\ C*) # Sun C++ 5.9 _LT_TAGVAR(no_undefined_flag, $1)=' -zdefs' - _LT_TAGVAR(archive_cmds, $1)='$CC -G${allow_undefined_flag} -h$soname -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags' - _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -G${allow_undefined_flag} -h$soname -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-retain-symbols-file ${wl}$export_symbols' + _LT_TAGVAR(archive_cmds, $1)='$CC -G$allow_undefined_flag -h$soname -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags' + _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -G$allow_undefined_flag -h$soname -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags $wl-retain-symbols-file $wl$export_symbols' _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='-R$libdir' - _LT_TAGVAR(whole_archive_flag_spec, $1)='${wl}--whole-archive`new_convenience=; for conv in $convenience\"\"; do test -z \"$conv\" || new_convenience=\"$new_convenience,$conv\"; done; func_echo_all \"$new_convenience\"` ${wl}--no-whole-archive' + _LT_TAGVAR(whole_archive_flag_spec, $1)='$wl--whole-archive`new_convenience=; for conv in $convenience\"\"; do test -z \"$conv\" || new_convenience=\"$new_convenience,$conv\"; done; func_echo_all \"$new_convenience\"` $wl--no-whole-archive' _LT_TAGVAR(compiler_needs_object, $1)=yes # Not sure whether something based on @@ -6571,22 +7111,17 @@ if test "$_lt_caught_CXX_error" != yes; then _LT_TAGVAR(ld_shlibs, $1)=yes ;; - openbsd2*) - # C++ shared libraries are fairly broken - _LT_TAGVAR(ld_shlibs, $1)=no - ;; - - openbsd*) + openbsd* | bitrig*) if test -f /usr/libexec/ld.so; then _LT_TAGVAR(hardcode_direct, $1)=yes _LT_TAGVAR(hardcode_shlibpath_var, $1)=no _LT_TAGVAR(hardcode_direct_absolute, $1)=yes _LT_TAGVAR(archive_cmds, $1)='$CC -shared $pic_flag $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags -o $lib' - _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}-rpath,$libdir' - if test -z "`echo __ELF__ | $CC -E - | grep __ELF__`" || test "$host_os-$host_cpu" = "openbsd2.8-powerpc"; then - _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -shared $pic_flag $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-retain-symbols-file,$export_symbols -o $lib' - _LT_TAGVAR(export_dynamic_flag_spec, $1)='${wl}-E' - _LT_TAGVAR(whole_archive_flag_spec, $1)="$wlarc"'--whole-archive$convenience '"$wlarc"'--no-whole-archive' + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='$wl-rpath,$libdir' + if test -z "`echo __ELF__ | $CC -E - | grep __ELF__`"; then + _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -shared $pic_flag $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags $wl-retain-symbols-file,$export_symbols -o $lib' + _LT_TAGVAR(export_dynamic_flag_spec, $1)='$wl-E' + _LT_TAGVAR(whole_archive_flag_spec, $1)=$wlarc'--whole-archive$convenience '$wlarc'--no-whole-archive' fi output_verbose_link_cmd=func_echo_all else @@ -6602,9 +7137,9 @@ if test "$_lt_caught_CXX_error" != yes; then # KCC will only create a shared library if the output file # ends with ".so" (or ".sl" for HP-UX), so rename the library # to its proper name (with version) after linking. - _LT_TAGVAR(archive_cmds, $1)='tempext=`echo $shared_ext | $SED -e '\''s/\([[^()0-9A-Za-z{}]]\)/\\\\\1/g'\''`; templib=`echo "$lib" | $SED -e "s/\${tempext}\..*/.so/"`; $CC $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags --soname $soname -o \$templib; mv \$templib $lib' + _LT_TAGVAR(archive_cmds, $1)='tempext=`echo $shared_ext | $SED -e '\''s/\([[^()0-9A-Za-z{}]]\)/\\\\\1/g'\''`; templib=`echo "$lib" | $SED -e "s/\$tempext\..*/.so/"`; $CC $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags --soname $soname -o \$templib; mv \$templib $lib' - _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}-rpath,$libdir' + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='$wl-rpath,$libdir' _LT_TAGVAR(hardcode_libdir_separator, $1)=: # Archives containing C++ object files must be created using @@ -6622,17 +7157,17 @@ if test "$_lt_caught_CXX_error" != yes; then cxx*) case $host in osf3*) - _LT_TAGVAR(allow_undefined_flag, $1)=' ${wl}-expect_unresolved ${wl}\*' - _LT_TAGVAR(archive_cmds, $1)='$CC -shared${allow_undefined_flag} $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-soname $soname `test -n "$verstring" && func_echo_all "${wl}-set_version $verstring"` -update_registry ${output_objdir}/so_locations -o $lib' - _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}-rpath ${wl}$libdir' + _LT_TAGVAR(allow_undefined_flag, $1)=' $wl-expect_unresolved $wl\*' + _LT_TAGVAR(archive_cmds, $1)='$CC -shared$allow_undefined_flag $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags $wl-soname $soname `test -n "$verstring" && func_echo_all "$wl-set_version $verstring"` -update_registry $output_objdir/so_locations -o $lib' + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='$wl-rpath $wl$libdir' ;; *) _LT_TAGVAR(allow_undefined_flag, $1)=' -expect_unresolved \*' - _LT_TAGVAR(archive_cmds, $1)='$CC -shared${allow_undefined_flag} $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags -msym -soname $soname `test -n "$verstring" && func_echo_all "-set_version $verstring"` -update_registry ${output_objdir}/so_locations -o $lib' + _LT_TAGVAR(archive_cmds, $1)='$CC -shared$allow_undefined_flag $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags -msym -soname $soname `test -n "$verstring" && func_echo_all "-set_version $verstring"` -update_registry $output_objdir/so_locations -o $lib' _LT_TAGVAR(archive_expsym_cmds, $1)='for i in `cat $export_symbols`; do printf "%s %s\\n" -exported_symbol "\$i" >> $lib.exp; done~ - echo "-hidden">> $lib.exp~ - $CC -shared$allow_undefined_flag $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags -msym -soname $soname ${wl}-input ${wl}$lib.exp `test -n "$verstring" && $ECHO "-set_version $verstring"` -update_registry ${output_objdir}/so_locations -o $lib~ - $RM $lib.exp' + echo "-hidden">> $lib.exp~ + $CC -shared$allow_undefined_flag $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags -msym -soname $soname $wl-input $wl$lib.exp `test -n "$verstring" && $ECHO "-set_version $verstring"` -update_registry $output_objdir/so_locations -o $lib~ + $RM $lib.exp' _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='-rpath $libdir' ;; esac @@ -6647,21 +7182,21 @@ if test "$_lt_caught_CXX_error" != yes; then # explicitly linking system object files so we need to strip them # from the output so that they don't get included in the library # dependencies. - output_verbose_link_cmd='templist=`$CC -shared $CFLAGS -v conftest.$objext 2>&1 | $GREP "ld" | $GREP -v "ld:"`; templist=`func_echo_all "$templist" | $SED "s/\(^.*ld.*\)\( .*ld.*$\)/\1/"`; list=""; for z in $templist; do case $z in conftest.$objext) list="$list $z";; *.$objext);; *) list="$list $z";;esac; done; func_echo_all "$list"' + output_verbose_link_cmd='templist=`$CC -shared $CFLAGS -v conftest.$objext 2>&1 | $GREP "ld" | $GREP -v "ld:"`; templist=`func_echo_all "$templist" | $SED "s/\(^.*ld.*\)\( .*ld.*$\)/\1/"`; list= ; for z in $templist; do case $z in conftest.$objext) list="$list $z";; *.$objext);; *) list="$list $z";;esac; done; func_echo_all "$list"' ;; *) - if test "$GXX" = yes && test "$with_gnu_ld" = no; then - _LT_TAGVAR(allow_undefined_flag, $1)=' ${wl}-expect_unresolved ${wl}\*' + if test yes,no = "$GXX,$with_gnu_ld"; then + _LT_TAGVAR(allow_undefined_flag, $1)=' $wl-expect_unresolved $wl\*' case $host in osf3*) - _LT_TAGVAR(archive_cmds, $1)='$CC -shared -nostdlib ${allow_undefined_flag} $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-soname ${wl}$soname `test -n "$verstring" && func_echo_all "${wl}-set_version ${wl}$verstring"` ${wl}-update_registry ${wl}${output_objdir}/so_locations -o $lib' + _LT_TAGVAR(archive_cmds, $1)='$CC -shared -nostdlib $allow_undefined_flag $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags $wl-soname $wl$soname `test -n "$verstring" && func_echo_all "$wl-set_version $wl$verstring"` $wl-update_registry $wl$output_objdir/so_locations -o $lib' ;; *) - _LT_TAGVAR(archive_cmds, $1)='$CC -shared $pic_flag -nostdlib ${allow_undefined_flag} $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-msym ${wl}-soname ${wl}$soname `test -n "$verstring" && func_echo_all "${wl}-set_version ${wl}$verstring"` ${wl}-update_registry ${wl}${output_objdir}/so_locations -o $lib' + _LT_TAGVAR(archive_cmds, $1)='$CC -shared $pic_flag -nostdlib $allow_undefined_flag $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags $wl-msym $wl-soname $wl$soname `test -n "$verstring" && func_echo_all "$wl-set_version $wl$verstring"` $wl-update_registry $wl$output_objdir/so_locations -o $lib' ;; esac - _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}-rpath ${wl}$libdir' + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='$wl-rpath $wl$libdir' _LT_TAGVAR(hardcode_libdir_separator, $1)=: # Commands to make compiler produce verbose output that lists @@ -6707,9 +7242,9 @@ if test "$_lt_caught_CXX_error" != yes; then # Sun C++ 4.2, 5.x and Centerline C++ _LT_TAGVAR(archive_cmds_need_lc,$1)=yes _LT_TAGVAR(no_undefined_flag, $1)=' -zdefs' - _LT_TAGVAR(archive_cmds, $1)='$CC -G${allow_undefined_flag} -h$soname -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags' + _LT_TAGVAR(archive_cmds, $1)='$CC -G$allow_undefined_flag -h$soname -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags' _LT_TAGVAR(archive_expsym_cmds, $1)='echo "{ global:" > $lib.exp~cat $export_symbols | $SED -e "s/\(.*\)/\1;/" >> $lib.exp~echo "local: *; };" >> $lib.exp~ - $CC -G${allow_undefined_flag} ${wl}-M ${wl}$lib.exp -h$soname -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags~$RM $lib.exp' + $CC -G$allow_undefined_flag $wl-M $wl$lib.exp -h$soname -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags~$RM $lib.exp' _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='-R$libdir' _LT_TAGVAR(hardcode_shlibpath_var, $1)=no @@ -6717,7 +7252,7 @@ if test "$_lt_caught_CXX_error" != yes; then solaris2.[[0-5]] | solaris2.[[0-5]].*) ;; *) # The compiler driver will combine and reorder linker options, - # but understands `-z linker_flag'. + # but understands '-z linker_flag'. # Supported since Solaris 2.6 (maybe 2.5.1?) _LT_TAGVAR(whole_archive_flag_spec, $1)='-z allextract$convenience -z defaultextract' ;; @@ -6734,30 +7269,30 @@ if test "$_lt_caught_CXX_error" != yes; then ;; gcx*) # Green Hills C++ Compiler - _LT_TAGVAR(archive_cmds, $1)='$CC -shared $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-h $wl$soname -o $lib' + _LT_TAGVAR(archive_cmds, $1)='$CC -shared $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags $wl-h $wl$soname -o $lib' # The C++ compiler must be used to create the archive. _LT_TAGVAR(old_archive_cmds, $1)='$CC $LDFLAGS -archive -o $oldlib $oldobjs' ;; *) # GNU C++ compiler with Solaris linker - if test "$GXX" = yes && test "$with_gnu_ld" = no; then - _LT_TAGVAR(no_undefined_flag, $1)=' ${wl}-z ${wl}defs' + if test yes,no = "$GXX,$with_gnu_ld"; then + _LT_TAGVAR(no_undefined_flag, $1)=' $wl-z ${wl}defs' if $CC --version | $GREP -v '^2\.7' > /dev/null; then - _LT_TAGVAR(archive_cmds, $1)='$CC -shared $pic_flag -nostdlib $LDFLAGS $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-h $wl$soname -o $lib' + _LT_TAGVAR(archive_cmds, $1)='$CC -shared $pic_flag -nostdlib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags $wl-h $wl$soname -o $lib' _LT_TAGVAR(archive_expsym_cmds, $1)='echo "{ global:" > $lib.exp~cat $export_symbols | $SED -e "s/\(.*\)/\1;/" >> $lib.exp~echo "local: *; };" >> $lib.exp~ - $CC -shared $pic_flag -nostdlib ${wl}-M $wl$lib.exp -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags~$RM $lib.exp' + $CC -shared $pic_flag -nostdlib $wl-M $wl$lib.exp $wl-h $wl$soname -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags~$RM $lib.exp' # Commands to make compiler produce verbose output that lists # what "hidden" libraries, object files and flags are used when # linking a shared library. output_verbose_link_cmd='$CC -shared $CFLAGS -v conftest.$objext 2>&1 | $GREP -v "^Configured with:" | $GREP "\-L"' else - # g++ 2.7 appears to require `-G' NOT `-shared' on this + # g++ 2.7 appears to require '-G' NOT '-shared' on this # platform. - _LT_TAGVAR(archive_cmds, $1)='$CC -G -nostdlib $LDFLAGS $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags ${wl}-h $wl$soname -o $lib' + _LT_TAGVAR(archive_cmds, $1)='$CC -G -nostdlib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags $wl-h $wl$soname -o $lib' _LT_TAGVAR(archive_expsym_cmds, $1)='echo "{ global:" > $lib.exp~cat $export_symbols | $SED -e "s/\(.*\)/\1;/" >> $lib.exp~echo "local: *; };" >> $lib.exp~ - $CC -G -nostdlib ${wl}-M $wl$lib.exp -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags~$RM $lib.exp' + $CC -G -nostdlib $wl-M $wl$lib.exp $wl-h $wl$soname -o $lib $predep_objects $libobjs $deplibs $postdep_objects $compiler_flags~$RM $lib.exp' # Commands to make compiler produce verbose output that lists # what "hidden" libraries, object files and flags are used when @@ -6765,11 +7300,11 @@ if test "$_lt_caught_CXX_error" != yes; then output_verbose_link_cmd='$CC -G $CFLAGS -v conftest.$objext 2>&1 | $GREP -v "^Configured with:" | $GREP "\-L"' fi - _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}-R $wl$libdir' + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='$wl-R $wl$libdir' case $host_os in solaris2.[[0-5]] | solaris2.[[0-5]].*) ;; *) - _LT_TAGVAR(whole_archive_flag_spec, $1)='${wl}-z ${wl}allextract$convenience ${wl}-z ${wl}defaultextract' + _LT_TAGVAR(whole_archive_flag_spec, $1)='$wl-z ${wl}allextract$convenience $wl-z ${wl}defaultextract' ;; esac fi @@ -6778,52 +7313,52 @@ if test "$_lt_caught_CXX_error" != yes; then ;; sysv4*uw2* | sysv5OpenUNIX* | sysv5UnixWare7.[[01]].[[10]]* | unixware7* | sco3.2v5.0.[[024]]*) - _LT_TAGVAR(no_undefined_flag, $1)='${wl}-z,text' + _LT_TAGVAR(no_undefined_flag, $1)='$wl-z,text' _LT_TAGVAR(archive_cmds_need_lc, $1)=no _LT_TAGVAR(hardcode_shlibpath_var, $1)=no runpath_var='LD_RUN_PATH' case $cc_basename in CC*) - _LT_TAGVAR(archive_cmds, $1)='$CC -G ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' - _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -G ${wl}-Bexport:$export_symbols ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + _LT_TAGVAR(archive_cmds, $1)='$CC -G $wl-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -G $wl-Bexport:$export_symbols $wl-h,$soname -o $lib $libobjs $deplibs $compiler_flags' ;; *) - _LT_TAGVAR(archive_cmds, $1)='$CC -shared ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' - _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -shared ${wl}-Bexport:$export_symbols ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + _LT_TAGVAR(archive_cmds, $1)='$CC -shared $wl-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -shared $wl-Bexport:$export_symbols $wl-h,$soname -o $lib $libobjs $deplibs $compiler_flags' ;; esac ;; sysv5* | sco3.2v5* | sco5v6*) - # Note: We can NOT use -z defs as we might desire, because we do not + # Note: We CANNOT use -z defs as we might desire, because we do not # link with -lc, and that would cause any symbols used from libc to # always be unresolved, which means just about no library would # ever link correctly. If we're not using GNU ld we use -z text # though, which does catch some bad symbols but isn't as heavy-handed # as -z defs. - _LT_TAGVAR(no_undefined_flag, $1)='${wl}-z,text' - _LT_TAGVAR(allow_undefined_flag, $1)='${wl}-z,nodefs' + _LT_TAGVAR(no_undefined_flag, $1)='$wl-z,text' + _LT_TAGVAR(allow_undefined_flag, $1)='$wl-z,nodefs' _LT_TAGVAR(archive_cmds_need_lc, $1)=no _LT_TAGVAR(hardcode_shlibpath_var, $1)=no - _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='${wl}-R,$libdir' + _LT_TAGVAR(hardcode_libdir_flag_spec, $1)='$wl-R,$libdir' _LT_TAGVAR(hardcode_libdir_separator, $1)=':' _LT_TAGVAR(link_all_deplibs, $1)=yes - _LT_TAGVAR(export_dynamic_flag_spec, $1)='${wl}-Bexport' + _LT_TAGVAR(export_dynamic_flag_spec, $1)='$wl-Bexport' runpath_var='LD_RUN_PATH' case $cc_basename in CC*) - _LT_TAGVAR(archive_cmds, $1)='$CC -G ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' - _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -G ${wl}-Bexport:$export_symbols ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + _LT_TAGVAR(archive_cmds, $1)='$CC -G $wl-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -G $wl-Bexport:$export_symbols $wl-h,$soname -o $lib $libobjs $deplibs $compiler_flags' _LT_TAGVAR(old_archive_cmds, $1)='$CC -Tprelink_objects $oldobjs~ - '"$_LT_TAGVAR(old_archive_cmds, $1)" + '"$_LT_TAGVAR(old_archive_cmds, $1)" _LT_TAGVAR(reload_cmds, $1)='$CC -Tprelink_objects $reload_objs~ - '"$_LT_TAGVAR(reload_cmds, $1)" + '"$_LT_TAGVAR(reload_cmds, $1)" ;; *) - _LT_TAGVAR(archive_cmds, $1)='$CC -shared ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' - _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -shared ${wl}-Bexport:$export_symbols ${wl}-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + _LT_TAGVAR(archive_cmds, $1)='$CC -shared $wl-h,$soname -o $lib $libobjs $deplibs $compiler_flags' + _LT_TAGVAR(archive_expsym_cmds, $1)='$CC -shared $wl-Bexport:$export_symbols $wl-h,$soname -o $lib $libobjs $deplibs $compiler_flags' ;; esac ;; @@ -6854,10 +7389,10 @@ if test "$_lt_caught_CXX_error" != yes; then esac AC_MSG_RESULT([$_LT_TAGVAR(ld_shlibs, $1)]) - test "$_LT_TAGVAR(ld_shlibs, $1)" = no && can_build_shared=no + test no = "$_LT_TAGVAR(ld_shlibs, $1)" && can_build_shared=no - _LT_TAGVAR(GCC, $1)="$GXX" - _LT_TAGVAR(LD, $1)="$LD" + _LT_TAGVAR(GCC, $1)=$GXX + _LT_TAGVAR(LD, $1)=$LD ## CAVEAT EMPTOR: ## There is no encapsulation within the following macros, do not change @@ -6884,7 +7419,7 @@ if test "$_lt_caught_CXX_error" != yes; then lt_cv_path_LD=$lt_save_path_LD lt_cv_prog_gnu_ldcxx=$lt_cv_prog_gnu_ld lt_cv_prog_gnu_ld=$lt_save_with_gnu_ld -fi # test "$_lt_caught_CXX_error" != yes +fi # test yes != "$_lt_caught_CXX_error" AC_LANG_POP ])# _LT_LANG_CXX_CONFIG @@ -6906,13 +7441,14 @@ AC_REQUIRE([_LT_DECL_SED]) AC_REQUIRE([_LT_PROG_ECHO_BACKSLASH]) func_stripname_cnf () { - case ${2} in - .*) func_stripname_result=`$ECHO "${3}" | $SED "s%^${1}%%; s%\\\\${2}\$%%"`;; - *) func_stripname_result=`$ECHO "${3}" | $SED "s%^${1}%%; s%${2}\$%%"`;; + case @S|@2 in + .*) func_stripname_result=`$ECHO "@S|@3" | $SED "s%^@S|@1%%; s%\\\\@S|@2\$%%"`;; + *) func_stripname_result=`$ECHO "@S|@3" | $SED "s%^@S|@1%%; s%@S|@2\$%%"`;; esac } # func_stripname_cnf ])# _LT_FUNC_STRIPNAME_CNF + # _LT_SYS_HIDDEN_LIBDEPS([TAGNAME]) # --------------------------------- # Figure out "hidden" library dependencies from verbose @@ -6996,13 +7532,13 @@ if AC_TRY_EVAL(ac_compile); then pre_test_object_deps_done=no for p in `eval "$output_verbose_link_cmd"`; do - case ${prev}${p} in + case $prev$p in -L* | -R* | -l*) # Some compilers place space between "-{L,R}" and the path. # Remove the space. - if test $p = "-L" || - test $p = "-R"; then + if test x-L = "$p" || + test x-R = "$p"; then prev=$p continue fi @@ -7018,16 +7554,16 @@ if AC_TRY_EVAL(ac_compile); then case $p in =*) func_stripname_cnf '=' '' "$p"; p=$lt_sysroot$func_stripname_result ;; esac - if test "$pre_test_object_deps_done" = no; then - case ${prev} in + if test no = "$pre_test_object_deps_done"; then + case $prev in -L | -R) # Internal compiler library paths should come after those # provided the user. The postdeps already come after the # user supplied libs so there is no need to process them. if test -z "$_LT_TAGVAR(compiler_lib_search_path, $1)"; then - _LT_TAGVAR(compiler_lib_search_path, $1)="${prev}${p}" + _LT_TAGVAR(compiler_lib_search_path, $1)=$prev$p else - _LT_TAGVAR(compiler_lib_search_path, $1)="${_LT_TAGVAR(compiler_lib_search_path, $1)} ${prev}${p}" + _LT_TAGVAR(compiler_lib_search_path, $1)="${_LT_TAGVAR(compiler_lib_search_path, $1)} $prev$p" fi ;; # The "-l" case would never come before the object being @@ -7035,9 +7571,9 @@ if AC_TRY_EVAL(ac_compile); then esac else if test -z "$_LT_TAGVAR(postdeps, $1)"; then - _LT_TAGVAR(postdeps, $1)="${prev}${p}" + _LT_TAGVAR(postdeps, $1)=$prev$p else - _LT_TAGVAR(postdeps, $1)="${_LT_TAGVAR(postdeps, $1)} ${prev}${p}" + _LT_TAGVAR(postdeps, $1)="${_LT_TAGVAR(postdeps, $1)} $prev$p" fi fi prev= @@ -7052,15 +7588,15 @@ if AC_TRY_EVAL(ac_compile); then continue fi - if test "$pre_test_object_deps_done" = no; then + if test no = "$pre_test_object_deps_done"; then if test -z "$_LT_TAGVAR(predep_objects, $1)"; then - _LT_TAGVAR(predep_objects, $1)="$p" + _LT_TAGVAR(predep_objects, $1)=$p else _LT_TAGVAR(predep_objects, $1)="$_LT_TAGVAR(predep_objects, $1) $p" fi else if test -z "$_LT_TAGVAR(postdep_objects, $1)"; then - _LT_TAGVAR(postdep_objects, $1)="$p" + _LT_TAGVAR(postdep_objects, $1)=$p else _LT_TAGVAR(postdep_objects, $1)="$_LT_TAGVAR(postdep_objects, $1) $p" fi @@ -7091,51 +7627,6 @@ interix[[3-9]]*) _LT_TAGVAR(postdep_objects,$1)= _LT_TAGVAR(postdeps,$1)= ;; - -linux*) - case `$CC -V 2>&1 | sed 5q` in - *Sun\ C*) - # Sun C++ 5.9 - - # The more standards-conforming stlport4 library is - # incompatible with the Cstd library. Avoid specifying - # it if it's in CXXFLAGS. Ignore libCrun as - # -library=stlport4 depends on it. - case " $CXX $CXXFLAGS " in - *" -library=stlport4 "*) - solaris_use_stlport4=yes - ;; - esac - - if test "$solaris_use_stlport4" != yes; then - _LT_TAGVAR(postdeps,$1)='-library=Cstd -library=Crun' - fi - ;; - esac - ;; - -solaris*) - case $cc_basename in - CC* | sunCC*) - # The more standards-conforming stlport4 library is - # incompatible with the Cstd library. Avoid specifying - # it if it's in CXXFLAGS. Ignore libCrun as - # -library=stlport4 depends on it. - case " $CXX $CXXFLAGS " in - *" -library=stlport4 "*) - solaris_use_stlport4=yes - ;; - esac - - # Adding this requires a known-good setup of shared libraries for - # Sun compiler versions before 5.6, else PIC objects from an old - # archive will be linked into the output, leading to subtle bugs. - if test "$solaris_use_stlport4" != yes; then - _LT_TAGVAR(postdeps,$1)='-library=Cstd -library=Crun' - fi - ;; - esac - ;; esac ]) @@ -7144,7 +7635,7 @@ case " $_LT_TAGVAR(postdeps, $1) " in esac _LT_TAGVAR(compiler_lib_search_dirs, $1)= if test -n "${_LT_TAGVAR(compiler_lib_search_path, $1)}"; then - _LT_TAGVAR(compiler_lib_search_dirs, $1)=`echo " ${_LT_TAGVAR(compiler_lib_search_path, $1)}" | ${SED} -e 's! -L! !g' -e 's!^ !!'` + _LT_TAGVAR(compiler_lib_search_dirs, $1)=`echo " ${_LT_TAGVAR(compiler_lib_search_path, $1)}" | $SED -e 's! -L! !g' -e 's!^ !!'` fi _LT_TAGDECL([], [compiler_lib_search_dirs], [1], [The directories searched by this compiler when creating a shared library]) @@ -7164,10 +7655,10 @@ _LT_TAGDECL([], [compiler_lib_search_path], [1], # -------------------------- # Ensure that the configuration variables for a Fortran 77 compiler are # suitably defined. These variables are subsequently used by _LT_CONFIG -# to write the compiler configuration to `libtool'. +# to write the compiler configuration to 'libtool'. m4_defun([_LT_LANG_F77_CONFIG], [AC_LANG_PUSH(Fortran 77) -if test -z "$F77" || test "X$F77" = "Xno"; then +if test -z "$F77" || test no = "$F77"; then _lt_disable_F77=yes fi @@ -7204,7 +7695,7 @@ _LT_TAGVAR(objext, $1)=$objext # the F77 compiler isn't working. Some variables (like enable_shared) # are currently assumed to apply to all compilers on this platform, # and will be corrupted by setting them based on a non-working compiler. -if test "$_lt_disable_F77" != yes; then +if test yes != "$_lt_disable_F77"; then # Code to be used in simple compile tests lt_simple_compile_test_code="\ subroutine t @@ -7226,7 +7717,7 @@ if test "$_lt_disable_F77" != yes; then _LT_LINKER_BOILERPLATE # Allow CC to be a program name with arguments. - lt_save_CC="$CC" + lt_save_CC=$CC lt_save_GCC=$GCC lt_save_CFLAGS=$CFLAGS CC=${F77-"f77"} @@ -7240,21 +7731,25 @@ if test "$_lt_disable_F77" != yes; then AC_MSG_RESULT([$can_build_shared]) AC_MSG_CHECKING([whether to build shared libraries]) - test "$can_build_shared" = "no" && enable_shared=no + test no = "$can_build_shared" && enable_shared=no # On AIX, shared libraries and static libraries use the same namespace, and # are all built from PIC. case $host_os in aix3*) - test "$enable_shared" = yes && enable_static=no + test yes = "$enable_shared" && enable_static=no if test -n "$RANLIB"; then archive_cmds="$archive_cmds~\$RANLIB \$lib" postinstall_cmds='$RANLIB $lib' fi ;; aix[[4-9]]*) - if test "$host_cpu" != ia64 && test "$aix_use_runtimelinking" = no ; then - test "$enable_shared" = yes && enable_static=no + if test ia64 != "$host_cpu"; then + case $enable_shared,$with_aix_soname,$aix_use_runtimelinking in + yes,aix,yes) ;; # shared object as lib.so file only + yes,svr4,*) ;; # shared object as lib.so archive member only + yes,*) enable_static=no ;; # shared object in lib.a archive as well + esac fi ;; esac @@ -7262,11 +7757,11 @@ if test "$_lt_disable_F77" != yes; then AC_MSG_CHECKING([whether to build static libraries]) # Make sure either enable_shared or enable_static is yes. - test "$enable_shared" = yes || enable_static=yes + test yes = "$enable_shared" || enable_static=yes AC_MSG_RESULT([$enable_static]) - _LT_TAGVAR(GCC, $1)="$G77" - _LT_TAGVAR(LD, $1)="$LD" + _LT_TAGVAR(GCC, $1)=$G77 + _LT_TAGVAR(LD, $1)=$LD ## CAVEAT EMPTOR: ## There is no encapsulation within the following macros, do not change @@ -7283,9 +7778,9 @@ if test "$_lt_disable_F77" != yes; then fi # test -n "$compiler" GCC=$lt_save_GCC - CC="$lt_save_CC" - CFLAGS="$lt_save_CFLAGS" -fi # test "$_lt_disable_F77" != yes + CC=$lt_save_CC + CFLAGS=$lt_save_CFLAGS +fi # test yes != "$_lt_disable_F77" AC_LANG_POP ])# _LT_LANG_F77_CONFIG @@ -7295,11 +7790,11 @@ AC_LANG_POP # ------------------------- # Ensure that the configuration variables for a Fortran compiler are # suitably defined. These variables are subsequently used by _LT_CONFIG -# to write the compiler configuration to `libtool'. +# to write the compiler configuration to 'libtool'. m4_defun([_LT_LANG_FC_CONFIG], [AC_LANG_PUSH(Fortran) -if test -z "$FC" || test "X$FC" = "Xno"; then +if test -z "$FC" || test no = "$FC"; then _lt_disable_FC=yes fi @@ -7336,7 +7831,7 @@ _LT_TAGVAR(objext, $1)=$objext # the FC compiler isn't working. Some variables (like enable_shared) # are currently assumed to apply to all compilers on this platform, # and will be corrupted by setting them based on a non-working compiler. -if test "$_lt_disable_FC" != yes; then +if test yes != "$_lt_disable_FC"; then # Code to be used in simple compile tests lt_simple_compile_test_code="\ subroutine t @@ -7358,7 +7853,7 @@ if test "$_lt_disable_FC" != yes; then _LT_LINKER_BOILERPLATE # Allow CC to be a program name with arguments. - lt_save_CC="$CC" + lt_save_CC=$CC lt_save_GCC=$GCC lt_save_CFLAGS=$CFLAGS CC=${FC-"f95"} @@ -7374,21 +7869,25 @@ if test "$_lt_disable_FC" != yes; then AC_MSG_RESULT([$can_build_shared]) AC_MSG_CHECKING([whether to build shared libraries]) - test "$can_build_shared" = "no" && enable_shared=no + test no = "$can_build_shared" && enable_shared=no # On AIX, shared libraries and static libraries use the same namespace, and # are all built from PIC. case $host_os in aix3*) - test "$enable_shared" = yes && enable_static=no + test yes = "$enable_shared" && enable_static=no if test -n "$RANLIB"; then archive_cmds="$archive_cmds~\$RANLIB \$lib" postinstall_cmds='$RANLIB $lib' fi ;; aix[[4-9]]*) - if test "$host_cpu" != ia64 && test "$aix_use_runtimelinking" = no ; then - test "$enable_shared" = yes && enable_static=no + if test ia64 != "$host_cpu"; then + case $enable_shared,$with_aix_soname,$aix_use_runtimelinking in + yes,aix,yes) ;; # shared object as lib.so file only + yes,svr4,*) ;; # shared object as lib.so archive member only + yes,*) enable_static=no ;; # shared object in lib.a archive as well + esac fi ;; esac @@ -7396,11 +7895,11 @@ if test "$_lt_disable_FC" != yes; then AC_MSG_CHECKING([whether to build static libraries]) # Make sure either enable_shared or enable_static is yes. - test "$enable_shared" = yes || enable_static=yes + test yes = "$enable_shared" || enable_static=yes AC_MSG_RESULT([$enable_static]) - _LT_TAGVAR(GCC, $1)="$ac_cv_fc_compiler_gnu" - _LT_TAGVAR(LD, $1)="$LD" + _LT_TAGVAR(GCC, $1)=$ac_cv_fc_compiler_gnu + _LT_TAGVAR(LD, $1)=$LD ## CAVEAT EMPTOR: ## There is no encapsulation within the following macros, do not change @@ -7420,7 +7919,7 @@ if test "$_lt_disable_FC" != yes; then GCC=$lt_save_GCC CC=$lt_save_CC CFLAGS=$lt_save_CFLAGS -fi # test "$_lt_disable_FC" != yes +fi # test yes != "$_lt_disable_FC" AC_LANG_POP ])# _LT_LANG_FC_CONFIG @@ -7430,7 +7929,7 @@ AC_LANG_POP # -------------------------- # Ensure that the configuration variables for the GNU Java Compiler compiler # are suitably defined. These variables are subsequently used by _LT_CONFIG -# to write the compiler configuration to `libtool'. +# to write the compiler configuration to 'libtool'. m4_defun([_LT_LANG_GCJ_CONFIG], [AC_REQUIRE([LT_PROG_GCJ])dnl AC_LANG_SAVE @@ -7464,7 +7963,7 @@ CC=${GCJ-"gcj"} CFLAGS=$GCJFLAGS compiler=$CC _LT_TAGVAR(compiler, $1)=$CC -_LT_TAGVAR(LD, $1)="$LD" +_LT_TAGVAR(LD, $1)=$LD _LT_CC_BASENAME([$compiler]) # GCJ did not exist at the time GCC didn't implicitly link libc in. @@ -7501,7 +8000,7 @@ CFLAGS=$lt_save_CFLAGS # -------------------------- # Ensure that the configuration variables for the GNU Go compiler # are suitably defined. These variables are subsequently used by _LT_CONFIG -# to write the compiler configuration to `libtool'. +# to write the compiler configuration to 'libtool'. m4_defun([_LT_LANG_GO_CONFIG], [AC_REQUIRE([LT_PROG_GO])dnl AC_LANG_SAVE @@ -7535,7 +8034,7 @@ CC=${GOC-"gccgo"} CFLAGS=$GOFLAGS compiler=$CC _LT_TAGVAR(compiler, $1)=$CC -_LT_TAGVAR(LD, $1)="$LD" +_LT_TAGVAR(LD, $1)=$LD _LT_CC_BASENAME([$compiler]) # Go did not exist at the time GCC didn't implicitly link libc in. @@ -7572,7 +8071,7 @@ CFLAGS=$lt_save_CFLAGS # ------------------------- # Ensure that the configuration variables for the Windows resource compiler # are suitably defined. These variables are subsequently used by _LT_CONFIG -# to write the compiler configuration to `libtool'. +# to write the compiler configuration to 'libtool'. m4_defun([_LT_LANG_RC_CONFIG], [AC_REQUIRE([LT_PROG_RC])dnl AC_LANG_SAVE @@ -7588,7 +8087,7 @@ _LT_TAGVAR(objext, $1)=$objext lt_simple_compile_test_code='sample MENU { MENUITEM "&Soup", 100, CHECKED }' # Code to be used in simple link tests -lt_simple_link_test_code="$lt_simple_compile_test_code" +lt_simple_link_test_code=$lt_simple_compile_test_code # ltmain only uses $CC for tagged configurations so make sure $CC is set. _LT_TAG_COMPILER @@ -7598,7 +8097,7 @@ _LT_COMPILER_BOILERPLATE _LT_LINKER_BOILERPLATE # Allow CC to be a program name with arguments. -lt_save_CC="$CC" +lt_save_CC=$CC lt_save_CFLAGS=$CFLAGS lt_save_GCC=$GCC GCC= @@ -7627,7 +8126,7 @@ AC_DEFUN([LT_PROG_GCJ], [m4_ifdef([AC_PROG_GCJ], [AC_PROG_GCJ], [m4_ifdef([A][M_PROG_GCJ], [A][M_PROG_GCJ], [AC_CHECK_TOOL(GCJ, gcj,) - test "x${GCJFLAGS+set}" = xset || GCJFLAGS="-g -O2" + test set = "${GCJFLAGS+set}" || GCJFLAGS="-g -O2" AC_SUBST(GCJFLAGS)])])[]dnl ]) @@ -7738,7 +8237,7 @@ lt_ac_count=0 # Add /usr/xpg4/bin/sed as it is typically found on Solaris # along with /bin/sed that truncates output. for lt_ac_sed in $lt_ac_sed_list /usr/xpg4/bin/sed; do - test ! -f $lt_ac_sed && continue + test ! -f "$lt_ac_sed" && continue cat /dev/null > conftest.in lt_ac_count=0 echo $ECHO_N "0123456789$ECHO_C" >conftest.in @@ -7755,9 +8254,9 @@ for lt_ac_sed in $lt_ac_sed_list /usr/xpg4/bin/sed; do $lt_ac_sed -e 's/a$//' < conftest.nl >conftest.out || break cmp -s conftest.out conftest.nl || break # 10000 chars as input seems more than enough - test $lt_ac_count -gt 10 && break + test 10 -lt "$lt_ac_count" && break lt_ac_count=`expr $lt_ac_count + 1` - if test $lt_ac_count -gt $lt_ac_max; then + if test "$lt_ac_count" -gt "$lt_ac_max"; then lt_ac_max=$lt_ac_count lt_cv_path_SED=$lt_ac_sed fi @@ -7781,27 +8280,7 @@ dnl AC_DEFUN([LT_AC_PROG_SED], []) # Find out whether the shell is Bourne or XSI compatible, # or has some other useful features. m4_defun([_LT_CHECK_SHELL_FEATURES], -[AC_MSG_CHECKING([whether the shell understands some XSI constructs]) -# Try some XSI features -xsi_shell=no -( _lt_dummy="a/b/c" - test "${_lt_dummy##*/},${_lt_dummy%/*},${_lt_dummy#??}"${_lt_dummy%"$_lt_dummy"}, \ - = c,a/b,b/c, \ - && eval 'test $(( 1 + 1 )) -eq 2 \ - && test "${#_lt_dummy}" -eq 5' ) >/dev/null 2>&1 \ - && xsi_shell=yes -AC_MSG_RESULT([$xsi_shell]) -_LT_CONFIG_LIBTOOL_INIT([xsi_shell='$xsi_shell']) - -AC_MSG_CHECKING([whether the shell understands "+="]) -lt_shell_append=no -( foo=bar; set foo baz; eval "$[1]+=\$[2]" && test "$foo" = barbaz ) \ - >/dev/null 2>&1 \ - && lt_shell_append=yes -AC_MSG_RESULT([$lt_shell_append]) -_LT_CONFIG_LIBTOOL_INIT([lt_shell_append='$lt_shell_append']) - -if ( (MAIL=60; unset MAIL) || exit) >/dev/null 2>&1; then +[if ( (MAIL=60; unset MAIL) || exit) >/dev/null 2>&1; then lt_unset=unset else lt_unset=false @@ -7825,102 +8304,9 @@ _LT_DECL([NL2SP], [lt_NL2SP], [1], [turn newlines into spaces])dnl ])# _LT_CHECK_SHELL_FEATURES -# _LT_PROG_FUNCTION_REPLACE (FUNCNAME, REPLACEMENT-BODY) -# ------------------------------------------------------ -# In `$cfgfile', look for function FUNCNAME delimited by `^FUNCNAME ()$' and -# '^} FUNCNAME ', and replace its body with REPLACEMENT-BODY. -m4_defun([_LT_PROG_FUNCTION_REPLACE], -[dnl { -sed -e '/^$1 ()$/,/^} # $1 /c\ -$1 ()\ -{\ -m4_bpatsubsts([$2], [$], [\\], [^\([ ]\)], [\\\1]) -} # Extended-shell $1 implementation' "$cfgfile" > $cfgfile.tmp \ - && mv -f "$cfgfile.tmp" "$cfgfile" \ - || (rm -f "$cfgfile" && cp "$cfgfile.tmp" "$cfgfile" && rm -f "$cfgfile.tmp") -test 0 -eq $? || _lt_function_replace_fail=: -]) - - -# _LT_PROG_REPLACE_SHELLFNS -# ------------------------- -# Replace existing portable implementations of several shell functions with -# equivalent extended shell implementations where those features are available.. -m4_defun([_LT_PROG_REPLACE_SHELLFNS], -[if test x"$xsi_shell" = xyes; then - _LT_PROG_FUNCTION_REPLACE([func_dirname], [dnl - case ${1} in - */*) func_dirname_result="${1%/*}${2}" ;; - * ) func_dirname_result="${3}" ;; - esac]) - - _LT_PROG_FUNCTION_REPLACE([func_basename], [dnl - func_basename_result="${1##*/}"]) - - _LT_PROG_FUNCTION_REPLACE([func_dirname_and_basename], [dnl - case ${1} in - */*) func_dirname_result="${1%/*}${2}" ;; - * ) func_dirname_result="${3}" ;; - esac - func_basename_result="${1##*/}"]) - - _LT_PROG_FUNCTION_REPLACE([func_stripname], [dnl - # pdksh 5.2.14 does not do ${X%$Y} correctly if both X and Y are - # positional parameters, so assign one to ordinary parameter first. - func_stripname_result=${3} - func_stripname_result=${func_stripname_result#"${1}"} - func_stripname_result=${func_stripname_result%"${2}"}]) - - _LT_PROG_FUNCTION_REPLACE([func_split_long_opt], [dnl - func_split_long_opt_name=${1%%=*} - func_split_long_opt_arg=${1#*=}]) - - _LT_PROG_FUNCTION_REPLACE([func_split_short_opt], [dnl - func_split_short_opt_arg=${1#??} - func_split_short_opt_name=${1%"$func_split_short_opt_arg"}]) - - _LT_PROG_FUNCTION_REPLACE([func_lo2o], [dnl - case ${1} in - *.lo) func_lo2o_result=${1%.lo}.${objext} ;; - *) func_lo2o_result=${1} ;; - esac]) - - _LT_PROG_FUNCTION_REPLACE([func_xform], [ func_xform_result=${1%.*}.lo]) - - _LT_PROG_FUNCTION_REPLACE([func_arith], [ func_arith_result=$(( $[*] ))]) - - _LT_PROG_FUNCTION_REPLACE([func_len], [ func_len_result=${#1}]) -fi - -if test x"$lt_shell_append" = xyes; then - _LT_PROG_FUNCTION_REPLACE([func_append], [ eval "${1}+=\\${2}"]) - - _LT_PROG_FUNCTION_REPLACE([func_append_quoted], [dnl - func_quote_for_eval "${2}" -dnl m4 expansion turns \\\\ into \\, and then the shell eval turns that into \ - eval "${1}+=\\\\ \\$func_quote_for_eval_result"]) - - # Save a `func_append' function call where possible by direct use of '+=' - sed -e 's%func_append \([[a-zA-Z_]]\{1,\}\) "%\1+="%g' $cfgfile > $cfgfile.tmp \ - && mv -f "$cfgfile.tmp" "$cfgfile" \ - || (rm -f "$cfgfile" && cp "$cfgfile.tmp" "$cfgfile" && rm -f "$cfgfile.tmp") - test 0 -eq $? || _lt_function_replace_fail=: -else - # Save a `func_append' function call even when '+=' is not available - sed -e 's%func_append \([[a-zA-Z_]]\{1,\}\) "%\1="$\1%g' $cfgfile > $cfgfile.tmp \ - && mv -f "$cfgfile.tmp" "$cfgfile" \ - || (rm -f "$cfgfile" && cp "$cfgfile.tmp" "$cfgfile" && rm -f "$cfgfile.tmp") - test 0 -eq $? || _lt_function_replace_fail=: -fi - -if test x"$_lt_function_replace_fail" = x":"; then - AC_MSG_WARN([Unable to substitute extended shell functions in $ofile]) -fi -]) - # _LT_PATH_CONVERSION_FUNCTIONS # ----------------------------- -# Determine which file name conversion functions should be used by +# Determine what file name conversion functions should be used by # func_to_host_file (and, implicitly, by func_to_host_path). These are needed # for certain cross-compile configurations and native mingw. m4_defun([_LT_PATH_CONVERSION_FUNCTIONS], diff --git a/gtsam/3rdparty/GeographicLib/m4/ltoptions.m4 b/gtsam/3rdparty/GeographicLib/m4/ltoptions.m4 index 5d9acd8e2..94b082976 100644 --- a/gtsam/3rdparty/GeographicLib/m4/ltoptions.m4 +++ b/gtsam/3rdparty/GeographicLib/m4/ltoptions.m4 @@ -1,14 +1,14 @@ # Helper functions for option handling. -*- Autoconf -*- # -# Copyright (C) 2004, 2005, 2007, 2008, 2009 Free Software Foundation, -# Inc. +# Copyright (C) 2004-2005, 2007-2009, 2011-2015 Free Software +# Foundation, Inc. # Written by Gary V. Vaughan, 2004 # # This file is free software; the Free Software Foundation gives # unlimited permission to copy and/or distribute it, with or without # modifications, as long as this notice is preserved. -# serial 7 ltoptions.m4 +# serial 8 ltoptions.m4 # This is to help aclocal find these macros, as it can't see m4_define. AC_DEFUN([LTOPTIONS_VERSION], [m4_if([1])]) @@ -29,7 +29,7 @@ m4_define([_LT_SET_OPTION], [m4_define(_LT_MANGLE_OPTION([$1], [$2]))dnl m4_ifdef(_LT_MANGLE_DEFUN([$1], [$2]), _LT_MANGLE_DEFUN([$1], [$2]), - [m4_warning([Unknown $1 option `$2'])])[]dnl + [m4_warning([Unknown $1 option '$2'])])[]dnl ]) @@ -75,13 +75,15 @@ m4_if([$1],[LT_INIT],[ dnl dnl If no reference was made to various pairs of opposing options, then dnl we run the default mode handler for the pair. For example, if neither - dnl `shared' nor `disable-shared' was passed, we enable building of shared + dnl 'shared' nor 'disable-shared' was passed, we enable building of shared dnl archives by default: _LT_UNLESS_OPTIONS([LT_INIT], [shared disable-shared], [_LT_ENABLE_SHARED]) _LT_UNLESS_OPTIONS([LT_INIT], [static disable-static], [_LT_ENABLE_STATIC]) _LT_UNLESS_OPTIONS([LT_INIT], [pic-only no-pic], [_LT_WITH_PIC]) _LT_UNLESS_OPTIONS([LT_INIT], [fast-install disable-fast-install], - [_LT_ENABLE_FAST_INSTALL]) + [_LT_ENABLE_FAST_INSTALL]) + _LT_UNLESS_OPTIONS([LT_INIT], [aix-soname=aix aix-soname=both aix-soname=svr4], + [_LT_WITH_AIX_SONAME([aix])]) ]) ])# _LT_SET_OPTIONS @@ -112,7 +114,7 @@ AU_DEFUN([AC_LIBTOOL_DLOPEN], [_LT_SET_OPTION([LT_INIT], [dlopen]) AC_DIAGNOSE([obsolete], [$0: Remove this warning and the call to _LT_SET_OPTION when you -put the `dlopen' option into LT_INIT's first parameter.]) +put the 'dlopen' option into LT_INIT's first parameter.]) ]) dnl aclocal-1.4 backwards compatibility: @@ -148,7 +150,7 @@ AU_DEFUN([AC_LIBTOOL_WIN32_DLL], _LT_SET_OPTION([LT_INIT], [win32-dll]) AC_DIAGNOSE([obsolete], [$0: Remove this warning and the call to _LT_SET_OPTION when you -put the `win32-dll' option into LT_INIT's first parameter.]) +put the 'win32-dll' option into LT_INIT's first parameter.]) ]) dnl aclocal-1.4 backwards compatibility: @@ -157,9 +159,9 @@ dnl AC_DEFUN([AC_LIBTOOL_WIN32_DLL], []) # _LT_ENABLE_SHARED([DEFAULT]) # ---------------------------- -# implement the --enable-shared flag, and supports the `shared' and -# `disable-shared' LT_INIT options. -# DEFAULT is either `yes' or `no'. If omitted, it defaults to `yes'. +# implement the --enable-shared flag, and supports the 'shared' and +# 'disable-shared' LT_INIT options. +# DEFAULT is either 'yes' or 'no'. If omitted, it defaults to 'yes'. m4_define([_LT_ENABLE_SHARED], [m4_define([_LT_ENABLE_SHARED_DEFAULT], [m4_if($1, no, no, yes)])dnl AC_ARG_ENABLE([shared], @@ -172,14 +174,14 @@ AC_ARG_ENABLE([shared], *) enable_shared=no # Look at the argument we got. We use all the common list separators. - lt_save_ifs="$IFS"; IFS="${IFS}$PATH_SEPARATOR," + lt_save_ifs=$IFS; IFS=$IFS$PATH_SEPARATOR, for pkg in $enableval; do - IFS="$lt_save_ifs" + IFS=$lt_save_ifs if test "X$pkg" = "X$p"; then enable_shared=yes fi done - IFS="$lt_save_ifs" + IFS=$lt_save_ifs ;; esac], [enable_shared=]_LT_ENABLE_SHARED_DEFAULT) @@ -211,9 +213,9 @@ dnl AC_DEFUN([AM_DISABLE_SHARED], []) # _LT_ENABLE_STATIC([DEFAULT]) # ---------------------------- -# implement the --enable-static flag, and support the `static' and -# `disable-static' LT_INIT options. -# DEFAULT is either `yes' or `no'. If omitted, it defaults to `yes'. +# implement the --enable-static flag, and support the 'static' and +# 'disable-static' LT_INIT options. +# DEFAULT is either 'yes' or 'no'. If omitted, it defaults to 'yes'. m4_define([_LT_ENABLE_STATIC], [m4_define([_LT_ENABLE_STATIC_DEFAULT], [m4_if($1, no, no, yes)])dnl AC_ARG_ENABLE([static], @@ -226,14 +228,14 @@ AC_ARG_ENABLE([static], *) enable_static=no # Look at the argument we got. We use all the common list separators. - lt_save_ifs="$IFS"; IFS="${IFS}$PATH_SEPARATOR," + lt_save_ifs=$IFS; IFS=$IFS$PATH_SEPARATOR, for pkg in $enableval; do - IFS="$lt_save_ifs" + IFS=$lt_save_ifs if test "X$pkg" = "X$p"; then enable_static=yes fi done - IFS="$lt_save_ifs" + IFS=$lt_save_ifs ;; esac], [enable_static=]_LT_ENABLE_STATIC_DEFAULT) @@ -265,9 +267,9 @@ dnl AC_DEFUN([AM_DISABLE_STATIC], []) # _LT_ENABLE_FAST_INSTALL([DEFAULT]) # ---------------------------------- -# implement the --enable-fast-install flag, and support the `fast-install' -# and `disable-fast-install' LT_INIT options. -# DEFAULT is either `yes' or `no'. If omitted, it defaults to `yes'. +# implement the --enable-fast-install flag, and support the 'fast-install' +# and 'disable-fast-install' LT_INIT options. +# DEFAULT is either 'yes' or 'no'. If omitted, it defaults to 'yes'. m4_define([_LT_ENABLE_FAST_INSTALL], [m4_define([_LT_ENABLE_FAST_INSTALL_DEFAULT], [m4_if($1, no, no, yes)])dnl AC_ARG_ENABLE([fast-install], @@ -280,14 +282,14 @@ AC_ARG_ENABLE([fast-install], *) enable_fast_install=no # Look at the argument we got. We use all the common list separators. - lt_save_ifs="$IFS"; IFS="${IFS}$PATH_SEPARATOR," + lt_save_ifs=$IFS; IFS=$IFS$PATH_SEPARATOR, for pkg in $enableval; do - IFS="$lt_save_ifs" + IFS=$lt_save_ifs if test "X$pkg" = "X$p"; then enable_fast_install=yes fi done - IFS="$lt_save_ifs" + IFS=$lt_save_ifs ;; esac], [enable_fast_install=]_LT_ENABLE_FAST_INSTALL_DEFAULT) @@ -304,14 +306,14 @@ AU_DEFUN([AC_ENABLE_FAST_INSTALL], [_LT_SET_OPTION([LT_INIT], m4_if([$1], [no], [disable-])[fast-install]) AC_DIAGNOSE([obsolete], [$0: Remove this warning and the call to _LT_SET_OPTION when you put -the `fast-install' option into LT_INIT's first parameter.]) +the 'fast-install' option into LT_INIT's first parameter.]) ]) AU_DEFUN([AC_DISABLE_FAST_INSTALL], [_LT_SET_OPTION([LT_INIT], [disable-fast-install]) AC_DIAGNOSE([obsolete], [$0: Remove this warning and the call to _LT_SET_OPTION when you put -the `disable-fast-install' option into LT_INIT's first parameter.]) +the 'disable-fast-install' option into LT_INIT's first parameter.]) ]) dnl aclocal-1.4 backwards compatibility: @@ -319,11 +321,64 @@ dnl AC_DEFUN([AC_ENABLE_FAST_INSTALL], []) dnl AC_DEFUN([AM_DISABLE_FAST_INSTALL], []) +# _LT_WITH_AIX_SONAME([DEFAULT]) +# ---------------------------------- +# implement the --with-aix-soname flag, and support the `aix-soname=aix' +# and `aix-soname=both' and `aix-soname=svr4' LT_INIT options. DEFAULT +# is either `aix', `both' or `svr4'. If omitted, it defaults to `aix'. +m4_define([_LT_WITH_AIX_SONAME], +[m4_define([_LT_WITH_AIX_SONAME_DEFAULT], [m4_if($1, svr4, svr4, m4_if($1, both, both, aix))])dnl +shared_archive_member_spec= +case $host,$enable_shared in +power*-*-aix[[5-9]]*,yes) + AC_MSG_CHECKING([which variant of shared library versioning to provide]) + AC_ARG_WITH([aix-soname], + [AS_HELP_STRING([--with-aix-soname=aix|svr4|both], + [shared library versioning (aka "SONAME") variant to provide on AIX, @<:@default=]_LT_WITH_AIX_SONAME_DEFAULT[@:>@.])], + [case $withval in + aix|svr4|both) + ;; + *) + AC_MSG_ERROR([Unknown argument to --with-aix-soname]) + ;; + esac + lt_cv_with_aix_soname=$with_aix_soname], + [AC_CACHE_VAL([lt_cv_with_aix_soname], + [lt_cv_with_aix_soname=]_LT_WITH_AIX_SONAME_DEFAULT) + with_aix_soname=$lt_cv_with_aix_soname]) + AC_MSG_RESULT([$with_aix_soname]) + if test aix != "$with_aix_soname"; then + # For the AIX way of multilib, we name the shared archive member + # based on the bitwidth used, traditionally 'shr.o' or 'shr_64.o', + # and 'shr.imp' or 'shr_64.imp', respectively, for the Import File. + # Even when GNU compilers ignore OBJECT_MODE but need '-maix64' flag, + # the AIX toolchain works better with OBJECT_MODE set (default 32). + if test 64 = "${OBJECT_MODE-32}"; then + shared_archive_member_spec=shr_64 + else + shared_archive_member_spec=shr + fi + fi + ;; +*) + with_aix_soname=aix + ;; +esac + +_LT_DECL([], [shared_archive_member_spec], [0], + [Shared archive member basename, for filename based shared library versioning on AIX])dnl +])# _LT_WITH_AIX_SONAME + +LT_OPTION_DEFINE([LT_INIT], [aix-soname=aix], [_LT_WITH_AIX_SONAME([aix])]) +LT_OPTION_DEFINE([LT_INIT], [aix-soname=both], [_LT_WITH_AIX_SONAME([both])]) +LT_OPTION_DEFINE([LT_INIT], [aix-soname=svr4], [_LT_WITH_AIX_SONAME([svr4])]) + + # _LT_WITH_PIC([MODE]) # -------------------- -# implement the --with-pic flag, and support the `pic-only' and `no-pic' +# implement the --with-pic flag, and support the 'pic-only' and 'no-pic' # LT_INIT options. -# MODE is either `yes' or `no'. If omitted, it defaults to `both'. +# MODE is either 'yes' or 'no'. If omitted, it defaults to 'both'. m4_define([_LT_WITH_PIC], [AC_ARG_WITH([pic], [AS_HELP_STRING([--with-pic@<:@=PKGS@:>@], @@ -334,19 +389,17 @@ m4_define([_LT_WITH_PIC], *) pic_mode=default # Look at the argument we got. We use all the common list separators. - lt_save_ifs="$IFS"; IFS="${IFS}$PATH_SEPARATOR," + lt_save_ifs=$IFS; IFS=$IFS$PATH_SEPARATOR, for lt_pkg in $withval; do - IFS="$lt_save_ifs" + IFS=$lt_save_ifs if test "X$lt_pkg" = "X$lt_p"; then pic_mode=yes fi done - IFS="$lt_save_ifs" + IFS=$lt_save_ifs ;; esac], - [pic_mode=default]) - -test -z "$pic_mode" && pic_mode=m4_default([$1], [default]) + [pic_mode=m4_default([$1], [default])]) _LT_DECL([], [pic_mode], [0], [What type of objects to build])dnl ])# _LT_WITH_PIC @@ -359,7 +412,7 @@ AU_DEFUN([AC_LIBTOOL_PICMODE], [_LT_SET_OPTION([LT_INIT], [pic-only]) AC_DIAGNOSE([obsolete], [$0: Remove this warning and the call to _LT_SET_OPTION when you -put the `pic-only' option into LT_INIT's first parameter.]) +put the 'pic-only' option into LT_INIT's first parameter.]) ]) dnl aclocal-1.4 backwards compatibility: diff --git a/gtsam/3rdparty/GeographicLib/m4/ltsugar.m4 b/gtsam/3rdparty/GeographicLib/m4/ltsugar.m4 index 9000a057d..48bc9344a 100644 --- a/gtsam/3rdparty/GeographicLib/m4/ltsugar.m4 +++ b/gtsam/3rdparty/GeographicLib/m4/ltsugar.m4 @@ -1,6 +1,7 @@ # ltsugar.m4 -- libtool m4 base layer. -*-Autoconf-*- # -# Copyright (C) 2004, 2005, 2007, 2008 Free Software Foundation, Inc. +# Copyright (C) 2004-2005, 2007-2008, 2011-2015 Free Software +# Foundation, Inc. # Written by Gary V. Vaughan, 2004 # # This file is free software; the Free Software Foundation gives @@ -33,7 +34,7 @@ m4_define([_lt_join], # ------------ # Manipulate m4 lists. # These macros are necessary as long as will still need to support -# Autoconf-2.59 which quotes differently. +# Autoconf-2.59, which quotes differently. m4_define([lt_car], [[$1]]) m4_define([lt_cdr], [m4_if([$#], 0, [m4_fatal([$0: cannot be called without arguments])], @@ -44,7 +45,7 @@ m4_define([lt_unquote], $1) # lt_append(MACRO-NAME, STRING, [SEPARATOR]) # ------------------------------------------ -# Redefine MACRO-NAME to hold its former content plus `SEPARATOR'`STRING'. +# Redefine MACRO-NAME to hold its former content plus 'SEPARATOR''STRING'. # Note that neither SEPARATOR nor STRING are expanded; they are appended # to MACRO-NAME as is (leaving the expansion for when MACRO-NAME is invoked). # No SEPARATOR is output if MACRO-NAME was previously undefined (different diff --git a/gtsam/3rdparty/GeographicLib/m4/ltversion.m4 b/gtsam/3rdparty/GeographicLib/m4/ltversion.m4 index 07a8602d4..fa04b52a3 100644 --- a/gtsam/3rdparty/GeographicLib/m4/ltversion.m4 +++ b/gtsam/3rdparty/GeographicLib/m4/ltversion.m4 @@ -1,6 +1,6 @@ # ltversion.m4 -- version numbers -*- Autoconf -*- # -# Copyright (C) 2004 Free Software Foundation, Inc. +# Copyright (C) 2004, 2011-2015 Free Software Foundation, Inc. # Written by Scott James Remnant, 2004 # # This file is free software; the Free Software Foundation gives @@ -9,15 +9,15 @@ # @configure_input@ -# serial 3337 ltversion.m4 +# serial 4179 ltversion.m4 # This file is part of GNU Libtool -m4_define([LT_PACKAGE_VERSION], [2.4.2]) -m4_define([LT_PACKAGE_REVISION], [1.3337]) +m4_define([LT_PACKAGE_VERSION], [2.4.6]) +m4_define([LT_PACKAGE_REVISION], [2.4.6]) AC_DEFUN([LTVERSION_VERSION], -[macro_version='2.4.2' -macro_revision='1.3337' +[macro_version='2.4.6' +macro_revision='2.4.6' _LT_DECL(, macro_version, 0, [Which release of libtool.m4 was used?]) _LT_DECL(, macro_revision, 0) ]) diff --git a/gtsam/3rdparty/GeographicLib/m4/lt~obsolete.m4 b/gtsam/3rdparty/GeographicLib/m4/lt~obsolete.m4 index c573da90c..c6b26f88f 100644 --- a/gtsam/3rdparty/GeographicLib/m4/lt~obsolete.m4 +++ b/gtsam/3rdparty/GeographicLib/m4/lt~obsolete.m4 @@ -1,6 +1,7 @@ # lt~obsolete.m4 -- aclocal satisfying obsolete definitions. -*-Autoconf-*- # -# Copyright (C) 2004, 2005, 2007, 2009 Free Software Foundation, Inc. +# Copyright (C) 2004-2005, 2007, 2009, 2011-2015 Free Software +# Foundation, Inc. # Written by Scott James Remnant, 2004. # # This file is free software; the Free Software Foundation gives @@ -11,7 +12,7 @@ # These exist entirely to fool aclocal when bootstrapping libtool. # -# In the past libtool.m4 has provided macros via AC_DEFUN (or AU_DEFUN) +# In the past libtool.m4 has provided macros via AC_DEFUN (or AU_DEFUN), # which have later been changed to m4_define as they aren't part of the # exported API, or moved to Autoconf or Automake where they belong. # @@ -25,7 +26,7 @@ # included after everything else. This provides aclocal with the # AC_DEFUNs it wants, but when m4 processes it, it doesn't do anything # because those macros already exist, or will be overwritten later. -# We use AC_DEFUN over AU_DEFUN for compatibility with aclocal-1.6. +# We use AC_DEFUN over AU_DEFUN for compatibility with aclocal-1.6. # # Anytime we withdraw an AC_DEFUN or AU_DEFUN, remember to add it here. # Yes, that means every name once taken will need to remain here until diff --git a/gtsam/3rdparty/GeographicLib/m4/pkg.m4 b/gtsam/3rdparty/GeographicLib/m4/pkg.m4 new file mode 100644 index 000000000..8d24e9170 --- /dev/null +++ b/gtsam/3rdparty/GeographicLib/m4/pkg.m4 @@ -0,0 +1,287 @@ +# pkg.m4 - Macros to locate and utilise pkg-config. -*- Autoconf -*- +# serial 1 (pkg-config-0.24) +# +# Copyright © 2004 Scott James Remnant . +# +# 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 2 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, write to the Free Software +# Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. +# +# As a special exception to the GNU General Public License, if you +# distribute this file as part of a program that contains a +# configuration script generated by Autoconf, you may include it under +# the same distribution terms that you use for the rest of that program. + +# PKG_PROG_PKG_CONFIG([MIN-VERSION]) +# ---------------------------------- +AC_DEFUN([PKG_PROG_PKG_CONFIG], +[m4_pattern_forbid([^_?PKG_[A-Z_]+$]) +m4_pattern_allow([^PKG_CONFIG(_(PATH|LIBDIR|SYSROOT_DIR|ALLOW_SYSTEM_(CFLAGS|LIBS)))?$]) +m4_pattern_allow([^PKG_CONFIG_(DISABLE_UNINSTALLED|TOP_BUILD_DIR|DEBUG_SPEW)$]) +AC_ARG_VAR([PKG_CONFIG], [path to pkg-config utility]) +AC_ARG_VAR([PKG_CONFIG_PATH], [directories to add to pkg-config's search path]) +AC_ARG_VAR([PKG_CONFIG_LIBDIR], [path overriding pkg-config's built-in search path]) + +if test "x$ac_cv_env_PKG_CONFIG_set" != "xset"; then + AC_PATH_TOOL([PKG_CONFIG], [pkg-config]) +fi +if test -n "$PKG_CONFIG"; then + _pkg_min_version=m4_default([$1], [0.9.0]) + AC_MSG_CHECKING([pkg-config is at least version $_pkg_min_version]) + if $PKG_CONFIG --atleast-pkgconfig-version $_pkg_min_version; then + AC_MSG_RESULT([yes]) + else + AC_MSG_RESULT([no]) + PKG_CONFIG="" + fi +fi[]dnl +])# PKG_PROG_PKG_CONFIG + +# PKG_CHECK_EXISTS(MODULES, [ACTION-IF-FOUND], [ACTION-IF-NOT-FOUND]) +# +# Check to see whether a particular set of modules exists. Similar +# to PKG_CHECK_MODULES(), but does not set variables or print errors. +# +# Please remember that m4 expands AC_REQUIRE([PKG_PROG_PKG_CONFIG]) +# only at the first occurence in configure.ac, so if the first place +# it's called might be skipped (such as if it is within an "if", you +# have to call PKG_CHECK_EXISTS manually +# -------------------------------------------------------------- +AC_DEFUN([PKG_CHECK_EXISTS], +[AC_REQUIRE([PKG_PROG_PKG_CONFIG])dnl +if test -n "$PKG_CONFIG" && \ + AC_RUN_LOG([$PKG_CONFIG --exists --print-errors "$1"]); then + m4_default([$2], [:]) +m4_ifvaln([$3], [else + $3])dnl +fi]) + +# _PKG_CONFIG([VARIABLE], [COMMAND], [MODULES]) +# --------------------------------------------- +m4_define([_PKG_CONFIG], +[if test -n "$$1"; then + pkg_cv_[]$1="$$1" + elif test -n "$PKG_CONFIG"; then + PKG_CHECK_EXISTS([$3], + [pkg_cv_[]$1=`$PKG_CONFIG --[]$2 "$3" 2>/dev/null` + test "x$?" != "x0" && pkg_failed=yes ], + [pkg_failed=yes]) + else + pkg_failed=untried +fi[]dnl +])# _PKG_CONFIG + +# _PKG_SHORT_ERRORS_SUPPORTED +# ----------------------------- +AC_DEFUN([_PKG_SHORT_ERRORS_SUPPORTED], +[AC_REQUIRE([PKG_PROG_PKG_CONFIG]) +if $PKG_CONFIG --atleast-pkgconfig-version 0.20; then + _pkg_short_errors_supported=yes +else + _pkg_short_errors_supported=no +fi[]dnl +])# _PKG_SHORT_ERRORS_SUPPORTED + + +# PKG_CHECK_MODULES(VARIABLE-PREFIX, MODULES, [ACTION-IF-FOUND], +# [ACTION-IF-NOT-FOUND]) +# +# +# Note that if there is a possibility the first call to +# PKG_CHECK_MODULES might not happen, you should be sure to include an +# explicit call to PKG_PROG_PKG_CONFIG in your configure.ac +# +# +# -------------------------------------------------------------- +AC_DEFUN([PKG_CHECK_MODULES], +[AC_REQUIRE([PKG_PROG_PKG_CONFIG])dnl +AC_ARG_VAR([$1][_CFLAGS], [C compiler flags for $1, overriding pkg-config])dnl +AC_ARG_VAR([$1][_LIBS], [linker flags for $1, overriding pkg-config])dnl + +pkg_failed=no +AC_MSG_CHECKING([for $1]) + +_PKG_CONFIG([$1][_CFLAGS], [cflags], [$2]) +_PKG_CONFIG([$1][_LIBS], [libs], [$2]) + +m4_define([_PKG_TEXT], [Alternatively, you may set the environment variables $1[]_CFLAGS +and $1[]_LIBS to avoid the need to call pkg-config. +See the pkg-config man page for more details.]) + +if test $pkg_failed = yes; then + AC_MSG_RESULT([no]) + _PKG_SHORT_ERRORS_SUPPORTED + if test $_pkg_short_errors_supported = yes; then + $1[]_PKG_ERRORS=`$PKG_CONFIG --short-errors --print-errors --cflags --libs "$2" 2>&1` + else + $1[]_PKG_ERRORS=`$PKG_CONFIG --print-errors --cflags --libs "$2" 2>&1` + fi + # Put the nasty error message in config.log where it belongs + echo "$$1[]_PKG_ERRORS" >&AS_MESSAGE_LOG_FD + + m4_default([$4], [AC_MSG_ERROR( +[Package requirements ($2) were not met: + +$$1_PKG_ERRORS + +Consider adjusting the PKG_CONFIG_PATH environment variable if you +installed software in a non-standard prefix. + +_PKG_TEXT])[]dnl + ]) +elif test $pkg_failed = untried; then + AC_MSG_RESULT([no]) + m4_default([$4], [AC_MSG_FAILURE( +[The pkg-config script could not be found or is too old. Make sure it +is in your PATH or set the PKG_CONFIG environment variable to the full +path to pkg-config. + +_PKG_TEXT + +To get pkg-config, see .])[]dnl + ]) +else + $1[]_CFLAGS=$pkg_cv_[]$1[]_CFLAGS + $1[]_LIBS=$pkg_cv_[]$1[]_LIBS + AC_MSG_RESULT([yes]) + $3 +fi[]dnl +])# PKG_CHECK_MODULES + +# PKG_INSTALLDIR(DIRECTORY) +# ------------------------- +# Substitutes the variable pkgconfigdir as the location where a module +# should install pkg-config .pc files. By default the directory is +# $libdir/pkgconfig, but the default can be changed by passing +# DIRECTORY. The user can override through the --with-pkgconfigdir +# parameter. +AC_DEFUN([PKG_INSTALLDIR], +[m4_pushdef([pkg_default], [m4_default([$1], ['${libdir}/pkgconfig'])]) +m4_pushdef([pkg_description], + [pkg-config installation directory @<:@]pkg_default[@:>@]) +AC_ARG_WITH([pkgconfigdir], + [AS_HELP_STRING([--with-pkgconfigdir], pkg_description)],, + [with_pkgconfigdir=]pkg_default) +AC_SUBST([pkgconfigdir], [$with_pkgconfigdir]) +m4_popdef([pkg_default]) +m4_popdef([pkg_description]) +]) dnl PKG_INSTALLDIR + + +# PKG_NOARCH_INSTALLDIR(DIRECTORY) +# ------------------------- +# Substitutes the variable noarch_pkgconfigdir as the location where a +# module should install arch-independent pkg-config .pc files. By +# default the directory is $datadir/pkgconfig, but the default can be +# changed by passing DIRECTORY. The user can override through the +# --with-noarch-pkgconfigdir parameter. +AC_DEFUN([PKG_NOARCH_INSTALLDIR], +[m4_pushdef([pkg_default], [m4_default([$1], ['${datadir}/pkgconfig'])]) +m4_pushdef([pkg_description], + [pkg-config arch-independent installation directory @<:@]pkg_default[@:>@]) +AC_ARG_WITH([noarch-pkgconfigdir], + [AS_HELP_STRING([--with-noarch-pkgconfigdir], pkg_description)],, + [with_noarch_pkgconfigdir=]pkg_default) +AC_SUBST([noarch_pkgconfigdir], [$with_noarch_pkgconfigdir]) +m4_popdef([pkg_default]) +m4_popdef([pkg_description]) +]) dnl PKG_NOARCH_INSTALLDIR + + +# PKG_CHECK_VAR(VARIABLE, MODULE, CONFIG-VARIABLE, +# [ACTION-IF-FOUND], [ACTION-IF-NOT-FOUND]) +# ------------------------------------------- +# Retrieves the value of the pkg-config variable for the given module. +AC_DEFUN([PKG_CHECK_VAR], +[AC_REQUIRE([PKG_PROG_PKG_CONFIG])dnl +AC_ARG_VAR([$1], [value of $3 for $2, overriding pkg-config])dnl + +_PKG_CONFIG([$1], [variable="][$3]["], [$2]) +AS_VAR_COPY([$1], [pkg_cv_][$1]) + +AS_VAR_IF([$1], [""], [$5], [$4])dnl +])# PKG_CHECK_VAR + +# PKG_WITH_MODULES(VARIABLE-PREFIX, MODULES, +# [ACTION-IF-FOUND],[ACTION-IF-NOT-FOUND], +# [DESCRIPTION], [DEFAULT]) +# +# Prepare a "--with-" configure option using the lowercase [VARIABLE-PREFIX] +# name, merging the behaviour of AC_ARG_WITH and PKG_CHECK_MODULES in a single +# macro +# +# -------------------------------------------------------------- +AC_DEFUN([PKG_WITH_MODULES], +[ +m4_pushdef([with_arg], m4_tolower([$1])) + +m4_pushdef([description], + [m4_default([$5], [build with ]with_arg[ support])]) + +m4_pushdef([def_arg], [m4_default([$6], [auto])]) +m4_pushdef([def_action_if_found], [AS_TR_SH([with_]with_arg)=yes]) +m4_pushdef([def_action_if_not_found], [AS_TR_SH([with_]with_arg)=no]) + +m4_case(def_arg, + [yes],[m4_pushdef([with_without], [--without-]with_arg)], + [m4_pushdef([with_without],[--with-]with_arg)]) + +AC_ARG_WITH(with_arg, + AS_HELP_STRING(with_without, description[ @<:@default=]def_arg[@:>@]),, + [AS_TR_SH([with_]with_arg)=def_arg]) + +AS_CASE([$AS_TR_SH([with_]with_arg)], + [yes],[PKG_CHECK_MODULES([$1],[$2],$3,$4)], + [auto],[PKG_CHECK_MODULES([$1],[$2], + [m4_n([def_action_if_found]) $3], + [m4_n([def_action_if_not_found]) $4])]) + +m4_popdef([with_arg]) +m4_popdef([description]) +m4_popdef([def_arg]) + +]) dnl PKG_WITH_MODULES + +# PKG_HAVE_WITH_MODULES(VARIABLE-PREFIX, MODULES, +# [DESCRIPTION], [DEFAULT]) +# +# Convenience macro to trigger AM_CONDITIONAL after +# PKG_WITH_MODULES check. +# +# HAVE_[VARIABLE-PREFIX] is exported as make variable. +# +# -------------------------------------------------------------- +AC_DEFUN([PKG_HAVE_WITH_MODULES], +[ +PKG_WITH_MODULES([$1],[$2],,,[$3],[$4]) + +AM_CONDITIONAL([HAVE_][$1], + [test "$AS_TR_SH([with_]m4_tolower([$1]))" = "yes"]) +]) + +# PKG_HAVE_DEFINE_WITH_MODULES(VARIABLE-PREFIX, MODULES, +# [DESCRIPTION], [DEFAULT]) +# +# Convenience macro to run AM_CONDITIONAL and AC_DEFINE after +# PKG_WITH_MODULES check. +# +# HAVE_[VARIABLE-PREFIX] is exported as make and preprocessor variable. +# +# -------------------------------------------------------------- +AC_DEFUN([PKG_HAVE_DEFINE_WITH_MODULES], +[ +PKG_HAVE_WITH_MODULES([$1],[$2],[$3],[$4]) + +AS_IF([test "$AS_TR_SH([with_]m4_tolower([$1]))" = "yes"], + [AC_DEFINE([HAVE_][$1], 1, [Enable ]m4_tolower([$1])[ support])]) +]) diff --git a/gtsam/3rdparty/GeographicLib/man/CMakeLists.txt b/gtsam/3rdparty/GeographicLib/man/CMakeLists.txt index ccdf213c3..633df5690 100644 --- a/gtsam/3rdparty/GeographicLib/man/CMakeLists.txt +++ b/gtsam/3rdparty/GeographicLib/man/CMakeLists.txt @@ -15,6 +15,7 @@ endif () set (MANPAGES) set (USAGE) set (HTMLMAN) +set (SYSMANPAGES) # Loop over the tools building up lists of the derived files. Also in # maintainer mode, specify how the derived files are created. The sed @@ -32,10 +33,11 @@ foreach (TOOL ${TOOLS}) ${CMAKE_CURRENT_SOURCE_DIR}/${TOOL}.pod > ${TOOL}.1 COMMENT "Building man page for ${TOOL}" MAIN_DEPENDENCY ${TOOL}.pod) - add_custom_command (OUTPUT ${TOOL}.1.html - COMMAND - pod2html --title "'${TOOL}(1)'" --noindex ${CMAKE_CURRENT_SOURCE_DIR}/${TOOL}.pod | - sed -e 's%%%' + add_custom_command (OUTPUT ${TOOL}.1.html COMMAND + pod2html --title "'${TOOL}(1)'" + --noindex ${CMAKE_CURRENT_SOURCE_DIR}/${TOOL}.pod | + sed + -e 's%%%' -e 's%\\\([^<>]*\\\)\(\\\(.\\\)\)%&%'g > ${TOOL}.1.html && cp ${TOOL}.1.html ../doc/html-stage/ COMMENT "Building html version of man page for ${TOOL}" @@ -69,6 +71,14 @@ foreach (TOOL ${TOOLS}) endif () endforeach () +if (NOT WIN32) + foreach (SCRIPT ${SCRIPTS}) + string (REPLACE geographiclib-get- "" DATA ${SCRIPT}) + set (SYSMANPAGES ${SYSMANPAGES} ${CMAKE_CURRENT_BINARY_DIR}/${SCRIPT}.8) + configure_file (script.8.in ${SCRIPT}.8 @ONLY) + endforeach () +endif () + # Add the extra maintainer tasks into the dependency list. The # distrib-man target copies the derived documentation files into the # source tree. @@ -84,11 +94,14 @@ if (MAINTAINER) add_custom_command (TARGET distrib-man COMMAND for f in ${MANPAGES} ${USAGE} ${HTMLMAN}\; do - cmp "$$f" ${CMAKE_CURRENT_SOURCE_DIR}/`basename "$$f" ` - >/dev/null 2>&1 || - install -m 644 "$$f" ${CMAKE_CURRENT_SOURCE_DIR}\; done + install -C -m 644 "$$f" ${CMAKE_CURRENT_SOURCE_DIR}\; done COMMENT "Installing man documentation page in source tree") +else () + add_custom_target (htmlman ALL DEPENDS ${HTMLMAN}) endif () # Install the man pages. install (FILES ${MANPAGES} DESTINATION share/man/man1) +if (NOT WIN32) + install (FILES ${SYSMANPAGES} DESTINATION share/man/man8) +endif () diff --git a/gtsam/3rdparty/GeographicLib/man/CartConvert.1 b/gtsam/3rdparty/GeographicLib/man/CartConvert.1 index 9a2f74660..32c04f910 100644 --- a/gtsam/3rdparty/GeographicLib/man/CartConvert.1 +++ b/gtsam/3rdparty/GeographicLib/man/CartConvert.1 @@ -1,4 +1,4 @@ -.\" Automatically generated by Pod::Man 2.25 (Pod::Simple 3.20) +.\" Automatically generated by Pod::Man 4.09 (Pod::Simple 3.35) .\" .\" Standard preamble: .\" ======================================================================== @@ -38,26 +38,31 @@ . ds PI \(*p . ds L" `` . ds R" '' +. ds C` +. ds C' 'br\} .\" .\" Escape single quotes in literal strings from groff's Unicode transform. .ie \n(.g .ds Aq \(aq .el .ds Aq ' .\" -.\" If the F register is turned on, we'll generate index entries on stderr for +.\" If the F register is >0, we'll generate index entries on stderr for .\" titles (.TH), headers (.SH), subsections (.SS), items (.Ip), and index .\" entries marked with X<> in POD. Of course, you'll have to process the .\" output yourself in some meaningful fashion. -.ie \nF \{\ +.\" +.\" Avoid warning from groff about undefined register 'F'. +.de IX +.. +.if !\nF .nr F 0 +.if \nF>0 \{\ . de IX . tm Index:\\$1\t\\n%\t"\\$2" .. -. nr % 0 -. rr F -.\} -.el \{\ -. de IX -.. +. if !\nF==2 \{\ +. nr % 0 +. nr F 2 +. \} .\} .\" .\" Accent mark definitions (@(#)ms.acc 1.5 88/02/08 SMI; from UCB 4.2). @@ -124,7 +129,7 @@ .\" ======================================================================== .\" .IX Title "CARTCONVERT 1" -.TH CARTCONVERT 1 "2014-03-13" "GeographicLib 1.35" "GeographicLib Utilities" +.TH CARTCONVERT 1 "2017-10-05" "GeographicLib 1.49" "GeographicLib Utilities" .\" For nroff, turn off justification. Always turn off hyphenation; it makes .\" way too many mistakes in technical documents. .if n .ad l @@ -133,7 +138,8 @@ CartConvert \-\- convert geodetic coordinates to geocentric or local cartesian .SH "SYNOPSIS" .IX Header "SYNOPSIS" -\&\fBCartConvert\fR [ \fB\-r\fR ] [ \fB\-l\fR \fIlat0\fR \fIlon0\fR \fIh0\fR ] [ \fB\-e\fR \fIa\fR \fIf\fR ] +\&\fBCartConvert\fR [ \fB\-r\fR ] [ \fB\-l\fR \fIlat0\fR \fIlon0\fR \fIh0\fR ] +[ \fB\-e\fR \fIa\fR \fIf\fR ] [ \fB\-w\fR ] [ \fB\-p\fR \fIprec\fR ] [ \fB\-\-comment\-delimiter\fR \fIcommentdelim\fR ] [ \fB\-\-version\fR | \fB\-h\fR | \fB\-\-help\fR ] [ \fB\-\-input\-file\fR \fIinfile\fR | \fB\-\-input\-string\fR \fIinstring\fR ] @@ -153,9 +159,10 @@ origin at \fIlatitude\fR = \fIlat0\fR, \fIlongitude\fR = \fIlon0\fR, \fIheight\f Geodetic coordinates are provided on standard input as a set of lines containing (blank separated) \fIlatitude\fR, \fIlongitude\fR (decimal degrees or degrees, minutes and seconds), and \fIheight\fR above the ellipsoid -(meters). For each set of geodetic coordinates, the corresponding -cartesian coordinates \fIx\fR, \fIy\fR, \fIz\fR (meters) are printed on standard -output. +(meters); for details on the allowed formats for latitude and longitude, +see the \f(CW\*(C`GEOGRAPHIC COORDINATES\*(C'\fR section of \fIGeoConvert\fR\|(1). For each +set of geodetic coordinates, the corresponding cartesian coordinates +\&\fIx\fR, \fIy\fR, \fIz\fR (meters) are printed on standard output. .SH "OPTIONS" .IX Header "OPTIONS" .IP "\fB\-r\fR" 4 @@ -163,16 +170,34 @@ output. perform the reverse projection. \fIx\fR, \fIy\fR, \fIz\fR are given on standard input and each line of standard output gives \fIlatitude\fR, \fIlongitude\fR, \&\fIheight\fR. -.IP "\fB\-e\fR" 4 -.IX Item "-e" -specify the ellipsoid via \fIa\fR \fIf\fR; the equatorial radius is \fIa\fR and -the flattening is \fIf\fR. Setting \fIf\fR = 0 results in a sphere. Specify +.IP "\fB\-l\fR \fIlat0\fR \fIlon0\fR \fIh0\fR" 4 +.IX Item "-l lat0 lon0 h0" +specifies conversions to and from a local cartesion coordinate systems +with origin \fIlat0\fR \fIlon0\fR \fIh0\fR, instead of a geocentric coordinate +system. The \fB\-w\fR flag can be used to swap the default order of the 2 +geographic coordinates, provided that it appears before \fB\-l\fR. +.IP "\fB\-e\fR \fIa\fR \fIf\fR" 4 +.IX Item "-e a f" +specify the ellipsoid via the equatorial radius, \fIa\fR and +the flattening, \fIf\fR. Setting \fIf\fR = 0 results in a sphere. Specify \&\fIf\fR < 0 for a prolate ellipsoid. A simple fraction, e.g., 1/297, -is allowed for \fIf\fR. (Also, if \fIf\fR > 1, the flattening is set to -1/\fIf\fR.) By default, the \s-1WGS84\s0 ellipsoid is used, \fIa\fR = 6378137 m, -\&\fIf\fR = 1/298.257223563. -.IP "\fB\-\-comment\-delimiter\fR" 4 -.IX Item "--comment-delimiter" +is allowed for \fIf\fR. By default, the \s-1WGS84\s0 ellipsoid is used, \fIa\fR = +6378137 m, \fIf\fR = 1/298.257223563. +.IP "\fB\-w\fR" 4 +.IX Item "-w" +toggle the longitude first flag (it starts off); if the flag is on, then +on input and output, longitude precedes latitude (except that, on input, +this can be overridden by a hemisphere designator, \fIN\fR, \fIS\fR, \fIE\fR, +\&\fIW\fR). +.IP "\fB\-p\fR \fIprec\fR" 4 +.IX Item "-p prec" +set the output precision to \fIprec\fR (default 6). \fIprec\fR is the number +of digits after the decimal point for geocentric and local cartesion +coordinates and for the height (in meters). For latitudes and +longitudes (in degrees), the number of digits after the decimal point is +\&\fIprec\fR + 5. +.IP "\fB\-\-comment\-delimiter\fR \fIcommentdelim\fR" 4 +.IX Item "--comment-delimiter commentdelim" set the comment delimiter to \fIcommentdelim\fR (e.g., \*(L"#\*(R" or \*(L"//\*(R"). If set, the input lines will be scanned for this delimiter and, if found, the delimiter and the rest of the line will be removed prior to @@ -187,21 +212,21 @@ print usage and exit. .IP "\fB\-\-help\fR" 4 .IX Item "--help" print full documentation and exit. -.IP "\fB\-\-input\-file\fR" 4 -.IX Item "--input-file" +.IP "\fB\-\-input\-file\fR \fIinfile\fR" 4 +.IX Item "--input-file infile" read input from the file \fIinfile\fR instead of from standard input; a file name of \*(L"\-\*(R" stands for standard input. -.IP "\fB\-\-input\-string\fR" 4 -.IX Item "--input-string" +.IP "\fB\-\-input\-string\fR \fIinstring\fR" 4 +.IX Item "--input-string instring" read input from the string \fIinstring\fR instead of from standard input. All occurrences of the line separator character (default is a semicolon) in \fIinstring\fR are converted to newlines before the reading begins. -.IP "\fB\-\-line\-separator\fR" 4 -.IX Item "--line-separator" +.IP "\fB\-\-line\-separator\fR \fIlinesep\fR" 4 +.IX Item "--line-separator linesep" set the line separator character to \fIlinesep\fR. By default this is a semicolon. -.IP "\fB\-\-output\-file\fR" 4 -.IX Item "--output-file" +.IP "\fB\-\-output\-file\fR \fIoutfile\fR" 4 +.IX Item "--output-file outfile" write output to the file \fIoutfile\fR instead of to standard output; a file name of \*(L"\-\*(R" stands for standard output. .SH "EXAMPLES" @@ -224,12 +249,12 @@ terminate; following lines will be converted. .IX Header "SEE ALSO" The algorithm for converting geocentric to geodetic coordinates is given in Appendix B of C. F. F. Karney, \fIGeodesics on an ellipsoid of -revolution\fR, Feb. 2011; preprint . +revolution\fR, Feb. 2011; preprint . .SH "AUTHOR" .IX Header "AUTHOR" \&\fBCartConvert\fR was written by Charles Karney. .SH "HISTORY" .IX Header "HISTORY" \&\fBCartConvert\fR was added to GeographicLib, -, in 2009\-02. Prior to 2009\-03 it was +, in 2009\-02. Prior to 2009\-03 it was called ECEFConvert. diff --git a/gtsam/3rdparty/GeographicLib/man/CartConvert.1.html b/gtsam/3rdparty/GeographicLib/man/CartConvert.1.html index 17ec77507..c5d88ddb2 100644 --- a/gtsam/3rdparty/GeographicLib/man/CartConvert.1.html +++ b/gtsam/3rdparty/GeographicLib/man/CartConvert.1.html @@ -7,7 +7,7 @@ - + @@ -17,13 +17,13 @@

    SYNOPSIS

    -

    CartConvert [ -r ] [ -l lat0 lon0 h0 ] [ -e a f ] [ --comment-delimiter commentdelim ] [ --version | -h | --help ] [ --input-file infile | --input-string instring ] [ --line-separator linesep ] [ --output-file outfile ]

    +

    CartConvert [ -r ] [ -l lat0 lon0 h0 ] [ -e a f ] [ -w ] [ -p prec ] [ --comment-delimiter commentdelim ] [ --version | -h | --help ] [ --input-file infile | --input-string instring ] [ --line-separator linesep ] [ --output-file outfile ]

    DESCRIPTION

    Convert geodetic coordinates to either geocentric or local cartesian coordinates. Geocentric coordinates have the origin at the center of the earth, with the z axis going thru the north pole, and the x axis thru latitude = 0, longitude = 0. By default, the conversion is to geocentric coordinates. Specifying -l lat0 lon0 h0 causes a local coordinate system to be used with the origin at latitude = lat0, longitude = lon0, height = h0, z normal to the ellipsoid and y due north.

    -

    Geodetic coordinates are provided on standard input as a set of lines containing (blank separated) latitude, longitude (decimal degrees or degrees, minutes and seconds), and height above the ellipsoid (meters). For each set of geodetic coordinates, the corresponding cartesian coordinates x, y, z (meters) are printed on standard output.

    +

    Geodetic coordinates are provided on standard input as a set of lines containing (blank separated) latitude, longitude (decimal degrees or degrees, minutes and seconds), and height above the ellipsoid (meters); for details on the allowed formats for latitude and longitude, see the GEOGRAPHIC COORDINATES section of GeoConvert(1). For each set of geodetic coordinates, the corresponding cartesian coordinates x, y, z (meters) are printed on standard output.

    OPTIONS

    @@ -35,13 +35,31 @@

    perform the reverse projection. x, y, z are given on standard input and each line of standard output gives latitude, longitude, height.

    -
    -e
    +
    -l lat0 lon0 h0
    -

    specify the ellipsoid via a f; the equatorial radius is a and the flattening is f. Setting f = 0 results in a sphere. Specify f < 0 for a prolate ellipsoid. A simple fraction, e.g., 1/297, is allowed for f. (Also, if f > 1, the flattening is set to 1/f.) By default, the WGS84 ellipsoid is used, a = 6378137 m, f = 1/298.257223563.

    +

    specifies conversions to and from a local cartesion coordinate systems with origin lat0 lon0 h0, instead of a geocentric coordinate system. The -w flag can be used to swap the default order of the 2 geographic coordinates, provided that it appears before -l.

    -
    --comment-delimiter
    +
    -e a f
    +
    + +

    specify the ellipsoid via the equatorial radius, a and the flattening, f. Setting f = 0 results in a sphere. Specify f < 0 for a prolate ellipsoid. A simple fraction, e.g., 1/297, is allowed for f. By default, the WGS84 ellipsoid is used, a = 6378137 m, f = 1/298.257223563.

    + +
    +
    -w
    +
    + +

    toggle the longitude first flag (it starts off); if the flag is on, then on input and output, longitude precedes latitude (except that, on input, this can be overridden by a hemisphere designator, N, S, E, W).

    + +
    +
    -p prec
    +
    + +

    set the output precision to prec (default 6). prec is the number of digits after the decimal point for geocentric and local cartesion coordinates and for the height (in meters). For latitudes and longitudes (in degrees), the number of digits after the decimal point is prec + 5.

    + +
    +
    --comment-delimiter commentdelim

    set the comment delimiter to commentdelim (e.g., "#" or "//"). If set, the input lines will be scanned for this delimiter and, if found, the delimiter and the rest of the line will be removed prior to processing and subsequently appended to the output line (separated by a space).

    @@ -65,25 +83,25 @@

    print full documentation and exit.

    -
    --input-file
    +
    --input-file infile

    read input from the file infile instead of from standard input; a file name of "-" stands for standard input.

    -
    --input-string
    +
    --input-string instring

    read input from the string instring instead of from standard input. All occurrences of the line separator character (default is a semicolon) in instring are converted to newlines before the reading begins.

    -
    --line-separator
    +
    --line-separator linesep

    set the line separator character to linesep. By default this is a semicolon.

    -
    --output-file
    +
    --output-file outfile

    write output to the file outfile instead of to standard output; a file name of "-" stands for standard output.

    @@ -106,7 +124,7 @@

    SEE ALSO

    -

    The algorithm for converting geocentric to geodetic coordinates is given in Appendix B of C. F. F. Karney, Geodesics on an ellipsoid of revolution, Feb. 2011; preprint http://arxiv.org/abs/1102.1215.

    +

    The algorithm for converting geocentric to geodetic coordinates is given in Appendix B of C. F. F. Karney, Geodesics on an ellipsoid of revolution, Feb. 2011; preprint https://arxiv.org/abs/1102.1215.

    AUTHOR

    @@ -114,7 +132,7 @@

    HISTORY

    -

    CartConvert was added to GeographicLib, http://geographiclib.sf.net, in 2009-02. Prior to 2009-03 it was called ECEFConvert.

    +

    CartConvert was added to GeographicLib, https://geographiclib.sourceforge.io, in 2009-02. Prior to 2009-03 it was called ECEFConvert.

    diff --git a/gtsam/3rdparty/GeographicLib/man/CartConvert.pod b/gtsam/3rdparty/GeographicLib/man/CartConvert.pod index d68f42a27..ced70a2ad 100644 --- a/gtsam/3rdparty/GeographicLib/man/CartConvert.pod +++ b/gtsam/3rdparty/GeographicLib/man/CartConvert.pod @@ -4,7 +4,8 @@ CartConvert -- convert geodetic coordinates to geocentric or local cartesian =head1 SYNOPSIS -B [ B<-r> ] [ B<-l> I I I ] [ B<-e> I I ] +B [ B<-r> ] [ B<-l> I I I ] +[ B<-e> I I ] [ B<-w> ] [ B<-p> I ] [ B<--comment-delimiter> I ] [ B<--version> | B<-h> | B<--help> ] [ B<--input-file> I | B<--input-string> I ] @@ -25,9 +26,10 @@ I, I normal to the ellipsoid and I due north. Geodetic coordinates are provided on standard input as a set of lines containing (blank separated) I, I (decimal degrees or degrees, minutes and seconds), and I above the ellipsoid -(meters). For each set of geodetic coordinates, the corresponding -cartesian coordinates I, I, I (meters) are printed on standard -output. +(meters); for details on the allowed formats for latitude and longitude, +see the C section of GeoConvert(1). For each +set of geodetic coordinates, the corresponding cartesian coordinates +I, I, I (meters) are printed on standard output. =head1 OPTIONS @@ -39,16 +41,37 @@ perform the reverse projection. I, I, I are given on standard input and each line of standard output gives I, I, I. -=item B<-e> +=item B<-l> I I I -specify the ellipsoid via I I; the equatorial radius is I and -the flattening is I. Setting I = 0 results in a sphere. Specify +specifies conversions to and from a local cartesion coordinate systems +with origin I I I, instead of a geocentric coordinate +system. The B<-w> flag can be used to swap the default order of the 2 +geographic coordinates, provided that it appears before B<-l>. + +=item B<-e> I I + +specify the ellipsoid via the equatorial radius, I and +the flattening, I. Setting I = 0 results in a sphere. Specify I E 0 for a prolate ellipsoid. A simple fraction, e.g., 1/297, -is allowed for I. (Also, if I E 1, the flattening is set to -1/I.) By default, the WGS84 ellipsoid is used, I = 6378137 m, -I = 1/298.257223563. +is allowed for I. By default, the WGS84 ellipsoid is used, I = +6378137 m, I = 1/298.257223563. -=item B<--comment-delimiter> +=item B<-w> + +toggle the longitude first flag (it starts off); if the flag is on, then +on input and output, longitude precedes latitude (except that, on input, +this can be overridden by a hemisphere designator, I, I, I, +I). + +=item B<-p> I + +set the output precision to I (default 6). I is the number +of digits after the decimal point for geocentric and local cartesion +coordinates and for the height (in meters). For latitudes and +longitudes (in degrees), the number of digits after the decimal point is +I + 5. + +=item B<--comment-delimiter> I set the comment delimiter to I (e.g., "#" or "//"). If set, the input lines will be scanned for this delimiter and, if found, @@ -68,23 +91,23 @@ print usage and exit. print full documentation and exit. -=item B<--input-file> +=item B<--input-file> I read input from the file I instead of from standard input; a file name of "-" stands for standard input. -=item B<--input-string> +=item B<--input-string> I read input from the string I instead of from standard input. All occurrences of the line separator character (default is a semicolon) in I are converted to newlines before the reading begins. -=item B<--line-separator> +=item B<--line-separator> I set the line separator character to I. By default this is a semicolon. -=item B<--output-file> +=item B<--output-file> I write output to the file I instead of to standard output; a file name of "-" stands for standard output. @@ -111,7 +134,7 @@ terminate; following lines will be converted. The algorithm for converting geocentric to geodetic coordinates is given in Appendix B of C. F. F. Karney, I, Feb. 2011; preprint L. +revolution>, Feb. 2011; preprint L. =head1 AUTHOR @@ -120,5 +143,5 @@ B was written by Charles Karney. =head1 HISTORY B was added to GeographicLib, -L, in 2009-02. Prior to 2009-03 it was +L, in 2009-02. Prior to 2009-03 it was called ECEFConvert. diff --git a/gtsam/3rdparty/GeographicLib/man/CartConvert.usage b/gtsam/3rdparty/GeographicLib/man/CartConvert.usage index 57374a78f..4167fc7f7 100644 --- a/gtsam/3rdparty/GeographicLib/man/CartConvert.usage +++ b/gtsam/3rdparty/GeographicLib/man/CartConvert.usage @@ -1,15 +1,15 @@ int usage(int retval, bool brief) { if (brief) ( retval ? std::cerr : std::cout ) << "Usage:\n" -" CartConvert [ -r ] [ -l lat0 lon0 h0 ] [ -e a f ] [ --comment-delimiter\n" -" commentdelim ] [ --version | -h | --help ] [ --input-file infile |\n" -" --input-string instring ] [ --line-separator linesep ] [ --output-file\n" -" outfile ]\n" +" CartConvert [ -r ] [ -l lat0 lon0 h0 ] [ -e a f ] [ -w ] [ -p prec ] [\n" +" --comment-delimiter commentdelim ] [ --version | -h | --help ] [\n" +" --input-file infile | --input-string instring ] [ --line-separator\n" +" linesep ] [ --output-file outfile ]\n" "\n" "For full documentation type:\n" " CartConvert --help\n" "or visit:\n" -" http://geographiclib.sf.net/1.35/CartConvert.1.html\n"; +" https://geographiclib.sourceforge.io/1.49/CartConvert.1.html\n"; else ( retval ? std::cerr : std::cout ) << "Man page:\n" "NAME\n" @@ -17,10 +17,10 @@ int usage(int retval, bool brief) { " cartesian\n" "\n" "SYNOPSIS\n" -" CartConvert [ -r ] [ -l lat0 lon0 h0 ] [ -e a f ] [ --comment-delimiter\n" -" commentdelim ] [ --version | -h | --help ] [ --input-file infile |\n" -" --input-string instring ] [ --line-separator linesep ] [ --output-file\n" -" outfile ]\n" +" CartConvert [ -r ] [ -l lat0 lon0 h0 ] [ -e a f ] [ -w ] [ -p prec ] [\n" +" --comment-delimiter commentdelim ] [ --version | -h | --help ] [\n" +" --input-file infile | --input-string instring ] [ --line-separator\n" +" linesep ] [ --output-file outfile ]\n" "\n" "DESCRIPTION\n" " Convert geodetic coordinates to either geocentric or local cartesian\n" @@ -34,23 +34,44 @@ int usage(int retval, bool brief) { "\n" " Geodetic coordinates are provided on standard input as a set of lines\n" " containing (blank separated) latitude, longitude (decimal degrees or\n" -" degrees, minutes and seconds), and height above the ellipsoid (meters).\n" -" For each set of geodetic coordinates, the corresponding cartesian\n" -" coordinates x, y, z (meters) are printed on standard output.\n" +" degrees, minutes and seconds), and height above the ellipsoid (meters);\n" +" for details on the allowed formats for latitude and longitude, see the\n" +" \"GEOGRAPHIC COORDINATES\" section of GeoConvert(1). For each set of\n" +" geodetic coordinates, the corresponding cartesian coordinates x, y, z\n" +" (meters) are printed on standard output.\n" "\n" "OPTIONS\n" " -r perform the reverse projection. x, y, z are given on standard\n" " input and each line of standard output gives latitude, longitude,\n" " height.\n" "\n" -" -e specify the ellipsoid via a f; the equatorial radius is a and the\n" -" flattening is f. Setting f = 0 results in a sphere. Specify f < 0\n" -" for a prolate ellipsoid. A simple fraction, e.g., 1/297, is\n" -" allowed for f. (Also, if f > 1, the flattening is set to 1/f.) By\n" -" default, the WGS84 ellipsoid is used, a = 6378137 m, f =\n" -" 1/298.257223563.\n" +" -l lat0 lon0 h0\n" +" specifies conversions to and from a local cartesion coordinate\n" +" systems with origin lat0 lon0 h0, instead of a geocentric\n" +" coordinate system. The -w flag can be used to swap the default\n" +" order of the 2 geographic coordinates, provided that it appears\n" +" before -l.\n" "\n" -" --comment-delimiter\n" +" -e a f\n" +" specify the ellipsoid via the equatorial radius, a and the\n" +" flattening, f. Setting f = 0 results in a sphere. Specify f < 0\n" +" for a prolate ellipsoid. A simple fraction, e.g., 1/297, is\n" +" allowed for f. By default, the WGS84 ellipsoid is used, a =\n" +" 6378137 m, f = 1/298.257223563.\n" +"\n" +" -w toggle the longitude first flag (it starts off); if the flag is on,\n" +" then on input and output, longitude precedes latitude (except that,\n" +" on input, this can be overridden by a hemisphere designator, N, S,\n" +" E, W).\n" +"\n" +" -p prec\n" +" set the output precision to prec (default 6). prec is the number\n" +" of digits after the decimal point for geocentric and local\n" +" cartesion coordinates and for the height (in meters). For\n" +" latitudes and longitudes (in degrees), the number of digits after\n" +" the decimal point is prec + 5.\n" +"\n" +" --comment-delimiter commentdelim\n" " set the comment delimiter to commentdelim (e.g., \"#\" or \"//\"). If\n" " set, the input lines will be scanned for this delimiter and, if\n" " found, the delimiter and the rest of the line will be removed prior\n" @@ -65,21 +86,21 @@ int usage(int retval, bool brief) { " --help\n" " print full documentation and exit.\n" "\n" -" --input-file\n" +" --input-file infile\n" " read input from the file infile instead of from standard input; a\n" " file name of \"-\" stands for standard input.\n" "\n" -" --input-string\n" +" --input-string instring\n" " read input from the string instring instead of from standard input.\n" " All occurrences of the line separator character (default is a\n" " semicolon) in instring are converted to newlines before the reading\n" " begins.\n" "\n" -" --line-separator\n" +" --line-separator linesep\n" " set the line separator character to linesep. By default this is a\n" " semicolon.\n" "\n" -" --output-file\n" +" --output-file outfile\n" " write output to the file outfile instead of to standard output; a\n" " file name of \"-\" stands for standard output.\n" "\n" @@ -100,14 +121,15 @@ int usage(int retval, bool brief) { "SEE ALSO\n" " The algorithm for converting geocentric to geodetic coordinates is\n" " given in Appendix B of C. F. F. Karney, Geodesics on an ellipsoid of\n" -" revolution, Feb. 2011; preprint .\n" +" revolution, Feb. 2011; preprint .\n" "\n" "AUTHOR\n" " CartConvert was written by Charles Karney.\n" "\n" "HISTORY\n" -" CartConvert was added to GeographicLib, ,\n" -" in 2009-02. Prior to 2009-03 it was called ECEFConvert.\n" +" CartConvert was added to GeographicLib,\n" +" , in 2009-02. Prior to 2009-03\n" +" it was called ECEFConvert.\n" ; return retval; } diff --git a/gtsam/3rdparty/GeographicLib/man/ConicProj.1 b/gtsam/3rdparty/GeographicLib/man/ConicProj.1 index 997017d7f..44db22383 100644 --- a/gtsam/3rdparty/GeographicLib/man/ConicProj.1 +++ b/gtsam/3rdparty/GeographicLib/man/ConicProj.1 @@ -1,4 +1,4 @@ -.\" Automatically generated by Pod::Man 2.25 (Pod::Simple 3.20) +.\" Automatically generated by Pod::Man 4.09 (Pod::Simple 3.35) .\" .\" Standard preamble: .\" ======================================================================== @@ -38,26 +38,31 @@ . ds PI \(*p . ds L" `` . ds R" '' +. ds C` +. ds C' 'br\} .\" .\" Escape single quotes in literal strings from groff's Unicode transform. .ie \n(.g .ds Aq \(aq .el .ds Aq ' .\" -.\" If the F register is turned on, we'll generate index entries on stderr for +.\" If the F register is >0, we'll generate index entries on stderr for .\" titles (.TH), headers (.SH), subsections (.SS), items (.Ip), and index .\" entries marked with X<> in POD. Of course, you'll have to process the .\" output yourself in some meaningful fashion. -.ie \nF \{\ +.\" +.\" Avoid warning from groff about undefined register 'F'. +.de IX +.. +.if !\nF .nr F 0 +.if \nF>0 \{\ . de IX . tm Index:\\$1\t\\n%\t"\\$2" .. -. nr % 0 -. rr F -.\} -.el \{\ -. de IX -.. +. if !\nF==2 \{\ +. nr % 0 +. nr F 2 +. \} .\} .\" .\" Accent mark definitions (@(#)ms.acc 1.5 88/02/08 SMI; from UCB 4.2). @@ -124,7 +129,7 @@ .\" ======================================================================== .\" .IX Title "CONICPROJ 1" -.TH CONICPROJ 1 "2014-03-13" "GeographicLib 1.35" "GeographicLib Utilities" +.TH CONICPROJ 1 "2017-10-05" "GeographicLib 1.49" "GeographicLib Utilities" .\" For nroff, turn off justification. Always turn off hyphenation; it makes .\" way too many mistakes in technical documents. .if n .ad l @@ -135,7 +140,7 @@ ConicProj \-\- perform conic projections .IX Header "SYNOPSIS" \&\fBConicProj\fR ( \fB\-c\fR | \fB\-a\fR ) \fIlat1\fR \fIlat2\fR [ \fB\-l\fR \fIlon0\fR ] [ \fB\-k\fR \fIk1\fR ] [ \fB\-r\fR ] -[ \fB\-e\fR \fIa\fR \fIf\fR ] +[ \fB\-e\fR \fIa\fR \fIf\fR ] [ \fB\-w\fR ] [ \fB\-p\fR \fIprec\fR ] [ \fB\-\-comment\-delimiter\fR \fIcommentdelim\fR ] [ \fB\-\-version\fR | \fB\-h\fR | \fB\-\-help\fR ] [ \fB\-\-input\-file\fR \fIinfile\fR | \fB\-\-input\-string\fR \fIinstring\fR ] @@ -156,12 +161,14 @@ area). The (azimuthal) scale on the standard parallels is \fIk1\fR. .PP Geodetic coordinates are provided on standard input as a set of lines containing (blank separated) \fIlatitude\fR and \fIlongitude\fR (decimal -degrees or degrees, minutes, seconds). For each set of geodetic -coordinates, the corresponding projected easting, \fIx\fR, and northing, -\&\fIy\fR, (meters) are printed on standard output together with the meridian -convergence \fIgamma\fR (degrees) and (azimuthal) scale \fIk\fR. For Albers -equal area, the radial scale is 1/\fIk\fR. The meridian convergence is the -bearing of the \fIy\fR axis measured clockwise from true north. +degrees or degrees, minutes, seconds); for details on the allowed +formats for latitude and longitude, see the \f(CW\*(C`GEOGRAPHIC COORDINATES\*(C'\fR +section of \fIGeoConvert\fR\|(1). For each set of geodetic coordinates, the +corresponding projected easting, \fIx\fR, and northing, \fIy\fR, (meters) are +printed on standard output together with the meridian convergence +\&\fIgamma\fR (degrees) and (azimuthal) scale \fIk\fR. For Albers equal area, +the radial scale is 1/\fIk\fR. The meridian convergence is the bearing of +the \fIy\fR axis measured clockwise from true north. .PP Special cases of the Lambert conformal projection are the Mercator projection (the standard latitudes equal and opposite) and the polar @@ -173,19 +180,19 @@ latitude corresponds to the same pole), and the Lambert equal area conic projection (one standard parallel is at a pole). .SH "OPTIONS" .IX Header "OPTIONS" -.IP "\fB\-c\fR" 4 -.IX Item "-c" +.IP "\fB\-c\fR \fIlat1\fR \fIlat2\fR" 4 +.IX Item "-c lat1 lat2" use the Lambert conformal conic projection with standard parallels \&\fIlat1\fR and \fIlat2\fR. -.IP "\fB\-a\fR" 4 -.IX Item "-a" +.IP "\fB\-a\fR \fIlat1\fR \fIlat2\fR" 4 +.IX Item "-a lat1 lat2" use the Albers equal area projection with standard parallels \fIlat1\fR and \&\fIlat2\fR. -.IP "\fB\-l\fR" 4 -.IX Item "-l" +.IP "\fB\-l\fR \fIlon0\fR" 4 +.IX Item "-l lon0" specify the longitude of origin \fIlon0\fR (degrees, default 0). -.IP "\fB\-k\fR" 4 -.IX Item "-k" +.IP "\fB\-k\fR \fIk1\fR" 4 +.IX Item "-k k1" specify the (azimuthal) scale \fIk1\fR on the standard parallels (default 1). .IP "\fB\-r\fR" 4 @@ -193,16 +200,28 @@ specify the (azimuthal) scale \fIk1\fR on the standard parallels (default perform the reverse projection. \fIx\fR and \fIy\fR are given on standard input and each line of standard output gives \fIlatitude\fR, \fIlongitude\fR, \&\fIgamma\fR, and \fIk\fR. -.IP "\fB\-e\fR" 4 -.IX Item "-e" -specify the ellipsoid via \fIa\fR \fIf\fR; the equatorial radius is \fIa\fR and -the flattening is \fIf\fR. Setting \fIf\fR = 0 results in a sphere. Specify +.IP "\fB\-e\fR \fIa\fR \fIf\fR" 4 +.IX Item "-e a f" +specify the ellipsoid via the equatorial radius, \fIa\fR and +the flattening, \fIf\fR. Setting \fIf\fR = 0 results in a sphere. Specify \&\fIf\fR < 0 for a prolate ellipsoid. A simple fraction, e.g., 1/297, -is allowed for \fIf\fR. (Also, if \fIf\fR > 1, the flattening is set to -1/\fIf\fR.) By default, the \s-1WGS84\s0 ellipsoid is used, \fIa\fR = 6378137 m, -\&\fIf\fR = 1/298.257223563. -.IP "\fB\-\-comment\-delimiter\fR" 4 -.IX Item "--comment-delimiter" +is allowed for \fIf\fR. By default, the \s-1WGS84\s0 ellipsoid is used, \fIa\fR = +6378137 m, \fIf\fR = 1/298.257223563. +.IP "\fB\-w\fR" 4 +.IX Item "-w" +toggle the longitude first flag (it starts off); if the flag is on, then +on input and output, longitude precedes latitude (except that, on input, +this can be overridden by a hemisphere designator, \fIN\fR, \fIS\fR, \fIE\fR, +\&\fIW\fR). +.IP "\fB\-p\fR \fIprec\fR" 4 +.IX Item "-p prec" +set the output precision to \fIprec\fR (default 6). \fIprec\fR is the number +of digits after the decimal point for lengths (in meters). For +latitudes and longitudes (in degrees), the number of digits after the +decimal point is \fIprec\fR + 5. For the convergence (in degrees) and +scale, the number of digits after the decimal point is \fIprec\fR + 6. +.IP "\fB\-\-comment\-delimiter\fR \fIcommentdelim\fR" 4 +.IX Item "--comment-delimiter commentdelim" set the comment delimiter to \fIcommentdelim\fR (e.g., \*(L"#\*(R" or \*(L"//\*(R"). If set, the input lines will be scanned for this delimiter and, if found, the delimiter and the rest of the line will be removed prior to @@ -217,21 +236,21 @@ print usage and exit. .IP "\fB\-\-help\fR" 4 .IX Item "--help" print full documentation and exit. -.IP "\fB\-\-input\-file\fR" 4 -.IX Item "--input-file" +.IP "\fB\-\-input\-file\fR \fIinfile\fR" 4 +.IX Item "--input-file infile" read input from the file \fIinfile\fR instead of from standard input; a file name of \*(L"\-\*(R" stands for standard input. -.IP "\fB\-\-input\-string\fR" 4 -.IX Item "--input-string" +.IP "\fB\-\-input\-string\fR \fIinstring\fR" 4 +.IX Item "--input-string instring" read input from the string \fIinstring\fR instead of from standard input. All occurrences of the line separator character (default is a semicolon) in \fIinstring\fR are converted to newlines before the reading begins. -.IP "\fB\-\-line\-separator\fR" 4 -.IX Item "--line-separator" +.IP "\fB\-\-line\-separator\fR \fIlinesep\fR" 4 +.IX Item "--line-separator linesep" set the line separator character to \fIlinesep\fR. By default this is a semicolon. -.IP "\fB\-\-output\-file\fR" 4 -.IX Item "--output-file" +.IP "\fB\-\-output\-file\fR \fIoutfile\fR" 4 +.IX Item "--output-file outfile" write output to the file \fIoutfile\fR instead of to standard output; a file name of \*(L"\-\*(R" stands for standard output. .SH "EXAMPLES" @@ -253,5 +272,5 @@ terminate; following lines will be converted. \&\fBConicProj\fR was written by Charles Karney. .SH "HISTORY" .IX Header "HISTORY" -\&\fBConicProj\fR was added to GeographicLib, , -in version 1.9. +\&\fBConicProj\fR was added to GeographicLib, +, in version 1.9. diff --git a/gtsam/3rdparty/GeographicLib/man/ConicProj.1.html b/gtsam/3rdparty/GeographicLib/man/ConicProj.1.html index 9de3fd683..47366a1d9 100644 --- a/gtsam/3rdparty/GeographicLib/man/ConicProj.1.html +++ b/gtsam/3rdparty/GeographicLib/man/ConicProj.1.html @@ -7,7 +7,7 @@ - + @@ -17,13 +17,13 @@

    SYNOPSIS

    -

    ConicProj ( -c | -a ) lat1 lat2 [ -l lon0 ] [ -k k1 ] [ -r ] [ -e a f ] [ --comment-delimiter commentdelim ] [ --version | -h | --help ] [ --input-file infile | --input-string instring ] [ --line-separator linesep ] [ --output-file outfile ]

    +

    ConicProj ( -c | -a ) lat1 lat2 [ -l lon0 ] [ -k k1 ] [ -r ] [ -e a f ] [ -w ] [ -p prec ] [ --comment-delimiter commentdelim ] [ --version | -h | --help ] [ --input-file infile | --input-string instring ] [ --line-separator linesep ] [ --output-file outfile ]

    DESCRIPTION

    Perform one of two conic projections geodesics. Convert geodetic coordinates to either Lambert conformal conic or Albers equal area coordinates. The standard latitudes lat1 and lat2 are specified by that the -c option (for Lambert conformal conic) or the -a option (for Albers equal area). At least one of these options must be given (the last one given is used). Specify lat1 = lat2, to obtain the case with a single standard parallel. The central meridian is given by lon0. The longitude of origin is given by the latitude of minimum (azimuthal) scale for Lambert conformal conic (Albers equal area). The (azimuthal) scale on the standard parallels is k1.

    -

    Geodetic coordinates are provided on standard input as a set of lines containing (blank separated) latitude and longitude (decimal degrees or degrees, minutes, seconds). For each set of geodetic coordinates, the corresponding projected easting, x, and northing, y, (meters) are printed on standard output together with the meridian convergence gamma (degrees) and (azimuthal) scale k. For Albers equal area, the radial scale is 1/k. The meridian convergence is the bearing of the y axis measured clockwise from true north.

    +

    Geodetic coordinates are provided on standard input as a set of lines containing (blank separated) latitude and longitude (decimal degrees or degrees, minutes, seconds); for details on the allowed formats for latitude and longitude, see the GEOGRAPHIC COORDINATES section of GeoConvert(1). For each set of geodetic coordinates, the corresponding projected easting, x, and northing, y, (meters) are printed on standard output together with the meridian convergence gamma (degrees) and (azimuthal) scale k. For Albers equal area, the radial scale is 1/k. The meridian convergence is the bearing of the y axis measured clockwise from true north.

    Special cases of the Lambert conformal projection are the Mercator projection (the standard latitudes equal and opposite) and the polar stereographic projection (both standard latitudes correspond to the same pole). Special cases of the Albers equal area projection are the cylindrical equal area projection (the standard latitudes equal and opposite), the Lambert azimuthal equal area projection (both standard latitude corresponds to the same pole), and the Lambert equal area conic projection (one standard parallel is at a pole).

    @@ -31,25 +31,25 @@
    -
    -c
    +
    -c lat1 lat2

    use the Lambert conformal conic projection with standard parallels lat1 and lat2.

    -
    -a
    +
    -a lat1 lat2

    use the Albers equal area projection with standard parallels lat1 and lat2.

    -
    -l
    +
    -l lon0

    specify the longitude of origin lon0 (degrees, default 0).

    -
    -k
    +
    -k k1

    specify the (azimuthal) scale k1 on the standard parallels (default 1).

    @@ -61,13 +61,25 @@

    perform the reverse projection. x and y are given on standard input and each line of standard output gives latitude, longitude, gamma, and k.

    -
    -e
    +
    -e a f
    -

    specify the ellipsoid via a f; the equatorial radius is a and the flattening is f. Setting f = 0 results in a sphere. Specify f < 0 for a prolate ellipsoid. A simple fraction, e.g., 1/297, is allowed for f. (Also, if f > 1, the flattening is set to 1/f.) By default, the WGS84 ellipsoid is used, a = 6378137 m, f = 1/298.257223563.

    +

    specify the ellipsoid via the equatorial radius, a and the flattening, f. Setting f = 0 results in a sphere. Specify f < 0 for a prolate ellipsoid. A simple fraction, e.g., 1/297, is allowed for f. By default, the WGS84 ellipsoid is used, a = 6378137 m, f = 1/298.257223563.

    -
    --comment-delimiter
    +
    -w
    +
    + +

    toggle the longitude first flag (it starts off); if the flag is on, then on input and output, longitude precedes latitude (except that, on input, this can be overridden by a hemisphere designator, N, S, E, W).

    + +
    +
    -p prec
    +
    + +

    set the output precision to prec (default 6). prec is the number of digits after the decimal point for lengths (in meters). For latitudes and longitudes (in degrees), the number of digits after the decimal point is prec + 5. For the convergence (in degrees) and scale, the number of digits after the decimal point is prec + 6.

    + +
    +
    --comment-delimiter commentdelim

    set the comment delimiter to commentdelim (e.g., "#" or "//"). If set, the input lines will be scanned for this delimiter and, if found, the delimiter and the rest of the line will be removed prior to processing and subsequently appended to the output line (separated by a space).

    @@ -91,25 +103,25 @@

    print full documentation and exit.

    -
    --input-file
    +
    --input-file infile

    read input from the file infile instead of from standard input; a file name of "-" stands for standard input.

    -
    --input-string
    +
    --input-string instring

    read input from the string instring instead of from standard input. All occurrences of the line separator character (default is a semicolon) in instring are converted to newlines before the reading begins.

    -
    --line-separator
    +
    --line-separator linesep

    set the line separator character to linesep. By default this is a semicolon.

    -
    --output-file
    +
    --output-file outfile

    write output to the file outfile instead of to standard output; a file name of "-" stands for standard output.

    @@ -134,7 +146,7 @@

    HISTORY

    -

    ConicProj was added to GeographicLib, http://geographiclib.sf.net, in version 1.9.

    +

    ConicProj was added to GeographicLib, https://geographiclib.sourceforge.io, in version 1.9.

    diff --git a/gtsam/3rdparty/GeographicLib/man/ConicProj.pod b/gtsam/3rdparty/GeographicLib/man/ConicProj.pod index 59e256156..26ae4e82a 100644 --- a/gtsam/3rdparty/GeographicLib/man/ConicProj.pod +++ b/gtsam/3rdparty/GeographicLib/man/ConicProj.pod @@ -6,7 +6,7 @@ ConicProj -- perform conic projections B ( B<-c> | B<-a> ) I I [ B<-l> I ] [ B<-k> I ] [ B<-r> ] -[ B<-e> I I ] +[ B<-e> I I ] [ B<-w> ] [ B<-p> I ] [ B<--comment-delimiter> I ] [ B<--version> | B<-h> | B<--help> ] [ B<--input-file> I | B<--input-string> I ] @@ -28,12 +28,14 @@ area). The (azimuthal) scale on the standard parallels is I. Geodetic coordinates are provided on standard input as a set of lines containing (blank separated) I and I (decimal -degrees or degrees, minutes, seconds). For each set of geodetic -coordinates, the corresponding projected easting, I, and northing, -I, (meters) are printed on standard output together with the meridian -convergence I (degrees) and (azimuthal) scale I. For Albers -equal area, the radial scale is 1/I. The meridian convergence is the -bearing of the I axis measured clockwise from true north. +degrees or degrees, minutes, seconds); for details on the allowed +formats for latitude and longitude, see the C +section of GeoConvert(1). For each set of geodetic coordinates, the +corresponding projected easting, I, and northing, I, (meters) are +printed on standard output together with the meridian convergence +I (degrees) and (azimuthal) scale I. For Albers equal area, +the radial scale is 1/I. The meridian convergence is the bearing of +the I axis measured clockwise from true north. Special cases of the Lambert conformal projection are the Mercator projection (the standard latitudes equal and opposite) and the polar @@ -48,21 +50,21 @@ projection (one standard parallel is at a pole). =over -=item B<-c> +=item B<-c> I I use the Lambert conformal conic projection with standard parallels I and I. -=item B<-a> +=item B<-a> I I use the Albers equal area projection with standard parallels I and I. -=item B<-l> +=item B<-l> I specify the longitude of origin I (degrees, default 0). -=item B<-k> +=item B<-k> I specify the (azimuthal) scale I on the standard parallels (default 1). @@ -73,16 +75,30 @@ perform the reverse projection. I and I are given on standard input and each line of standard output gives I, I, I, and I. -=item B<-e> +=item B<-e> I I -specify the ellipsoid via I I; the equatorial radius is I and -the flattening is I. Setting I = 0 results in a sphere. Specify +specify the ellipsoid via the equatorial radius, I and +the flattening, I. Setting I = 0 results in a sphere. Specify I E 0 for a prolate ellipsoid. A simple fraction, e.g., 1/297, -is allowed for I. (Also, if I E 1, the flattening is set to -1/I.) By default, the WGS84 ellipsoid is used, I = 6378137 m, -I = 1/298.257223563. +is allowed for I. By default, the WGS84 ellipsoid is used, I = +6378137 m, I = 1/298.257223563. -=item B<--comment-delimiter> +=item B<-w> + +toggle the longitude first flag (it starts off); if the flag is on, then +on input and output, longitude precedes latitude (except that, on input, +this can be overridden by a hemisphere designator, I, I, I, +I). + +=item B<-p> I + +set the output precision to I (default 6). I is the number +of digits after the decimal point for lengths (in meters). For +latitudes and longitudes (in degrees), the number of digits after the +decimal point is I + 5. For the convergence (in degrees) and +scale, the number of digits after the decimal point is I + 6. + +=item B<--comment-delimiter> I set the comment delimiter to I (e.g., "#" or "//"). If set, the input lines will be scanned for this delimiter and, if found, @@ -102,23 +118,23 @@ print usage and exit. print full documentation and exit. -=item B<--input-file> +=item B<--input-file> I read input from the file I instead of from standard input; a file name of "-" stands for standard input. -=item B<--input-string> +=item B<--input-string> I read input from the string I instead of from standard input. All occurrences of the line separator character (default is a semicolon) in I are converted to newlines before the reading begins. -=item B<--line-separator> +=item B<--line-separator> I set the line separator character to I. By default this is a semicolon. -=item B<--output-file> +=item B<--output-file> I write output to the file I instead of to standard output; a file name of "-" stands for standard output. @@ -145,5 +161,5 @@ B was written by Charles Karney. =head1 HISTORY -B was added to GeographicLib, L, -in version 1.9. +B was added to GeographicLib, +L, in version 1.9. diff --git a/gtsam/3rdparty/GeographicLib/man/ConicProj.usage b/gtsam/3rdparty/GeographicLib/man/ConicProj.usage index a84aa4fde..49e2cfbaf 100644 --- a/gtsam/3rdparty/GeographicLib/man/ConicProj.usage +++ b/gtsam/3rdparty/GeographicLib/man/ConicProj.usage @@ -2,14 +2,14 @@ int usage(int retval, bool brief) { if (brief) ( retval ? std::cerr : std::cout ) << "Usage:\n" " ConicProj ( -c | -a ) lat1 lat2 [ -l lon0 ] [ -k k1 ] [ -r ] [ -e a f ]\n" -" [ --comment-delimiter commentdelim ] [ --version | -h | --help ] [\n" -" --input-file infile | --input-string instring ] [ --line-separator\n" -" linesep ] [ --output-file outfile ]\n" +" [ -w ] [ -p prec ] [ --comment-delimiter commentdelim ] [ --version |\n" +" -h | --help ] [ --input-file infile | --input-string instring ] [\n" +" --line-separator linesep ] [ --output-file outfile ]\n" "\n" "For full documentation type:\n" " ConicProj --help\n" "or visit:\n" -" http://geographiclib.sf.net/1.35/ConicProj.1.html\n"; +" https://geographiclib.sourceforge.io/1.49/ConicProj.1.html\n"; else ( retval ? std::cerr : std::cout ) << "Man page:\n" "NAME\n" @@ -17,9 +17,9 @@ int usage(int retval, bool brief) { "\n" "SYNOPSIS\n" " ConicProj ( -c | -a ) lat1 lat2 [ -l lon0 ] [ -k k1 ] [ -r ] [ -e a f ]\n" -" [ --comment-delimiter commentdelim ] [ --version | -h | --help ] [\n" -" --input-file infile | --input-string instring ] [ --line-separator\n" -" linesep ] [ --output-file outfile ]\n" +" [ -w ] [ -p prec ] [ --comment-delimiter commentdelim ] [ --version |\n" +" -h | --help ] [ --input-file infile | --input-string instring ] [\n" +" --line-separator linesep ] [ --output-file outfile ]\n" "\n" "DESCRIPTION\n" " Perform one of two conic projections geodesics. Convert geodetic\n" @@ -35,12 +35,14 @@ int usage(int retval, bool brief) { "\n" " Geodetic coordinates are provided on standard input as a set of lines\n" " containing (blank separated) latitude and longitude (decimal degrees or\n" -" degrees, minutes, seconds). For each set of geodetic coordinates, the\n" -" corresponding projected easting, x, and northing, y, (meters) are\n" -" printed on standard output together with the meridian convergence gamma\n" -" (degrees) and (azimuthal) scale k. For Albers equal area, the radial\n" -" scale is 1/k. The meridian convergence is the bearing of the y axis\n" -" measured clockwise from true north.\n" +" degrees, minutes, seconds); for details on the allowed formats for\n" +" latitude and longitude, see the \"GEOGRAPHIC COORDINATES\" section of\n" +" GeoConvert(1). For each set of geodetic coordinates, the corresponding\n" +" projected easting, x, and northing, y, (meters) are printed on standard\n" +" output together with the meridian convergence gamma (degrees) and\n" +" (azimuthal) scale k. For Albers equal area, the radial scale is 1/k.\n" +" The meridian convergence is the bearing of the y axis measured\n" +" clockwise from true north.\n" "\n" " Special cases of the Lambert conformal projection are the Mercator\n" " projection (the standard latitudes equal and opposite) and the polar\n" @@ -52,29 +54,46 @@ int usage(int retval, bool brief) { " conic projection (one standard parallel is at a pole).\n" "\n" "OPTIONS\n" -" -c use the Lambert conformal conic projection with standard parallels\n" +" -c lat1 lat2\n" +" use the Lambert conformal conic projection with standard parallels\n" " lat1 and lat2.\n" "\n" -" -a use the Albers equal area projection with standard parallels lat1\n" +" -a lat1 lat2\n" +" use the Albers equal area projection with standard parallels lat1\n" " and lat2.\n" "\n" -" -l specify the longitude of origin lon0 (degrees, default 0).\n" +" -l lon0\n" +" specify the longitude of origin lon0 (degrees, default 0).\n" "\n" -" -k specify the (azimuthal) scale k1 on the standard parallels (default\n" +" -k k1\n" +" specify the (azimuthal) scale k1 on the standard parallels (default\n" " 1).\n" "\n" " -r perform the reverse projection. x and y are given on standard\n" " input and each line of standard output gives latitude, longitude,\n" " gamma, and k.\n" "\n" -" -e specify the ellipsoid via a f; the equatorial radius is a and the\n" -" flattening is f. Setting f = 0 results in a sphere. Specify f < 0\n" +" -e a f\n" +" specify the ellipsoid via the equatorial radius, a and the\n" +" flattening, f. Setting f = 0 results in a sphere. Specify f < 0\n" " for a prolate ellipsoid. A simple fraction, e.g., 1/297, is\n" -" allowed for f. (Also, if f > 1, the flattening is set to 1/f.) By\n" -" default, the WGS84 ellipsoid is used, a = 6378137 m, f =\n" -" 1/298.257223563.\n" +" allowed for f. By default, the WGS84 ellipsoid is used, a =\n" +" 6378137 m, f = 1/298.257223563.\n" "\n" -" --comment-delimiter\n" +" -w toggle the longitude first flag (it starts off); if the flag is on,\n" +" then on input and output, longitude precedes latitude (except that,\n" +" on input, this can be overridden by a hemisphere designator, N, S,\n" +" E, W).\n" +"\n" +" -p prec\n" +" set the output precision to prec (default 6). prec is the number\n" +" of digits after the decimal point for lengths (in meters). For\n" +" latitudes and longitudes (in degrees), the number of digits after\n" +" the decimal point is prec + 5. For the convergence (in degrees)\n" +" and scale, the number of digits after the decimal point is prec +\n" +" 6.\n" +"\n" +" --comment-delimiter commentdelim\n" " set the comment delimiter to commentdelim (e.g., \"#\" or \"//\"). If\n" " set, the input lines will be scanned for this delimiter and, if\n" " found, the delimiter and the rest of the line will be removed prior\n" @@ -89,21 +108,21 @@ int usage(int retval, bool brief) { " --help\n" " print full documentation and exit.\n" "\n" -" --input-file\n" +" --input-file infile\n" " read input from the file infile instead of from standard input; a\n" " file name of \"-\" stands for standard input.\n" "\n" -" --input-string\n" +" --input-string instring\n" " read input from the string instring instead of from standard input.\n" " All occurrences of the line separator character (default is a\n" " semicolon) in instring are converted to newlines before the reading\n" " begins.\n" "\n" -" --line-separator\n" +" --line-separator linesep\n" " set the line separator character to linesep. By default this is a\n" " semicolon.\n" "\n" -" --output-file\n" +" --output-file outfile\n" " write output to the file outfile instead of to standard output; a\n" " file name of \"-\" stands for standard output.\n" "\n" @@ -123,8 +142,8 @@ int usage(int retval, bool brief) { " ConicProj was written by Charles Karney.\n" "\n" "HISTORY\n" -" ConicProj was added to GeographicLib, , in\n" -" version 1.9.\n" +" ConicProj was added to GeographicLib,\n" +" , in version 1.9.\n" ; return retval; } diff --git a/gtsam/3rdparty/GeographicLib/man/GeoConvert.1 b/gtsam/3rdparty/GeographicLib/man/GeoConvert.1 index 747b8cd3f..e4235ce12 100644 --- a/gtsam/3rdparty/GeographicLib/man/GeoConvert.1 +++ b/gtsam/3rdparty/GeographicLib/man/GeoConvert.1 @@ -1,4 +1,4 @@ -.\" Automatically generated by Pod::Man 2.25 (Pod::Simple 3.20) +.\" Automatically generated by Pod::Man 4.09 (Pod::Simple 3.35) .\" .\" Standard preamble: .\" ======================================================================== @@ -38,26 +38,31 @@ . ds PI \(*p . ds L" `` . ds R" '' +. ds C` +. ds C' 'br\} .\" .\" Escape single quotes in literal strings from groff's Unicode transform. .ie \n(.g .ds Aq \(aq .el .ds Aq ' .\" -.\" If the F register is turned on, we'll generate index entries on stderr for +.\" If the F register is >0, we'll generate index entries on stderr for .\" titles (.TH), headers (.SH), subsections (.SS), items (.Ip), and index .\" entries marked with X<> in POD. Of course, you'll have to process the .\" output yourself in some meaningful fashion. -.ie \nF \{\ +.\" +.\" Avoid warning from groff about undefined register 'F'. +.de IX +.. +.if !\nF .nr F 0 +.if \nF>0 \{\ . de IX . tm Index:\\$1\t\\n%\t"\\$2" .. -. nr % 0 -. rr F -.\} -.el \{\ -. de IX -.. +. if !\nF==2 \{\ +. nr % 0 +. nr F 2 +. \} .\} .\" .\" Accent mark definitions (@(#)ms.acc 1.5 88/02/08 SMI; from UCB 4.2). @@ -124,7 +129,7 @@ .\" ======================================================================== .\" .IX Title "GEOCONVERT 1" -.TH GEOCONVERT 1 "2014-03-13" "GeographicLib 1.35" "GeographicLib Utilities" +.TH GEOCONVERT 1 "2017-10-05" "GeographicLib 1.49" "GeographicLib Utilities" .\" For nroff, turn off justification. Always turn off hyphenation; it makes .\" way too many mistakes in technical documents. .if n .ad l @@ -134,7 +139,8 @@ GeoConvert \-\- convert geographic coordinates .SH "SYNOPSIS" .IX Header "SYNOPSIS" \&\fBGeoConvert\fR [ \fB\-g\fR | \fB\-d\fR | \fB\-:\fR | \fB\-u\fR | \fB\-m\fR | \fB\-c\fR ] -[ \fB\-p\fR \fIprec\fR ] [ \fB\-z\fR \fIzone\fR | \fB\-s\fR | \fB\-t\fR ] [ \fB\-n\fR ] [ \fB\-w\fR ] +[ \fB\-z\fR \fIzone\fR | \fB\-s\fR | \fB\-t\fR | \fB\-S\fR | \fB\-T\fR ] +[ \fB\-n\fR ] [ \fB\-w\fR ] [ \fB\-p\fR \fIprec\fR ] [ \fB\-l\fR | \fB\-a\fR ] [ \fB\-\-comment\-delimiter\fR \fIcommentdelim\fR ] [ \fB\-\-version\fR | \fB\-h\fR | \fB\-\-help\fR ] [ \fB\-\-input\-file\fR \fIinfile\fR | \fB\-\-input\-string\fR \fIinstring\fR ] @@ -152,37 +158,30 @@ is used (\fIa\fR = 6378137 m, \fIf\fR = 1/298.257223563). .IP "\fBgeographic\fR" 4 .IX Item "geographic" 2 tokens (output options \fB\-g\fR, \fB\-d\fR, or \fB\-:\fR) given as \fIlatitude\fR -\&\fIlongitude\fR using decimal degrees or degrees minutes seconds. d, ', -and " are used to denote degrees, minutes, and seconds, with the least -significant designator optional. (See \*(L"\s-1QUOTING\s0\*(R" for how to -quote the characters ' and " when entering coordinates on the command -line.) Various unicode characters (encoded with \s-1UTF\-8\s0) may also be used -to denote degrees, minutes, and seconds, e.g., the degree, prime, and -double prime symbols. Alternatively, : (colon) may be used to separate -the various components. Latitude is given first (unless the \fB\-w\fR -option is given); however, on input, either may be given first by -appending or prepending \fIN\fR or \fIS\fR to the latitude and \fIE\fR or \fIW\fR to -the longitude. For example, the following are all equivalent +\&\fIlongitude\fR using decimal degrees or degrees, minutes, and seconds. +Latitude is given first (unless the \fB\-w\fR option is given). See +\&\*(L"\s-1GEOGRAPHIC COORDINATES\*(R"\s0 for a description of the format. For +example, the following are all equivalent .Sp .Vb 5 \& 33.3 44.4 \& E44.4 N33.3 \& 33d18\*(AqN 44d24\*(AqE \& 44d24 33d18N -\& 33:18 44:24 +\& 33:18 +44:24 .Ve .IP "\fB\s-1UTM/UPS\s0\fR" 4 .IX Item "UTM/UPS" 3 tokens (output option \fB\-u\fR) given as \fIzone\fR+\fIhemisphere\fR \fIeasting\fR \&\fInorthing\fR or \fIeasting\fR \fInorthing\fR \fIzone\fR+\fIhemisphere\fR, where -\&\fIhemisphere\fR is either \fIN\fR or \fIS\fR. The \fIzone\fR is absent for a \s-1UPS\s0 -specification. For example, +\&\fIhemisphere\fR is either \fIn\fR (or \fInorth\fR) or \fIs\fR (or \fIsouth\fR). The +\&\fIzone\fR is absent for a \s-1UPS\s0 specification. For example, .Sp .Vb 4 -\& 38N 444140.54 3684706.36 -\& 444140.54 3684706.36 38N -\& S 2173854.98 2985980.58 -\& 2173854.98 2985980.58 S +\& 38n 444140.54 3684706.36 +\& 444140.54 3684706.36 38n +\& s 2173854.98 2985980.58 +\& 2173854.98 2985980.58 s .Ve .IP "\fB\s-1MRGS\s0\fR" 4 .IX Item "MRGS" @@ -207,41 +206,57 @@ like \fB\-d\fR, except use : as a separator instead of the d, ', and " delimiters. .IP "\fB\-u\fR" 4 .IX Item "-u" -output \s-1UTM\s0 or \s-1UPS\s0. +output \s-1UTM\s0 or \s-1UPS.\s0 .IP "\fB\-m\fR" 4 .IX Item "-m" -output \s-1MGRS\s0. +output \s-1MGRS.\s0 .IP "\fB\-c\fR" 4 .IX Item "-c" -output meridian convergence and scale for the corresponding \s-1UTM\s0 or -\&\s-1UPS\s0 projection. Convergence is the bearing of grid north given as -degrees clockwise from true north. -.IP "\fB\-p\fR" 4 -.IX Item "-p" -set the output precision to \fIprec\fR (default 0); \fIprec\fR is the -precision relative to 1 m. See \*(L"\s-1PRECISION\s0\*(R". -.IP "\fB\-z\fR" 4 -.IX Item "-z" +output meridian convergence and scale for the corresponding \s-1UTM\s0 or \s-1UPS\s0 +projection. The meridian convergence is the bearing of grid north given +as degrees clockwise from true north. +.IP "\fB\-z\fR \fIzone\fR" 4 +.IX Item "-z zone" set the zone to \fIzone\fR for output. Use either 0 < \fIzone\fR <= -60 for a \s-1UTM\s0 zone or \fIzone\fR = 0 for \s-1UPS\s0. Alternatively use a -\&\fIzone\fR+\fIhemisphere\fR designation, e.g., 38N. See \*(L"\s-1ZONE\s0\*(R". +60 for a \s-1UTM\s0 zone or \fIzone\fR = 0 for \s-1UPS.\s0 Alternatively use a +\&\fIzone\fR+\fIhemisphere\fR designation, e.g., 38n. See \*(L"\s-1ZONE\*(R"\s0. .IP "\fB\-s\fR" 4 .IX Item "-s" use the standard \s-1UPS\s0 and \s-1UTM\s0 zones. .IP "\fB\-t\fR" 4 .IX Item "-t" similar to \fB\-s\fR but forces \s-1UPS\s0 regions to the closest \s-1UTM\s0 zone. +.IP "\fB\-S\fR or \fB\-T\fR" 4 +.IX Item "-S or -T" +behave the same as \fB\-s\fR and \fB\-t\fR, respectively, until the first legal +conversion is performed. For subsequent points, the zone and hemisphere +of that conversion are used. This enables a sequence of points to be +converted into \s-1UTM\s0 or \s-1UPS\s0 using a consistent coordinate system. .IP "\fB\-n\fR" 4 .IX Item "-n" on input, \s-1MGRS\s0 coordinates refer to the south-west corner of the \s-1MGRS\s0 -square instead of the center; see \*(L"\s-1MGRS\s0\*(R". +square instead of the center; see \*(L"\s-1MGRS\*(R"\s0. .IP "\fB\-w\fR" 4 .IX Item "-w" -on input and output, longitude precedes latitude (except that on input +toggle the longitude first flag (it starts off); if the flag is on, then +on input and output, longitude precedes latitude (except that, on input, this can be overridden by a hemisphere designator, \fIN\fR, \fIS\fR, \fIE\fR, \&\fIW\fR). -.IP "\fB\-\-comment\-delimiter\fR" 4 -.IX Item "--comment-delimiter" +.IP "\fB\-p\fR \fIprec\fR" 4 +.IX Item "-p prec" +set the output precision to \fIprec\fR (default 0); \fIprec\fR is the +precision relative to 1 m. See \*(L"\s-1PRECISION\*(R"\s0. +.IP "\fB\-l\fR" 4 +.IX Item "-l" +on output, \s-1UTM/UPS\s0 uses the long forms \fInorth\fR and \fIsouth\fR to +designate the hemisphere instead of \fIn\fR or \fIs\fR. +.IP "\fB\-a\fR" 4 +.IX Item "-a" +on output, \s-1UTM/UPS\s0 uses the abbreviations \fIn\fR and \fIs\fR to designate the +hemisphere instead of \fInorth\fR or \fIsouth\fR; this is the default +representation. +.IP "\fB\-\-comment\-delimiter\fR \fIcommentdelim\fR" 4 +.IX Item "--comment-delimiter commentdelim" set the comment delimiter to \fIcommentdelim\fR (e.g., \*(L"#\*(R" or \*(L"//\*(R"). If set, the input lines will be scanned for this delimiter and, if found, the delimiter and the rest of the line will be removed prior to @@ -256,47 +271,139 @@ print usage and exit. .IP "\fB\-\-help\fR" 4 .IX Item "--help" print full documentation and exit. -.IP "\fB\-\-input\-file\fR" 4 -.IX Item "--input-file" +.IP "\fB\-\-input\-file\fR \fIinfile\fR" 4 +.IX Item "--input-file infile" read input from the file \fIinfile\fR instead of from standard input; a file name of \*(L"\-\*(R" stands for standard input. -.IP "\fB\-\-input\-string\fR" 4 -.IX Item "--input-string" +.IP "\fB\-\-input\-string\fR \fIinstring\fR" 4 +.IX Item "--input-string instring" read input from the string \fIinstring\fR instead of from standard input. All occurrences of the line separator character (default is a semicolon) in \fIinstring\fR are converted to newlines before the reading begins. -.IP "\fB\-\-line\-separator\fR" 4 -.IX Item "--line-separator" +.IP "\fB\-\-line\-separator\fR \fIlinesep\fR" 4 +.IX Item "--line-separator linesep" set the line separator character to \fIlinesep\fR. By default this is a semicolon. -.IP "\fB\-\-output\-file\fR" 4 -.IX Item "--output-file" +.IP "\fB\-\-output\-file\fR \fIoutfile\fR" 4 +.IX Item "--output-file outfile" write output to the file \fIoutfile\fR instead of to standard output; a file name of \*(L"\-\*(R" stands for standard output. .SH "PRECISION" .IX Header "PRECISION" \&\fIprec\fR gives precision of the output with \fIprec\fR = 0 giving 1 m -precision, \fIprec\fR = 3 giving 1 mm precision, etc. \fIprec\fR is the number -of digits after the decimal point for \s-1UTM/UPS\s0. The number of digits per -coordinate for \s-1MGRS\s0 is 5 + \fIprec\fR. For decimal degrees, the number of -digits after the decimal point is 5 + \fIprec\fR. For \s-1DMS\s0 (degree, minute, -seconds) output, the number of digits after the decimal point in the -seconds components is 1 + \fIprec\fR; if this is negative then use minutes -(\fIprec\fR = \-2 or \-3) or degrees (\fIprec\fR <= \-4) as the least significant -component. Print convergence, resp. scale, with 5 + \fIprec\fR, resp. 7 + -\&\fIprec\fR, digits after the decimal point. The minimum value of \fIprec\fR is -\&\-5 and the maximum is 9 for \s-1UTM/UPS\s0, 9 for decimal degrees, 10 for \s-1DMS\s0, -6 for \s-1MGRS\s0, and 8 for convergence and scale. +precision, \fIprec\fR = 3 giving 1 mm precision, etc. \fIprec\fR is the +number of digits after the decimal point for \s-1UTM/UPS.\s0 For \s-1MGRS,\s0 The +number of digits per coordinate is 5 + \fIprec\fR; = \-6 results in +just the grid zone. For decimal degrees, the number of digits after the +decimal point is 5 + \fIprec\fR. For \s-1DMS\s0 (degree, minute, seconds) output, +the number of digits after the decimal point in the seconds components +is 1 + \fIprec\fR; if this is negative then use minutes (\fIprec\fR = \-2 or +\&\-3) or degrees (\fIprec\fR <= \-4) as the least significant component. +Print convergence, resp. scale, with 5 + \fIprec\fR, resp. 7 + \fIprec\fR, +digits after the decimal point. The minimum value of \fIprec\fR is \-5 (\-6 +for \s-1MGRS\s0) and the maximum is 9 for \s-1UTM/UPS, 9\s0 for decimal degrees, 10 +for \s-1DMS, 6\s0 for \s-1MGRS,\s0 and 8 for convergence and scale. +.SH "GEOGRAPHIC COORDINATES" +.IX Header "GEOGRAPHIC COORDINATES" +The utility accepts geographic coordinates, latitude and longitude, in a +number of common formats. Latitude precedes longitude, unless the \fB\-w\fR +option is given which switches this convention. On input, either +coordinate may be given first by appending or prepending \fIN\fR or \fIS\fR to +the latitude and \fIE\fR or \fIW\fR to the longitude. These hemisphere +designators carry an implied sign, positive for \fIN\fR and \fIE\fR and +negative for \fIS\fR and \fIW\fR. This sign multiplies any +/\- sign prefixing +the coordinate. The coordinates may be given as decimal degree or as +degrees, minutes, and seconds. d, ', and " are used to denote degrees, +minutes, and seconds, with the least significant designator optional. +(See \*(L"\s-1QUOTING\*(R"\s0 for how to quote the characters ' and " when entering +coordinates on the command line.) Alternatively, : (colon) may be used +to separate the various components. Only the final component of +coordinate can include a decimal point, and the minutes and seconds +components must be less than 60. +.PP +It is also possible to carry out addition or subtraction operations in +geographic coordinates. If the coordinate includes interior signs +(i.e., not at the beginning or immediately after an initial hemisphere +designator), then the coordinate is split before such signs; the pieces +are parsed separately and the results summed. For example the point 15" +east of 39N 70W is +.PP +.Vb 1 +\& 39N 70W+0:0:15E +.Ve +.PP +\&\fB\s-1WARNING:\s0\fR \*(L"Exponential\*(R" notation is not recognized for geographic +coordinates. Thus 7.0E1 is illegal, while 7.0E+1 is parsed +as (7.0E) + (+1), yielding the same result as 8.0E. +.PP +Various unicode characters (encoded with \s-1UTF\-8\s0) may also be used to +denote degrees, minutes, and seconds, e.g., the degree, prime, and +double prime symbols; in addition two single quotes can be used to +represent ". +.PP +The other GeographicLib utilities use the same rules for interpreting +geographic coordinates; in addition, azimuths and arc lengths are +interpreted the same way. +.SH "QUOTING" +.IX Header "QUOTING" +Unfortunately the characters ' and \*(L" have special meanings in many +shells and have to be entered with care. However note (1) that the +trailing designator is optional and that (2) you can use colons as a +separator character. Thus 10d20' can be entered as 10d20 or 10:20 and +10d20'30\*(R" can be entered as 10:20:30. +.IP "Unix shells (sh, bash, tsch)" 4 +.IX Item "Unix shells (sh, bash, tsch)" +The characters ' and \*(L" can be quoted by preceding them with a \e +(backslash); or you can quote a string containing ' with a pair of \*(R"s. +The two alternatives are illustrated by +.Sp +.Vb 2 +\& echo 10d20\e\*(Aq30\e" "20d30\*(Aq40" | GeoConvert \-d \-p \-1 +\& => 10d20\*(Aq30"N 020d30\*(Aq40"E +.Ve +.Sp +Quoting of command line arguments is similar +.Sp +.Vb 2 +\& GeoConvert \-d \-p \-1 \-\-input\-string "10d20\*(Aq30\e" 20d30\*(Aq40" +\& => 10d20\*(Aq30"N 020d30\*(Aq40"E +.Ve +.IP "Windows command shell (cmd)" 4 +.IX Item "Windows command shell (cmd)" +The ' character needs no quoting; the " character can either be quoted +by a ^ or can be represented by typing ' twice. (This quoting is +usually unnecessary because the trailing designator can be omitted.) +Thus +.Sp +.Vb 2 +\& echo 10d20\*(Aq30\*(Aq\*(Aq 20d30\*(Aq40 | GeoConvert \-d \-p \-1 +\& => 10d20\*(Aq30"N 020d30\*(Aq40"E +.Ve +.Sp +Use \e to quote the " character in a command line argument +.Sp +.Vb 2 +\& GeoConvert \-d \-p \-1 \-\-input\-string "10d20\*(Aq30\e" 20d30\*(Aq40" +\& => 10d20\*(Aq30"N 020d30\*(Aq40"E +.Ve +.IP "Input from a file" 4 +.IX Item "Input from a file" +No quoting need be done if the input from a file. Thus each line of the +file \f(CW\*(C`input.txt\*(C'\fR should just contain the plain coordinates. +.Sp +.Vb 1 +\& GeoConvert \-d \-p \-1 < input.txt +.Ve .SH "MGRS" .IX Header "MGRS" \&\s-1MGRS\s0 coordinates represent a square patch of the earth, thus \f(CW\*(C`38SMB4488\*(C'\fR -is in zone \f(CW\*(C`38N\*(C'\fR with 444km <= \fIeasting\fR < 445km and 3688km <= +is in zone \f(CW\*(C`38n\*(C'\fR with 444km <= \fIeasting\fR < 445km and 3688km <= \&\fInorthing\fR < 3689km. Consistent with this representation, coordinates are \fItruncated\fR (instead of \fIrounded\fR) to the requested precision. Similarly, on input an \s-1MGRS\s0 coordinate represents the -\&\fIcenter\fR of the square (\f(CW\*(C`38N 444500 3688500\*(C'\fR in the example above). +\&\fIcenter\fR of the square (\f(CW\*(C`38n 444500 3688500\*(C'\fR in the example above). However, if the \fB\-n\fR option is given then the south-west corner of the -square is returned instead (\f(CW\*(C`38N 444000 3688000\*(C'\fR in the example above). +square is returned instead (\f(CW\*(C`38n 444000 3688000\*(C'\fR in the example above). .SH "ZONE" .IX Header "ZONE" If the input is \fBgeographic\fR, \fBGeoConvert\fR uses the standard rules of @@ -304,7 +411,7 @@ selecting \s-1UTM\s0 vs \s-1UPS\s0 and for assigning the \s-1UTM\s0 zone (with t Svalbard exceptions). If the input is \fB\s-1UTM/UPS\s0\fR or \fB\s-1MGRS\s0\fR, then the choice between \s-1UTM\s0 and \s-1UPS\s0 and the \s-1UTM\s0 zone mirrors the input. The \fB\-z\fR \&\fIzone\fR, \fB\-s\fR, and \fB\-t\fR options allow these rules to be overridden -with \fIzone\fR = 0 being used to indicate \s-1UPS\s0. For example, the point +with \fIzone\fR = 0 being used to indicate \s-1UPS.\s0 For example, the point .PP .Vb 1 \& 79.9S 6.1E @@ -331,73 +438,49 @@ Is \fIzone\fR is specified with a hemisphere, then this is honored when printing \s-1UTM\s0 coordinates: .PP .Vb 4 -\& echo \-1 3 | GeoConvert \-u => 31S 500000 9889470 -\& echo \-1 3 | GeoConvert \-u \-z 31 => 31S 500000 9889470 -\& echo \-1 3 | GeoConvert \-u \-z 31S => 31S 500000 9889470 -\& echo \-1 3 | GeoConvert \-u \-z 31N => 31N 500000 \-110530 +\& echo \-1 3 | GeoConvert \-u => 31s 500000 9889470 +\& echo \-1 3 | GeoConvert \-u \-z 31 => 31s 500000 9889470 +\& echo \-1 3 | GeoConvert \-u \-z 31s => 31s 500000 9889470 +\& echo \-1 3 | GeoConvert \-u \-z 31n => 31n 500000 \-110530 .Ve .PP \&\fB\s-1NOTE\s0\fR: the letter in the zone specification for \s-1UTM\s0 is a hemisphere -designator \fIN\fR or \fIS\fR and \fInot\fR an \s-1MGRS\s0 latitude band letter. +designator \fIn\fR or \fIs\fR and \fInot\fR an \s-1MGRS\s0 latitude band letter. Convert the \s-1MGRS\s0 latitude band letter to a hemisphere as follows: -replace \fIC\fR thru \fIM\fR by \fIS\fR; replace \fIN\fR thru \fIX\fR by \fIN\fR. -.SH "QUOTING" -.IX Header "QUOTING" -Unfortunately the characters ' and \*(L" have special meanings in many -shells and have to be entered with care. However note (1) that the -trailing designator is optional and that (2) you can use colons as a -separator character. Thus 10d20' can be entered as 10d20 or 10:20 and -10d20'30\*(R" can be entered as 10:20:30. -.IP "Unix shells (sh, bash, tsch)" 4 -.IX Item "Unix shells (sh, bash, tsch)" -The characters ' and \*(L" can be quoted by preceding them with a \e -(backslash); or you can quote a ' with a pair of \*(R"s. The two -alternatives are illustrated by -.Sp -.Vb 2 -\& echo 10d20\e\*(Aq30\e" "20d30\*(Aq40" | GeoConvert \-d \-p \-1 -\& => 10d20\*(Aq30"N 020d30\*(Aq40"E -.Ve -.Sp -Quoting of command line arguments is similar -.Sp -.Vb 2 -\& GeoConvert \-d \-p \-1 \-\-input\-string "10d20\*(Aq30\e" 20d30\*(Aq40" -\& => 10d20\*(Aq30"N 020d30\*(Aq40"E -.Ve -.IP "Windows command shell (cmd)" 4 -.IX Item "Windows command shell (cmd)" -The ' character needs no quoting and the " character can be quoted by a -^. (This quoting is usually unnecessary because the trailing designator -can be omitted.) Thus -.Sp -.Vb 2 -\& echo 10d20\*(Aq30^" 20d30\*(Aq40 | GeoConvert \-d \-p \-1 -\& => 10d20\*(Aq30"N 020d30\*(Aq40"E -.Ve -.Sp -Use \e to quote the " character in a command line argument -.Sp -.Vb 2 -\& GeoConvert \-d \-p \-1 \-\-input\-string "10d20\*(Aq30\e" 20d30\*(Aq40" -\& => 10d20\*(Aq30"N 020d30\*(Aq40"E -.Ve -.IP "Input from a file" 4 -.IX Item "Input from a file" -No quoting need be done if the input from a file. Thus each line of the -file \f(CW\*(C`input.txt\*(C'\fR should just contain the plain coordinates. -.Sp -.Vb 1 -\& GeoConvert \-d \-p \-1 < input.txt -.Ve +replace \fIC\fR thru \fIM\fR by \fIs\fR (or \fIsouth\fR); replace \fIN\fR thru \fIX\fR by +\&\fIn\fR (or \fInorth\fR). .SH "EXAMPLES" .IX Header "EXAMPLES" .Vb 4 \& echo 38SMB4488 | GeoConvert => 33.33424 44.40363 \& echo 38SMB4488 | GeoConvert \-: \-p 1 => 33:20:03.25N 044:2413.06E -\& echo 38SMB4488 | GeoConvert \-u => 38N 444500 3688500 +\& echo 38SMB4488 | GeoConvert \-u => 38n 444500 3688500 \& echo E44d24 N33d20 | GeoConvert \-m \-p \-3 => 38SMB4488 .Ve +.PP +GeoConvert can be used to do simple arithmetic using degree, minutes, +and seconds. For example, sometimes data is tiled in 15 second squares +tagged by the \s-1DMS\s0 representation of the \s-1SW\s0 corner. The tags of the tile +at 38:59:45N 077:02:00W and its 8 neighbors are then given by +.PP +.Vb 10 +\& t=0:0:15 +\& for y in \-$t +0 +$t; do +\& for x in \-$t +0 +$t; do +\& echo 38:59:45N$y 077:02:00W$x +\& done +\& done | GeoConvert \-: \-p \-1 | tr \-d \*(Aq: \*(Aq +\& => +\& 385930N0770215W +\& 385930N0770200W +\& 385930N0770145W +\& 385945N0770215W +\& 385945N0770200W +\& 385945N0770145W +\& 390000N0770215W +\& 390000N0770200W +\& 390000N0770145W +.Ve .SH "ERRORS" .IX Header "ERRORS" An illegal line of input will print an error message to standard output @@ -409,30 +492,33 @@ following lines will be converted. .IP "\fB\s-1UTM\s0\fR" 4 .IX Item "UTM" Universal Transverse Mercator, -. +. .IP "\fB\s-1UPS\s0\fR" 4 .IX Item "UPS" Universal Polar Stereographic, -. +. .IP "\fB\s-1MGRS\s0\fR" 4 .IX Item "MGRS" Military Grid Reference System, -. +. .IP "\fB\s-1WGS84\s0\fR" 4 .IX Item "WGS84" World Geodetic System 1984, -. +. .SH "SEE ALSO" .IX Header "SEE ALSO" +An online version of this utility is availbable at +. +.PP The algorithms for the transverse Mercator projection are described in C. F. F. Karney, \fITransverse Mercator with an accuracy of a few nanometers\fR, J. Geodesy \fB85\fR(8), 475\-485 (Aug. 2011); \s-1DOI\s0 -http://dx.doi.org/10.1007/s00190\-011\-0445\-3 ; preprint -. +; preprint +. .SH "AUTHOR" .IX Header "AUTHOR" \&\fBGeoConvert\fR was written by Charles Karney. .SH "HISTORY" .IX Header "HISTORY" \&\fBGeoConvert\fR was added to GeographicLib, -, in 2009\-01. +, in 2009\-01. diff --git a/gtsam/3rdparty/GeographicLib/man/GeoConvert.1.html b/gtsam/3rdparty/GeographicLib/man/GeoConvert.1.html index 5c117b49e..14096f46f 100644 --- a/gtsam/3rdparty/GeographicLib/man/GeoConvert.1.html +++ b/gtsam/3rdparty/GeographicLib/man/GeoConvert.1.html @@ -7,7 +7,7 @@ - + @@ -17,7 +17,7 @@

    SYNOPSIS

    -

    GeoConvert [ -g | -d | -: | -u | -m | -c ] [ -p prec ] [ -z zone | -s | -t ] [ -n ] [ -w ] [ --comment-delimiter commentdelim ] [ --version | -h | --help ] [ --input-file infile | --input-string instring ] [ --line-separator linesep ] [ --output-file outfile ]

    +

    GeoConvert [ -g | -d | -: | -u | -m | -c ] [ -z zone | -s | -t | -S | -T ] [ -n ] [ -w ] [ -p prec ] [ -l | -a ] [ --comment-delimiter commentdelim ] [ --version | -h | --help ] [ --input-file infile | --input-string instring ] [ --line-separator linesep ] [ --output-file outfile ]

    DESCRIPTION

    @@ -28,24 +28,24 @@
    geographic
    -

    2 tokens (output options -g, -d, or -:) given as latitude longitude using decimal degrees or degrees minutes seconds. d, ', and " are used to denote degrees, minutes, and seconds, with the least significant designator optional. (See "QUOTING" for how to quote the characters ' and " when entering coordinates on the command line.) Various unicode characters (encoded with UTF-8) may also be used to denote degrees, minutes, and seconds, e.g., the degree, prime, and double prime symbols. Alternatively, : (colon) may be used to separate the various components. Latitude is given first (unless the -w option is given); however, on input, either may be given first by appending or prepending N or S to the latitude and E or W to the longitude. For example, the following are all equivalent

    +

    2 tokens (output options -g, -d, or -:) given as latitude longitude using decimal degrees or degrees, minutes, and seconds. Latitude is given first (unless the -w option is given). See "GEOGRAPHIC COORDINATES" for a description of the format. For example, the following are all equivalent

        33.3 44.4
         E44.4 N33.3
         33d18'N 44d24'E
         44d24 33d18N
    -    33:18 44:24
    + 33:18 +44:24
    UTM/UPS
    -

    3 tokens (output option -u) given as zone+hemisphere easting northing or easting northing zone+hemisphere, where hemisphere is either N or S. The zone is absent for a UPS specification. For example,

    +

    3 tokens (output option -u) given as zone+hemisphere easting northing or easting northing zone+hemisphere, where hemisphere is either n (or north) or s (or south). The zone is absent for a UPS specification. For example,

    -
        38N 444140.54 3684706.36
    -    444140.54 3684706.36 38N
    -    S 2173854.98 2985980.58
    -    2173854.98 2985980.58 S
    +
        38n 444140.54 3684706.36
    +    444140.54 3684706.36 38n
    +    s 2173854.98 2985980.58
    +    2173854.98 2985980.58 s
    MRGS
    @@ -75,7 +75,7 @@

    output latitude and longitude using degrees, minutes, and seconds (DMS).

    -
    -:
    +
    -:

    like -d, except use : as a separator instead of the d, ', and " delimiters.

    @@ -96,19 +96,13 @@
    -c
    -

    output meridian convergence and scale for the corresponding UTM or UPS projection. Convergence is the bearing of grid north given as degrees clockwise from true north.

    +

    output meridian convergence and scale for the corresponding UTM or UPS projection. The meridian convergence is the bearing of grid north given as degrees clockwise from true north.

    -
    -p
    +
    -z zone
    -

    set the output precision to prec (default 0); prec is the precision relative to 1 m. See "PRECISION".

    - -
    -
    -z
    -
    - -

    set the zone to zone for output. Use either 0 < zone <= 60 for a UTM zone or zone = 0 for UPS. Alternatively use a zone+hemisphere designation, e.g., 38N. See "ZONE".

    +

    set the zone to zone for output. Use either 0 < zone <= 60 for a UTM zone or zone = 0 for UPS. Alternatively use a zone+hemisphere designation, e.g., 38n. See "ZONE".

    -s
    @@ -122,6 +116,12 @@

    similar to -s but forces UPS regions to the closest UTM zone.

    + +
    -S or -T
    +
    + +

    behave the same as -s and -t, respectively, until the first legal conversion is performed. For subsequent points, the zone and hemisphere of that conversion are used. This enables a sequence of points to be converted into UTM or UPS using a consistent coordinate system.

    +
    -n
    @@ -132,10 +132,28 @@
    -w
    -

    on input and output, longitude precedes latitude (except that on input this can be overridden by a hemisphere designator, N, S, E, W).

    +

    toggle the longitude first flag (it starts off); if the flag is on, then on input and output, longitude precedes latitude (except that, on input, this can be overridden by a hemisphere designator, N, S, E, W).

    -
    --comment-delimiter
    +
    -p prec
    +
    + +

    set the output precision to prec (default 0); prec is the precision relative to 1 m. See "PRECISION".

    + +
    +
    -l
    +
    + +

    on output, UTM/UPS uses the long forms north and south to designate the hemisphere instead of n or s.

    + +
    +
    -a
    +
    + +

    on output, UTM/UPS uses the abbreviations n and s to designate the hemisphere instead of north or south; this is the default representation.

    + +
    +
    --comment-delimiter commentdelim

    set the comment delimiter to commentdelim (e.g., "#" or "//"). If set, the input lines will be scanned for this delimiter and, if found, the delimiter and the rest of the line will be removed prior to processing and subsequently appended to the output line (separated by a space).

    @@ -159,25 +177,25 @@

    print full documentation and exit.

    -
    --input-file
    +
    --input-file infile

    read input from the file infile instead of from standard input; a file name of "-" stands for standard input.

    -
    --input-string
    +
    --input-string instring

    read input from the string instring instead of from standard input. All occurrences of the line separator character (default is a semicolon) in instring are converted to newlines before the reading begins.

    -
    --line-separator
    +
    --line-separator linesep

    set the line separator character to linesep. By default this is a semicolon.

    -
    --output-file
    +
    --output-file outfile

    write output to the file outfile instead of to standard output; a file name of "-" stands for standard output.

    @@ -187,11 +205,69 @@

    PRECISION

    -

    prec gives precision of the output with prec = 0 giving 1 m precision, prec = 3 giving 1 mm precision, etc. prec is the number of digits after the decimal point for UTM/UPS. The number of digits per coordinate for MGRS is 5 + prec. For decimal degrees, the number of digits after the decimal point is 5 + prec. For DMS (degree, minute, seconds) output, the number of digits after the decimal point in the seconds components is 1 + prec; if this is negative then use minutes (prec = -2 or -3) or degrees (prec <= -4) as the least significant component. Print convergence, resp. scale, with 5 + prec, resp. 7 + prec, digits after the decimal point. The minimum value of prec is -5 and the maximum is 9 for UTM/UPS, 9 for decimal degrees, 10 for DMS, 6 for MGRS, and 8 for convergence and scale.

    +

    prec gives precision of the output with prec = 0 giving 1 m precision, prec = 3 giving 1 mm precision, etc. prec is the number of digits after the decimal point for UTM/UPS. For MGRS, The number of digits per coordinate is 5 + prec; <prec> = -6 results in just the grid zone. For decimal degrees, the number of digits after the decimal point is 5 + prec. For DMS (degree, minute, seconds) output, the number of digits after the decimal point in the seconds components is 1 + prec; if this is negative then use minutes (prec = -2 or -3) or degrees (prec <= -4) as the least significant component. Print convergence, resp. scale, with 5 + prec, resp. 7 + prec, digits after the decimal point. The minimum value of prec is -5 (-6 for MGRS) and the maximum is 9 for UTM/UPS, 9 for decimal degrees, 10 for DMS, 6 for MGRS, and 8 for convergence and scale.

    + +

    GEOGRAPHIC COORDINATES

    + +

    The utility accepts geographic coordinates, latitude and longitude, in a number of common formats. Latitude precedes longitude, unless the -w option is given which switches this convention. On input, either coordinate may be given first by appending or prepending N or S to the latitude and E or W to the longitude. These hemisphere designators carry an implied sign, positive for N and E and negative for S and W. This sign multiplies any +/- sign prefixing the coordinate. The coordinates may be given as decimal degree or as degrees, minutes, and seconds. d, ', and " are used to denote degrees, minutes, and seconds, with the least significant designator optional. (See "QUOTING" for how to quote the characters ' and " when entering coordinates on the command line.) Alternatively, : (colon) may be used to separate the various components. Only the final component of coordinate can include a decimal point, and the minutes and seconds components must be less than 60.

    + +

    It is also possible to carry out addition or subtraction operations in geographic coordinates. If the coordinate includes interior signs (i.e., not at the beginning or immediately after an initial hemisphere designator), then the coordinate is split before such signs; the pieces are parsed separately and the results summed. For example the point 15" east of 39N 70W is

    + +
        39N 70W+0:0:15E
    + +

    WARNING: "Exponential" notation is not recognized for geographic coordinates. Thus 7.0E1 is illegal, while 7.0E+1 is parsed as (7.0E) + (+1), yielding the same result as 8.0E.

    + +

    Various unicode characters (encoded with UTF-8) may also be used to denote degrees, minutes, and seconds, e.g., the degree, prime, and double prime symbols; in addition two single quotes can be used to represent ".

    + +

    The other GeographicLib utilities use the same rules for interpreting geographic coordinates; in addition, azimuths and arc lengths are interpreted the same way.

    + +

    QUOTING

    + +

    Unfortunately the characters ' and " have special meanings in many shells and have to be entered with care. However note (1) that the trailing designator is optional and that (2) you can use colons as a separator character. Thus 10d20' can be entered as 10d20 or 10:20 and 10d20'30" can be entered as 10:20:30.

    + +
    + +
    Unix shells (sh, bash, tsch)
    +
    + +

    The characters ' and " can be quoted by preceding them with a \ (backslash); or you can quote a string containing ' with a pair of "s. The two alternatives are illustrated by

    + +
       echo 10d20\'30\" "20d30'40" | GeoConvert -d -p -1
    +   => 10d20'30"N 020d30'40"E
    + +

    Quoting of command line arguments is similar

    + +
       GeoConvert -d -p -1 --input-string "10d20'30\" 20d30'40"
    +   => 10d20'30"N 020d30'40"E
    + +
    +
    Windows command shell (cmd)
    +
    + +

    The ' character needs no quoting; the " character can either be quoted by a ^ or can be represented by typing ' twice. (This quoting is usually unnecessary because the trailing designator can be omitted.) Thus

    + +
       echo 10d20'30'' 20d30'40 | GeoConvert -d -p -1
    +   => 10d20'30"N 020d30'40"E
    + +

    Use \ to quote the " character in a command line argument

    + +
       GeoConvert -d -p -1 --input-string "10d20'30\" 20d30'40"
    +   => 10d20'30"N 020d30'40"E
    + +
    +
    Input from a file
    +
    + +

    No quoting need be done if the input from a file. Thus each line of the file input.txt should just contain the plain coordinates.

    + +
      GeoConvert -d -p -1 < input.txt
    + +
    +

    MGRS

    -

    MGRS coordinates represent a square patch of the earth, thus 38SMB4488 is in zone 38N with 444km <= easting < 445km and 3688km <= northing < 3689km. Consistent with this representation, coordinates are truncated (instead of rounded) to the requested precision. Similarly, on input an MGRS coordinate represents the center of the square (38N 444500 3688500 in the example above). However, if the -n option is given then the south-west corner of the square is returned instead (38N 444000 3688000 in the example above).

    +

    MGRS coordinates represent a square patch of the earth, thus 38SMB4488 is in zone 38n with 444km <= easting < 445km and 3688km <= northing < 3689km. Consistent with this representation, coordinates are truncated (instead of rounded) to the requested precision. Similarly, on input an MGRS coordinate represents the center of the square (38n 444500 3688500 in the example above). However, if the -n option is given then the south-west corner of the square is returned instead (38n 444000 3688000 in the example above).

    ZONE

    @@ -214,64 +290,39 @@

    Is zone is specified with a hemisphere, then this is honored when printing UTM coordinates:

    -
       echo -1 3 | GeoConvert -u         => 31S 500000 9889470
    -   echo -1 3 | GeoConvert -u -z 31   => 31S 500000 9889470
    -   echo -1 3 | GeoConvert -u -z 31S  => 31S 500000 9889470
    -   echo -1 3 | GeoConvert -u -z 31N  => 31N 500000 -110530
    +
       echo -1 3 | GeoConvert -u         => 31s 500000 9889470
    +   echo -1 3 | GeoConvert -u -z 31   => 31s 500000 9889470
    +   echo -1 3 | GeoConvert -u -z 31s  => 31s 500000 9889470
    +   echo -1 3 | GeoConvert -u -z 31n  => 31n 500000 -110530
    -

    NOTE: the letter in the zone specification for UTM is a hemisphere designator N or S and not an MGRS latitude band letter. Convert the MGRS latitude band letter to a hemisphere as follows: replace C thru M by S; replace N thru X by N.

    - -

    QUOTING

    - -

    Unfortunately the characters ' and " have special meanings in many shells and have to be entered with care. However note (1) that the trailing designator is optional and that (2) you can use colons as a separator character. Thus 10d20' can be entered as 10d20 or 10:20 and 10d20'30" can be entered as 10:20:30.

    - -
    - -
    Unix shells (sh, bash, tsch)
    -
    - -

    The characters ' and " can be quoted by preceding them with a \ (backslash); or you can quote a ' with a pair of "s. The two alternatives are illustrated by

    - -
       echo 10d20\'30\" "20d30'40" | GeoConvert -d -p -1
    -   => 10d20'30"N 020d30'40"E
    - -

    Quoting of command line arguments is similar

    - -
       GeoConvert -d -p -1 --input-string "10d20'30\" 20d30'40"
    -   => 10d20'30"N 020d30'40"E
    - -
    -
    Windows command shell (cmd)
    -
    - -

    The ' character needs no quoting and the " character can be quoted by a ^. (This quoting is usually unnecessary because the trailing designator can be omitted.) Thus

    - -
       echo 10d20'30^" 20d30'40 | GeoConvert -d -p -1
    -   => 10d20'30"N 020d30'40"E
    - -

    Use \ to quote the " character in a command line argument

    - -
       GeoConvert -d -p -1 --input-string "10d20'30\" 20d30'40"
    -   => 10d20'30"N 020d30'40"E
    - -
    -
    Input from a file
    -
    - -

    No quoting need be done if the input from a file. Thus each line of the file input.txt should just contain the plain coordinates.

    - -
      GeoConvert -d -p -1 < input.txt
    - -
    -
    +

    NOTE: the letter in the zone specification for UTM is a hemisphere designator n or s and not an MGRS latitude band letter. Convert the MGRS latitude band letter to a hemisphere as follows: replace C thru M by s (or south); replace N thru X by n (or north).

    EXAMPLES

       echo 38SMB4488 | GeoConvert         => 33.33424 44.40363
        echo 38SMB4488 | GeoConvert -: -p 1 => 33:20:03.25N 044:2413.06E
    -   echo 38SMB4488 | GeoConvert -u      => 38N 444500 3688500
    +   echo 38SMB4488 | GeoConvert -u      => 38n 444500 3688500
        echo E44d24 N33d20 | GeoConvert -m -p -3 => 38SMB4488
    +

    GeoConvert can be used to do simple arithmetic using degree, minutes, and seconds. For example, sometimes data is tiled in 15 second squares tagged by the DMS representation of the SW corner. The tags of the tile at 38:59:45N 077:02:00W and its 8 neighbors are then given by

    + +
        t=0:0:15
    +    for y in -$t +0 +$t; do
    +        for x in -$t +0 +$t; do
    +            echo 38:59:45N$y 077:02:00W$x
    +        done
    +    done | GeoConvert -: -p -1 | tr -d ': '
    +    =>
    +    385930N0770215W
    +    385930N0770200W
    +    385930N0770145W
    +    385945N0770215W
    +    385945N0770200W
    +    385945N0770145W
    +    390000N0770215W
    +    390000N0770200W
    +    390000N0770145W
    +

    ERRORS

    An illegal line of input will print an error message to standard output beginning with ERROR: and causes GeoConvert to return an exit code of 1. However, an error does not cause GeoConvert to terminate; following lines will be converted.

    @@ -283,32 +334,34 @@
    UTM
    -

    Universal Transverse Mercator, http://en.wikipedia.org/wiki/Universal_Transverse_Mercator_coordinate_system.

    +

    Universal Transverse Mercator, https://en.wikipedia.org/wiki/Universal_Transverse_Mercator_coordinate_system.

    UPS
    -

    Universal Polar Stereographic, http://en.wikipedia.org/wiki/Universal_Polar_Stereographic.

    +

    Universal Polar Stereographic, https://en.wikipedia.org/wiki/Universal_Polar_Stereographic.

    MGRS
    -

    Military Grid Reference System, http://en.wikipedia.org/wiki/Military_grid_reference_system.

    +

    Military Grid Reference System, https://en.wikipedia.org/wiki/Military_grid_reference_system.

    WGS84
    -

    World Geodetic System 1984, http://en.wikipedia.org/wiki/WGS84.

    +

    World Geodetic System 1984, https://en.wikipedia.org/wiki/WGS84.

    SEE ALSO

    -

    The algorithms for the transverse Mercator projection are described in C. F. F. Karney, Transverse Mercator with an accuracy of a few nanometers, J. Geodesy 85(8), 475-485 (Aug. 2011); DOI http://dx.doi.org/10.1007/s00190-011-0445-3; preprint http://arxiv.org/abs/1002.1417.

    +

    An online version of this utility is availbable at https://geographiclib.sourceforge.io/cgi-bin/GeoConvert.

    + +

    The algorithms for the transverse Mercator projection are described in C. F. F. Karney, Transverse Mercator with an accuracy of a few nanometers, J. Geodesy 85(8), 475-485 (Aug. 2011); DOI https://doi.org/10.1007/s00190-011-0445-3; preprint https://arxiv.org/abs/1002.1417.

    AUTHOR

    @@ -316,7 +369,7 @@

    HISTORY

    -

    GeoConvert was added to GeographicLib, http://geographiclib.sf.net, in 2009-01.

    +

    GeoConvert was added to GeographicLib, https://geographiclib.sourceforge.io, in 2009-01.

    diff --git a/gtsam/3rdparty/GeographicLib/man/GeoConvert.pod b/gtsam/3rdparty/GeographicLib/man/GeoConvert.pod index f3681ca2c..60290b91c 100644 --- a/gtsam/3rdparty/GeographicLib/man/GeoConvert.pod +++ b/gtsam/3rdparty/GeographicLib/man/GeoConvert.pod @@ -5,7 +5,8 @@ GeoConvert -- convert geographic coordinates =head1 SYNOPSIS B [ B<-g> | B<-d> | B<-:> | B<-u> | B<-m> | B<-c> ] -[ B<-p> I ] [ B<-z> I | B<-s> | B<-t> ] [ B<-n> ] [ B<-w> ] +[ B<-z> I | B<-s> | B<-t> | B<-S> | B<-T> ] +[ B<-n> ] [ B<-w> ] [ B<-p> I ] [ B<-l> | B<-a> ] [ B<--comment-delimiter> I ] [ B<--version> | B<-h> | B<--help> ] [ B<--input-file> I | B<--input-string> I ] @@ -27,35 +28,28 @@ is used (I = 6378137 m, I = 1/298.257223563). =item B 2 tokens (output options B<-g>, B<-d>, or B<-:>) given as I -I using decimal degrees or degrees minutes seconds. d, ', -and " are used to denote degrees, minutes, and seconds, with the least -significant designator optional. (See L for how to -quote the characters ' and " when entering coordinates on the command -line.) Various unicode characters (encoded with UTF-8) may also be used -to denote degrees, minutes, and seconds, e.g., the degree, prime, and -double prime symbols. Alternatively, : (colon) may be used to separate -the various components. Latitude is given first (unless the B<-w> -option is given); however, on input, either may be given first by -appending or prepending I or I to the latitude and I or I to -the longitude. For example, the following are all equivalent +I using decimal degrees or degrees, minutes, and seconds. +Latitude is given first (unless the B<-w> option is given). See +L for a description of the format. For +example, the following are all equivalent 33.3 44.4 E44.4 N33.3 33d18'N 44d24'E 44d24 33d18N - 33:18 44:24 + 33:18 +44:24 =item B 3 tokens (output option B<-u>) given as I+I I I or I I I+I, where -I is either I or I. The I is absent for a UPS -specification. For example, +I is either I (or I) or I (or I). The +I is absent for a UPS specification. For example, - 38N 444140.54 3684706.36 - 444140.54 3684706.36 38N - S 2173854.98 2985980.58 - 2173854.98 2985980.58 S + 38n 444140.54 3684706.36 + 444140.54 3684706.36 38n + s 2173854.98 2985980.58 + 2173854.98 2985980.58 s =item B @@ -94,20 +88,15 @@ output MGRS. =item B<-c> -output meridian convergence and scale for the corresponding UTM or -UPS projection. Convergence is the bearing of grid north given as -degrees clockwise from true north. +output meridian convergence and scale for the corresponding UTM or UPS +projection. The meridian convergence is the bearing of grid north given +as degrees clockwise from true north. -=item B<-p> - -set the output precision to I (default 0); I is the -precision relative to 1 m. See L. - -=item B<-z> +=item B<-z> I set the zone to I for output. Use either 0 E I E= 60 for a UTM zone or I = 0 for UPS. Alternatively use a -I+I designation, e.g., 38N. See L. +I+I designation, e.g., 38n. See L. =item B<-s> @@ -117,6 +106,13 @@ use the standard UPS and UTM zones. similar to B<-s> but forces UPS regions to the closest UTM zone. +=item B<-S> or B<-T> + +behave the same as B<-s> and B<-t>, respectively, until the first legal +conversion is performed. For subsequent points, the zone and hemisphere +of that conversion are used. This enables a sequence of points to be +converted into UTM or UPS using a consistent coordinate system. + =item B<-n> on input, MGRS coordinates refer to the south-west corner of the MGRS @@ -124,11 +120,28 @@ square instead of the center; see L. =item B<-w> -on input and output, longitude precedes latitude (except that on input +toggle the longitude first flag (it starts off); if the flag is on, then +on input and output, longitude precedes latitude (except that, on input, this can be overridden by a hemisphere designator, I, I, I, I). -=item B<--comment-delimiter> +=item B<-p> I + +set the output precision to I (default 0); I is the +precision relative to 1 m. See L. + +=item B<-l> + +on output, UTM/UPS uses the long forms I and I to +designate the hemisphere instead of I or I. + +=item B<-a> + +on output, UTM/UPS uses the abbreviations I and I to designate the +hemisphere instead of I or I; this is the default +representation. + +=item B<--comment-delimiter> I set the comment delimiter to I (e.g., "#" or "//"). If set, the input lines will be scanned for this delimiter and, if found, @@ -148,23 +161,23 @@ print usage and exit. print full documentation and exit. -=item B<--input-file> +=item B<--input-file> I read input from the file I instead of from standard input; a file name of "-" stands for standard input. -=item B<--input-string> +=item B<--input-string> I read input from the string I instead of from standard input. All occurrences of the line separator character (default is a semicolon) in I are converted to newlines before the reading begins. -=item B<--line-separator> +=item B<--line-separator> I set the line separator character to I. By default this is a semicolon. -=item B<--output-file> +=item B<--output-file> I write output to the file I instead of to standard output; a file name of "-" stands for standard output. @@ -174,28 +187,117 @@ file name of "-" stands for standard output. =head1 PRECISION I gives precision of the output with I = 0 giving 1 m -precision, I = 3 giving 1 mm precision, etc. I is the number -of digits after the decimal point for UTM/UPS. The number of digits per -coordinate for MGRS is 5 + I. For decimal degrees, the number of -digits after the decimal point is 5 + I. For DMS (degree, minute, -seconds) output, the number of digits after the decimal point in the -seconds components is 1 + I; if this is negative then use minutes -(I = -2 or -3) or degrees (I E= -4) as the least significant -component. Print convergence, resp. scale, with 5 + I, resp. 7 + -I, digits after the decimal point. The minimum value of I is --5 and the maximum is 9 for UTM/UPS, 9 for decimal degrees, 10 for DMS, -6 for MGRS, and 8 for convergence and scale. +precision, I = 3 giving 1 mm precision, etc. I is the +number of digits after the decimal point for UTM/UPS. For MGRS, The +number of digits per coordinate is 5 + I; = -6 results in +just the grid zone. For decimal degrees, the number of digits after the +decimal point is 5 + I. For DMS (degree, minute, seconds) output, +the number of digits after the decimal point in the seconds components +is 1 + I; if this is negative then use minutes (I = -2 or +-3) or degrees (I E= -4) as the least significant component. +Print convergence, resp. scale, with 5 + I, resp. 7 + I, +digits after the decimal point. The minimum value of I is -5 (-6 +for MGRS) and the maximum is 9 for UTM/UPS, 9 for decimal degrees, 10 +for DMS, 6 for MGRS, and 8 for convergence and scale. + +=head1 GEOGRAPHIC COORDINATES + +The utility accepts geographic coordinates, latitude and longitude, in a +number of common formats. Latitude precedes longitude, unless the B<-w> +option is given which switches this convention. On input, either +coordinate may be given first by appending or prepending I or I to +the latitude and I or I to the longitude. These hemisphere +designators carry an implied sign, positive for I and I and +negative for I and I. This sign multiplies any +/- sign prefixing +the coordinate. The coordinates may be given as decimal degree or as +degrees, minutes, and seconds. d, ', and " are used to denote degrees, +minutes, and seconds, with the least significant designator optional. +(See L for how to quote the characters ' and " when entering +coordinates on the command line.) Alternatively, : (colon) may be used +to separate the various components. Only the final component of +coordinate can include a decimal point, and the minutes and seconds +components must be less than 60. + +It is also possible to carry out addition or subtraction operations in +geographic coordinates. If the coordinate includes interior signs +(i.e., not at the beginning or immediately after an initial hemisphere +designator), then the coordinate is split before such signs; the pieces +are parsed separately and the results summed. For example the point 15" +east of 39N 70W is + + 39N 70W+0:0:15E + +B "Exponential" notation is not recognized for geographic +coordinates. Thus 7.0E1 is illegal, while 7.0E+1 is parsed +as (7.0E) + (+1), yielding the same result as 8.0E. + +Various unicode characters (encoded with UTF-8) may also be used to +denote degrees, minutes, and seconds, e.g., the degree, prime, and +double prime symbols; in addition two single quotes can be used to +represent ". + +The other GeographicLib utilities use the same rules for interpreting +geographic coordinates; in addition, azimuths and arc lengths are +interpreted the same way. + +=head1 QUOTING + +Unfortunately the characters ' and " have special meanings in many +shells and have to be entered with care. However note (1) that the +trailing designator is optional and that (2) you can use colons as a +separator character. Thus 10d20' can be entered as 10d20 or 10:20 and +10d20'30" can be entered as 10:20:30. + +=over + +=item Unix shells (sh, bash, tsch) + +The characters ' and " can be quoted by preceding them with a \ +(backslash); or you can quote a string containing ' with a pair of "s. +The two alternatives are illustrated by + + echo 10d20\'30\" "20d30'40" | GeoConvert -d -p -1 + => 10d20'30"N 020d30'40"E + +Quoting of command line arguments is similar + + GeoConvert -d -p -1 --input-string "10d20'30\" 20d30'40" + => 10d20'30"N 020d30'40"E + +=item Windows command shell (cmd) + +The ' character needs no quoting; the " character can either be quoted +by a ^ or can be represented by typing ' twice. (This quoting is +usually unnecessary because the trailing designator can be omitted.) +Thus + + echo 10d20'30'' 20d30'40 | GeoConvert -d -p -1 + => 10d20'30"N 020d30'40"E + +Use \ to quote the " character in a command line argument + + GeoConvert -d -p -1 --input-string "10d20'30\" 20d30'40" + => 10d20'30"N 020d30'40"E + +=item Input from a file + +No quoting need be done if the input from a file. Thus each line of the +file C should just contain the plain coordinates. + + GeoConvert -d -p -1 < input.txt + +=back =head1 MGRS MGRS coordinates represent a square patch of the earth, thus C<38SMB4488> -is in zone C<38N> with 444km E= I E 445km and 3688km E= +is in zone C<38n> with 444km E= I E 445km and 3688km E= I E 3689km. Consistent with this representation, coordinates are I (instead of I) to the requested precision. Similarly, on input an MGRS coordinate represents the -I
    of the square (C<38N 444500 3688500> in the example above). +I
    of the square (C<38n 444500 3688500> in the example above). However, if the B<-n> option is given then the south-west corner of the -square is returned instead (C<38N 444000 3688000> in the example above). +square is returned instead (C<38n 444000 3688000> in the example above). =head1 ZONE @@ -224,70 +326,46 @@ then Is I is specified with a hemisphere, then this is honored when printing UTM coordinates: - echo -1 3 | GeoConvert -u => 31S 500000 9889470 - echo -1 3 | GeoConvert -u -z 31 => 31S 500000 9889470 - echo -1 3 | GeoConvert -u -z 31S => 31S 500000 9889470 - echo -1 3 | GeoConvert -u -z 31N => 31N 500000 -110530 + echo -1 3 | GeoConvert -u => 31s 500000 9889470 + echo -1 3 | GeoConvert -u -z 31 => 31s 500000 9889470 + echo -1 3 | GeoConvert -u -z 31s => 31s 500000 9889470 + echo -1 3 | GeoConvert -u -z 31n => 31n 500000 -110530 B: the letter in the zone specification for UTM is a hemisphere -designator I or I and I an MGRS latitude band letter. +designator I or I and I an MGRS latitude band letter. Convert the MGRS latitude band letter to a hemisphere as follows: -replace I thru I by I; replace I thru I by I. - -=head1 QUOTING - -Unfortunately the characters ' and " have special meanings in many -shells and have to be entered with care. However note (1) that the -trailing designator is optional and that (2) you can use colons as a -separator character. Thus 10d20' can be entered as 10d20 or 10:20 and -10d20'30" can be entered as 10:20:30. - -=over - -=item Unix shells (sh, bash, tsch) - -The characters ' and " can be quoted by preceding them with a \ -(backslash); or you can quote a ' with a pair of "s. The two -alternatives are illustrated by - - echo 10d20\'30\" "20d30'40" | GeoConvert -d -p -1 - => 10d20'30"N 020d30'40"E - -Quoting of command line arguments is similar - - GeoConvert -d -p -1 --input-string "10d20'30\" 20d30'40" - => 10d20'30"N 020d30'40"E - -=item Windows command shell (cmd) - -The ' character needs no quoting and the " character can be quoted by a -^. (This quoting is usually unnecessary because the trailing designator -can be omitted.) Thus - - echo 10d20'30^" 20d30'40 | GeoConvert -d -p -1 - => 10d20'30"N 020d30'40"E - -Use \ to quote the " character in a command line argument - - GeoConvert -d -p -1 --input-string "10d20'30\" 20d30'40" - => 10d20'30"N 020d30'40"E - -=item Input from a file - -No quoting need be done if the input from a file. Thus each line of the -file C should just contain the plain coordinates. - - GeoConvert -d -p -1 < input.txt - -=back +replace I thru I by I (or I); replace I thru I by +I (or I). =head1 EXAMPLES echo 38SMB4488 | GeoConvert => 33.33424 44.40363 echo 38SMB4488 | GeoConvert -: -p 1 => 33:20:03.25N 044:2413.06E - echo 38SMB4488 | GeoConvert -u => 38N 444500 3688500 + echo 38SMB4488 | GeoConvert -u => 38n 444500 3688500 echo E44d24 N33d20 | GeoConvert -m -p -3 => 38SMB4488 +GeoConvert can be used to do simple arithmetic using degree, minutes, +and seconds. For example, sometimes data is tiled in 15 second squares +tagged by the DMS representation of the SW corner. The tags of the tile +at 38:59:45N 077:02:00W and its 8 neighbors are then given by + + t=0:0:15 + for y in -$t +0 +$t; do + for x in -$t +0 +$t; do + echo 38:59:45N$y 077:02:00W$x + done + done | GeoConvert -: -p -1 | tr -d ': ' + => + 385930N0770215W + 385930N0770200W + 385930N0770145W + 385945N0770215W + 385945N0770200W + 385945N0770145W + 390000N0770215W + 390000N0770200W + 390000N0770145W + =head1 ERRORS An illegal line of input will print an error message to standard output @@ -302,32 +380,35 @@ following lines will be converted. =item B Universal Transverse Mercator, -L. +L. =item B Universal Polar Stereographic, -L. +L. =item B Military Grid Reference System, -L. +L. =item B World Geodetic System 1984, -L. +L. =back =head1 SEE ALSO +An online version of this utility is availbable at +L. + The algorithms for the transverse Mercator projection are described in C. F. F. Karney, I, J. Geodesy B<85>(8), 475-485 (Aug. 2011); DOI -L; preprint -L. +L; preprint +L. =head1 AUTHOR @@ -336,4 +417,4 @@ B was written by Charles Karney. =head1 HISTORY B was added to GeographicLib, -L, in 2009-01. +L, in 2009-01. diff --git a/gtsam/3rdparty/GeographicLib/man/GeoConvert.usage b/gtsam/3rdparty/GeographicLib/man/GeoConvert.usage index 19d78a3ef..55e24201f 100644 --- a/gtsam/3rdparty/GeographicLib/man/GeoConvert.usage +++ b/gtsam/3rdparty/GeographicLib/man/GeoConvert.usage @@ -1,25 +1,27 @@ int usage(int retval, bool brief) { if (brief) ( retval ? std::cerr : std::cout ) << "Usage:\n" -" GeoConvert [ -g | -d | -: | -u | -m | -c ] [ -p prec ] [ -z zone | -s |\n" -" -t ] [ -n ] [ -w ] [ --comment-delimiter commentdelim ] [ --version |\n" -" -h | --help ] [ --input-file infile | --input-string instring ] [\n" -" --line-separator linesep ] [ --output-file outfile ]\n" +" GeoConvert [ -g | -d | -: | -u | -m | -c ] [ -z zone | -s | -t | -S |\n" +" -T ] [ -n ] [ -w ] [ -p prec ] [ -l | -a ] [ --comment-delimiter\n" +" commentdelim ] [ --version | -h | --help ] [ --input-file infile |\n" +" --input-string instring ] [ --line-separator linesep ] [ --output-file\n" +" outfile ]\n" "\n" "For full documentation type:\n" " GeoConvert --help\n" "or visit:\n" -" http://geographiclib.sf.net/1.35/GeoConvert.1.html\n"; +" https://geographiclib.sourceforge.io/1.49/GeoConvert.1.html\n"; else ( retval ? std::cerr : std::cout ) << "Man page:\n" "NAME\n" " GeoConvert -- convert geographic coordinates\n" "\n" "SYNOPSIS\n" -" GeoConvert [ -g | -d | -: | -u | -m | -c ] [ -p prec ] [ -z zone | -s |\n" -" -t ] [ -n ] [ -w ] [ --comment-delimiter commentdelim ] [ --version |\n" -" -h | --help ] [ --input-file infile | --input-string instring ] [\n" -" --line-separator linesep ] [ --output-file outfile ]\n" +" GeoConvert [ -g | -d | -: | -u | -m | -c ] [ -z zone | -s | -t | -S |\n" +" -T ] [ -n ] [ -w ] [ -p prec ] [ -l | -a ] [ --comment-delimiter\n" +" commentdelim ] [ --version | -h | --help ] [ --input-file infile |\n" +" --input-string instring ] [ --line-separator linesep ] [ --output-file\n" +" outfile ]\n" "\n" "DESCRIPTION\n" " GeoConvert reads from standard input interpreting each line as a\n" @@ -32,35 +34,27 @@ int usage(int retval, bool brief) { "\n" " geographic\n" " 2 tokens (output options -g, -d, or -:) given as latitude longitude\n" -" using decimal degrees or degrees minutes seconds. d, ', and \" are\n" -" used to denote degrees, minutes, and seconds, with the least\n" -" significant designator optional. (See \"QUOTING\" for how to quote\n" -" the characters ' and \" when entering coordinates on the command\n" -" line.) Various unicode characters (encoded with UTF-8) may also be\n" -" used to denote degrees, minutes, and seconds, e.g., the degree,\n" -" prime, and double prime symbols. Alternatively, : (colon) may be\n" -" used to separate the various components. Latitude is given first\n" -" (unless the -w option is given); however, on input, either may be\n" -" given first by appending or prepending N or S to the latitude and E\n" -" or W to the longitude. For example, the following are all\n" -" equivalent\n" +" using decimal degrees or degrees, minutes, and seconds. Latitude\n" +" is given first (unless the -w option is given). See \"GEOGRAPHIC\n" +" COORDINATES\" for a description of the format. For example, the\n" +" following are all equivalent\n" "\n" " 33.3 44.4\n" " E44.4 N33.3\n" " 33d18'N 44d24'E\n" " 44d24 33d18N\n" -" 33:18 44:24\n" +" 33:18 +44:24\n" "\n" " UTM/UPS\n" " 3 tokens (output option -u) given as zone+hemisphere easting\n" " northing or easting northing zone+hemisphere, where hemisphere is\n" -" either N or S. The zone is absent for a UPS specification. For\n" -" example,\n" +" either n (or north) or s (or south). The zone is absent for a UPS\n" +" specification. For example,\n" "\n" -" 38N 444140.54 3684706.36\n" -" 444140.54 3684706.36 38N\n" -" S 2173854.98 2985980.58\n" -" 2173854.98 2985980.58 S\n" +" 38n 444140.54 3684706.36\n" +" 444140.54 3684706.36 38n\n" +" s 2173854.98 2985980.58\n" +" 2173854.98 2985980.58 s\n" "\n" " MRGS\n" " 1 token (output option -m) is used to specify the center of an MGRS\n" @@ -84,28 +78,45 @@ int usage(int retval, bool brief) { " -m output MGRS.\n" "\n" " -c output meridian convergence and scale for the corresponding UTM or\n" -" UPS projection. Convergence is the bearing of grid north given as\n" -" degrees clockwise from true north.\n" +" UPS projection. The meridian convergence is the bearing of grid\n" +" north given as degrees clockwise from true north.\n" "\n" -" -p set the output precision to prec (default 0); prec is the precision\n" -" relative to 1 m. See \"PRECISION\".\n" -"\n" -" -z set the zone to zone for output. Use either 0 < zone <= 60 for a\n" +" -z zone\n" +" set the zone to zone for output. Use either 0 < zone <= 60 for a\n" " UTM zone or zone = 0 for UPS. Alternatively use a zone+hemisphere\n" -" designation, e.g., 38N. See \"ZONE\".\n" +" designation, e.g., 38n. See \"ZONE\".\n" "\n" " -s use the standard UPS and UTM zones.\n" "\n" " -t similar to -s but forces UPS regions to the closest UTM zone.\n" "\n" +" -S or -T\n" +" behave the same as -s and -t, respectively, until the first legal\n" +" conversion is performed. For subsequent points, the zone and\n" +" hemisphere of that conversion are used. This enables a sequence of\n" +" points to be converted into UTM or UPS using a consistent\n" +" coordinate system.\n" +"\n" " -n on input, MGRS coordinates refer to the south-west corner of the\n" " MGRS square instead of the center; see \"MGRS\".\n" "\n" -" -w on input and output, longitude precedes latitude (except that on\n" -" input this can be overridden by a hemisphere designator, N, S, E,\n" -" W).\n" +" -w toggle the longitude first flag (it starts off); if the flag is on,\n" +" then on input and output, longitude precedes latitude (except that,\n" +" on input, this can be overridden by a hemisphere designator, N, S,\n" +" E, W).\n" "\n" -" --comment-delimiter\n" +" -p prec\n" +" set the output precision to prec (default 0); prec is the precision\n" +" relative to 1 m. See \"PRECISION\".\n" +"\n" +" -l on output, UTM/UPS uses the long forms north and south to designate\n" +" the hemisphere instead of n or s.\n" +"\n" +" -a on output, UTM/UPS uses the abbreviations n and s to designate the\n" +" hemisphere instead of north or south; this is the default\n" +" representation.\n" +"\n" +" --comment-delimiter commentdelim\n" " set the comment delimiter to commentdelim (e.g., \"#\" or \"//\"). If\n" " set, the input lines will be scanned for this delimiter and, if\n" " found, the delimiter and the rest of the line will be removed prior\n" @@ -120,47 +131,127 @@ int usage(int retval, bool brief) { " --help\n" " print full documentation and exit.\n" "\n" -" --input-file\n" +" --input-file infile\n" " read input from the file infile instead of from standard input; a\n" " file name of \"-\" stands for standard input.\n" "\n" -" --input-string\n" +" --input-string instring\n" " read input from the string instring instead of from standard input.\n" " All occurrences of the line separator character (default is a\n" " semicolon) in instring are converted to newlines before the reading\n" " begins.\n" "\n" -" --line-separator\n" +" --line-separator linesep\n" " set the line separator character to linesep. By default this is a\n" " semicolon.\n" "\n" -" --output-file\n" +" --output-file outfile\n" " write output to the file outfile instead of to standard output; a\n" " file name of \"-\" stands for standard output.\n" "\n" "PRECISION\n" " prec gives precision of the output with prec = 0 giving 1 m precision,\n" " prec = 3 giving 1 mm precision, etc. prec is the number of digits\n" -" after the decimal point for UTM/UPS. The number of digits per\n" -" coordinate for MGRS is 5 + prec. For decimal degrees, the number of\n" -" digits after the decimal point is 5 + prec. For DMS (degree, minute,\n" -" seconds) output, the number of digits after the decimal point in the\n" -" seconds components is 1 + prec; if this is negative then use minutes\n" -" (prec = -2 or -3) or degrees (prec <= -4) as the least significant\n" -" component. Print convergence, resp. scale, with 5 + prec, resp. 7 +\n" -" prec, digits after the decimal point. The minimum value of prec is -5\n" -" and the maximum is 9 for UTM/UPS, 9 for decimal degrees, 10 for DMS, 6\n" -" for MGRS, and 8 for convergence and scale.\n" +" after the decimal point for UTM/UPS. For MGRS, The number of digits\n" +" per coordinate is 5 + prec; = -6 results in just the grid zone.\n" +" For decimal degrees, the number of digits after the decimal point is 5\n" +" + prec. For DMS (degree, minute, seconds) output, the number of digits\n" +" after the decimal point in the seconds components is 1 + prec; if this\n" +" is negative then use minutes (prec = -2 or -3) or degrees (prec <= -4)\n" +" as the least significant component. Print convergence, resp. scale,\n" +" with 5 + prec, resp. 7 + prec, digits after the decimal point. The\n" +" minimum value of prec is -5 (-6 for MGRS) and the maximum is 9 for\n" +" UTM/UPS, 9 for decimal degrees, 10 for DMS, 6 for MGRS, and 8 for\n" +" convergence and scale.\n" +"\n" +"GEOGRAPHIC COORDINATES\n" +" The utility accepts geographic coordinates, latitude and longitude, in\n" +" a number of common formats. Latitude precedes longitude, unless the -w\n" +" option is given which switches this convention. On input, either\n" +" coordinate may be given first by appending or prepending N or S to the\n" +" latitude and E or W to the longitude. These hemisphere designators\n" +" carry an implied sign, positive for N and E and negative for S and W.\n" +" This sign multiplies any +/- sign prefixing the coordinate. The\n" +" coordinates may be given as decimal degree or as degrees, minutes, and\n" +" seconds. d, ', and \" are used to denote degrees, minutes, and seconds,\n" +" with the least significant designator optional. (See \"QUOTING\" for how\n" +" to quote the characters ' and \" when entering coordinates on the\n" +" command line.) Alternatively, : (colon) may be used to separate the\n" +" various components. Only the final component of coordinate can include\n" +" a decimal point, and the minutes and seconds components must be less\n" +" than 60.\n" +"\n" +" It is also possible to carry out addition or subtraction operations in\n" +" geographic coordinates. If the coordinate includes interior signs\n" +" (i.e., not at the beginning or immediately after an initial hemisphere\n" +" designator), then the coordinate is split before such signs; the pieces\n" +" are parsed separately and the results summed. For example the point\n" +" 15\" east of 39N 70W is\n" +"\n" +" 39N 70W+0:0:15E\n" +"\n" +" WARNING: \"Exponential\" notation is not recognized for geographic\n" +" coordinates. Thus 7.0E1 is illegal, while 7.0E+1 is parsed as (7.0E) +\n" +" (+1), yielding the same result as 8.0E.\n" +"\n" +" Various unicode characters (encoded with UTF-8) may also be used to\n" +" denote degrees, minutes, and seconds, e.g., the degree, prime, and\n" +" double prime symbols; in addition two single quotes can be used to\n" +" represent \".\n" +"\n" +" The other GeographicLib utilities use the same rules for interpreting\n" +" geographic coordinates; in addition, azimuths and arc lengths are\n" +" interpreted the same way.\n" +"\n" +"QUOTING\n" +" Unfortunately the characters ' and \" have special meanings in many\n" +" shells and have to be entered with care. However note (1) that the\n" +" trailing designator is optional and that (2) you can use colons as a\n" +" separator character. Thus 10d20' can be entered as 10d20 or 10:20 and\n" +" 10d20'30\" can be entered as 10:20:30.\n" +"\n" +" Unix shells (sh, bash, tsch)\n" +" The characters ' and \" can be quoted by preceding them with a \\\n" +" (backslash); or you can quote a string containing ' with a pair of\n" +" \"s. The two alternatives are illustrated by\n" +"\n" +" echo 10d20\\'30\\\" \"20d30'40\" | GeoConvert -d -p -1\n" +" => 10d20'30\"N 020d30'40\"E\n" +"\n" +" Quoting of command line arguments is similar\n" +"\n" +" GeoConvert -d -p -1 --input-string \"10d20'30\\\" 20d30'40\"\n" +" => 10d20'30\"N 020d30'40\"E\n" +"\n" +" Windows command shell (cmd)\n" +" The ' character needs no quoting; the \" character can either be\n" +" quoted by a ^ or can be represented by typing ' twice. (This\n" +" quoting is usually unnecessary because the trailing designator can\n" +" be omitted.) Thus\n" +"\n" +" echo 10d20'30'' 20d30'40 | GeoConvert -d -p -1\n" +" => 10d20'30\"N 020d30'40\"E\n" +"\n" +" Use \\ to quote the \" character in a command line argument\n" +"\n" +" GeoConvert -d -p -1 --input-string \"10d20'30\\\" 20d30'40\"\n" +" => 10d20'30\"N 020d30'40\"E\n" +"\n" +" Input from a file\n" +" No quoting need be done if the input from a file. Thus each line\n" +" of the file \"input.txt\" should just contain the plain coordinates.\n" +"\n" +" GeoConvert -d -p -1 < input.txt\n" "\n" "MGRS\n" " MGRS coordinates represent a square patch of the earth, thus\n" -" \"38SMB4488\" is in zone \"38N\" with 444km <= easting < 445km and 3688km\n" +" \"38SMB4488\" is in zone \"38n\" with 444km <= easting < 445km and 3688km\n" " <= northing < 3689km. Consistent with this representation, coordinates\n" " are truncated (instead of rounded) to the requested precision.\n" " Similarly, on input an MGRS coordinate represents the center of the\n" -" square (\"38N 444500 3688500\" in the example above). However, if the -n\n" +" square (\"38n 444500 3688500\" in the example above). However, if the -n\n" " option is given then the south-west corner of the square is returned\n" -" instead (\"38N 444000 3688000\" in the example above).\n" +" instead (\"38n 444000 3688000\" in the example above).\n" "\n" "ZONE\n" " If the input is geographic, GeoConvert uses the standard rules of\n" @@ -188,61 +279,44 @@ int usage(int retval, bool brief) { " Is zone is specified with a hemisphere, then this is honored when\n" " printing UTM coordinates:\n" "\n" -" echo -1 3 | GeoConvert -u => 31S 500000 9889470\n" -" echo -1 3 | GeoConvert -u -z 31 => 31S 500000 9889470\n" -" echo -1 3 | GeoConvert -u -z 31S => 31S 500000 9889470\n" -" echo -1 3 | GeoConvert -u -z 31N => 31N 500000 -110530\n" +" echo -1 3 | GeoConvert -u => 31s 500000 9889470\n" +" echo -1 3 | GeoConvert -u -z 31 => 31s 500000 9889470\n" +" echo -1 3 | GeoConvert -u -z 31s => 31s 500000 9889470\n" +" echo -1 3 | GeoConvert -u -z 31n => 31n 500000 -110530\n" "\n" " NOTE: the letter in the zone specification for UTM is a hemisphere\n" -" designator N or S and not an MGRS latitude band letter. Convert the\n" +" designator n or s and not an MGRS latitude band letter. Convert the\n" " MGRS latitude band letter to a hemisphere as follows: replace C thru M\n" -" by S; replace N thru X by N.\n" -"\n" -"QUOTING\n" -" Unfortunately the characters ' and \" have special meanings in many\n" -" shells and have to be entered with care. However note (1) that the\n" -" trailing designator is optional and that (2) you can use colons as a\n" -" separator character. Thus 10d20' can be entered as 10d20 or 10:20 and\n" -" 10d20'30\" can be entered as 10:20:30.\n" -"\n" -" Unix shells (sh, bash, tsch)\n" -" The characters ' and \" can be quoted by preceding them with a \\\n" -" (backslash); or you can quote a ' with a pair of \"s. The two\n" -" alternatives are illustrated by\n" -"\n" -" echo 10d20\\'30\\\" \"20d30'40\" | GeoConvert -d -p -1\n" -" => 10d20'30\"N 020d30'40\"E\n" -"\n" -" Quoting of command line arguments is similar\n" -"\n" -" GeoConvert -d -p -1 --input-string \"10d20'30\\\" 20d30'40\"\n" -" => 10d20'30\"N 020d30'40\"E\n" -"\n" -" Windows command shell (cmd)\n" -" The ' character needs no quoting and the \" character can be quoted\n" -" by a ^. (This quoting is usually unnecessary because the trailing\n" -" designator can be omitted.) Thus\n" -"\n" -" echo 10d20'30^\" 20d30'40 | GeoConvert -d -p -1\n" -" => 10d20'30\"N 020d30'40\"E\n" -"\n" -" Use \\ to quote the \" character in a command line argument\n" -"\n" -" GeoConvert -d -p -1 --input-string \"10d20'30\\\" 20d30'40\"\n" -" => 10d20'30\"N 020d30'40\"E\n" -"\n" -" Input from a file\n" -" No quoting need be done if the input from a file. Thus each line\n" -" of the file \"input.txt\" should just contain the plain coordinates.\n" -"\n" -" GeoConvert -d -p -1 < input.txt\n" +" by s (or south); replace N thru X by n (or north).\n" "\n" "EXAMPLES\n" " echo 38SMB4488 | GeoConvert => 33.33424 44.40363\n" " echo 38SMB4488 | GeoConvert -: -p 1 => 33:20:03.25N 044:2413.06E\n" -" echo 38SMB4488 | GeoConvert -u => 38N 444500 3688500\n" +" echo 38SMB4488 | GeoConvert -u => 38n 444500 3688500\n" " echo E44d24 N33d20 | GeoConvert -m -p -3 => 38SMB4488\n" "\n" +" GeoConvert can be used to do simple arithmetic using degree, minutes,\n" +" and seconds. For example, sometimes data is tiled in 15 second squares\n" +" tagged by the DMS representation of the SW corner. The tags of the\n" +" tile at 38:59:45N 077:02:00W and its 8 neighbors are then given by\n" +"\n" +" t=0:0:15\n" +" for y in -$t +0 +$t; do\n" +" for x in -$t +0 +$t; do\n" +" echo 38:59:45N$y 077:02:00W$x\n" +" done\n" +" done | GeoConvert -: -p -1 | tr -d ': '\n" +" =>\n" +" 385930N0770215W\n" +" 385930N0770200W\n" +" 385930N0770145W\n" +" 385945N0770215W\n" +" 385945N0770200W\n" +" 385945N0770145W\n" +" 390000N0770215W\n" +" 390000N0770200W\n" +" 390000N0770145W\n" +"\n" "ERRORS\n" " An illegal line of input will print an error message to standard output\n" " beginning with \"ERROR:\" and causes GeoConvert to return an exit code of\n" @@ -251,32 +325,34 @@ int usage(int retval, bool brief) { "\n" "ABBREVIATIONS\n" " UTM Universal Transverse Mercator,\n" -" .\n" +" .\n" "\n" " UPS Universal Polar Stereographic,\n" -" .\n" +" .\n" "\n" " MGRS\n" " Military Grid Reference System,\n" -" .\n" +" .\n" "\n" " WGS84\n" -" World Geodetic System 1984, .\n" +" World Geodetic System 1984, .\n" "\n" "SEE ALSO\n" +" An online version of this utility is availbable at\n" +" .\n" +"\n" " The algorithms for the transverse Mercator projection are described in\n" " C. F. F. Karney, Transverse Mercator with an accuracy of a few\n" " nanometers, J. Geodesy 85(8), 475-485 (Aug. 2011); DOI\n" -" http://dx.doi.org/10.1007/s00190-011-0445-3\n" -" ; preprint\n" -" .\n" +" ; preprint\n" +" .\n" "\n" "AUTHOR\n" " GeoConvert was written by Charles Karney.\n" "\n" "HISTORY\n" -" GeoConvert was added to GeographicLib, ,\n" -" in 2009-01.\n" +" GeoConvert was added to GeographicLib,\n" +" , in 2009-01.\n" ; return retval; } diff --git a/gtsam/3rdparty/GeographicLib/man/GeodSolve.1 b/gtsam/3rdparty/GeographicLib/man/GeodSolve.1 index 3bd025aa4..ee976b810 100644 --- a/gtsam/3rdparty/GeographicLib/man/GeodSolve.1 +++ b/gtsam/3rdparty/GeographicLib/man/GeodSolve.1 @@ -1,4 +1,4 @@ -.\" Automatically generated by Pod::Man 2.25 (Pod::Simple 3.20) +.\" Automatically generated by Pod::Man 4.09 (Pod::Simple 3.35) .\" .\" Standard preamble: .\" ======================================================================== @@ -38,26 +38,31 @@ . ds PI \(*p . ds L" `` . ds R" '' +. ds C` +. ds C' 'br\} .\" .\" Escape single quotes in literal strings from groff's Unicode transform. .ie \n(.g .ds Aq \(aq .el .ds Aq ' .\" -.\" If the F register is turned on, we'll generate index entries on stderr for +.\" If the F register is >0, we'll generate index entries on stderr for .\" titles (.TH), headers (.SH), subsections (.SS), items (.Ip), and index .\" entries marked with X<> in POD. Of course, you'll have to process the .\" output yourself in some meaningful fashion. -.ie \nF \{\ +.\" +.\" Avoid warning from groff about undefined register 'F'. +.de IX +.. +.if !\nF .nr F 0 +.if \nF>0 \{\ . de IX . tm Index:\\$1\t\\n%\t"\\$2" .. -. nr % 0 -. rr F -.\} -.el \{\ -. de IX -.. +. if !\nF==2 \{\ +. nr % 0 +. nr F 2 +. \} .\} .\" .\" Accent mark definitions (@(#)ms.acc 1.5 88/02/08 SMI; from UCB 4.2). @@ -124,7 +129,7 @@ .\" ======================================================================== .\" .IX Title "GEODSOLVE 1" -.TH GEODSOLVE 1 "2014-03-13" "GeographicLib 1.35" "GeographicLib Utilities" +.TH GEODSOLVE 1 "2017-10-05" "GeographicLib 1.49" "GeographicLib Utilities" .\" For nroff, turn off justification. Always turn off hyphenation; it makes .\" way too many mistakes in technical documents. .if n .ad l @@ -133,9 +138,11 @@ GeodSolve \-\- perform geodesic calculations .SH "SYNOPSIS" .IX Header "SYNOPSIS" -\&\fBGeodSolve\fR [ \fB\-i\fR | \fB\-l\fR \fIlat1\fR \fIlon1\fR \fIazi1\fR ] [ \fB\-a\fR ] -[ \fB\-e\fR \fIa\fR \fIf\fR ] -[ \fB\-d\fR | \fB\-:\fR ] [ \fB\-b\fR ] [ \fB\-f\fR ] [ \fB\-p\fR \fIprec\fR ] [ \fB\-E\fR ] +\&\fBGeodSolve\fR +[ \fB\-i\fR | \fB\-L\fR \fIlat1\fR \fIlon1\fR \fIazi1\fR | +\&\fB\-D\fR \fIlat1\fR \fIlon1\fR \fIazi1\fR \fIs13\fR | \fB\-I\fR \fIlat1\fR \fIlon1\fR \fIlat3\fR \fIlon3\fR ] +[ \fB\-a\fR ] [ \fB\-e\fR \fIa\fR \fIf\fR ] [ \fB\-u\fR ] [ \fB\-F\fR ] +[ \fB\-d\fR | \fB\-:\fR ] [ \fB\-w\fR ] [ \fB\-b\fR ] [ \fB\-f\fR ] [ \fB\-p\fR \fIprec\fR ] [ \fB\-E\fR ] [ \fB\-\-comment\-delimiter\fR \fIcommentdelim\fR ] [ \fB\-\-version\fR | \fB\-h\fR | \fB\-\-help\fR ] [ \fB\-\-input\-file\fR \fIinfile\fR | \fB\-\-input\-string\fR \fIinstring\fR ] @@ -154,35 +161,68 @@ By default, \fBGeodSolve\fR accepts lines on the standard input containing \&\fIlat1\fR \fIlon1\fR \fIazi1\fR \fIs12\fR and prints \fIlat2\fR \fIlon2\fR \fIazi2\fR on standard output. This is the direct geodesic calculation. .IP "2." 4 -Command line arguments \fB\-l\fR \fIlat1\fR \fIlon1\fR \fIazi1\fR specify a geodesic -line. \fBGeodSolve\fR then accepts a sequence of \fIs12\fR values (one per -line) on standard input and prints \fIlat2\fR \fIlon2\fR \fIazi2\fR for each. -This generates a sequence of points on a single geodesic. -.IP "3." 4 With the \fB\-i\fR command line argument, \fBGeodSolve\fR performs the inverse geodesic calculation. It reads lines containing \fIlat1\fR \fIlon1\fR \fIlat2\fR \&\fIlon2\fR and prints the corresponding values of \fIazi1\fR \fIazi2\fR \fIs12\fR. +.IP "3." 4 +Command line arguments \fB\-L\fR \fIlat1\fR \fIlon1\fR \fIazi1\fR specify a geodesic +line. \fBGeodSolve\fR then accepts a sequence of \fIs12\fR values (one per +line) on standard input and prints \fIlat2\fR \fIlon2\fR \fIazi2\fR for each. +This generates a sequence of points on a single geodesic. Command line +arguments \fB\-D\fR and \fB\-I\fR work similarly with the geodesic line defined +in terms of a direct or inverse geodesic calculation, respectively. .SH "OPTIONS" .IX Header "OPTIONS" .IP "\fB\-i\fR" 4 .IX Item "-i" -perform an inverse geodesic calculation (see 3 above). -.IP "\fB\-l\fR" 4 -.IX Item "-l" -line mode (see 2 above); generate a sequence of points along the -geodesic specified by \fIlat1\fR \fIlon1\fR \fIazi1\fR. +perform an inverse geodesic calculation (see 2 above). +.IP "\fB\-L\fR \fIlat1\fR \fIlon1\fR \fIazi1\fR" 4 +.IX Item "-L lat1 lon1 azi1" +line mode (see 3 above); generate a sequence of points along the +geodesic specified by \fIlat1\fR \fIlon1\fR \fIazi1\fR. The \fB\-w\fR flag can be +used to swap the default order of the 2 geographic coordinates, provided +that it appears before \fB\-L\fR. (\fB\-l\fR is an alternative, deprecated, +spelling of this flag.) +.IP "\fB\-D\fR \fIlat1\fR \fIlon1\fR \fIazi1\fR \fIs13\fR" 4 +.IX Item "-D lat1 lon1 azi1 s13" +line mode (see 3 above); generate a sequence of points along the +geodesic specified by \fIlat1\fR \fIlon1\fR \fIazi1\fR \fIs13\fR. The \fB\-w\fR flag +can be used to swap the default order of the 2 geographic coordinates, +provided that it appears before \fB\-D\fR. Similarly, the \fB\-a\fR flag can be +used to change the interpretation of \fIs13\fR to \fIa13\fR, provided that it +appears before \fB\-D\fR. +.IP "\fB\-I\fR \fIlat1\fR \fIlon1\fR \fIlat3\fR \fIlon3\fR" 4 +.IX Item "-I lat1 lon1 lat3 lon3" +line mode (see 3 above); generate a sequence of points along the +geodesic specified by \fIlat1\fR \fIlon1\fR \fIlat3\fR \fIlon3\fR. The \fB\-w\fR flag +can be used to swap the default order of the 2 geographic coordinates, +provided that it appears before \fB\-I\fR. .IP "\fB\-a\fR" 4 .IX Item "-a" -arc mode; on input \fIand\fR output \fIs12\fR is replaced by \fIa12\fR the arc -length (in degrees) on the auxiliary sphere. See \*(L"\s-1AUXILIARY\s0 \s-1SPHERE\s0\*(R". -.IP "\fB\-e\fR" 4 -.IX Item "-e" -specify the ellipsoid via \fIa\fR \fIf\fR; the equatorial radius is \fIa\fR and -the flattening is \fIf\fR. Setting \fIf\fR = 0 results in a sphere. Specify +toggle the arc mode flag (it starts off); if this flag is on, then on +input \fIand\fR output \fIs12\fR is replaced by \fIa12\fR the arc length (in +degrees) on the auxiliary sphere. See \*(L"\s-1AUXILIARY SPHERE\*(R"\s0. +.IP "\fB\-e\fR \fIa\fR \fIf\fR" 4 +.IX Item "-e a f" +specify the ellipsoid via the equatorial radius, \fIa\fR and +the flattening, \fIf\fR. Setting \fIf\fR = 0 results in a sphere. Specify \&\fIf\fR < 0 for a prolate ellipsoid. A simple fraction, e.g., 1/297, -is allowed for \fIf\fR. (Also, if \fIf\fR > 1, the flattening is set to -1/\fIf\fR.) By default, the \s-1WGS84\s0 ellipsoid is used, \fIa\fR = 6378137 m, -\&\fIf\fR = 1/298.257223563. +is allowed for \fIf\fR. By default, the \s-1WGS84\s0 ellipsoid is used, \fIa\fR = +6378137 m, \fIf\fR = 1/298.257223563. +.IP "\fB\-u\fR" 4 +.IX Item "-u" +unroll the longitude. Normally, on output longitudes are reduced to lie +in [\-180deg,180deg). However with this option, the returned longitude +\&\fIlon2\fR is \*(L"unrolled\*(R" so that \fIlon2\fR \- \fIlon1\fR indicates how often and +in what sense the geodesic has encircled the earth. Use the \fB\-f\fR +option, to get both longitudes printed. +.IP "\fB\-F\fR" 4 +.IX Item "-F" +fractional mode. This only has any effect with the \fB\-D\fR and \fB\-I\fR +options (and is otherwise ignored). The values read on standard input +are interpreted as fractional distances to point 3, i.e., as +\&\fIs12\fR/\fIs13\fR instead of \fIs12\fR. If arc mode is in effect, then the +values denote fractional arc length, i.e., \fIa12\fR/\fIa13\fR. .IP "\fB\-d\fR" 4 .IX Item "-d" output angles as degrees, minutes, seconds instead of decimal degrees. @@ -190,6 +230,12 @@ output angles as degrees, minutes, seconds instead of decimal degrees. .IX Item "-:" like \fB\-d\fR, except use : as a separator instead of the d, ', and " delimiters. +.IP "\fB\-w\fR" 4 +.IX Item "-w" +toggle the longitude first flag (it starts off); if the flag is on, then +on input and output, longitude precedes latitude (except that, on input, +this can be overridden by a hemisphere designator, \fIN\fR, \fIS\fR, \fIE\fR, +\&\fIW\fR). .IP "\fB\-b\fR" 4 .IX Item "-b" report the \fIback\fR azimuth at point 2 instead of the forward azimuth. @@ -197,20 +243,20 @@ report the \fIback\fR azimuth at point 2 instead of the forward azimuth. .IX Item "-f" full output; each line of output consists of 12 quantities: \fIlat1\fR \&\fIlon1\fR \fIazi1\fR \fIlat2\fR \fIlon2\fR \fIazi2\fR \fIs12\fR \fIa12\fR \fIm12\fR \fIM12\fR -\&\fIM21\fR \fIS12\fR. \fIa12\fR is described in \*(L"\s-1AUXILIARY\s0 \s-1SPHERE\s0\*(R". The four +\&\fIM21\fR \fIS12\fR. \fIa12\fR is described in \*(L"\s-1AUXILIARY SPHERE\*(R"\s0. The four quantities \fIm12\fR, \fIM12\fR, \fIM21\fR, and \fIS12\fR are described in -\&\*(L"\s-1ADDITIONAL\s0 \s-1QUANTITIES\s0\*(R". -.IP "\fB\-p\fR" 4 -.IX Item "-p" +\&\*(L"\s-1ADDITIONAL QUANTITIES\*(R"\s0. +.IP "\fB\-p\fR \fIprec\fR" 4 +.IX Item "-p prec" set the output precision to \fIprec\fR (default 3); \fIprec\fR is the -precision relative to 1 m. See \*(L"\s-1PRECISION\s0\*(R". +precision relative to 1 m. See \*(L"\s-1PRECISION\*(R"\s0. .IP "\fB\-E\fR" 4 .IX Item "-E" use \*(L"exact\*(R" algorithms (based on elliptic integrals) for the geodesic calculations. These are more accurate than the (default) series expansions for |\fIf\fR| > 0.02. -.IP "\fB\-\-comment\-delimiter\fR" 4 -.IX Item "--comment-delimiter" +.IP "\fB\-\-comment\-delimiter\fR \fIcommentdelim\fR" 4 +.IX Item "--comment-delimiter commentdelim" set the comment delimiter to \fIcommentdelim\fR (e.g., \*(L"#\*(R" or \*(L"//\*(R"). If set, the input lines will be scanned for this delimiter and, if found, the delimiter and the rest of the line will be removed prior to @@ -225,38 +271,38 @@ print usage and exit. .IP "\fB\-\-help\fR" 4 .IX Item "--help" print full documentation and exit. -.IP "\fB\-\-input\-file\fR" 4 -.IX Item "--input-file" +.IP "\fB\-\-input\-file\fR \fIinfile\fR" 4 +.IX Item "--input-file infile" read input from the file \fIinfile\fR instead of from standard input; a file name of \*(L"\-\*(R" stands for standard input. -.IP "\fB\-\-input\-string\fR" 4 -.IX Item "--input-string" +.IP "\fB\-\-input\-string\fR \fIinstring\fR" 4 +.IX Item "--input-string instring" read input from the string \fIinstring\fR instead of from standard input. All occurrences of the line separator character (default is a semicolon) in \fIinstring\fR are converted to newlines before the reading begins. -.IP "\fB\-\-line\-separator\fR" 4 -.IX Item "--line-separator" +.IP "\fB\-\-line\-separator\fR \fIlinesep\fR" 4 +.IX Item "--line-separator linesep" set the line separator character to \fIlinesep\fR. By default this is a semicolon. -.IP "\fB\-\-output\-file\fR" 4 -.IX Item "--output-file" +.IP "\fB\-\-output\-file\fR \fIoutfile\fR" 4 +.IX Item "--output-file outfile" write output to the file \fIoutfile\fR instead of to standard output; a file name of \*(L"\-\*(R" stands for standard output. .SH "INPUT" .IX Header "INPUT" \&\fBGeodSolve\fR measures all angles in degrees and all lengths (\fIs12\fR) in -meters. On input angles (latitude, longitude, azimuth, arc length) can -be as decimal degrees or degrees (d), minutes ('), seconds (\*(L"). A -decimal point can only appear in the least significant component and the -designator (d, ', or \*(R") for this component is optional; thus \f(CW\*(C`40d30\*(C'\fR, -\&\f(CW\*(C`40d30\*(Aq\*(C'\fR, \f(CW\*(C`40.5d\*(C'\fR, and \f(CW40.5\fR are all equivalent. By default, -latitude precedes longitude for each point; however on input either may -be given first by appending (or prepending) \fIN\fR or \fIS\fR to the latitude -and \fIE\fR or \fIW\fR to the longitude. Azimuths are measured clockwise from -north; however this may be overridden with \fIE\fR or \fIW\fR. +meters, and all areas (\fIS12\fR) in meters^2. On input angles (latitude, +longitude, azimuth, arc length) can be as decimal degrees or degrees, +minutes, seconds. For example, \f(CW\*(C`40d30\*(C'\fR, \f(CW\*(C`40d30\*(Aq\*(C'\fR, \f(CW\*(C`40:30\*(C'\fR, \f(CW\*(C`40.5d\*(C'\fR, +and \f(CW40.5\fR are all equivalent. By default, latitude precedes longitude +for each point (the \fB\-w\fR flag switches this convention); however on +input either may be given first by appending (or prepending) \fIN\fR or +\&\fIS\fR to the latitude and \fIE\fR or \fIW\fR to the longitude. Azimuths are +measured clockwise from north; however this may be overridden with \fIE\fR +or \fIW\fR. .PP -See the \f(CW\*(C`QUOTING\*(C'\fR section of \fIGeoConvert\fR\|(1) for how to quote the \s-1DMS\s0 -designators ' and ". +For details on the allowed formats for angles, see the \f(CW\*(C`GEOGRAPHIC +COORDINATES\*(C'\fR section of \fIGeoConvert\fR\|(1). .SH "AUXILIARY SPHERE" .IX Header "AUXILIARY SPHERE" Geodesics on the ellipsoid can be transferred to the \fIauxiliary sphere\fR @@ -287,13 +333,16 @@ and \fIM21\fR are dimensionless quantities. On a flat surface, we have \&\fIM12\fR = \fIM21\fR = 1. .PP If points 1, 2, and 3 lie on a single geodesic, then the following -addition rules hold, -\&\fIs13\fR = \fIs12\fR + \fIs23\fR, -\&\fIa13\fR = \fIa12\fR + \fIa23\fR, -\&\fIS13\fR = \fIS12\fR + \fIS23\fR, -\&\fIm13\fR = \fIm12\fR \fIM23\fR + \fIm23\fR \fIM21\fR, -\&\fIM13\fR = \fIM12\fR \fIM23\fR \- (1 \- \fIM12\fR \fIM21\fR) \fIm23\fR / \fIm12\fR, and -\&\fIM31\fR = \fIM32\fR \fIM21\fR \- (1 \- \fIM23\fR \fIM32\fR) \fIm12\fR / \fIm23\fR. +addition rules hold: +.PP +.Vb 6 +\& s13 = s12 + s23, +\& a13 = a12 + a23, +\& S13 = S12 + S23, +\& m13 = m12 M23 + m23 M21, +\& M13 = M12 M23 \- (1 \- M12 M21) m23 / m12, +\& M31 = M32 M21 \- (1 \- M23 M32) m12 / m23. +.Ve .PP Finally, \fIS12\fR is the area between the geodesic from point 1 to point 2 and the equator; i.e., it is the area, measured counter-clockwise, of @@ -304,9 +353,9 @@ the geodesic quadrilateral with corners (\fIlat1\fR,\fIlon1\fR), (0,\fIlon1\fR), \&\fIprec\fR gives precision of the output with \fIprec\fR = 0 giving 1 m precision, \fIprec\fR = 3 giving 1 mm precision, etc. \fIprec\fR is the number of digits after the decimal point for lengths. For decimal -degrees, the number of digits after the decimal point is 5 + \fIprec\fR. +degrees, the number of digits after the decimal point is \fIprec\fR + 5. For \s-1DMS\s0 (degree, minute, seconds) output, the number of digits after the -decimal point in the seconds component is 1 + \fIprec\fR. The minimum +decimal point in the seconds component is \fIprec\fR + 1. The minimum value of \fIprec\fR is 0 and the maximum is 10. .SH "ERRORS" .IX Header "ERRORS" @@ -318,7 +367,7 @@ following lines will be converted. .IX Header "ACCURACY" Using the (default) series solution, GeodSolve is accurate to about 15 nm (15 nanometers) for the \s-1WGS84\s0 ellipsoid. The approximate maximum -error (expressed as a distance) for an ellipsoid with the same major +error (expressed as a distance) for an ellipsoid with the same equatorial radius as the \s-1WGS84\s0 ellipsoid and different values of the flattening is .PP .Vb 6 @@ -393,35 +442,44 @@ Route from \s-1JFK\s0 Airport to Singapore Changi Airport: \& 003:18:29.9 177:29:09.2 15347628 .Ve .PP -Waypoints on the route at intervals of 2000km: +Equally spaced waypoints on the route: .PP .Vb 2 -\& for ((i = 0; i <= 16; i += 2)); do echo ${i}000000;done | -\& GeodSolve \-l 40:38:23N 073:46:44W 003:18:29.9 \-: \-p 0 +\& for ((i = 0; i <= 10; ++i)); do echo ${i}e\-1; done | +\& GeodSolve \-I 40:38:23N 073:46:44W 01:21:33N 103:59:22E \-F \-: \-p 0 \& \& 40:38:23.0N 073:46:44.0W 003:18:29.9 -\& 58:34:45.1N 071:49:36.7W 004:48:48.8 -\& 76:22:28.4N 065:32:17.8W 010:41:38.4 -\& 84:50:28.0N 075:04:39.2E 150:55:00.9 -\& 67:26:20.3N 098:00:51.2E 173:27:20.3 -\& 49:33:03.2N 101:06:52.6E 176:07:54.3 -\& 31:34:16.5N 102:30:46.3E 177:03:08.4 -\& 13:31:56.0N 103:26:50.7E 177:24:55.0 -\& 04:32:05.7S 104:14:48.7E 177:28:43.6 +\& 54:24:51.3N 072:25:39.6W 004:18:44.1 +\& 68:07:37.7N 069:40:42.9W 006:44:25.4 +\& 81:38:00.4N 058:37:53.9W 017:28:52.7 +\& 83:43:26.0N 080:37:16.9E 156:26:00.4 +\& 70:20:29.2N 097:01:29.4E 172:31:56.4 +\& 56:38:36.0N 100:14:47.6E 175:26:10.5 +\& 42:52:37.1N 101:43:37.2E 176:34:28.6 +\& 29:03:57.0N 102:39:34.8E 177:07:35.2 +\& 15:13:18.6N 103:22:08.0E 177:23:44.7 +\& 01:21:33.0N 103:59:22.0E 177:29:09.2 .Ve .SH "SEE ALSO" .IX Header "SEE ALSO" -\&\fIGeoConvert\fR\|(1). The algorithms are described in C. F. F. Karney, +\&\fIGeoConvert\fR\|(1). +.PP +An online version of this utility is availbable at +. +.PP +The algorithms are described in C. F. F. Karney, \&\fIAlgorithms for geodesics\fR, J. Geodesy 87, 43\-55 (2013); \s-1DOI:\s0 -http://dx.doi.org/10.1007/s00190\-012\-0578\-z ; -addenda: http://geographiclib.sf.net/geod\-addenda.html . -The wikipedia page, Geodesics on an ellipsoid, -. +; +addenda: . +.PP +The Wikipedia page, Geodesics on an ellipsoid, +. .SH "AUTHOR" .IX Header "AUTHOR" \&\fBGeodSolve\fR was written by Charles Karney. .SH "HISTORY" .IX Header "HISTORY" -\&\fBGeodSolve\fR was added to GeographicLib, , -in 2009\-03. Prior to version 1.30, it was called \fBGeod\fR. (The name -was changed to avoid a conflict with the \fBgeod\fR utility in \fIproj.4\fR.) +\&\fBGeodSolve\fR was added to GeographicLib, +, in 2009\-03. Prior to version +1.30, it was called \fBGeod\fR. (The name was changed to avoid a conflict +with the \fBgeod\fR utility in \fIproj.4\fR.) diff --git a/gtsam/3rdparty/GeographicLib/man/GeodSolve.1.html b/gtsam/3rdparty/GeographicLib/man/GeodSolve.1.html index 8af2af9e7..9a17eaff5 100644 --- a/gtsam/3rdparty/GeographicLib/man/GeodSolve.1.html +++ b/gtsam/3rdparty/GeographicLib/man/GeodSolve.1.html @@ -7,7 +7,7 @@ - + @@ -17,7 +17,7 @@

    SYNOPSIS

    -

    GeodSolve [ -i | -l lat1 lon1 azi1 ] [ -a ] [ -e a f ] [ -d | -: ] [ -b ] [ -f ] [ -p prec ] [ -E ] [ --comment-delimiter commentdelim ] [ --version | -h | --help ] [ --input-file infile | --input-string instring ] [ --line-separator linesep ] [ --output-file outfile ]

    +

    GeodSolve [ -i | -L lat1 lon1 azi1 | -D lat1 lon1 azi1 s13 | -I lat1 lon1 lat3 lon3 ] [ -a ] [ -e a f ] [ -u ] [ -F ] [ -d | -: ] [ -w ] [ -b ] [ -f ] [ -p prec ] [ -E ] [ --comment-delimiter commentdelim ] [ --version | -h | --help ] [ --input-file infile | --input-string instring ] [ --line-separator linesep ] [ --output-file outfile ]

    DESCRIPTION

    @@ -30,10 +30,10 @@
  • By default, GeodSolve accepts lines on the standard input containing lat1 lon1 azi1 s12 and prints lat2 lon2 azi2 on standard output. This is the direct geodesic calculation.

  • -
  • Command line arguments -l lat1 lon1 azi1 specify a geodesic line. GeodSolve then accepts a sequence of s12 values (one per line) on standard input and prints lat2 lon2 azi2 for each. This generates a sequence of points on a single geodesic.

    +
  • With the -i command line argument, GeodSolve performs the inverse geodesic calculation. It reads lines containing lat1 lon1 lat2 lon2 and prints the corresponding values of azi1 azi2 s12.

  • -
  • With the -i command line argument, GeodSolve performs the inverse geodesic calculation. It reads lines containing lat1 lon1 lat2 lon2 and prints the corresponding values of azi1 azi2 s12.

    +
  • Command line arguments -L lat1 lon1 azi1 specify a geodesic line. GeodSolve then accepts a sequence of s12 values (one per line) on standard input and prints lat2 lon2 azi2 for each. This generates a sequence of points on a single geodesic. Command line arguments -D and -I work similarly with the geodesic line defined in terms of a direct or inverse geodesic calculation, respectively.

  • @@ -45,25 +45,49 @@
    -i
    -

    perform an inverse geodesic calculation (see 3 above).

    +

    perform an inverse geodesic calculation (see 2 above).

    -
    -l
    +
    -L lat1 lon1 azi1
    -

    line mode (see 2 above); generate a sequence of points along the geodesic specified by lat1 lon1 azi1.

    +

    line mode (see 3 above); generate a sequence of points along the geodesic specified by lat1 lon1 azi1. The -w flag can be used to swap the default order of the 2 geographic coordinates, provided that it appears before -L. (-l is an alternative, deprecated, spelling of this flag.)

    + +
    +
    -D lat1 lon1 azi1 s13
    +
    + +

    line mode (see 3 above); generate a sequence of points along the geodesic specified by lat1 lon1 azi1 s13. The -w flag can be used to swap the default order of the 2 geographic coordinates, provided that it appears before -D. Similarly, the -a flag can be used to change the interpretation of s13 to a13, provided that it appears before -D.

    + +
    +
    -I lat1 lon1 lat3 lon3
    +
    + +

    line mode (see 3 above); generate a sequence of points along the geodesic specified by lat1 lon1 lat3 lon3. The -w flag can be used to swap the default order of the 2 geographic coordinates, provided that it appears before -I.

    -a
    -
    -e
    +
    -e a f
    -

    specify the ellipsoid via a f; the equatorial radius is a and the flattening is f. Setting f = 0 results in a sphere. Specify f < 0 for a prolate ellipsoid. A simple fraction, e.g., 1/297, is allowed for f. (Also, if f > 1, the flattening is set to 1/f.) By default, the WGS84 ellipsoid is used, a = 6378137 m, f = 1/298.257223563.

    +

    specify the ellipsoid via the equatorial radius, a and the flattening, f. Setting f = 0 results in a sphere. Specify f < 0 for a prolate ellipsoid. A simple fraction, e.g., 1/297, is allowed for f. By default, the WGS84 ellipsoid is used, a = 6378137 m, f = 1/298.257223563.

    + +
    +
    -u
    +
    + +

    unroll the longitude. Normally, on output longitudes are reduced to lie in [-180deg,180deg). However with this option, the returned longitude lon2 is "unrolled" so that lon2 - lon1 indicates how often and in what sense the geodesic has encircled the earth. Use the -f option, to get both longitudes printed.

    + +
    +
    -F
    +
    + +

    fractional mode. This only has any effect with the -D and -I options (and is otherwise ignored). The values read on standard input are interpreted as fractional distances to point 3, i.e., as s12/s13 instead of s12. If arc mode is in effect, then the values denote fractional arc length, i.e., a12/a13.

    -d
    @@ -72,11 +96,17 @@

    output angles as degrees, minutes, seconds instead of decimal degrees.

    -
    -:
    +
    -:

    like -d, except use : as a separator instead of the d, ', and " delimiters.

    +
    +
    -w
    +
    + +

    toggle the longitude first flag (it starts off); if the flag is on, then on input and output, longitude precedes latitude (except that, on input, this can be overridden by a hemisphere designator, N, S, E, W).

    +
    -b
    @@ -90,7 +120,7 @@

    full output; each line of output consists of 12 quantities: lat1 lon1 azi1 lat2 lon2 azi2 s12 a12 m12 M12 M21 S12. a12 is described in "AUXILIARY SPHERE". The four quantities m12, M12, M21, and S12 are described in "ADDITIONAL QUANTITIES".

    -
    -p
    +
    -p prec

    set the output precision to prec (default 3); prec is the precision relative to 1 m. See "PRECISION".

    @@ -102,7 +132,7 @@

    use "exact" algorithms (based on elliptic integrals) for the geodesic calculations. These are more accurate than the (default) series expansions for |f| > 0.02.

    -
    --comment-delimiter
    +
    --comment-delimiter commentdelim

    set the comment delimiter to commentdelim (e.g., "#" or "//"). If set, the input lines will be scanned for this delimiter and, if found, the delimiter and the rest of the line will be removed prior to processing and subsequently appended to the output line (separated by a space).

    @@ -126,25 +156,25 @@

    print full documentation and exit.

    -
    --input-file
    +
    --input-file infile

    read input from the file infile instead of from standard input; a file name of "-" stands for standard input.

    -
    --input-string
    +
    --input-string instring

    read input from the string instring instead of from standard input. All occurrences of the line separator character (default is a semicolon) in instring are converted to newlines before the reading begins.

    -
    --line-separator
    +
    --line-separator linesep

    set the line separator character to linesep. By default this is a semicolon.

    -
    --output-file
    +
    --output-file outfile

    write output to the file outfile instead of to standard output; a file name of "-" stands for standard output.

    @@ -154,9 +184,9 @@

    INPUT

    -

    GeodSolve measures all angles in degrees and all lengths (s12) in meters. On input angles (latitude, longitude, azimuth, arc length) can be as decimal degrees or degrees (d), minutes ('), seconds ("). A decimal point can only appear in the least significant component and the designator (d, ', or ") for this component is optional; thus 40d30, 40d30', 40.5d, and 40.5 are all equivalent. By default, latitude precedes longitude for each point; however on input either may be given first by appending (or prepending) N or S to the latitude and E or W to the longitude. Azimuths are measured clockwise from north; however this may be overridden with E or W.

    +

    GeodSolve measures all angles in degrees and all lengths (s12) in meters, and all areas (S12) in meters^2. On input angles (latitude, longitude, azimuth, arc length) can be as decimal degrees or degrees, minutes, seconds. For example, 40d30, 40d30', 40:30, 40.5d, and 40.5 are all equivalent. By default, latitude precedes longitude for each point (the -w flag switches this convention); however on input either may be given first by appending (or prepending) N or S to the latitude and E or W to the longitude. Azimuths are measured clockwise from north; however this may be overridden with E or W.

    -

    See the QUOTING section of GeoConvert(1) for how to quote the DMS designators ' and ".

    +

    For details on the allowed formats for angles, see the GEOGRAPHIC COORDINATES section of GeoConvert(1).

    AUXILIARY SPHERE

    @@ -170,13 +200,20 @@

    M12 and M21 are geodesic scales. If two geodesics are parallel at point 1 and separated by a small distance dt, then they are separated by a distance M12 dt at point 2. M21 is defined similarly (with the geodesics being parallel to one another at point 2). M12 and M21 are dimensionless quantities. On a flat surface, we have M12 = M21 = 1.

    -

    If points 1, 2, and 3 lie on a single geodesic, then the following addition rules hold, s13 = s12 + s23, a13 = a12 + a23, S13 = S12 + S23, m13 = m12 M23 + m23 M21, M13 = M12 M23 - (1 - M12 M21) m23 / m12, and M31 = M32 M21 - (1 - M23 M32) m12 / m23.

    +

    If points 1, 2, and 3 lie on a single geodesic, then the following addition rules hold:

    + +
       s13 = s12 + s23,
    +   a13 = a12 + a23,
    +   S13 = S12 + S23,
    +   m13 = m12 M23 + m23 M21,
    +   M13 = M12 M23 - (1 - M12 M21) m23 / m12,
    +   M31 = M32 M21 - (1 - M23 M32) m12 / m23.

    Finally, S12 is the area between the geodesic from point 1 to point 2 and the equator; i.e., it is the area, measured counter-clockwise, of the geodesic quadrilateral with corners (lat1,lon1), (0,lon1), (0,lon2), and (lat2,lon2). It is given in meters^2.

    PRECISION

    -

    prec gives precision of the output with prec = 0 giving 1 m precision, prec = 3 giving 1 mm precision, etc. prec is the number of digits after the decimal point for lengths. For decimal degrees, the number of digits after the decimal point is 5 + prec. For DMS (degree, minute, seconds) output, the number of digits after the decimal point in the seconds component is 1 + prec. The minimum value of prec is 0 and the maximum is 10.

    +

    prec gives precision of the output with prec = 0 giving 1 m precision, prec = 3 giving 1 mm precision, etc. prec is the number of digits after the decimal point for lengths. For decimal degrees, the number of digits after the decimal point is prec + 5. For DMS (degree, minute, seconds) output, the number of digits after the decimal point in the seconds component is prec + 1. The minimum value of prec is 0 and the maximum is 10.

    ERRORS

    @@ -184,7 +221,7 @@

    ACCURACY

    -

    Using the (default) series solution, GeodSolve is accurate to about 15 nm (15 nanometers) for the WGS84 ellipsoid. The approximate maximum error (expressed as a distance) for an ellipsoid with the same major radius as the WGS84 ellipsoid and different values of the flattening is

    +

    Using the (default) series solution, GeodSolve is accurate to about 15 nm (15 nanometers) for the WGS84 ellipsoid. The approximate maximum error (expressed as a distance) for an ellipsoid with the same equatorial radius as the WGS84 ellipsoid and different values of the flattening is

       |f|     error
        0.01    25 nm
    @@ -218,13 +255,13 @@
     
     
    -
    lat1 = -lat2 (with neither point at a pole)
    +
    lat1 = -lat2 (with neither point at a pole)

    If azi1 = azi2, the geodesic is unique. Otherwise there are two geodesics and the second one is obtained by setting [azi1,azi2] = [azi2,azi1], [M12,M21] = [M21,M12], S12 = -S12. (This occurs when the longitude difference is near +/-180 for oblate ellipsoids.)

    -
    lon2 = lon1 +/- 180 (with neither point at a pole)
    +
    lon2 = lon1 +/- 180 (with neither point at a pole)

    If azi1 = 0 or +/-180, the geodesic is unique. Otherwise there are two geodesics and the second one is obtained by setting [azi1,azi2] = [-azi1,-azi2], S12 = -S12. (This occurs when lat2 is near -lat1 for prolate ellipsoids.)

    @@ -236,7 +273,7 @@

    There are infinitely many geodesics which can be generated by setting [azi1,azi2] = [azi1,azi2] + [d,-d], for arbitrary d. (For spheres, this prescription applies when points 1 and 2 are antipodal.)

    -
    s12 = 0 (coincident points)
    +
    s12 = 0 (coincident points)

    There are infinitely many geodesics which can be generated by setting [azi1,azi2] = [azi1,azi2] + [d,d], for arbitrary d.

    @@ -253,24 +290,32 @@ 003:18:29.9 177:29:09.2 15347628
    -

    Waypoints on the route at intervals of 2000km:

    +

    Equally spaced waypoints on the route:

    -
       for ((i = 0; i <= 16; i += 2)); do echo ${i}000000;done |
    -   GeodSolve -l 40:38:23N 073:46:44W 003:18:29.9 -: -p 0
    +
       for ((i = 0; i <= 10; ++i)); do echo ${i}e-1; done |
    +   GeodSolve -I 40:38:23N 073:46:44W 01:21:33N 103:59:22E -F -: -p 0
     
        40:38:23.0N 073:46:44.0W 003:18:29.9
    -   58:34:45.1N 071:49:36.7W 004:48:48.8
    -   76:22:28.4N 065:32:17.8W 010:41:38.4
    -   84:50:28.0N 075:04:39.2E 150:55:00.9
    -   67:26:20.3N 098:00:51.2E 173:27:20.3
    -   49:33:03.2N 101:06:52.6E 176:07:54.3
    -   31:34:16.5N 102:30:46.3E 177:03:08.4
    -   13:31:56.0N 103:26:50.7E 177:24:55.0
    -   04:32:05.7S 104:14:48.7E 177:28:43.6
    + 54:24:51.3N 072:25:39.6W 004:18:44.1 + 68:07:37.7N 069:40:42.9W 006:44:25.4 + 81:38:00.4N 058:37:53.9W 017:28:52.7 + 83:43:26.0N 080:37:16.9E 156:26:00.4 + 70:20:29.2N 097:01:29.4E 172:31:56.4 + 56:38:36.0N 100:14:47.6E 175:26:10.5 + 42:52:37.1N 101:43:37.2E 176:34:28.6 + 29:03:57.0N 102:39:34.8E 177:07:35.2 + 15:13:18.6N 103:22:08.0E 177:23:44.7 + 01:21:33.0N 103:59:22.0E 177:29:09.2

    SEE ALSO

    -

    GeoConvert(1). The algorithms are described in C. F. F. Karney, Algorithms for geodesics, J. Geodesy 87, 43-55 (2013); DOI: http://dx.doi.org/10.1007/s00190-012-0578-z; addenda: http://geographiclib.sf.net/geod-addenda.html. The wikipedia page, Geodesics on an ellipsoid, http://en.wikipedia.org/wiki/Geodesics_on_an_ellipsoid.

    +

    GeoConvert(1).

    + +

    An online version of this utility is availbable at https://geographiclib.sourceforge.io/cgi-bin/GeodSolve.

    + +

    The algorithms are described in C. F. F. Karney, Algorithms for geodesics, J. Geodesy 87, 43-55 (2013); DOI: https://doi.org/10.1007/s00190-012-0578-z; addenda: https://geographiclib.sourceforge.io/geod-addenda.html.

    + +

    The Wikipedia page, Geodesics on an ellipsoid, https://en.wikipedia.org/wiki/Geodesics_on_an_ellipsoid.

    AUTHOR

    @@ -278,7 +323,7 @@

    HISTORY

    -

    GeodSolve was added to GeographicLib, http://geographiclib.sf.net, in 2009-03. Prior to version 1.30, it was called Geod. (The name was changed to avoid a conflict with the geod utility in proj.4.)

    +

    GeodSolve was added to GeographicLib, https://geographiclib.sourceforge.io, in 2009-03. Prior to version 1.30, it was called Geod. (The name was changed to avoid a conflict with the geod utility in proj.4.)

    diff --git a/gtsam/3rdparty/GeographicLib/man/GeodSolve.pod b/gtsam/3rdparty/GeographicLib/man/GeodSolve.pod index 1159b108d..709c9ab65 100644 --- a/gtsam/3rdparty/GeographicLib/man/GeodSolve.pod +++ b/gtsam/3rdparty/GeographicLib/man/GeodSolve.pod @@ -4,9 +4,11 @@ GeodSolve -- perform geodesic calculations =head1 SYNOPSIS -B [ B<-i> | B<-l> I I I ] [ B<-a> ] -[ B<-e> I I ] -[ B<-d> | B<-:> ] [ B<-b> ] [ B<-f> ] [ B<-p> I ] [ B<-E> ] +B +[ B<-i> | B<-L> I I I | +B<-D> I I I I | B<-I> I I I I ] +[ B<-a> ] [ B<-e> I I ] [ B<-u> ] [ B<-F> ] +[ B<-d> | B<-:> ] [ B<-w> ] [ B<-b> ] [ B<-f> ] [ B<-p> I ] [ B<-E> ] [ B<--comment-delimiter> I ] [ B<--version> | B<-h> | B<--help> ] [ B<--input-file> I | B<--input-string> I ] @@ -32,17 +34,19 @@ on standard output. This is the direct geodesic calculation. =item 2. -Command line arguments B<-l> I I I specify a geodesic -line. B then accepts a sequence of I values (one per -line) on standard input and prints I I I for each. -This generates a sequence of points on a single geodesic. - -=item 3. - With the B<-i> command line argument, B performs the inverse geodesic calculation. It reads lines containing I I I I and prints the corresponding values of I I I. +=item 3. + +Command line arguments B<-L> I I I specify a geodesic +line. B then accepts a sequence of I values (one per +line) on standard input and prints I I I for each. +This generates a sequence of points on a single geodesic. Command line +arguments B<-D> and B<-I> work similarly with the geodesic line defined +in terms of a direct or inverse geodesic calculation, respectively. + =back =head1 OPTIONS @@ -51,26 +55,61 @@ I and prints the corresponding values of I I I. =item B<-i> -perform an inverse geodesic calculation (see 3 above). +perform an inverse geodesic calculation (see 2 above). -=item B<-l> +=item B<-L> I I I -line mode (see 2 above); generate a sequence of points along the -geodesic specified by I I I. +line mode (see 3 above); generate a sequence of points along the +geodesic specified by I I I. The B<-w> flag can be +used to swap the default order of the 2 geographic coordinates, provided +that it appears before B<-L>. (B<-l> is an alternative, deprecated, +spelling of this flag.) + +=item B<-D> I I I I + +line mode (see 3 above); generate a sequence of points along the +geodesic specified by I I I I. The B<-w> flag +can be used to swap the default order of the 2 geographic coordinates, +provided that it appears before B<-D>. Similarly, the B<-a> flag can be +used to change the interpretation of I to I, provided that it +appears before B<-D>. + +=item B<-I> I I I I + +line mode (see 3 above); generate a sequence of points along the +geodesic specified by I I I I. The B<-w> flag +can be used to swap the default order of the 2 geographic coordinates, +provided that it appears before B<-I>. =item B<-a> -arc mode; on input I output I is replaced by I the arc -length (in degrees) on the auxiliary sphere. See L. +toggle the arc mode flag (it starts off); if this flag is on, then on +input I output I is replaced by I the arc length (in +degrees) on the auxiliary sphere. See L. -=item B<-e> +=item B<-e> I I -specify the ellipsoid via I I; the equatorial radius is I and -the flattening is I. Setting I = 0 results in a sphere. Specify +specify the ellipsoid via the equatorial radius, I and +the flattening, I. Setting I = 0 results in a sphere. Specify I E 0 for a prolate ellipsoid. A simple fraction, e.g., 1/297, -is allowed for I. (Also, if I E 1, the flattening is set to -1/I.) By default, the WGS84 ellipsoid is used, I = 6378137 m, -I = 1/298.257223563. +is allowed for I. By default, the WGS84 ellipsoid is used, I = +6378137 m, I = 1/298.257223563. + +=item B<-u> + +unroll the longitude. Normally, on output longitudes are reduced to lie +in [-180deg,180deg). However with this option, the returned longitude +I is "unrolled" so that I - I indicates how often and +in what sense the geodesic has encircled the earth. Use the B<-f> +option, to get both longitudes printed. + +=item B<-F> + +fractional mode. This only has any effect with the B<-D> and B<-I> +options (and is otherwise ignored). The values read on standard input +are interpreted as fractional distances to point 3, i.e., as +I/I instead of I. If arc mode is in effect, then the +values denote fractional arc length, i.e., I/I. =item B<-d> @@ -81,6 +120,13 @@ output angles as degrees, minutes, seconds instead of decimal degrees. like B<-d>, except use : as a separator instead of the d, ', and " delimiters. +=item B<-w> + +toggle the longitude first flag (it starts off); if the flag is on, then +on input and output, longitude precedes latitude (except that, on input, +this can be overridden by a hemisphere designator, I, I, I, +I). + =item B<-b> report the I azimuth at point 2 instead of the forward azimuth. @@ -93,7 +139,7 @@ I I. I is described in L. The four quantities I, I, I, and I are described in L. -=item B<-p> +=item B<-p> I set the output precision to I (default 3); I is the precision relative to 1 m. See L. @@ -102,9 +148,9 @@ precision relative to 1 m. See L. use "exact" algorithms (based on elliptic integrals) for the geodesic calculations. These are more accurate than the (default) series -expansions for |I| > 0.02. +expansions for |I| E 0.02. -=item B<--comment-delimiter> +=item B<--comment-delimiter> I set the comment delimiter to I (e.g., "#" or "//"). If set, the input lines will be scanned for this delimiter and, if found, @@ -124,23 +170,23 @@ print usage and exit. print full documentation and exit. -=item B<--input-file> +=item B<--input-file> I read input from the file I instead of from standard input; a file name of "-" stands for standard input. -=item B<--input-string> +=item B<--input-string> I read input from the string I instead of from standard input. All occurrences of the line separator character (default is a semicolon) in I are converted to newlines before the reading begins. -=item B<--line-separator> +=item B<--line-separator> I set the line separator character to I. By default this is a semicolon. -=item B<--output-file> +=item B<--output-file> I write output to the file I instead of to standard output; a file name of "-" stands for standard output. @@ -150,18 +196,18 @@ file name of "-" stands for standard output. =head1 INPUT B measures all angles in degrees and all lengths (I) in -meters. On input angles (latitude, longitude, azimuth, arc length) can -be as decimal degrees or degrees (d), minutes ('), seconds ("). A -decimal point can only appear in the least significant component and the -designator (d, ', or ") for this component is optional; thus C<40d30>, -C<40d30'>, C<40.5d>, and C<40.5> are all equivalent. By default, -latitude precedes longitude for each point; however on input either may -be given first by appending (or prepending) I or I to the latitude -and I or I to the longitude. Azimuths are measured clockwise from -north; however this may be overridden with I or I. +meters, and all areas (I) in meters^2. On input angles (latitude, +longitude, azimuth, arc length) can be as decimal degrees or degrees, +minutes, seconds. For example, C<40d30>, C<40d30'>, C<40:30>, C<40.5d>, +and C<40.5> are all equivalent. By default, latitude precedes longitude +for each point (the B<-w> flag switches this convention); however on +input either may be given first by appending (or prepending) I or +I to the latitude and I or I to the longitude. Azimuths are +measured clockwise from north; however this may be overridden with I +or I. -See the C section of GeoConvert(1) for how to quote the DMS -designators ' and ". +For details on the allowed formats for angles, see the C section of GeoConvert(1). =head1 AUXILIARY SPHERE @@ -194,13 +240,14 @@ and I are dimensionless quantities. On a flat surface, we have I = I = 1. If points 1, 2, and 3 lie on a single geodesic, then the following -addition rules hold, -I = I + I, -I = I + I, -I = I + I, -I = I I + I I, -I = I I - (1 - I I) I / I, and -I = I I - (1 - I I) I / I. +addition rules hold: + + s13 = s12 + s23, + a13 = a12 + a23, + S13 = S12 + S23, + m13 = m12 M23 + m23 M21, + M13 = M12 M23 - (1 - M12 M21) m23 / m12, + M31 = M32 M21 - (1 - M23 M32) m12 / m23. Finally, I is the area between the geodesic from point 1 to point 2 and the equator; i.e., it is the area, measured counter-clockwise, of @@ -212,9 +259,9 @@ the geodesic quadrilateral with corners (I,I), (0,I), I gives precision of the output with I = 0 giving 1 m precision, I = 3 giving 1 mm precision, etc. I is the number of digits after the decimal point for lengths. For decimal -degrees, the number of digits after the decimal point is 5 + I. +degrees, the number of digits after the decimal point is I + 5. For DMS (degree, minute, seconds) output, the number of digits after the -decimal point in the seconds component is 1 + I. The minimum +decimal point in the seconds component is I + 1. The minimum value of I is 0 and the maximum is 10. =head1 ERRORS @@ -228,7 +275,7 @@ following lines will be converted. Using the (default) series solution, GeodSolve is accurate to about 15 nm (15 nanometers) for the WGS84 ellipsoid. The approximate maximum -error (expressed as a distance) for an ellipsoid with the same major +error (expressed as a distance) for an ellipsoid with the same equatorial radius as the WGS84 ellipsoid and different values of the flattening is |f| error @@ -307,29 +354,37 @@ Route from JFK Airport to Singapore Changi Airport: 003:18:29.9 177:29:09.2 15347628 -Waypoints on the route at intervals of 2000km: +Equally spaced waypoints on the route: - for ((i = 0; i <= 16; i += 2)); do echo ${i}000000;done | - GeodSolve -l 40:38:23N 073:46:44W 003:18:29.9 -: -p 0 + for ((i = 0; i <= 10; ++i)); do echo ${i}e-1; done | + GeodSolve -I 40:38:23N 073:46:44W 01:21:33N 103:59:22E -F -: -p 0 40:38:23.0N 073:46:44.0W 003:18:29.9 - 58:34:45.1N 071:49:36.7W 004:48:48.8 - 76:22:28.4N 065:32:17.8W 010:41:38.4 - 84:50:28.0N 075:04:39.2E 150:55:00.9 - 67:26:20.3N 098:00:51.2E 173:27:20.3 - 49:33:03.2N 101:06:52.6E 176:07:54.3 - 31:34:16.5N 102:30:46.3E 177:03:08.4 - 13:31:56.0N 103:26:50.7E 177:24:55.0 - 04:32:05.7S 104:14:48.7E 177:28:43.6 + 54:24:51.3N 072:25:39.6W 004:18:44.1 + 68:07:37.7N 069:40:42.9W 006:44:25.4 + 81:38:00.4N 058:37:53.9W 017:28:52.7 + 83:43:26.0N 080:37:16.9E 156:26:00.4 + 70:20:29.2N 097:01:29.4E 172:31:56.4 + 56:38:36.0N 100:14:47.6E 175:26:10.5 + 42:52:37.1N 101:43:37.2E 176:34:28.6 + 29:03:57.0N 102:39:34.8E 177:07:35.2 + 15:13:18.6N 103:22:08.0E 177:23:44.7 + 01:21:33.0N 103:59:22.0E 177:29:09.2 =head1 SEE ALSO -GeoConvert(1). The algorithms are described in C. F. F. Karney, +GeoConvert(1). + +An online version of this utility is availbable at +L. + +The algorithms are described in C. F. F. Karney, I, J. Geodesy 87, 43-55 (2013); DOI: -L; -addenda: L. -The wikipedia page, Geodesics on an ellipsoid, -L. +L; +addenda: L. + +The Wikipedia page, Geodesics on an ellipsoid, +L. =head1 AUTHOR @@ -337,6 +392,7 @@ B was written by Charles Karney. =head1 HISTORY -B was added to GeographicLib, L, -in 2009-03. Prior to version 1.30, it was called B. (The name -was changed to avoid a conflict with the B utility in I.) +B was added to GeographicLib, +L, in 2009-03. Prior to version +1.30, it was called B. (The name was changed to avoid a conflict +with the B utility in I.) diff --git a/gtsam/3rdparty/GeographicLib/man/GeodSolve.usage b/gtsam/3rdparty/GeographicLib/man/GeodSolve.usage index 78ec73ec7..a549aca5d 100644 --- a/gtsam/3rdparty/GeographicLib/man/GeodSolve.usage +++ b/gtsam/3rdparty/GeographicLib/man/GeodSolve.usage @@ -1,23 +1,25 @@ int usage(int retval, bool brief) { if (brief) ( retval ? std::cerr : std::cout ) << "Usage:\n" -" GeodSolve [ -i | -l lat1 lon1 azi1 ] [ -a ] [ -e a f ] [ -d | -: ] [ -b\n" -" ] [ -f ] [ -p prec ] [ -E ] [ --comment-delimiter commentdelim ] [\n" +" GeodSolve [ -i | -L lat1 lon1 azi1 | -D lat1 lon1 azi1 s13 | -I lat1\n" +" lon1 lat3 lon3 ] [ -a ] [ -e a f ] [ -u ] [ -F ] [ -d | -: ] [ -w ] [\n" +" -b ] [ -f ] [ -p prec ] [ -E ] [ --comment-delimiter commentdelim ] [\n" " --version | -h | --help ] [ --input-file infile | --input-string\n" " instring ] [ --line-separator linesep ] [ --output-file outfile ]\n" "\n" "For full documentation type:\n" " GeodSolve --help\n" "or visit:\n" -" http://geographiclib.sf.net/1.35/GeodSolve.1.html\n"; +" https://geographiclib.sourceforge.io/1.49/GeodSolve.1.html\n"; else ( retval ? std::cerr : std::cout ) << "Man page:\n" "NAME\n" " GeodSolve -- perform geodesic calculations\n" "\n" "SYNOPSIS\n" -" GeodSolve [ -i | -l lat1 lon1 azi1 ] [ -a ] [ -e a f ] [ -d | -: ] [ -b\n" -" ] [ -f ] [ -p prec ] [ -E ] [ --comment-delimiter commentdelim ] [\n" +" GeodSolve [ -i | -L lat1 lon1 azi1 | -D lat1 lon1 azi1 s13 | -I lat1\n" +" lon1 lat3 lon3 ] [ -a ] [ -e a f ] [ -u ] [ -F ] [ -d | -: ] [ -w ] [\n" +" -b ] [ -f ] [ -p prec ] [ -E ] [ --comment-delimiter commentdelim ] [\n" " --version | -h | --help ] [ --input-file infile | --input-string\n" " instring ] [ --line-separator linesep ] [ --output-file outfile ]\n" "\n" @@ -33,30 +35,63 @@ int usage(int retval, bool brief) { " containing lat1 lon1 azi1 s12 and prints lat2 lon2 azi2 on standard\n" " output. This is the direct geodesic calculation.\n" "\n" -" 2. Command line arguments -l lat1 lon1 azi1 specify a geodesic line.\n" -" GeodSolve then accepts a sequence of s12 values (one per line) on\n" -" standard input and prints lat2 lon2 azi2 for each. This generates\n" -" a sequence of points on a single geodesic.\n" -"\n" -" 3. With the -i command line argument, GeodSolve performs the inverse\n" +" 2. With the -i command line argument, GeodSolve performs the inverse\n" " geodesic calculation. It reads lines containing lat1 lon1 lat2\n" " lon2 and prints the corresponding values of azi1 azi2 s12.\n" "\n" +" 3. Command line arguments -L lat1 lon1 azi1 specify a geodesic line.\n" +" GeodSolve then accepts a sequence of s12 values (one per line) on\n" +" standard input and prints lat2 lon2 azi2 for each. This generates\n" +" a sequence of points on a single geodesic. Command line arguments\n" +" -D and -I work similarly with the geodesic line defined in terms of\n" +" a direct or inverse geodesic calculation, respectively.\n" +"\n" "OPTIONS\n" -" -i perform an inverse geodesic calculation (see 3 above).\n" +" -i perform an inverse geodesic calculation (see 2 above).\n" "\n" -" -l line mode (see 2 above); generate a sequence of points along the\n" -" geodesic specified by lat1 lon1 azi1.\n" +" -L lat1 lon1 azi1\n" +" line mode (see 3 above); generate a sequence of points along the\n" +" geodesic specified by lat1 lon1 azi1. The -w flag can be used to\n" +" swap the default order of the 2 geographic coordinates, provided\n" +" that it appears before -L. (-l is an alternative, deprecated,\n" +" spelling of this flag.)\n" "\n" -" -a arc mode; on input and output s12 is replaced by a12 the arc length\n" -" (in degrees) on the auxiliary sphere. See \"AUXILIARY SPHERE\".\n" +" -D lat1 lon1 azi1 s13\n" +" line mode (see 3 above); generate a sequence of points along the\n" +" geodesic specified by lat1 lon1 azi1 s13. The -w flag can be used\n" +" to swap the default order of the 2 geographic coordinates, provided\n" +" that it appears before -D. Similarly, the -a flag can be used to\n" +" change the interpretation of s13 to a13, provided that it appears\n" +" before -D.\n" "\n" -" -e specify the ellipsoid via a f; the equatorial radius is a and the\n" -" flattening is f. Setting f = 0 results in a sphere. Specify f < 0\n" +" -I lat1 lon1 lat3 lon3\n" +" line mode (see 3 above); generate a sequence of points along the\n" +" geodesic specified by lat1 lon1 lat3 lon3. The -w flag can be used\n" +" to swap the default order of the 2 geographic coordinates, provided\n" +" that it appears before -I.\n" +"\n" +" -a toggle the arc mode flag (it starts off); if this flag is on, then\n" +" on input and output s12 is replaced by a12 the arc length (in\n" +" degrees) on the auxiliary sphere. See \"AUXILIARY SPHERE\".\n" +"\n" +" -e a f\n" +" specify the ellipsoid via the equatorial radius, a and the\n" +" flattening, f. Setting f = 0 results in a sphere. Specify f < 0\n" " for a prolate ellipsoid. A simple fraction, e.g., 1/297, is\n" -" allowed for f. (Also, if f > 1, the flattening is set to 1/f.) By\n" -" default, the WGS84 ellipsoid is used, a = 6378137 m, f =\n" -" 1/298.257223563.\n" +" allowed for f. By default, the WGS84 ellipsoid is used, a =\n" +" 6378137 m, f = 1/298.257223563.\n" +"\n" +" -u unroll the longitude. Normally, on output longitudes are reduced\n" +" to lie in [-180deg,180deg). However with this option, the returned\n" +" longitude lon2 is \"unrolled\" so that lon2 - lon1 indicates how\n" +" often and in what sense the geodesic has encircled the earth. Use\n" +" the -f option, to get both longitudes printed.\n" +"\n" +" -F fractional mode. This only has any effect with the -D and -I\n" +" options (and is otherwise ignored). The values read on standard\n" +" input are interpreted as fractional distances to point 3, i.e., as\n" +" s12/s13 instead of s12. If arc mode is in effect, then the values\n" +" denote fractional arc length, i.e., a12/a13.\n" "\n" " -d output angles as degrees, minutes, seconds instead of decimal\n" " degrees.\n" @@ -64,6 +99,11 @@ int usage(int retval, bool brief) { " -: like -d, except use : as a separator instead of the d, ', and \"\n" " delimiters.\n" "\n" +" -w toggle the longitude first flag (it starts off); if the flag is on,\n" +" then on input and output, longitude precedes latitude (except that,\n" +" on input, this can be overridden by a hemisphere designator, N, S,\n" +" E, W).\n" +"\n" " -b report the back azimuth at point 2 instead of the forward azimuth.\n" "\n" " -f full output; each line of output consists of 12 quantities: lat1\n" @@ -71,14 +111,15 @@ int usage(int retval, bool brief) { " in \"AUXILIARY SPHERE\". The four quantities m12, M12, M21, and S12\n" " are described in \"ADDITIONAL QUANTITIES\".\n" "\n" -" -p set the output precision to prec (default 3); prec is the precision\n" +" -p prec\n" +" set the output precision to prec (default 3); prec is the precision\n" " relative to 1 m. See \"PRECISION\".\n" "\n" " -E use \"exact\" algorithms (based on elliptic integrals) for the\n" " geodesic calculations. These are more accurate than the (default)\n" " series expansions for |f| > 0.02.\n" "\n" -" --comment-delimiter\n" +" --comment-delimiter commentdelim\n" " set the comment delimiter to commentdelim (e.g., \"#\" or \"//\"). If\n" " set, the input lines will be scanned for this delimiter and, if\n" " found, the delimiter and the rest of the line will be removed prior\n" @@ -93,38 +134,37 @@ int usage(int retval, bool brief) { " --help\n" " print full documentation and exit.\n" "\n" -" --input-file\n" +" --input-file infile\n" " read input from the file infile instead of from standard input; a\n" " file name of \"-\" stands for standard input.\n" "\n" -" --input-string\n" +" --input-string instring\n" " read input from the string instring instead of from standard input.\n" " All occurrences of the line separator character (default is a\n" " semicolon) in instring are converted to newlines before the reading\n" " begins.\n" "\n" -" --line-separator\n" +" --line-separator linesep\n" " set the line separator character to linesep. By default this is a\n" " semicolon.\n" "\n" -" --output-file\n" +" --output-file outfile\n" " write output to the file outfile instead of to standard output; a\n" " file name of \"-\" stands for standard output.\n" "\n" "INPUT\n" " GeodSolve measures all angles in degrees and all lengths (s12) in\n" -" meters. On input angles (latitude, longitude, azimuth, arc length) can\n" -" be as decimal degrees or degrees (d), minutes ('), seconds (\"). A\n" -" decimal point can only appear in the least significant component and\n" -" the designator (d, ', or \") for this component is optional; thus\n" -" \"40d30\", \"40d30'\", \"40.5d\", and 40.5 are all equivalent. By default,\n" -" latitude precedes longitude for each point; however on input either may\n" -" be given first by appending (or prepending) N or S to the latitude and\n" -" E or W to the longitude. Azimuths are measured clockwise from north;\n" -" however this may be overridden with E or W.\n" +" meters, and all areas (S12) in meters^2. On input angles (latitude,\n" +" longitude, azimuth, arc length) can be as decimal degrees or degrees,\n" +" minutes, seconds. For example, \"40d30\", \"40d30'\", \"40:30\", \"40.5d\",\n" +" and 40.5 are all equivalent. By default, latitude precedes longitude\n" +" for each point (the -w flag switches this convention); however on input\n" +" either may be given first by appending (or prepending) N or S to the\n" +" latitude and E or W to the longitude. Azimuths are measured clockwise\n" +" from north; however this may be overridden with E or W.\n" "\n" -" See the \"QUOTING\" section of GeoConvert(1) for how to quote the DMS\n" -" designators ' and \".\n" +" For details on the allowed formats for angles, see the \"GEOGRAPHIC\n" +" COORDINATES\" section of GeoConvert(1).\n" "\n" "AUXILIARY SPHERE\n" " Geodesics on the ellipsoid can be transferred to the auxiliary sphere\n" @@ -153,9 +193,14 @@ int usage(int retval, bool brief) { " dimensionless quantities. On a flat surface, we have M12 = M21 = 1.\n" "\n" " If points 1, 2, and 3 lie on a single geodesic, then the following\n" -" addition rules hold, s13 = s12 + s23, a13 = a12 + a23, S13 = S12 + S23,\n" -" m13 = m12 M23 + m23 M21, M13 = M12 M23 - (1 - M12 M21) m23 / m12, and\n" -" M31 = M32 M21 - (1 - M23 M32) m12 / m23.\n" +" addition rules hold:\n" +"\n" +" s13 = s12 + s23,\n" +" a13 = a12 + a23,\n" +" S13 = S12 + S23,\n" +" m13 = m12 M23 + m23 M21,\n" +" M13 = M12 M23 - (1 - M12 M21) m23 / m12,\n" +" M31 = M32 M21 - (1 - M23 M32) m12 / m23.\n" "\n" " Finally, S12 is the area between the geodesic from point 1 to point 2\n" " and the equator; i.e., it is the area, measured counter-clockwise, of\n" @@ -166,9 +211,9 @@ int usage(int retval, bool brief) { " prec gives precision of the output with prec = 0 giving 1 m precision,\n" " prec = 3 giving 1 mm precision, etc. prec is the number of digits\n" " after the decimal point for lengths. For decimal degrees, the number\n" -" of digits after the decimal point is 5 + prec. For DMS (degree,\n" +" of digits after the decimal point is prec + 5. For DMS (degree,\n" " minute, seconds) output, the number of digits after the decimal point\n" -" in the seconds component is 1 + prec. The minimum value of prec is 0\n" +" in the seconds component is prec + 1. The minimum value of prec is 0\n" " and the maximum is 10.\n" "\n" "ERRORS\n" @@ -180,8 +225,9 @@ int usage(int retval, bool brief) { "ACCURACY\n" " Using the (default) series solution, GeodSolve is accurate to about 15\n" " nm (15 nanometers) for the WGS84 ellipsoid. The approximate maximum\n" -" error (expressed as a distance) for an ellipsoid with the same major\n" -" radius as the WGS84 ellipsoid and different values of the flattening is\n" +" error (expressed as a distance) for an ellipsoid with the same\n" +" equatorial radius as the WGS84 ellipsoid and different values of the\n" +" flattening is\n" "\n" " |f| error\n" " 0.01 25 nm\n" @@ -248,38 +294,45 @@ int usage(int retval, bool brief) { "\n" " 003:18:29.9 177:29:09.2 15347628\n" "\n" -" Waypoints on the route at intervals of 2000km:\n" +" Equally spaced waypoints on the route:\n" "\n" -" for ((i = 0; i <= 16; i += 2)); do echo ${i}000000;done |\n" -" GeodSolve -l 40:38:23N 073:46:44W 003:18:29.9 -: -p 0\n" +" for ((i = 0; i <= 10; ++i)); do echo ${i}e-1; done |\n" +" GeodSolve -I 40:38:23N 073:46:44W 01:21:33N 103:59:22E -F -: -p 0\n" "\n" " 40:38:23.0N 073:46:44.0W 003:18:29.9\n" -" 58:34:45.1N 071:49:36.7W 004:48:48.8\n" -" 76:22:28.4N 065:32:17.8W 010:41:38.4\n" -" 84:50:28.0N 075:04:39.2E 150:55:00.9\n" -" 67:26:20.3N 098:00:51.2E 173:27:20.3\n" -" 49:33:03.2N 101:06:52.6E 176:07:54.3\n" -" 31:34:16.5N 102:30:46.3E 177:03:08.4\n" -" 13:31:56.0N 103:26:50.7E 177:24:55.0\n" -" 04:32:05.7S 104:14:48.7E 177:28:43.6\n" +" 54:24:51.3N 072:25:39.6W 004:18:44.1\n" +" 68:07:37.7N 069:40:42.9W 006:44:25.4\n" +" 81:38:00.4N 058:37:53.9W 017:28:52.7\n" +" 83:43:26.0N 080:37:16.9E 156:26:00.4\n" +" 70:20:29.2N 097:01:29.4E 172:31:56.4\n" +" 56:38:36.0N 100:14:47.6E 175:26:10.5\n" +" 42:52:37.1N 101:43:37.2E 176:34:28.6\n" +" 29:03:57.0N 102:39:34.8E 177:07:35.2\n" +" 15:13:18.6N 103:22:08.0E 177:23:44.7\n" +" 01:21:33.0N 103:59:22.0E 177:29:09.2\n" "\n" "SEE ALSO\n" -" GeoConvert(1). The algorithms are described in C. F. F. Karney,\n" -" Algorithms for geodesics, J. Geodesy 87, 43-55 (2013); DOI:\n" -" http://dx.doi.org/10.1007/s00190-012-0578-z\n" -" ; addenda:\n" -" http://geographiclib.sf.net/geod-addenda.html\n" -" . The wikipedia page,\n" -" Geodesics on an ellipsoid,\n" -" .\n" +" GeoConvert(1).\n" +"\n" +" An online version of this utility is availbable at\n" +" .\n" +"\n" +" The algorithms are described in C. F. F. Karney, Algorithms for\n" +" geodesics, J. Geodesy 87, 43-55 (2013); DOI:\n" +" ; addenda:\n" +" .\n" +"\n" +" The Wikipedia page, Geodesics on an ellipsoid,\n" +" .\n" "\n" "AUTHOR\n" " GeodSolve was written by Charles Karney.\n" "\n" "HISTORY\n" -" GeodSolve was added to GeographicLib, , in\n" -" 2009-03. Prior to version 1.30, it was called Geod. (The name was\n" -" changed to avoid a conflict with the geod utility in proj.4.)\n" +" GeodSolve was added to GeographicLib,\n" +" , in 2009-03. Prior to version\n" +" 1.30, it was called Geod. (The name was changed to avoid a conflict\n" +" with the geod utility in proj.4.)\n" ; return retval; } diff --git a/gtsam/3rdparty/GeographicLib/man/GeodesicProj.1 b/gtsam/3rdparty/GeographicLib/man/GeodesicProj.1 index 9b87078a3..0d15ab4cf 100644 --- a/gtsam/3rdparty/GeographicLib/man/GeodesicProj.1 +++ b/gtsam/3rdparty/GeographicLib/man/GeodesicProj.1 @@ -1,4 +1,4 @@ -.\" Automatically generated by Pod::Man 2.25 (Pod::Simple 3.20) +.\" Automatically generated by Pod::Man 4.09 (Pod::Simple 3.35) .\" .\" Standard preamble: .\" ======================================================================== @@ -38,26 +38,31 @@ . ds PI \(*p . ds L" `` . ds R" '' +. ds C` +. ds C' 'br\} .\" .\" Escape single quotes in literal strings from groff's Unicode transform. .ie \n(.g .ds Aq \(aq .el .ds Aq ' .\" -.\" If the F register is turned on, we'll generate index entries on stderr for +.\" If the F register is >0, we'll generate index entries on stderr for .\" titles (.TH), headers (.SH), subsections (.SS), items (.Ip), and index .\" entries marked with X<> in POD. Of course, you'll have to process the .\" output yourself in some meaningful fashion. -.ie \nF \{\ +.\" +.\" Avoid warning from groff about undefined register 'F'. +.de IX +.. +.if !\nF .nr F 0 +.if \nF>0 \{\ . de IX . tm Index:\\$1\t\\n%\t"\\$2" .. -. nr % 0 -. rr F -.\} -.el \{\ -. de IX -.. +. if !\nF==2 \{\ +. nr % 0 +. nr F 2 +. \} .\} .\" .\" Accent mark definitions (@(#)ms.acc 1.5 88/02/08 SMI; from UCB 4.2). @@ -124,7 +129,7 @@ .\" ======================================================================== .\" .IX Title "GEODESICPROJ 1" -.TH GEODESICPROJ 1 "2014-03-13" "GeographicLib 1.35" "GeographicLib Utilities" +.TH GEODESICPROJ 1 "2017-10-05" "GeographicLib 1.49" "GeographicLib Utilities" .\" For nroff, turn off justification. Always turn off hyphenation; it makes .\" way too many mistakes in technical documents. .if n .ad l @@ -134,7 +139,7 @@ GeodesicProj \-\- perform projections based on geodesics .SH "SYNOPSIS" .IX Header "SYNOPSIS" \&\fBGeodesicProj\fR ( \fB\-z\fR | \fB\-c\fR | \fB\-g\fR ) \fIlat0\fR \fIlon0\fR [ \fB\-r\fR ] -[ \fB\-e\fR \fIa\fR \fIf\fR ] +[ \fB\-e\fR \fIa\fR \fIf\fR ] [ \fB\-w\fR ] [ \fB\-p\fR \fIprec\fR ] [ \fB\-\-comment\-delimiter\fR \fIcommentdelim\fR ] [ \fB\-\-version\fR | \fB\-h\fR | \fB\-\-help\fR ] [ \fB\-\-input\-file\fR \fIinfile\fR | \fB\-\-input\-string\fR \fIinstring\fR ] @@ -144,52 +149,69 @@ GeodesicProj \-\- perform projections based on geodesics .IX Header "DESCRIPTION" Perform projections based on geodesics. Convert geodetic coordinates to either azimuthal equidistant, Cassini-Soldner, or gnomonic coordinates. -The center of the projection (\fIlat0\fR, \fIlon0\fR) is specified by either the \fB\-c\fR -option (for Cassini-Soldner), the \fB\-z\fR option (for azimuthal equidistant), -or the \fB\-g\fR option (for gnomonic). At least one of these options must be -given (the last one given is used). +The center of the projection (\fIlat0\fR, \fIlon0\fR) is specified by either +the \fB\-c\fR option (for Cassini-Soldner), the \fB\-z\fR option (for azimuthal +equidistant), or the \fB\-g\fR option (for gnomonic). At least one of these +options must be given (the last one given is used). .PP Geodetic coordinates are provided on standard input as a set of lines containing (blank separated) \fIlatitude\fR and \fIlongitude\fR (decimal -degrees or degrees, minutes, seconds). For each set of geodetic -coordinates, the corresponding projected coordinates \fIx\fR, \fIy\fR (meters) -are printed on standard output together with the azimuth \fIazi\fR -(degrees) and reciprocal scale \fIrk\fR. For Cassini-Soldner, \fIazi\fR is -the bearing of the easting direction and the scale in the easting -direction is 1 and the scale in the northing direction is 1/\fIrk\fR. For -azimuthal equidistant and gnomonic, \fIazi\fR is the bearing of the radial -direction and the scale in the azimuthal direction is 1/\fIrk\fR. For -azimuthal equidistant and gnomonic, the scales in the radial direction -are 1 and 1/\fIrk\fR^2, respectively. +degrees or degrees, minutes, seconds); for details on the allowed +formats for latitude and longitude, see the \f(CW\*(C`GEOGRAPHIC COORDINATES\*(C'\fR +section of \fIGeoConvert\fR\|(1). For each set of geodetic coordinates, the +corresponding projected coordinates \fIx\fR, \fIy\fR (meters) are printed on +standard output together with the azimuth \fIazi\fR (degrees) and +reciprocal scale \fIrk\fR. For Cassini-Soldner, \fIazi\fR is the bearing of +the easting direction and the scale in the easting direction is 1 and +the scale in the northing direction is 1/\fIrk\fR. For azimuthal +equidistant and gnomonic, \fIazi\fR is the bearing of the radial direction +and the scale in the azimuthal direction is 1/\fIrk\fR. For azimuthal +equidistant and gnomonic, the scales in the radial direction are 1 and +1/\fIrk\fR^2, respectively. .SH "OPTIONS" .IX Header "OPTIONS" -.IP "\fB\-z\fR" 4 -.IX Item "-z" +.IP "\fB\-z\fR \fIlat0\fR \fIlon0\fR" 4 +.IX Item "-z lat0 lon0" use the azimuthal equidistant projection centered at latitude = \fIlat0\fR, -longitude = \fIlon0\fR. -.IP "\fB\-c\fR" 4 -.IX Item "-c" +longitude = \fIlon0\fR. The \fB\-w\fR flag can be used to swap the default +order of the 2 coordinates, provided that it appears before \fB\-z\fR. +.IP "\fB\-c\fR \fIlat0\fR \fIlon0\fR" 4 +.IX Item "-c lat0 lon0" use the Cassini-Soldner projection centered at latitude = \fIlat0\fR, -longitude = \fIlon0\fR. -.IP "\fB\-g\fR" 4 -.IX Item "-g" +longitude = \fIlon0\fR. The \fB\-w\fR flag can be used to swap the default +order of the 2 coordinates, provided that it appears before \fB\-c\fR. +.IP "\fB\-g\fR \fIlat0\fR \fIlon0\fR" 4 +.IX Item "-g lat0 lon0" use the ellipsoidal gnomonic projection centered at latitude = \fIlat0\fR, -longitude = \fIlon0\fR. +longitude = \fIlon0\fR. The \fB\-w\fR flag can be used to swap the default +order of the 2 coordinates, provided that it appears before \fB\-g\fR. .IP "\fB\-r\fR" 4 .IX Item "-r" perform the reverse projection. \fIx\fR and \fIy\fR are given on standard input and each line of standard output gives \fIlatitude\fR, \fIlongitude\fR, \&\fIazi\fR, and \fIrk\fR. -.IP "\fB\-e\fR" 4 -.IX Item "-e" -specify the ellipsoid via \fIa\fR \fIf\fR; the equatorial radius is \fIa\fR and -the flattening is \fIf\fR. Setting \fIf\fR = 0 results in a sphere. Specify +.IP "\fB\-e\fR \fIa\fR \fIf\fR" 4 +.IX Item "-e a f" +specify the ellipsoid via the equatorial radius, \fIa\fR and +the flattening, \fIf\fR. Setting \fIf\fR = 0 results in a sphere. Specify \&\fIf\fR < 0 for a prolate ellipsoid. A simple fraction, e.g., 1/297, -is allowed for \fIf\fR. (Also, if \fIf\fR > 1, the flattening is set to -1/\fIf\fR.) By default, the \s-1WGS84\s0 ellipsoid is used, \fIa\fR = 6378137 m, -\&\fIf\fR = 1/298.257223563. -.IP "\fB\-\-comment\-delimiter\fR" 4 -.IX Item "--comment-delimiter" +is allowed for \fIf\fR. By default, the \s-1WGS84\s0 ellipsoid is used, \fIa\fR = +6378137 m, \fIf\fR = 1/298.257223563. +.IP "\fB\-w\fR" 4 +.IX Item "-w" +toggle the longitude first flag (it starts off); if the flag is on, then +on input and output, longitude precedes latitude (except that, on input, +this can be overridden by a hemisphere designator, \fIN\fR, \fIS\fR, \fIE\fR, +\&\fIW\fR). +.IP "\fB\-p\fR \fIprec\fR" 4 +.IX Item "-p prec" +set the output precision to \fIprec\fR (default 6). \fIprec\fR is the number +of digits after the decimal point for lengths (in meters). For +latitudes, longitudes, and azimuths (in degrees), the number of digits +after the decimal point is \fIprec\fR + 5. For the scale, the number of +digits after the decimal point is \fIprec\fR + 6. +.IP "\fB\-\-comment\-delimiter\fR \fIcommentdelim\fR" 4 +.IX Item "--comment-delimiter commentdelim" set the comment delimiter to \fIcommentdelim\fR (e.g., \*(L"#\*(R" or \*(L"//\*(R"). If set, the input lines will be scanned for this delimiter and, if found, the delimiter and the rest of the line will be removed prior to @@ -204,21 +226,21 @@ print usage and exit. .IP "\fB\-\-help\fR" 4 .IX Item "--help" print full documentation and exit. -.IP "\fB\-\-input\-file\fR" 4 -.IX Item "--input-file" +.IP "\fB\-\-input\-file\fR \fIinfile\fR" 4 +.IX Item "--input-file infile" read input from the file \fIinfile\fR instead of from standard input; a file name of \*(L"\-\*(R" stands for standard input. -.IP "\fB\-\-input\-string\fR" 4 -.IX Item "--input-string" +.IP "\fB\-\-input\-string\fR \fIinstring\fR" 4 +.IX Item "--input-string instring" read input from the string \fIinstring\fR instead of from standard input. All occurrences of the line separator character (default is a semicolon) in \fIinstring\fR are converted to newlines before the reading begins. -.IP "\fB\-\-line\-separator\fR" 4 -.IX Item "--line-separator" +.IP "\fB\-\-line\-separator\fR \fIlinesep\fR" 4 +.IX Item "--line-separator linesep" set the line separator character to \fIlinesep\fR. By default this is a semicolon. -.IP "\fB\-\-output\-file\fR" 4 -.IX Item "--output-file" +.IP "\fB\-\-output\-file\fR \fIoutfile\fR" 4 +.IX Item "--output-file outfile" write output to the file \fIoutfile\fR instead of to standard output; a file name of \*(L"\-\*(R" stands for standard output. .SH "EXAMPLES" @@ -239,13 +261,13 @@ terminate; following lines will be converted. .IX Header "SEE ALSO" The ellipsoidal gnomonic projection is derived in Section 8 of C. F. F. Karney, \fIAlgorithms for geodesics\fR, J. Geodesy 87, 43\-55 (2013); \s-1DOI\s0 -http://dx.doi.org/10.1007/s00190\-012\-0578\-z ; -addenda: http://geographiclib.sf.net/geod\-addenda.html . +; +addenda: . .SH "AUTHOR" .IX Header "AUTHOR" \&\fBGeodesicProj\fR was written by Charles Karney. .SH "HISTORY" .IX Header "HISTORY" \&\fBGeodesicProj\fR was added to GeographicLib, -, in 2009\-08. Prior to version 1.9 it was -called EquidistantTest. +, in 2009\-08. +Prior to version 1.9 it was called EquidistantTest. diff --git a/gtsam/3rdparty/GeographicLib/man/GeodesicProj.1.html b/gtsam/3rdparty/GeographicLib/man/GeodesicProj.1.html index 2b63cf7de..cabc84a07 100644 --- a/gtsam/3rdparty/GeographicLib/man/GeodesicProj.1.html +++ b/gtsam/3rdparty/GeographicLib/man/GeodesicProj.1.html @@ -7,7 +7,7 @@ - + @@ -17,34 +17,34 @@

    SYNOPSIS

    -

    GeodesicProj ( -z | -c | -g ) lat0 lon0 [ -r ] [ -e a f ] [ --comment-delimiter commentdelim ] [ --version | -h | --help ] [ --input-file infile | --input-string instring ] [ --line-separator linesep ] [ --output-file outfile ]

    +

    GeodesicProj ( -z | -c | -g ) lat0 lon0 [ -r ] [ -e a f ] [ -w ] [ -p prec ] [ --comment-delimiter commentdelim ] [ --version | -h | --help ] [ --input-file infile | --input-string instring ] [ --line-separator linesep ] [ --output-file outfile ]

    DESCRIPTION

    Perform projections based on geodesics. Convert geodetic coordinates to either azimuthal equidistant, Cassini-Soldner, or gnomonic coordinates. The center of the projection (lat0, lon0) is specified by either the -c option (for Cassini-Soldner), the -z option (for azimuthal equidistant), or the -g option (for gnomonic). At least one of these options must be given (the last one given is used).

    -

    Geodetic coordinates are provided on standard input as a set of lines containing (blank separated) latitude and longitude (decimal degrees or degrees, minutes, seconds). For each set of geodetic coordinates, the corresponding projected coordinates x, y (meters) are printed on standard output together with the azimuth azi (degrees) and reciprocal scale rk. For Cassini-Soldner, azi is the bearing of the easting direction and the scale in the easting direction is 1 and the scale in the northing direction is 1/rk. For azimuthal equidistant and gnomonic, azi is the bearing of the radial direction and the scale in the azimuthal direction is 1/rk. For azimuthal equidistant and gnomonic, the scales in the radial direction are 1 and 1/rk^2, respectively.

    +

    Geodetic coordinates are provided on standard input as a set of lines containing (blank separated) latitude and longitude (decimal degrees or degrees, minutes, seconds); for details on the allowed formats for latitude and longitude, see the GEOGRAPHIC COORDINATES section of GeoConvert(1). For each set of geodetic coordinates, the corresponding projected coordinates x, y (meters) are printed on standard output together with the azimuth azi (degrees) and reciprocal scale rk. For Cassini-Soldner, azi is the bearing of the easting direction and the scale in the easting direction is 1 and the scale in the northing direction is 1/rk. For azimuthal equidistant and gnomonic, azi is the bearing of the radial direction and the scale in the azimuthal direction is 1/rk. For azimuthal equidistant and gnomonic, the scales in the radial direction are 1 and 1/rk^2, respectively.

    OPTIONS

    -
    -z
    +
    -z lat0 lon0
    -

    use the azimuthal equidistant projection centered at latitude = lat0, longitude = lon0.

    +

    use the azimuthal equidistant projection centered at latitude = lat0, longitude = lon0. The -w flag can be used to swap the default order of the 2 coordinates, provided that it appears before -z.

    -
    -c
    +
    -c lat0 lon0
    -

    use the Cassini-Soldner projection centered at latitude = lat0, longitude = lon0.

    +

    use the Cassini-Soldner projection centered at latitude = lat0, longitude = lon0. The -w flag can be used to swap the default order of the 2 coordinates, provided that it appears before -c.

    -
    -g
    +
    -g lat0 lon0
    -

    use the ellipsoidal gnomonic projection centered at latitude = lat0, longitude = lon0.

    +

    use the ellipsoidal gnomonic projection centered at latitude = lat0, longitude = lon0. The -w flag can be used to swap the default order of the 2 coordinates, provided that it appears before -g.

    -r
    @@ -53,13 +53,25 @@

    perform the reverse projection. x and y are given on standard input and each line of standard output gives latitude, longitude, azi, and rk.

    -
    -e
    +
    -e a f
    -

    specify the ellipsoid via a f; the equatorial radius is a and the flattening is f. Setting f = 0 results in a sphere. Specify f < 0 for a prolate ellipsoid. A simple fraction, e.g., 1/297, is allowed for f. (Also, if f > 1, the flattening is set to 1/f.) By default, the WGS84 ellipsoid is used, a = 6378137 m, f = 1/298.257223563.

    +

    specify the ellipsoid via the equatorial radius, a and the flattening, f. Setting f = 0 results in a sphere. Specify f < 0 for a prolate ellipsoid. A simple fraction, e.g., 1/297, is allowed for f. By default, the WGS84 ellipsoid is used, a = 6378137 m, f = 1/298.257223563.

    -
    --comment-delimiter
    +
    -w
    +
    + +

    toggle the longitude first flag (it starts off); if the flag is on, then on input and output, longitude precedes latitude (except that, on input, this can be overridden by a hemisphere designator, N, S, E, W).

    + +
    +
    -p prec
    +
    + +

    set the output precision to prec (default 6). prec is the number of digits after the decimal point for lengths (in meters). For latitudes, longitudes, and azimuths (in degrees), the number of digits after the decimal point is prec + 5. For the scale, the number of digits after the decimal point is prec + 6.

    + +
    +
    --comment-delimiter commentdelim

    set the comment delimiter to commentdelim (e.g., "#" or "//"). If set, the input lines will be scanned for this delimiter and, if found, the delimiter and the rest of the line will be removed prior to processing and subsequently appended to the output line (separated by a space).

    @@ -83,25 +95,25 @@

    print full documentation and exit.

    -
    --input-file
    +
    --input-file infile

    read input from the file infile instead of from standard input; a file name of "-" stands for standard input.

    -
    --input-string
    +
    --input-string instring

    read input from the string instring instead of from standard input. All occurrences of the line separator character (default is a semicolon) in instring are converted to newlines before the reading begins.

    -
    --line-separator
    +
    --line-separator linesep

    set the line separator character to linesep. By default this is a semicolon.

    -
    --output-file
    +
    --output-file outfile

    write output to the file outfile instead of to standard output; a file name of "-" stands for standard output.

    @@ -122,7 +134,7 @@

    SEE ALSO

    -

    The ellipsoidal gnomonic projection is derived in Section 8 of C. F. F. Karney, Algorithms for geodesics, J. Geodesy 87, 43-55 (2013); DOI http://dx.doi.org/10.1007/s00190-012-0578-z; addenda: http://geographiclib.sf.net/geod-addenda.html.

    +

    The ellipsoidal gnomonic projection is derived in Section 8 of C. F. F. Karney, Algorithms for geodesics, J. Geodesy 87, 43-55 (2013); DOI https://doi.org/10.1007/s00190-012-0578-z; addenda: https://geographiclib.sourceforge.io/geod-addenda.html.

    AUTHOR

    @@ -130,7 +142,7 @@

    HISTORY

    -

    GeodesicProj was added to GeographicLib, http://geographiclib.sf.net, in 2009-08. Prior to version 1.9 it was called EquidistantTest.

    +

    GeodesicProj was added to GeographicLib, https://geographiclib.sourceforge.io, in 2009-08. Prior to version 1.9 it was called EquidistantTest.

    diff --git a/gtsam/3rdparty/GeographicLib/man/GeodesicProj.pod b/gtsam/3rdparty/GeographicLib/man/GeodesicProj.pod index 2e2e961e6..5c71421c4 100644 --- a/gtsam/3rdparty/GeographicLib/man/GeodesicProj.pod +++ b/gtsam/3rdparty/GeographicLib/man/GeodesicProj.pod @@ -5,7 +5,7 @@ GeodesicProj -- perform projections based on geodesics =head1 SYNOPSIS B ( B<-z> | B<-c> | B<-g> ) I I [ B<-r> ] -[ B<-e> I I ] +[ B<-e> I I ] [ B<-w> ] [ B<-p> I ] [ B<--comment-delimiter> I ] [ B<--version> | B<-h> | B<--help> ] [ B<--input-file> I | B<--input-string> I ] @@ -16,42 +16,47 @@ B ( B<-z> | B<-c> | B<-g> ) I I [ B<-r> ] Perform projections based on geodesics. Convert geodetic coordinates to either azimuthal equidistant, Cassini-Soldner, or gnomonic coordinates. -The center of the projection (I, I) is specified by either the B<-c> -option (for Cassini-Soldner), the B<-z> option (for azimuthal equidistant), -or the B<-g> option (for gnomonic). At least one of these options must be -given (the last one given is used). +The center of the projection (I, I) is specified by either +the B<-c> option (for Cassini-Soldner), the B<-z> option (for azimuthal +equidistant), or the B<-g> option (for gnomonic). At least one of these +options must be given (the last one given is used). Geodetic coordinates are provided on standard input as a set of lines containing (blank separated) I and I (decimal -degrees or degrees, minutes, seconds). For each set of geodetic -coordinates, the corresponding projected coordinates I, I (meters) -are printed on standard output together with the azimuth I -(degrees) and reciprocal scale I. For Cassini-Soldner, I is -the bearing of the easting direction and the scale in the easting -direction is 1 and the scale in the northing direction is 1/I. For -azimuthal equidistant and gnomonic, I is the bearing of the radial -direction and the scale in the azimuthal direction is 1/I. For -azimuthal equidistant and gnomonic, the scales in the radial direction -are 1 and 1/I^2, respectively. +degrees or degrees, minutes, seconds); for details on the allowed +formats for latitude and longitude, see the C +section of GeoConvert(1). For each set of geodetic coordinates, the +corresponding projected coordinates I, I (meters) are printed on +standard output together with the azimuth I (degrees) and +reciprocal scale I. For Cassini-Soldner, I is the bearing of +the easting direction and the scale in the easting direction is 1 and +the scale in the northing direction is 1/I. For azimuthal +equidistant and gnomonic, I is the bearing of the radial direction +and the scale in the azimuthal direction is 1/I. For azimuthal +equidistant and gnomonic, the scales in the radial direction are 1 and +1/I^2, respectively. =head1 OPTIONS =over -=item B<-z> +=item B<-z> I I use the azimuthal equidistant projection centered at latitude = I, -longitude = I. +longitude = I. The B<-w> flag can be used to swap the default +order of the 2 coordinates, provided that it appears before B<-z>. -=item B<-c> +=item B<-c> I I use the Cassini-Soldner projection centered at latitude = I, -longitude = I. +longitude = I. The B<-w> flag can be used to swap the default +order of the 2 coordinates, provided that it appears before B<-c>. -=item B<-g> +=item B<-g> I I use the ellipsoidal gnomonic projection centered at latitude = I, -longitude = I. +longitude = I. The B<-w> flag can be used to swap the default +order of the 2 coordinates, provided that it appears before B<-g>. =item B<-r> @@ -59,16 +64,30 @@ perform the reverse projection. I and I are given on standard input and each line of standard output gives I, I, I, and I. -=item B<-e> +=item B<-e> I I -specify the ellipsoid via I I; the equatorial radius is I and -the flattening is I. Setting I = 0 results in a sphere. Specify +specify the ellipsoid via the equatorial radius, I and +the flattening, I. Setting I = 0 results in a sphere. Specify I E 0 for a prolate ellipsoid. A simple fraction, e.g., 1/297, -is allowed for I. (Also, if I E 1, the flattening is set to -1/I.) By default, the WGS84 ellipsoid is used, I = 6378137 m, -I = 1/298.257223563. +is allowed for I. By default, the WGS84 ellipsoid is used, I = +6378137 m, I = 1/298.257223563. -=item B<--comment-delimiter> +=item B<-w> + +toggle the longitude first flag (it starts off); if the flag is on, then +on input and output, longitude precedes latitude (except that, on input, +this can be overridden by a hemisphere designator, I, I, I, +I). + +=item B<-p> I + +set the output precision to I (default 6). I is the number +of digits after the decimal point for lengths (in meters). For +latitudes, longitudes, and azimuths (in degrees), the number of digits +after the decimal point is I + 5. For the scale, the number of +digits after the decimal point is I + 6. + +=item B<--comment-delimiter> I set the comment delimiter to I (e.g., "#" or "//"). If set, the input lines will be scanned for this delimiter and, if found, @@ -88,23 +107,23 @@ print usage and exit. print full documentation and exit. -=item B<--input-file> +=item B<--input-file> I read input from the file I instead of from standard input; a file name of "-" stands for standard input. -=item B<--input-string> +=item B<--input-string> I read input from the string I instead of from standard input. All occurrences of the line separator character (default is a semicolon) in I are converted to newlines before the reading begins. -=item B<--line-separator> +=item B<--line-separator> I set the line separator character to I. By default this is a semicolon. -=item B<--output-file> +=item B<--output-file> I write output to the file I instead of to standard output; a file name of "-" stands for standard output. @@ -129,8 +148,8 @@ terminate; following lines will be converted. The ellipsoidal gnomonic projection is derived in Section 8 of C. F. F. Karney, I, J. Geodesy 87, 43-55 (2013); DOI -L; -addenda: L. +L; +addenda: L. =head1 AUTHOR @@ -139,5 +158,5 @@ B was written by Charles Karney. =head1 HISTORY B was added to GeographicLib, -L, in 2009-08. Prior to version 1.9 it was -called EquidistantTest. +L, in 2009-08. +Prior to version 1.9 it was called EquidistantTest. diff --git a/gtsam/3rdparty/GeographicLib/man/GeodesicProj.usage b/gtsam/3rdparty/GeographicLib/man/GeodesicProj.usage index 013fb7acf..7803eda20 100644 --- a/gtsam/3rdparty/GeographicLib/man/GeodesicProj.usage +++ b/gtsam/3rdparty/GeographicLib/man/GeodesicProj.usage @@ -1,24 +1,24 @@ int usage(int retval, bool brief) { if (brief) ( retval ? std::cerr : std::cout ) << "Usage:\n" -" GeodesicProj ( -z | -c | -g ) lat0 lon0 [ -r ] [ -e a f ] [\n" -" --comment-delimiter commentdelim ] [ --version | -h | --help ] [\n" -" --input-file infile | --input-string instring ] [ --line-separator\n" +" GeodesicProj ( -z | -c | -g ) lat0 lon0 [ -r ] [ -e a f ] [ -w ] [ -p\n" +" prec ] [ --comment-delimiter commentdelim ] [ --version | -h | --help ]\n" +" [ --input-file infile | --input-string instring ] [ --line-separator\n" " linesep ] [ --output-file outfile ]\n" "\n" "For full documentation type:\n" " GeodesicProj --help\n" "or visit:\n" -" http://geographiclib.sf.net/1.35/GeodesicProj.1.html\n"; +" https://geographiclib.sourceforge.io/1.49/GeodesicProj.1.html\n"; else ( retval ? std::cerr : std::cout ) << "Man page:\n" "NAME\n" " GeodesicProj -- perform projections based on geodesics\n" "\n" "SYNOPSIS\n" -" GeodesicProj ( -z | -c | -g ) lat0 lon0 [ -r ] [ -e a f ] [\n" -" --comment-delimiter commentdelim ] [ --version | -h | --help ] [\n" -" --input-file infile | --input-string instring ] [ --line-separator\n" +" GeodesicProj ( -z | -c | -g ) lat0 lon0 [ -r ] [ -e a f ] [ -w ] [ -p\n" +" prec ] [ --comment-delimiter commentdelim ] [ --version | -h | --help ]\n" +" [ --input-file infile | --input-string instring ] [ --line-separator\n" " linesep ] [ --output-file outfile ]\n" "\n" "DESCRIPTION\n" @@ -31,39 +31,60 @@ int usage(int retval, bool brief) { "\n" " Geodetic coordinates are provided on standard input as a set of lines\n" " containing (blank separated) latitude and longitude (decimal degrees or\n" -" degrees, minutes, seconds). For each set of geodetic coordinates, the\n" -" corresponding projected coordinates x, y (meters) are printed on\n" -" standard output together with the azimuth azi (degrees) and reciprocal\n" -" scale rk. For Cassini-Soldner, azi is the bearing of the easting\n" -" direction and the scale in the easting direction is 1 and the scale in\n" -" the northing direction is 1/rk. For azimuthal equidistant and\n" -" gnomonic, azi is the bearing of the radial direction and the scale in\n" -" the azimuthal direction is 1/rk. For azimuthal equidistant and\n" -" gnomonic, the scales in the radial direction are 1 and 1/rk^2,\n" -" respectively.\n" +" degrees, minutes, seconds); for details on the allowed formats for\n" +" latitude and longitude, see the \"GEOGRAPHIC COORDINATES\" section of\n" +" GeoConvert(1). For each set of geodetic coordinates, the corresponding\n" +" projected coordinates x, y (meters) are printed on standard output\n" +" together with the azimuth azi (degrees) and reciprocal scale rk. For\n" +" Cassini-Soldner, azi is the bearing of the easting direction and the\n" +" scale in the easting direction is 1 and the scale in the northing\n" +" direction is 1/rk. For azimuthal equidistant and gnomonic, azi is the\n" +" bearing of the radial direction and the scale in the azimuthal\n" +" direction is 1/rk. For azimuthal equidistant and gnomonic, the scales\n" +" in the radial direction are 1 and 1/rk^2, respectively.\n" "\n" "OPTIONS\n" -" -z use the azimuthal equidistant projection centered at latitude =\n" -" lat0, longitude = lon0.\n" +" -z lat0 lon0\n" +" use the azimuthal equidistant projection centered at latitude =\n" +" lat0, longitude = lon0. The -w flag can be used to swap the\n" +" default order of the 2 coordinates, provided that it appears before\n" +" -z.\n" "\n" -" -c use the Cassini-Soldner projection centered at latitude = lat0,\n" -" longitude = lon0.\n" +" -c lat0 lon0\n" +" use the Cassini-Soldner projection centered at latitude = lat0,\n" +" longitude = lon0. The -w flag can be used to swap the default\n" +" order of the 2 coordinates, provided that it appears before -c.\n" "\n" -" -g use the ellipsoidal gnomonic projection centered at latitude =\n" -" lat0, longitude = lon0.\n" +" -g lat0 lon0\n" +" use the ellipsoidal gnomonic projection centered at latitude =\n" +" lat0, longitude = lon0. The -w flag can be used to swap the\n" +" default order of the 2 coordinates, provided that it appears before\n" +" -g.\n" "\n" " -r perform the reverse projection. x and y are given on standard\n" " input and each line of standard output gives latitude, longitude,\n" " azi, and rk.\n" "\n" -" -e specify the ellipsoid via a f; the equatorial radius is a and the\n" -" flattening is f. Setting f = 0 results in a sphere. Specify f < 0\n" +" -e a f\n" +" specify the ellipsoid via the equatorial radius, a and the\n" +" flattening, f. Setting f = 0 results in a sphere. Specify f < 0\n" " for a prolate ellipsoid. A simple fraction, e.g., 1/297, is\n" -" allowed for f. (Also, if f > 1, the flattening is set to 1/f.) By\n" -" default, the WGS84 ellipsoid is used, a = 6378137 m, f =\n" -" 1/298.257223563.\n" +" allowed for f. By default, the WGS84 ellipsoid is used, a =\n" +" 6378137 m, f = 1/298.257223563.\n" "\n" -" --comment-delimiter\n" +" -w toggle the longitude first flag (it starts off); if the flag is on,\n" +" then on input and output, longitude precedes latitude (except that,\n" +" on input, this can be overridden by a hemisphere designator, N, S,\n" +" E, W).\n" +"\n" +" -p prec\n" +" set the output precision to prec (default 6). prec is the number\n" +" of digits after the decimal point for lengths (in meters). For\n" +" latitudes, longitudes, and azimuths (in degrees), the number of\n" +" digits after the decimal point is prec + 5. For the scale, the\n" +" number of digits after the decimal point is prec + 6.\n" +"\n" +" --comment-delimiter commentdelim\n" " set the comment delimiter to commentdelim (e.g., \"#\" or \"//\"). If\n" " set, the input lines will be scanned for this delimiter and, if\n" " found, the delimiter and the rest of the line will be removed prior\n" @@ -78,21 +99,21 @@ int usage(int retval, bool brief) { " --help\n" " print full documentation and exit.\n" "\n" -" --input-file\n" +" --input-file infile\n" " read input from the file infile instead of from standard input; a\n" " file name of \"-\" stands for standard input.\n" "\n" -" --input-string\n" +" --input-string instring\n" " read input from the string instring instead of from standard input.\n" " All occurrences of the line separator character (default is a\n" " semicolon) in instring are converted to newlines before the reading\n" " begins.\n" "\n" -" --line-separator\n" +" --line-separator linesep\n" " set the line separator character to linesep. By default this is a\n" " semicolon.\n" "\n" -" --output-file\n" +" --output-file outfile\n" " write output to the file outfile instead of to standard output; a\n" " file name of \"-\" stands for standard output.\n" "\n" @@ -111,17 +132,16 @@ int usage(int retval, bool brief) { "SEE ALSO\n" " The ellipsoidal gnomonic projection is derived in Section 8 of C. F. F.\n" " Karney, Algorithms for geodesics, J. Geodesy 87, 43-55 (2013); DOI\n" -" http://dx.doi.org/10.1007/s00190-012-0578-z\n" -" ; addenda:\n" -" http://geographiclib.sf.net/geod-addenda.html\n" -" .\n" +" ; addenda:\n" +" .\n" "\n" "AUTHOR\n" " GeodesicProj was written by Charles Karney.\n" "\n" "HISTORY\n" -" GeodesicProj was added to GeographicLib, ,\n" -" in 2009-08. Prior to version 1.9 it was called EquidistantTest.\n" +" GeodesicProj was added to GeographicLib,\n" +" , in 2009-08. Prior to version\n" +" 1.9 it was called EquidistantTest.\n" ; return retval; } diff --git a/gtsam/3rdparty/GeographicLib/man/GeoidEval.1 b/gtsam/3rdparty/GeographicLib/man/GeoidEval.1 index 7c5086e1c..e0aee0780 100644 --- a/gtsam/3rdparty/GeographicLib/man/GeoidEval.1 +++ b/gtsam/3rdparty/GeographicLib/man/GeoidEval.1 @@ -1,4 +1,4 @@ -.\" Automatically generated by Pod::Man 2.25 (Pod::Simple 3.20) +.\" Automatically generated by Pod::Man 4.09 (Pod::Simple 3.35) .\" .\" Standard preamble: .\" ======================================================================== @@ -38,26 +38,31 @@ . ds PI \(*p . ds L" `` . ds R" '' +. ds C` +. ds C' 'br\} .\" .\" Escape single quotes in literal strings from groff's Unicode transform. .ie \n(.g .ds Aq \(aq .el .ds Aq ' .\" -.\" If the F register is turned on, we'll generate index entries on stderr for +.\" If the F register is >0, we'll generate index entries on stderr for .\" titles (.TH), headers (.SH), subsections (.SS), items (.Ip), and index .\" entries marked with X<> in POD. Of course, you'll have to process the .\" output yourself in some meaningful fashion. -.ie \nF \{\ +.\" +.\" Avoid warning from groff about undefined register 'F'. +.de IX +.. +.if !\nF .nr F 0 +.if \nF>0 \{\ . de IX . tm Index:\\$1\t\\n%\t"\\$2" .. -. nr % 0 -. rr F -.\} -.el \{\ -. de IX -.. +. if !\nF==2 \{\ +. nr % 0 +. nr F 2 +. \} .\} .\" .\" Accent mark definitions (@(#)ms.acc 1.5 88/02/08 SMI; from UCB 4.2). @@ -124,7 +129,7 @@ .\" ======================================================================== .\" .IX Title "GEOIDEVAL 1" -.TH GEOIDEVAL 1 "2014-03-13" "GeographicLib 1.35" "GeographicLib Utilities" +.TH GEOIDEVAL 1 "2017-10-05" "GeographicLib 1.49" "GeographicLib Utilities" .\" For nroff, turn off justification. Always turn off hyphenation; it makes .\" way too many mistakes in technical documents. .if n .ad l @@ -134,7 +139,7 @@ GeoidEval \-\- look up geoid heights .SH "SYNOPSIS" .IX Header "SYNOPSIS" \&\fBGeoidEval\fR [ \fB\-n\fR \fIname\fR ] [ \fB\-d\fR \fIdir\fR ] [ \fB\-l\fR ] -[ \fB\-a\fR | \fB\-c\fR \fIsouth\fR \fIwest\fR \fInorth\fR \fIeast\fR ] [ \fB\-g\fR ] +[ \fB\-a\fR | \fB\-c\fR \fIsouth\fR \fIwest\fR \fInorth\fR \fIeast\fR ] [ \fB\-w\fR ] [ \fB\-z\fR \fIzone\fR ] [ \fB\-\-msltohae\fR ] [ \fB\-\-haetomsl\fR ] [ \fB\-v\fR ] [ \fB\-\-comment\-delimiter\fR \fIcommentdelim\fR ] @@ -145,10 +150,10 @@ GeoidEval \-\- look up geoid heights .SH "DESCRIPTION" .IX Header "DESCRIPTION" \&\fBGeoidEval\fR reads in positions on standard input and prints out the -corresponding geoid heights on standard output. Optionally, it also -prints the northerly and easterly gradients of the geoid height. +corresponding heights of the geoid above the \s-1WGS84\s0 ellipsoid on standard +output. .PP -Positions are given as latitude and longitude, \s-1UTM/UPS\s0, or \s-1MGRS\s0, in any +Positions are given as latitude and longitude, \s-1UTM/UPS,\s0 or \s-1MGRS,\s0 in any of the formats accepted by \fIGeoConvert\fR\|(1). (\s-1MGRS\s0 coordinates signify the \&\fIcenter\fR of the corresponding \s-1MGRS\s0 square.) If the \fB\-z\fR option is specified then the specified zone is prepended to each line of input @@ -157,38 +162,48 @@ eastings and northings in a single zone to be used as standard input. .PP More accurate results for the geoid height are provided by \fIGravity\fR\|(1). This utility can also compute the direction of gravity accurately. +.PP +The height of the geoid above the ellipsoid, \fIN\fR, is sometimes called +the geoid undulation. It can be used to convert a height above the +ellipsoid, \fIh\fR, to the corresponding height above the geoid (the +orthometric height, roughly the height above mean sea level), \fIH\fR, +using the relations +.Sp +.RS 4 +\&\fIh\fR = \fIN\fR + \fIH\fR, \ \ \fIH\fR = \-\fIN\fR + \fIh\fR. +.RE .SH "OPTIONS" .IX Header "OPTIONS" -.IP "\fB\-n\fR" 4 -.IX Item "-n" +.IP "\fB\-n\fR \fIname\fR" 4 +.IX Item "-n name" use geoid \fIname\fR instead of the default \f(CW\*(C`egm96\-5\*(C'\fR. See -\&\*(L"\s-1GEOIDS\s0\*(R". -.IP "\fB\-d\fR" 4 -.IX Item "-d" +\&\*(L"\s-1GEOIDS\*(R"\s0. +.IP "\fB\-d\fR \fIdir\fR" 4 +.IX Item "-d dir" read geoid data from \fIdir\fR instead of the default. See -\&\*(L"\s-1GEOIDS\s0\*(R". +\&\*(L"\s-1GEOIDS\*(R"\s0. .IP "\fB\-l\fR" 4 .IX Item "-l" use bilinear interpolation instead of cubic. See -\&\*(L"\s-1INTERPOLATION\s0\*(R". +\&\*(L"\s-1INTERPOLATION\*(R"\s0. .IP "\fB\-a\fR" 4 .IX Item "-a" -cache the entire data set in memory. See \*(L"\s-1CACHE\s0\*(R". -.IP "\fB\-c\fR" 4 -.IX Item "-c" +cache the entire data set in memory. See \*(L"\s-1CACHE\*(R"\s0. +.IP "\fB\-c\fR \fIsouth\fR \fIwest\fR \fInorth\fR \fIeast\fR" 4 +.IX Item "-c south west north east" cache the data bounded by \fIsouth\fR \fIwest\fR \fInorth\fR \fIeast\fR in memory. -See \*(L"\s-1CACHE\s0\*(R". -.IP "\fB\-g\fR" 4 -.IX Item "-g" -print the northerly and easterly gradients after the geoid height (i.e., -the rate at which the geoid height changes per unit distance along the -\&\s-1WGS84\s0 ellipsoid in the specified directions). As a result of the way -that the geoid data is stored, the calculation of gradients can result -in large quantization errors. This is particularly acute at high -latitudes and for the easterly gradient. -.IP "\fB\-z\fR" 4 -.IX Item "-z" -prefix each line of input by \fIzone\fR, e.g., \f(CW\*(C`38N\*(C'\fR. This should be used +The first two arguments specify the \s-1SW\s0 corner of the cache and the last +two arguments specify the \s-1NE\s0 corner. The \fB\-w\fR flag specifies that +longitude precedes latitude for these corners, provided that it appears +before \fB\-c\fR. See \*(L"\s-1CACHE\*(R"\s0. +.IP "\fB\-w\fR" 4 +.IX Item "-w" +toggle the longitude first flag (it starts off); if the flag is on, then +when reading geographic coordinates, longitude precedes latitude (this +can be overridden by a hemisphere designator, \fIN\fR, \fIS\fR, \fIE\fR, \fIW\fR). +.IP "\fB\-z\fR \fIzone\fR" 4 +.IX Item "-z zone" +prefix each line of input by \fIzone\fR, e.g., \f(CW\*(C`38n\*(C'\fR. This should be used when the input consists of \s-1UTM/UPS\s0 eastings and northings. .IP "\fB\-\-msltohae\fR" 4 .IX Item "--msltohae" @@ -207,8 +222,8 @@ input line with the height converted to height above the geoid (\s-1MSL\s0). .IX Item "-v" print information about the geoid on standard error before processing the input. -.IP "\fB\-\-comment\-delimiter\fR" 4 -.IX Item "--comment-delimiter" +.IP "\fB\-\-comment\-delimiter\fR \fIcommentdelim\fR" 4 +.IX Item "--comment-delimiter commentdelim" set the comment delimiter to \fIcommentdelim\fR (e.g., \*(L"#\*(R" or \*(L"//\*(R"). If set, the input lines will be scanned for this delimiter and, if found, the delimiter and the rest of the line will be removed prior to @@ -223,27 +238,27 @@ print usage, the default geoid path and name, and exit. .IP "\fB\-\-help\fR" 4 .IX Item "--help" print full documentation and exit. -.IP "\fB\-\-input\-file\fR" 4 -.IX Item "--input-file" +.IP "\fB\-\-input\-file\fR \fIinfile\fR" 4 +.IX Item "--input-file infile" read input from the file \fIinfile\fR instead of from standard input; a file name of \*(L"\-\*(R" stands for standard input. -.IP "\fB\-\-input\-string\fR" 4 -.IX Item "--input-string" +.IP "\fB\-\-input\-string\fR \fIinstring\fR" 4 +.IX Item "--input-string instring" read input from the string \fIinstring\fR instead of from standard input. All occurrences of the line separator character (default is a semicolon) in \fIinstring\fR are converted to newlines before the reading begins. -.IP "\fB\-\-line\-separator\fR" 4 -.IX Item "--line-separator" +.IP "\fB\-\-line\-separator\fR \fIlinesep\fR" 4 +.IX Item "--line-separator linesep" set the line separator character to \fIlinesep\fR. By default this is a semicolon. -.IP "\fB\-\-output\-file\fR" 4 -.IX Item "--output-file" +.IP "\fB\-\-output\-file\fR \fIoutfile\fR" 4 +.IX Item "--output-file outfile" write output to the file \fIoutfile\fR instead of to standard output; a file name of \*(L"\-\*(R" stands for standard output. .SH "GEOIDS" .IX Header "GEOIDS" \&\fBGeoidEval\fR computes geoid heights by interpolating on the data in a -regularly spaced table (see \*(L"\s-1INTERPOLATION\s0\*(R"). The following geoid +regularly spaced table (see \*(L"\s-1INTERPOLATION\*(R"\s0). The following geoid tables are available (however, some may not be installed): .PP .Vb 9 @@ -259,18 +274,19 @@ tables are available (however, some may not be installed): .Ve .PP By default, the \f(CW\*(C`egm96\-5\*(C'\fR geoid is used. This may changed by setting -the environment variable \f(CW\*(C`GEOID_NAME\*(C'\fR or with the \fB\-n\fR option. The -errors listed here are estimates of the quantization and interpolation -errors in the reported heights compared to the specified geoid. +the environment variable \f(CW\*(C`GEOGRAPHICLIB_GEOID_NAME\*(C'\fR or with the \fB\-n\fR +option. The errors listed here are estimates of the quantization and +interpolation errors in the reported heights compared to the specified +geoid. .PP The geoid data will be loaded from a directory specified at compile time. This may changed by setting the environment variables -\&\f(CW\*(C`GEOID_PATH\*(C'\fR or \f(CW\*(C`GEOGRAPHICLIB_DATA\*(C'\fR, or with the \fB\-d\fR option. The -\&\fB\-h\fR option prints the default geoid path and name. Use the \fB\-v\fR -option to ascertain the full path name of the data file. +\&\f(CW\*(C`GEOGRAPHICLIB_GEOID_PATH\*(C'\fR or \f(CW\*(C`GEOGRAPHICLIB_DATA\*(C'\fR, or with the \fB\-d\fR +option. The \fB\-h\fR option prints the default geoid path and name. Use +the \fB\-v\fR option to ascertain the full path name of the data file. .PP Instructions for downloading and installing geoid data are available at -. +. .PP \&\fB\s-1NOTE\s0\fR: all the geoids above apply to the \s-1WGS84\s0 ellipsoid (\fIa\fR = 6378137 m, \fIf\fR = 1/298.257223563) only. @@ -291,8 +307,7 @@ interpolation is based on a least-squares fit of a cubic polynomial to a The cubic is constrained to be independent of longitude when evaluating the height at one of the poles. Cubic interpolation is considerably more accurate than bilinear; however it results in small discontinuities -in the returned height on cell boundaries. The gradients are computed -by differentiating the interpolated results. +in the returned height on cell boundaries. .SH "CACHE" .IX Header "CACHE" By default, the data file is randomly read to compute the geoid heights @@ -301,7 +316,7 @@ If many heights are to be computed, use \fB\-c\fR \fIsouth\fR \fIwest\fR \fInort \&\fIeast\fR to notify \fBGeoidEval\fR to read a rectangle of data into memory; heights within the this rectangle can then be computed without any disk access. If \fB\-a\fR is specified all the geoid data is read; in the case -of \f(CW\*(C`egm2008\-1\*(C'\fR, this requires about 0.5 \s-1GB\s0 of \s-1RAM\s0. The evaluation of +of \f(CW\*(C`egm2008\-1\*(C'\fR, this requires about 0.5 \s-1GB\s0 of \s-1RAM.\s0 The evaluation of heights outside the cached area causes the necessary data to be read from disk. Use the \fB\-v\fR option to verify the size of the cache. .PP @@ -311,26 +326,25 @@ the geoid height along a continuous path to be returned with little disk overhead. .SH "ENVIRONMENT" .IX Header "ENVIRONMENT" -.IP "\fB\s-1GEOID_NAME\s0\fR" 4 -.IX Item "GEOID_NAME" +.IP "\fB\s-1GEOGRAPHICLIB_GEOID_NAME\s0\fR" 4 +.IX Item "GEOGRAPHICLIB_GEOID_NAME" Override the compile-time default geoid name of \f(CW\*(C`egm96\-5\*(C'\fR. The \fB\-h\fR -option reports the value of \fB\s-1GEOID_NAME\s0\fR, if defined, otherwise it -reports the compile-time value. If the \fB\-n\fR \fIname\fR option is used, -then \fIname\fR takes precedence. -.IP "\fB\s-1GEOID_PATH\s0\fR" 4 -.IX Item "GEOID_PATH" +option reports the value of \fB\s-1GEOGRAPHICLIB_GEOID_NAME\s0\fR, if defined, +otherwise it reports the compile-time value. If the \fB\-n\fR \fIname\fR +option is used, then \fIname\fR takes precedence. +.IP "\fB\s-1GEOGRAPHICLIB_GEOID_PATH\s0\fR" 4 +.IX Item "GEOGRAPHICLIB_GEOID_PATH" Override the compile-time default geoid path. This is typically \&\f(CW\*(C`/usr/local/share/GeographicLib/geoids\*(C'\fR on Unix-like systems and -\&\f(CW\*(C`C:/Documents and Settings/All Users/Application -Data/GeographicLib/geoids\*(C'\fR on Windows systems. The \fB\-h\fR option reports -the value of \fB\s-1GEOID_PATH\s0\fR, if defined, otherwise it reports the -compile-time value. If the \fB\-d\fR \fIdir\fR option is used, then \fIdir\fR -takes precedence. +\&\f(CW\*(C`C:/ProgramData/GeographicLib/geoids\*(C'\fR on Windows systems. The \fB\-h\fR +option reports the value of \fB\s-1GEOGRAPHICLIB_GEOID_PATH\s0\fR, if defined, +otherwise it reports the compile-time value. If the \fB\-d\fR \fIdir\fR option +is used, then \fIdir\fR takes precedence. .IP "\fB\s-1GEOGRAPHICLIB_DATA\s0\fR" 4 .IX Item "GEOGRAPHICLIB_DATA" -Another way of overriding the compile-time default magnetic path. If it -is set (and if \fB\s-1MAGNETIC_PATH\s0\fR is not set), then -$\fB\s-1GEOGRAPHICLIB_DATA\s0\fR/magnetic is used. +Another way of overriding the compile-time default geoid path. If it +is set (and if \fB\s-1GEOGRAPHICLIB_GEOID_PATH\s0\fR is not set), then +$\fB\s-1GEOGRAPHICLIB_DATA\s0\fR/geoids is used. .SH "ERRORS" .IX Header "ERRORS" An illegal line of input will print an error message to standard output @@ -344,19 +358,19 @@ models published by the \s-1NGA\s0 are: .IP "\fB\s-1EGM84\s0\fR" 4 .IX Item "EGM84" An earth gravity model published by the \s-1NGA\s0 in 1984, -http://earth\-info.nga.mil/GandG/wgs84/gravitymod/wgs84_180/wgs84_180.html . +. .IP "\fB\s-1EGM96\s0\fR" 4 .IX Item "EGM96" An earth gravity model published by the \s-1NGA\s0 in 1996, -http://earth\-info.nga.mil/GandG/wgs84/gravitymod/egm96/egm96.html . +. .IP "\fB\s-1EGM2008\s0\fR" 4 .IX Item "EGM2008" An earth gravity model published by the \s-1NGA\s0 in 2008, -http://earth\-info.nga.mil/GandG/wgs84/gravitymod/egm2008 . +. .IP "\fB\s-1WGS84\s0\fR" 4 .IX Item "WGS84" World Geodetic System 1984, -. +. .IP "\fB\s-1HAE\s0\fR" 4 .IX Item "HAE" Height above the \s-1WGS84\s0 ellipsoid. @@ -377,19 +391,22 @@ The height of the \s-1EGM96\s0 geoid at Timbuktu The first number returned is the height of the geoid and the 2nd and 3rd are its slopes in the northerly and easterly directions. .PP -Convert a point in \s-1UTM\s0 zone 18N from \s-1MSL\s0 to \s-1HAE\s0 +Convert a point in \s-1UTM\s0 zone 18n from \s-1MSL\s0 to \s-1HAE\s0 .PP .Vb 2 -\& echo 531595 4468135 23 | GeoidEval \-\-msltohae \-z 18N +\& echo 531595 4468135 23 | GeoidEval \-\-msltohae \-z 18n \& => 531595 4468135 \-10.842 .Ve .SH "SEE ALSO" .IX Header "SEE ALSO" -\&\fIGeoConvert\fR\|(1), \fIGravity\fR\|(1). +\&\fIGeoConvert\fR\|(1), \fIGravity\fR\|(1), \fIgeographiclib\-get\-geoids\fR\|(8). +.PP +An online version of this utility is availbable at +. .SH "AUTHOR" .IX Header "AUTHOR" \&\fBGeoidEval\fR was written by Charles Karney. .SH "HISTORY" .IX Header "HISTORY" -\&\fBGeoidEval\fR was added to GeographicLib, , -in 2009\-09. +\&\fBGeoidEval\fR was added to GeographicLib, +, in 2009\-09. diff --git a/gtsam/3rdparty/GeographicLib/man/GeoidEval.1.html b/gtsam/3rdparty/GeographicLib/man/GeoidEval.1.html index ea131d8a7..58eb4d63a 100644 --- a/gtsam/3rdparty/GeographicLib/man/GeoidEval.1.html +++ b/gtsam/3rdparty/GeographicLib/man/GeoidEval.1.html @@ -7,7 +7,7 @@ - + @@ -17,27 +17,35 @@

    SYNOPSIS

    -

    GeoidEval [ -n name ] [ -d dir ] [ -l ] [ -a | -c south west north east ] [ -g ] [ -z zone ] [ --msltohae ] [ --haetomsl ] [ -v ] [ --comment-delimiter commentdelim ] [ --version | -h | --help ] [ --input-file infile | --input-string instring ] [ --line-separator linesep ] [ --output-file outfile ]

    +

    GeoidEval [ -n name ] [ -d dir ] [ -l ] [ -a | -c south west north east ] [ -w ] [ -z zone ] [ --msltohae ] [ --haetomsl ] [ -v ] [ --comment-delimiter commentdelim ] [ --version | -h | --help ] [ --input-file infile | --input-string instring ] [ --line-separator linesep ] [ --output-file outfile ]

    DESCRIPTION

    -

    GeoidEval reads in positions on standard input and prints out the corresponding geoid heights on standard output. Optionally, it also prints the northerly and easterly gradients of the geoid height.

    +

    GeoidEval reads in positions on standard input and prints out the corresponding heights of the geoid above the WGS84 ellipsoid on standard output.

    Positions are given as latitude and longitude, UTM/UPS, or MGRS, in any of the formats accepted by GeoConvert(1). (MGRS coordinates signify the center of the corresponding MGRS square.) If the -z option is specified then the specified zone is prepended to each line of input (which must be in UTM/UPS coordinates). This allows a file with UTM eastings and northings in a single zone to be used as standard input.

    More accurate results for the geoid height are provided by Gravity(1). This utility can also compute the direction of gravity accurately.

    +

    The height of the geoid above the ellipsoid, N, is sometimes called the geoid undulation. It can be used to convert a height above the ellipsoid, h, to the corresponding height above the geoid (the orthometric height, roughly the height above mean sea level), H, using the relations

    + +
      + +

      h = N + H,   H = -N + h.

      + +
    +

    OPTIONS

    -
    -n
    +
    -n name

    use geoid name instead of the default egm96-5. See "GEOIDS".

    -
    -d
    +
    -d dir

    read geoid data from dir instead of the default. See "GEOIDS".

    @@ -55,22 +63,22 @@

    cache the entire data set in memory. See "CACHE".

    -
    -c
    +
    -c south west north east
    -

    cache the data bounded by south west north east in memory. See "CACHE".

    +

    cache the data bounded by south west north east in memory. The first two arguments specify the SW corner of the cache and the last two arguments specify the NE corner. The -w flag specifies that longitude precedes latitude for these corners, provided that it appears before -c. See "CACHE".

    -
    -g
    +
    -w
    -

    print the northerly and easterly gradients after the geoid height (i.e., the rate at which the geoid height changes per unit distance along the WGS84 ellipsoid in the specified directions). As a result of the way that the geoid data is stored, the calculation of gradients can result in large quantization errors. This is particularly acute at high latitudes and for the easterly gradient.

    +

    toggle the longitude first flag (it starts off); if the flag is on, then when reading geographic coordinates, longitude precedes latitude (this can be overridden by a hemisphere designator, N, S, E, W).

    -
    -z
    +
    -z zone
    -

    prefix each line of input by zone, e.g., 38N. This should be used when the input consists of UTM/UPS eastings and northings.

    +

    prefix each line of input by zone, e.g., 38n. This should be used when the input consists of UTM/UPS eastings and northings.

    --msltohae
    @@ -91,7 +99,7 @@

    print information about the geoid on standard error before processing the input.

    -
    --comment-delimiter
    +
    --comment-delimiter commentdelim

    set the comment delimiter to commentdelim (e.g., "#" or "//"). If set, the input lines will be scanned for this delimiter and, if found, the delimiter and the rest of the line will be removed prior to processing and subsequently appended to the output line (separated by a space).

    @@ -115,25 +123,25 @@

    print full documentation and exit.

    -
    --input-file
    +
    --input-file infile

    read input from the file infile instead of from standard input; a file name of "-" stands for standard input.

    -
    --input-string
    +
    --input-string instring

    read input from the string instring instead of from standard input. All occurrences of the line separator character (default is a semicolon) in instring are converted to newlines before the reading begins.

    -
    --line-separator
    +
    --line-separator linesep

    set the line separator character to linesep. By default this is a semicolon.

    -
    --output-file
    +
    --output-file outfile

    write output to the file outfile instead of to standard output; a file name of "-" stands for standard output.

    @@ -155,11 +163,11 @@ egm2008-2_5 EGM2008 2.5' 0.135 m 3.2 mm 0.031 m 0.8 mm egm2008-1 EGM2008 1' 0.025 m 0.8 mm .0022 m 0.7 mm
    -

    arc mode; on input and output s12 is replaced by a12 the arc length (in degrees) on the auxiliary sphere. See "AUXILIARY SPHERE".

    +

    toggle the arc mode flag (it starts off); if this flag is on, then on input and output s12 is replaced by a12 the arc length (in degrees) on the auxiliary sphere. See "AUXILIARY SPHERE".

    -

    By default, the egm96-5 geoid is used. This may changed by setting the environment variable GEOID_NAME or with the -n option. The errors listed here are estimates of the quantization and interpolation errors in the reported heights compared to the specified geoid.

    +

    By default, the egm96-5 geoid is used. This may changed by setting the environment variable GEOGRAPHICLIB_GEOID_NAME or with the -n option. The errors listed here are estimates of the quantization and interpolation errors in the reported heights compared to the specified geoid.

    -

    The geoid data will be loaded from a directory specified at compile time. This may changed by setting the environment variables GEOID_PATH or GEOGRAPHICLIB_DATA, or with the -d option. The -h option prints the default geoid path and name. Use the -v option to ascertain the full path name of the data file.

    +

    The geoid data will be loaded from a directory specified at compile time. This may changed by setting the environment variables GEOGRAPHICLIB_GEOID_PATH or GEOGRAPHICLIB_DATA, or with the -d option. The -h option prints the default geoid path and name. Use the -v option to ascertain the full path name of the data file.

    -

    Instructions for downloading and installing geoid data are available at http://geographiclib.sf.net/html/geoid.html#geoidinst.

    +

    Instructions for downloading and installing geoid data are available at https://geographiclib.sourceforge.io/html/geoid.html#geoidinst.

    NOTE: all the geoids above apply to the WGS84 ellipsoid (a = 6378137 m, f = 1/298.257223563) only.

    @@ -172,7 +180,7 @@ 1 2 2 1 . 1 1 .
    -

    The cubic is constrained to be independent of longitude when evaluating the height at one of the poles. Cubic interpolation is considerably more accurate than bilinear; however it results in small discontinuities in the returned height on cell boundaries. The gradients are computed by differentiating the interpolated results.

    +

    The cubic is constrained to be independent of longitude when evaluating the height at one of the poles. Cubic interpolation is considerably more accurate than bilinear; however it results in small discontinuities in the returned height on cell boundaries.

    CACHE

    @@ -184,22 +192,22 @@
    -
    GEOID_NAME
    +
    GEOGRAPHICLIB_GEOID_NAME
    -

    Override the compile-time default geoid name of egm96-5. The -h option reports the value of GEOID_NAME, if defined, otherwise it reports the compile-time value. If the -n name option is used, then name takes precedence.

    +

    Override the compile-time default geoid name of egm96-5. The -h option reports the value of GEOGRAPHICLIB_GEOID_NAME, if defined, otherwise it reports the compile-time value. If the -n name option is used, then name takes precedence.

    -
    GEOID_PATH
    +
    GEOGRAPHICLIB_GEOID_PATH
    -

    Override the compile-time default geoid path. This is typically /usr/local/share/GeographicLib/geoids on Unix-like systems and C:/Documents and Settings/All Users/Application Data/GeographicLib/geoids on Windows systems. The -h option reports the value of GEOID_PATH, if defined, otherwise it reports the compile-time value. If the -d dir option is used, then dir takes precedence.

    +

    Override the compile-time default geoid path. This is typically /usr/local/share/GeographicLib/geoids on Unix-like systems and C:/ProgramData/GeographicLib/geoids on Windows systems. The -h option reports the value of GEOGRAPHICLIB_GEOID_PATH, if defined, otherwise it reports the compile-time value. If the -d dir option is used, then dir takes precedence.

    GEOGRAPHICLIB_DATA
    -

    Another way of overriding the compile-time default magnetic path. If it is set (and if MAGNETIC_PATH is not set), then $GEOGRAPHICLIB_DATA/magnetic is used.

    +

    Another way of overriding the compile-time default geoid path. If it is set (and if GEOGRAPHICLIB_GEOID_PATH is not set), then $GEOGRAPHICLIB_DATA/geoids is used.

    @@ -235,7 +243,7 @@
    WGS84
    -

    World Geodetic System 1984, http://en.wikipedia.org/wiki/WGS84.

    +

    World Geodetic System 1984, https://en.wikipedia.org/wiki/WGS84.

    HAE
    @@ -261,14 +269,16 @@

    The first number returned is the height of the geoid and the 2nd and 3rd are its slopes in the northerly and easterly directions.

    -

    Convert a point in UTM zone 18N from MSL to HAE

    +

    Convert a point in UTM zone 18n from MSL to HAE

    -
       echo 531595 4468135 23 | GeoidEval --msltohae -z 18N
    +
       echo 531595 4468135 23 | GeoidEval --msltohae -z 18n
        => 531595 4468135 -10.842

    SEE ALSO

    -

    GeoConvert(1), Gravity(1).

    +

    GeoConvert(1), Gravity(1), geographiclib-get-geoids(8).

    + +

    An online version of this utility is availbable at https://geographiclib.sourceforge.io/cgi-bin/GeoidEval.

    AUTHOR

    @@ -276,7 +286,7 @@

    HISTORY

    -

    GeoidEval was added to GeographicLib, http://geographiclib.sf.net, in 2009-09.

    +

    GeoidEval was added to GeographicLib, https://geographiclib.sourceforge.io, in 2009-09.

    diff --git a/gtsam/3rdparty/GeographicLib/man/GeoidEval.pod b/gtsam/3rdparty/GeographicLib/man/GeoidEval.pod index c6ca929fc..1e4529557 100644 --- a/gtsam/3rdparty/GeographicLib/man/GeoidEval.pod +++ b/gtsam/3rdparty/GeographicLib/man/GeoidEval.pod @@ -5,7 +5,7 @@ GeoidEval -- look up geoid heights =head1 SYNOPSIS B [ B<-n> I ] [ B<-d> I
    ] [ B<-l> ] -[ B<-a> | B<-c> I I I I ] [ B<-g> ] +[ B<-a> | B<-c> I I I I ] [ B<-w> ] [ B<-z> I ] [ B<--msltohae> ] [ B<--haetomsl> ] [ B<-v> ] [ B<--comment-delimiter> I ] @@ -17,8 +17,8 @@ B [ B<-n> I ] [ B<-d> I ] [ B<-l> ] =head1 DESCRIPTION B reads in positions on standard input and prints out the -corresponding geoid heights on standard output. Optionally, it also -prints the northerly and easterly gradients of the geoid height. +corresponding heights of the geoid above the WGS84 ellipsoid on standard +output. Positions are given as latitude and longitude, UTM/UPS, or MGRS, in any of the formats accepted by GeoConvert(1). (MGRS coordinates signify the @@ -30,16 +30,28 @@ eastings and northings in a single zone to be used as standard input. More accurate results for the geoid height are provided by Gravity(1). This utility can also compute the direction of gravity accurately. +The height of the geoid above the ellipsoid, I, is sometimes called +the geoid undulation. It can be used to convert a height above the +ellipsoid, I, to the corresponding height above the geoid (the +orthometric height, roughly the height above mean sea level), I, +using the relations + +=over + +I = I + I, EEI = -I + I. + +=back + =head1 OPTIONS =over -=item B<-n> +=item B<-n> I use geoid I instead of the default C. See L. -=item B<-d> +=item B<-d> I read geoid data from I instead of the default. See L. @@ -53,23 +65,23 @@ L. cache the entire data set in memory. See L. -=item B<-c> +=item B<-c> I I I I cache the data bounded by I I I I in memory. -See L. +The first two arguments specify the SW corner of the cache and the last +two arguments specify the NE corner. The B<-w> flag specifies that +longitude precedes latitude for these corners, provided that it appears +before B<-c>. See L. -=item B<-g> +=item B<-w> -print the northerly and easterly gradients after the geoid height (i.e., -the rate at which the geoid height changes per unit distance along the -WGS84 ellipsoid in the specified directions). As a result of the way -that the geoid data is stored, the calculation of gradients can result -in large quantization errors. This is particularly acute at high -latitudes and for the easterly gradient. +toggle the longitude first flag (it starts off); if the flag is on, then +when reading geographic coordinates, longitude precedes latitude (this +can be overridden by a hemisphere designator, I, I, I, I). -=item B<-z> +=item B<-z> I -prefix each line of input by I, e.g., C<38N>. This should be used +prefix each line of input by I, e.g., C<38n>. This should be used when the input consists of UTM/UPS eastings and northings. =item B<--msltohae> @@ -92,7 +104,7 @@ input line with the height converted to height above the geoid (MSL). print information about the geoid on standard error before processing the input. -=item B<--comment-delimiter> +=item B<--comment-delimiter> I set the comment delimiter to I (e.g., "#" or "//"). If set, the input lines will be scanned for this delimiter and, if found, @@ -112,23 +124,23 @@ print usage, the default geoid path and name, and exit. print full documentation and exit. -=item B<--input-file> +=item B<--input-file> I read input from the file I instead of from standard input; a file name of "-" stands for standard input. -=item B<--input-string> +=item B<--input-string> I read input from the string I instead of from standard input. All occurrences of the line separator character (default is a semicolon) in I are converted to newlines before the reading begins. -=item B<--line-separator> +=item B<--line-separator> I set the line separator character to I. By default this is a semicolon. -=item B<--output-file> +=item B<--output-file> I write output to the file I instead of to standard output; a file name of "-" stands for standard output. @@ -152,18 +164,19 @@ tables are available (however, some may not be installed): egm2008-1 EGM2008 1' 0.025 m 0.8 mm .0022 m 0.7 mm By default, the C geoid is used. This may changed by setting -the environment variable C or with the B<-n> option. The -errors listed here are estimates of the quantization and interpolation -errors in the reported heights compared to the specified geoid. +the environment variable C or with the B<-n> +option. The errors listed here are estimates of the quantization and +interpolation errors in the reported heights compared to the specified +geoid. The geoid data will be loaded from a directory specified at compile time. This may changed by setting the environment variables -C or C, or with the B<-d> option. The -B<-h> option prints the default geoid path and name. Use the B<-v> -option to ascertain the full path name of the data file. +C or C, or with the B<-d> +option. The B<-h> option prints the default geoid path and name. Use +the B<-v> option to ascertain the full path name of the data file. Instructions for downloading and installing geoid data are available at -L. +L. B: all the geoids above apply to the WGS84 ellipsoid (I = 6378137 m, I = 1/298.257223563) only. @@ -183,8 +196,7 @@ interpolation is based on a least-squares fit of a cubic polynomial to a The cubic is constrained to be independent of longitude when evaluating the height at one of the poles. Cubic interpolation is considerably more accurate than bilinear; however it results in small discontinuities -in the returned height on cell boundaries. The gradients are computed -by differentiating the interpolated results. +in the returned height on cell boundaries. =head1 CACHE @@ -207,28 +219,27 @@ disk overhead. =over -=item B +=item B Override the compile-time default geoid name of C. The B<-h> -option reports the value of B, if defined, otherwise it -reports the compile-time value. If the B<-n> I option is used, -then I takes precedence. +option reports the value of B, if defined, +otherwise it reports the compile-time value. If the B<-n> I +option is used, then I takes precedence. -=item B +=item B Override the compile-time default geoid path. This is typically C on Unix-like systems and -C on Windows systems. The B<-h> option reports -the value of B, if defined, otherwise it reports the -compile-time value. If the B<-d> I option is used, then I -takes precedence. +C on Windows systems. The B<-h> +option reports the value of B, if defined, +otherwise it reports the compile-time value. If the B<-d> I option +is used, then I takes precedence. =item B -Another way of overriding the compile-time default magnetic path. If it -is set (and if B is not set), then -$B/magnetic is used. +Another way of overriding the compile-time default geoid path. If it +is set (and if B is not set), then +$B/geoids is used. =back @@ -264,7 +275,7 @@ L. =item B World Geodetic System 1984, -L. +L. =item B @@ -288,14 +299,17 @@ The height of the EGM96 geoid at Timbuktu The first number returned is the height of the geoid and the 2nd and 3rd are its slopes in the northerly and easterly directions. -Convert a point in UTM zone 18N from MSL to HAE +Convert a point in UTM zone 18n from MSL to HAE - echo 531595 4468135 23 | GeoidEval --msltohae -z 18N + echo 531595 4468135 23 | GeoidEval --msltohae -z 18n => 531595 4468135 -10.842 =head1 SEE ALSO -GeoConvert(1), Gravity(1). +GeoConvert(1), Gravity(1), geographiclib-get-geoids(8). + +An online version of this utility is availbable at +L. =head1 AUTHOR @@ -303,5 +317,5 @@ B was written by Charles Karney. =head1 HISTORY -B was added to GeographicLib, L, -in 2009-09. +B was added to GeographicLib, +L, in 2009-09. diff --git a/gtsam/3rdparty/GeographicLib/man/GeoidEval.usage b/gtsam/3rdparty/GeographicLib/man/GeoidEval.usage index 4fa144ca7..49ba7398a 100644 --- a/gtsam/3rdparty/GeographicLib/man/GeoidEval.usage +++ b/gtsam/3rdparty/GeographicLib/man/GeoidEval.usage @@ -2,7 +2,7 @@ int usage(int retval, bool brief) { if (brief) ( retval ? std::cerr : std::cout ) << "Usage:\n" " GeoidEval [ -n name ] [ -d dir ] [ -l ] [ -a | -c south west north east\n" -" ] [ -g ] [ -z zone ] [ --msltohae ] [ --haetomsl ] [ -v ] [\n" +" ] [ -w ] [ -z zone ] [ --msltohae ] [ --haetomsl ] [ -v ] [\n" " --comment-delimiter commentdelim ] [ --version | -h | --help ] [\n" " --input-file infile | --input-string instring ] [ --line-separator\n" " linesep ] [ --output-file outfile ]\n" @@ -10,7 +10,7 @@ int usage(int retval, bool brief) { "For full documentation type:\n" " GeoidEval --help\n" "or visit:\n" -" http://geographiclib.sf.net/1.35/GeoidEval.1.html\n"; +" https://geographiclib.sourceforge.io/1.49/GeoidEval.1.html\n"; else ( retval ? std::cerr : std::cout ) << "Man page:\n" "NAME\n" @@ -18,15 +18,15 @@ int usage(int retval, bool brief) { "\n" "SYNOPSIS\n" " GeoidEval [ -n name ] [ -d dir ] [ -l ] [ -a | -c south west north east\n" -" ] [ -g ] [ -z zone ] [ --msltohae ] [ --haetomsl ] [ -v ] [\n" +" ] [ -w ] [ -z zone ] [ --msltohae ] [ --haetomsl ] [ -v ] [\n" " --comment-delimiter commentdelim ] [ --version | -h | --help ] [\n" " --input-file infile | --input-string instring ] [ --line-separator\n" " linesep ] [ --output-file outfile ]\n" "\n" "DESCRIPTION\n" " GeoidEval reads in positions on standard input and prints out the\n" -" corresponding geoid heights on standard output. Optionally, it also\n" -" prints the northerly and easterly gradients of the geoid height.\n" +" corresponding heights of the geoid above the WGS84 ellipsoid on\n" +" standard output.\n" "\n" " Positions are given as latitude and longitude, UTM/UPS, or MGRS, in any\n" " of the formats accepted by GeoConvert(1). (MGRS coordinates signify\n" @@ -38,26 +38,39 @@ int usage(int retval, bool brief) { " More accurate results for the geoid height are provided by Gravity(1).\n" " This utility can also compute the direction of gravity accurately.\n" "\n" -"OPTIONS\n" -" -n use geoid name instead of the default \"egm96-5\". See \"GEOIDS\".\n" +" The height of the geoid above the ellipsoid, N, is sometimes called the\n" +" geoid undulation. It can be used to convert a height above the\n" +" ellipsoid, h, to the corresponding height above the geoid (the\n" +" orthometric height, roughly the height above mean sea level), H, using\n" +" the relations\n" "\n" -" -d read geoid data from dir instead of the default. See \"GEOIDS\".\n" +" h = N + H, H = -N + h.\n" +"\n" +"OPTIONS\n" +" -n name\n" +" use geoid name instead of the default \"egm96-5\". See \"GEOIDS\".\n" +"\n" +" -d dir\n" +" read geoid data from dir instead of the default. See \"GEOIDS\".\n" "\n" " -l use bilinear interpolation instead of cubic. See \"INTERPOLATION\".\n" "\n" " -a cache the entire data set in memory. See \"CACHE\".\n" "\n" -" -c cache the data bounded by south west north east in memory. See\n" -" \"CACHE\".\n" +" -c south west north east\n" +" cache the data bounded by south west north east in memory. The\n" +" first two arguments specify the SW corner of the cache and the last\n" +" two arguments specify the NE corner. The -w flag specifies that\n" +" longitude precedes latitude for these corners, provided that it\n" +" appears before -c. See \"CACHE\".\n" "\n" -" -g print the northerly and easterly gradients after the geoid height\n" -" (i.e., the rate at which the geoid height changes per unit distance\n" -" along the WGS84 ellipsoid in the specified directions). As a\n" -" result of the way that the geoid data is stored, the calculation of\n" -" gradients can result in large quantization errors. This is\n" -" particularly acute at high latitudes and for the easterly gradient.\n" +" -w toggle the longitude first flag (it starts off); if the flag is on,\n" +" then when reading geographic coordinates, longitude precedes\n" +" latitude (this can be overridden by a hemisphere designator, N, S,\n" +" E, W).\n" "\n" -" -z prefix each line of input by zone, e.g., \"38N\". This should be\n" +" -z zone\n" +" prefix each line of input by zone, e.g., \"38n\". This should be\n" " used when the input consists of UTM/UPS eastings and northings.\n" "\n" " --msltohae\n" @@ -77,7 +90,7 @@ int usage(int retval, bool brief) { " -v print information about the geoid on standard error before\n" " processing the input.\n" "\n" -" --comment-delimiter\n" +" --comment-delimiter commentdelim\n" " set the comment delimiter to commentdelim (e.g., \"#\" or \"//\"). If\n" " set, the input lines will be scanned for this delimiter and, if\n" " found, the delimiter and the rest of the line will be removed prior\n" @@ -92,21 +105,21 @@ int usage(int retval, bool brief) { " --help\n" " print full documentation and exit.\n" "\n" -" --input-file\n" +" --input-file infile\n" " read input from the file infile instead of from standard input; a\n" " file name of \"-\" stands for standard input.\n" "\n" -" --input-string\n" +" --input-string instring\n" " read input from the string instring instead of from standard input.\n" " All occurrences of the line separator character (default is a\n" " semicolon) in instring are converted to newlines before the reading\n" " begins.\n" "\n" -" --line-separator\n" +" --line-separator linesep\n" " set the line separator character to linesep. By default this is a\n" " semicolon.\n" "\n" -" --output-file\n" +" --output-file outfile\n" " write output to the file outfile instead of to standard output; a\n" " file name of \"-\" stands for standard output.\n" "\n" @@ -126,18 +139,19 @@ int usage(int retval, bool brief) { " egm2008-1 EGM2008 1' 0.025 m 0.8 mm .0022 m 0.7 mm\n" "\n" " By default, the \"egm96-5\" geoid is used. This may changed by setting\n" -" the environment variable \"GEOID_NAME\" or with the -n option. The\n" -" errors listed here are estimates of the quantization and interpolation\n" -" errors in the reported heights compared to the specified geoid.\n" +" the environment variable \"GEOGRAPHICLIB_GEOID_NAME\" or with the -n\n" +" option. The errors listed here are estimates of the quantization and\n" +" interpolation errors in the reported heights compared to the specified\n" +" geoid.\n" "\n" " The geoid data will be loaded from a directory specified at compile\n" " time. This may changed by setting the environment variables\n" -" \"GEOID_PATH\" or \"GEOGRAPHICLIB_DATA\", or with the -d option. The -h\n" -" option prints the default geoid path and name. Use the -v option to\n" -" ascertain the full path name of the data file.\n" +" \"GEOGRAPHICLIB_GEOID_PATH\" or \"GEOGRAPHICLIB_DATA\", or with the -d\n" +" option. The -h option prints the default geoid path and name. Use the\n" +" -v option to ascertain the full path name of the data file.\n" "\n" " Instructions for downloading and installing geoid data are available at\n" -" .\n" +" .\n" "\n" " NOTE: all the geoids above apply to the WGS84 ellipsoid (a = 6378137 m,\n" " f = 1/298.257223563) only.\n" @@ -156,8 +170,7 @@ int usage(int retval, bool brief) { " The cubic is constrained to be independent of longitude when evaluating\n" " the height at one of the poles. Cubic interpolation is considerably\n" " more accurate than bilinear; however it results in small\n" -" discontinuities in the returned height on cell boundaries. The\n" -" gradients are computed by differentiating the interpolated results.\n" +" discontinuities in the returned height on cell boundaries.\n" "\n" "CACHE\n" " By default, the data file is randomly read to compute the geoid heights\n" @@ -176,25 +189,24 @@ int usage(int retval, bool brief) { " overhead.\n" "\n" "ENVIRONMENT\n" -" GEOID_NAME\n" +" GEOGRAPHICLIB_GEOID_NAME\n" " Override the compile-time default geoid name of \"egm96-5\". The -h\n" -" option reports the value of GEOID_NAME, if defined, otherwise it\n" -" reports the compile-time value. If the -n name option is used,\n" -" then name takes precedence.\n" +" option reports the value of GEOGRAPHICLIB_GEOID_NAME, if defined,\n" +" otherwise it reports the compile-time value. If the -n name option\n" +" is used, then name takes precedence.\n" "\n" -" GEOID_PATH\n" +" GEOGRAPHICLIB_GEOID_PATH\n" " Override the compile-time default geoid path. This is typically\n" " \"/usr/local/share/GeographicLib/geoids\" on Unix-like systems and\n" -" \"C:/Documents and Settings/All Users/Application\n" -" Data/GeographicLib/geoids\" on Windows systems. The -h option\n" -" reports the value of GEOID_PATH, if defined, otherwise it reports\n" -" the compile-time value. If the -d dir option is used, then dir\n" -" takes precedence.\n" +" \"C:/ProgramData/GeographicLib/geoids\" on Windows systems. The -h\n" +" option reports the value of GEOGRAPHICLIB_GEOID_PATH, if defined,\n" +" otherwise it reports the compile-time value. If the -d dir option\n" +" is used, then dir takes precedence.\n" "\n" " GEOGRAPHICLIB_DATA\n" -" Another way of overriding the compile-time default magnetic path.\n" -" If it is set (and if MAGNETIC_PATH is not set), then\n" -" $GEOGRAPHICLIB_DATA/magnetic is used.\n" +" Another way of overriding the compile-time default geoid path. If\n" +" it is set (and if GEOGRAPHICLIB_GEOID_PATH is not set), then\n" +" $GEOGRAPHICLIB_DATA/geoids is used.\n" "\n" "ERRORS\n" " An illegal line of input will print an error message to standard output\n" @@ -208,23 +220,18 @@ int usage(int retval, bool brief) { "\n" " EGM84\n" " An earth gravity model published by the NGA in 1984,\n" -" http://earth-info.nga.mil/GandG/wgs84/gravitymod/wgs84_180/wgs84_180.html\n" -" .\n" +" .\n" "\n" " EGM96\n" " An earth gravity model published by the NGA in 1996,\n" -" http://earth-info.nga.mil/GandG/wgs84/gravitymod/egm96/egm96.html\n" -" .\n" +" .\n" "\n" " EGM2008\n" " An earth gravity model published by the NGA in 2008,\n" -" http://earth-info.nga.mil/GandG/wgs84/gravitymod/egm2008\n" " .\n" "\n" " WGS84\n" -" World Geodetic System 1984, .\n" +" World Geodetic System 1984, .\n" "\n" " HAE Height above the WGS84 ellipsoid.\n" "\n" @@ -241,20 +248,23 @@ int usage(int retval, bool brief) { " The first number returned is the height of the geoid and the 2nd and\n" " 3rd are its slopes in the northerly and easterly directions.\n" "\n" -" Convert a point in UTM zone 18N from MSL to HAE\n" +" Convert a point in UTM zone 18n from MSL to HAE\n" "\n" -" echo 531595 4468135 23 | GeoidEval --msltohae -z 18N\n" +" echo 531595 4468135 23 | GeoidEval --msltohae -z 18n\n" " => 531595 4468135 -10.842\n" "\n" "SEE ALSO\n" -" GeoConvert(1), Gravity(1).\n" +" GeoConvert(1), Gravity(1), geographiclib-get-geoids(8).\n" +"\n" +" An online version of this utility is availbable at\n" +" .\n" "\n" "AUTHOR\n" " GeoidEval was written by Charles Karney.\n" "\n" "HISTORY\n" -" GeoidEval was added to GeographicLib, , in\n" -" 2009-09.\n" +" GeoidEval was added to GeographicLib,\n" +" , in 2009-09.\n" ; return retval; } diff --git a/gtsam/3rdparty/GeographicLib/man/Gravity.1 b/gtsam/3rdparty/GeographicLib/man/Gravity.1 index 96462b244..0d69dd01d 100644 --- a/gtsam/3rdparty/GeographicLib/man/Gravity.1 +++ b/gtsam/3rdparty/GeographicLib/man/Gravity.1 @@ -1,4 +1,4 @@ -.\" Automatically generated by Pod::Man 2.25 (Pod::Simple 3.20) +.\" Automatically generated by Pod::Man 4.09 (Pod::Simple 3.35) .\" .\" Standard preamble: .\" ======================================================================== @@ -38,26 +38,31 @@ . ds PI \(*p . ds L" `` . ds R" '' +. ds C` +. ds C' 'br\} .\" .\" Escape single quotes in literal strings from groff's Unicode transform. .ie \n(.g .ds Aq \(aq .el .ds Aq ' .\" -.\" If the F register is turned on, we'll generate index entries on stderr for +.\" If the F register is >0, we'll generate index entries on stderr for .\" titles (.TH), headers (.SH), subsections (.SS), items (.Ip), and index .\" entries marked with X<> in POD. Of course, you'll have to process the .\" output yourself in some meaningful fashion. -.ie \nF \{\ +.\" +.\" Avoid warning from groff about undefined register 'F'. +.de IX +.. +.if !\nF .nr F 0 +.if \nF>0 \{\ . de IX . tm Index:\\$1\t\\n%\t"\\$2" .. -. nr % 0 -. rr F -.\} -.el \{\ -. de IX -.. +. if !\nF==2 \{\ +. nr % 0 +. nr F 2 +. \} .\} .\" .\" Accent mark definitions (@(#)ms.acc 1.5 88/02/08 SMI; from UCB 4.2). @@ -124,7 +129,7 @@ .\" ======================================================================== .\" .IX Title "GRAVITY 1" -.TH GRAVITY 1 "2014-03-13" "GeographicLib 1.35" "GeographicLib Utilities" +.TH GRAVITY 1 "2017-10-05" "GeographicLib 1.49" "GeographicLib Utilities" .\" For nroff, turn off justification. Always turn off hyphenation; it makes .\" way too many mistakes in technical documents. .if n .ad l @@ -135,7 +140,7 @@ Gravity \-\- compute the earth's gravity field .IX Header "SYNOPSIS" \&\fBGravity\fR [ \fB\-n\fR \fIname\fR ] [ \fB\-d\fR \fIdir\fR ] [ \fB\-G\fR | \fB\-D\fR | \fB\-A\fR | \fB\-H\fR ] [ \fB\-c\fR \fIlat\fR \fIh\fR ] -[ \fB\-p\fR \fIprec\fR ] +[ \fB\-w\fR ] [ \fB\-p\fR \fIprec\fR ] [ \fB\-v\fR ] [ \fB\-\-comment\-delimiter\fR \fIcommentdelim\fR ] [ \fB\-\-version\fR | \fB\-h\fR | \fB\-\-help\fR ] @@ -149,27 +154,28 @@ gravitational field on standard output. .PP The input line is of the form \fIlat\fR \fIlon\fR \fIh\fR. \fIlat\fR and \fIlon\fR are the latitude and longitude expressed as decimal degrees or degrees, -minutes, and seconds; see \fIGeoConvert\fR\|(1) for details. \fIh\fR is the height -above the ellipsoid in meters; this quantity is optional and defaults to -0. Alternatively, the gravity field can be computed at various points -on a circle of latitude (constant \fIlat\fR and \fIh\fR) via the \fB\-c\fR option; -in this case only the longitude should be given on the input lines. The -quantities printed out are governed by the \fB\-G\fR (default), \fB\-D\fR, -\&\fB\-A\fR, or \fB\-H\fR options. +minutes, and seconds; for details on the allowed formats for latitude +and longitude, see the \f(CW\*(C`GEOGRAPHIC COORDINATES\*(C'\fR section of +\&\fIGeoConvert\fR\|(1). \fIh\fR is the height above the ellipsoid in meters; this +quantity is optional and defaults to 0. Alternatively, the gravity +field can be computed at various points on a circle of latitude +(constant \fIlat\fR and \fIh\fR) via the \fB\-c\fR option; in this case only the +longitude should be given on the input lines. The quantities printed +out are governed by the \fB\-G\fR (default), \fB\-D\fR, \fB\-A\fR, or \fB\-H\fR options. .PP -All the supported gravity models use \s-1WGS84\s0 as the reference ellipsoid -\&\fIa\fR = 6378137 m, \fIf\fR = 1/298.257223563, \fIomega\fR = 7292115e\-11 rad/s, -and \fI\s-1GM\s0\fR = 3986004.418e8 m^3/s^2. +All the supported gravity models, except for grs80, use \s-1WGS84\s0 as the +reference ellipsoid \fIa\fR = 6378137 m, \fIf\fR = 1/298.257223563, \fIomega\fR = +7292115e\-11 rad/s, and \fI\s-1GM\s0\fR = 3986004.418e8 m^3/s^2. .SH "OPTIONS" .IX Header "OPTIONS" -.IP "\fB\-n\fR" 4 -.IX Item "-n" +.IP "\fB\-n\fR \fIname\fR" 4 +.IX Item "-n name" use gravity field model \fIname\fR instead of the default \f(CW\*(C`egm96\*(C'\fR. See -\&\*(L"\s-1MODELS\s0\*(R". -.IP "\fB\-d\fR" 4 -.IX Item "-d" +\&\*(L"\s-1MODELS\*(R"\s0. +.IP "\fB\-d\fR \fIdir\fR" 4 +.IX Item "-d dir" read gravity models from \fIdir\fR instead of the default. See -\&\*(L"\s-1MODELS\s0\*(R". +\&\*(L"\s-1MODELS\*(R"\s0. .IP "\fB\-G\fR" 4 .IX Item "-G" compute the acceleration due to gravity (including the centrifugal @@ -205,14 +211,20 @@ match the results of the \s-1NGA\s0's synthesis programs. \fIGeoidEval\fR\|(1) compute geoid heights much more quickly by interpolating on a grid of precomputed results; however the results from \fIGeoidEval\fR\|(1) are only accurate to a few millimeters. -.IP "\fB\-c\fR" 4 -.IX Item "-c" +.IP "\fB\-c\fR \fIlat\fR \fIh\fR" 4 +.IX Item "-c lat h" evaluate the field on a circle of latitude given by \fIlat\fR and \fIh\fR instead of reading these quantities from the input lines. In this case, \&\fBGravity\fR can calculate the field considerably more quickly. If geoid heights are being computed (the \fB\-H\fR option), then \fIh\fR must be zero. -.IP "\fB\-p\fR" 4 -.IX Item "-p" +.IP "\fB\-w\fR" 4 +.IX Item "-w" +toggle the longitude first flag (it starts off); if the flag is on, then +on input and output, longitude precedes latitude (except that, on input, +this can be overridden by a hemisphere designator, \fIN\fR, \fIS\fR, \fIE\fR, +\&\fIW\fR). +.IP "\fB\-p\fR \fIprec\fR" 4 +.IX Item "-p prec" set the output precision to \fIprec\fR. By default \fIprec\fR is 5 for acceleration due to gravity, 3 for the gravity disturbance and anomaly, and 4 for the geoid height. @@ -220,8 +232,8 @@ and 4 for the geoid height. .IX Item "-v" print information about the gravity model on standard error before processing the input. -.IP "\fB\-\-comment\-delimiter\fR" 4 -.IX Item "--comment-delimiter" +.IP "\fB\-\-comment\-delimiter\fR \fIcommentdelim\fR" 4 +.IX Item "--comment-delimiter commentdelim" set the comment delimiter to \fIcommentdelim\fR (e.g., \*(L"#\*(R" or \*(L"//\*(R"). If set, the input lines will be scanned for this delimiter and, if found, the delimiter and the rest of the line will be removed prior to @@ -236,28 +248,28 @@ print usage, the default gravity path and name, and exit. .IP "\fB\-\-help\fR" 4 .IX Item "--help" print full documentation and exit. -.IP "\fB\-\-input\-file\fR" 4 -.IX Item "--input-file" +.IP "\fB\-\-input\-file\fR \fIinfile\fR" 4 +.IX Item "--input-file infile" read input from the file \fIinfile\fR instead of from standard input; a file name of \*(L"\-\*(R" stands for standard input. -.IP "\fB\-\-input\-string\fR" 4 -.IX Item "--input-string" +.IP "\fB\-\-input\-string\fR \fIinstring\fR" 4 +.IX Item "--input-string instring" read input from the string \fIinstring\fR instead of from standard input. All occurrences of the line separator character (default is a semicolon) in \fIinstring\fR are converted to newlines before the reading begins. -.IP "\fB\-\-line\-separator\fR" 4 -.IX Item "--line-separator" +.IP "\fB\-\-line\-separator\fR \fIlinesep\fR" 4 +.IX Item "--line-separator linesep" set the line separator character to \fIlinesep\fR. By default this is a semicolon. -.IP "\fB\-\-output\-file\fR" 4 -.IX Item "--output-file" +.IP "\fB\-\-output\-file\fR \fIoutfile\fR" 4 +.IX Item "--output-file outfile" write output to the file \fIoutfile\fR instead of to standard output; a file name of \*(L"\-\*(R" stands for standard output. .SH "MODELS" .IX Header "MODELS" \&\fBGravity\fR computes the gravity field using one of the following models .PP -.Vb 8 +.Vb 10 \& egm84, earth gravity model 1984. See \& http://earth\-info.nga.mil/GandG/wgs84/gravitymod/wgs84_180/wgs84_180.html \& egm96, earth gravity model 1996. See @@ -266,43 +278,44 @@ file name of \*(L"\-\*(R" stands for standard output. \& http://earth\-info.nga.mil/GandG/wgs84/gravitymod/egm2008 \& wgs84, world geodetic system 1984. This returns the normal \& gravity for the WGS84 ellipsoid. +\& grs80, geodetic reference system 1980. This returns the normal +\& gravity for the GRS80 ellipsoid. .Ve .PP These models approximate the gravitation field above the surface of the earth. By default, the \f(CW\*(C`egm96\*(C'\fR gravity model is used. This may -changed by setting the environment variable \f(CW\*(C`GRAVITY_NAME\*(C'\fR or with the -\&\fB\-n\fR option. +changed by setting the environment variable +\&\f(CW\*(C`GEOGRAPHICLIB_GRAVITY_NAME\*(C'\fR or with the \fB\-n\fR option. .PP The gravity models will be loaded from a directory specified at compile time. This may changed by setting the environment variables -\&\f(CW\*(C`GRAVITY_PATH\*(C'\fR or \f(CW\*(C`GEOGRAPHICLIB_DATA\*(C'\fR, or with the \fB\-d\fR option. -The \fB\-h\fR option prints the default gravity path and name. Use the -\&\fB\-v\fR option to ascertain the full path name of the data file. +\&\f(CW\*(C`GEOGRAPHICLIB_GRAVITY_PATH\*(C'\fR or \f(CW\*(C`GEOGRAPHICLIB_DATA\*(C'\fR, or with the +\&\fB\-d\fR option. The \fB\-h\fR option prints the default gravity path and +name. Use the \fB\-v\fR option to ascertain the full path name of the data +file. .PP -Instructions for downloading and installing gravity models are -available at -. +Instructions for downloading and installing gravity models are available +at . .SH "ENVIRONMENT" .IX Header "ENVIRONMENT" -.IP "\fB\s-1GRAVITY_NAME\s0\fR" 4 -.IX Item "GRAVITY_NAME" +.IP "\fB\s-1GEOGRAPHICLIB_GRAVITY_NAME\s0\fR" 4 +.IX Item "GEOGRAPHICLIB_GRAVITY_NAME" Override the compile-time default gravity name of \f(CW\*(C`egm96\*(C'\fR. The \fB\-h\fR -option reports the value of \fB\s-1GRAVITY_NAME\s0\fR, if defined, otherwise it -reports the compile-time value. If the \fB\-n\fR \fIname\fR option is used, -then \fIname\fR takes precedence. -.IP "\fB\s-1GRAVITY_PATH\s0\fR" 4 -.IX Item "GRAVITY_PATH" +option reports the value of \fB\s-1GEOGRAPHICLIB_GRAVITY_NAME\s0\fR, if defined, +otherwise it reports the compile-time value. If the \fB\-n\fR \fIname\fR +option is used, then \fIname\fR takes precedence. +.IP "\fB\s-1GEOGRAPHICLIB_GRAVITY_PATH\s0\fR" 4 +.IX Item "GEOGRAPHICLIB_GRAVITY_PATH" Override the compile-time default gravity path. This is typically \&\f(CW\*(C`/usr/local/share/GeographicLib/gravity\*(C'\fR on Unix-like systems and -\&\f(CW\*(C`C:/Documents and Settings/All Users/Application -Data/GeographicLib/gravity\*(C'\fR on Windows systems. The \fB\-h\fR option reports -the value of \fB\s-1GRAVITY_PATH\s0\fR, if defined, otherwise it reports the -compile-time value. If the \fB\-d\fR \fIdir\fR option is used, then \fIdir\fR -takes precedence. +\&\f(CW\*(C`C:/ProgramData/GeographicLib/gravity\*(C'\fR on Windows systems. The \fB\-h\fR +option reports the value of \fB\s-1GEOGRAPHICLIB_GRAVITY_PATH\s0\fR, if defined, +otherwise it reports the compile-time value. If the \fB\-d\fR \fIdir\fR option +is used, then \fIdir\fR takes precedence. .IP "\fB\s-1GEOGRAPHICLIB_DATA\s0\fR" 4 .IX Item "GEOGRAPHICLIB_DATA" Another way of overriding the compile-time default gravity path. If it -is set (and if \fB\s-1GRAVITY_PATH\s0\fR is not set), then +is set (and if \fB\s-1GEOGRAPHICLIB_GRAVITY_PATH\s0\fR is not set), then $\fB\s-1GEOGRAPHICLIB_DATA\s0\fR/gravity is used. .SH "ERRORS" .IX Header "ERRORS" @@ -320,11 +333,11 @@ The gravity field from \s-1EGM2008\s0 at the top of Mount Everest .Ve .SH "SEE ALSO" .IX Header "SEE ALSO" -\&\fIGeoConvert\fR\|(1), \fIGeoidEval\fR\|(1). +\&\fIGeoConvert\fR\|(1), \fIGeoidEval\fR\|(1), \fIgeographiclib\-get\-gravity\fR\|(8). .SH "AUTHOR" .IX Header "AUTHOR" \&\fBGravity\fR was written by Charles Karney. .SH "HISTORY" .IX Header "HISTORY" -\&\fBGravity\fR was added to GeographicLib, , +\&\fBGravity\fR was added to GeographicLib, , in version 1.16. diff --git a/gtsam/3rdparty/GeographicLib/man/Gravity.1.html b/gtsam/3rdparty/GeographicLib/man/Gravity.1.html index cca8ad941..e087ebbda 100644 --- a/gtsam/3rdparty/GeographicLib/man/Gravity.1.html +++ b/gtsam/3rdparty/GeographicLib/man/Gravity.1.html @@ -7,7 +7,7 @@ - + @@ -17,27 +17,27 @@

    SYNOPSIS

    -

    Gravity [ -n name ] [ -d dir ] [ -G | -D | -A | -H ] [ -c lat h ] [ -p prec ] [ -v ] [ --comment-delimiter commentdelim ] [ --version | -h | --help ] [ --input-file infile | --input-string instring ] [ --line-separator linesep ] [ --output-file outfile ]

    +

    Gravity [ -n name ] [ -d dir ] [ -G | -D | -A | -H ] [ -c lat h ] [ -w ] [ -p prec ] [ -v ] [ --comment-delimiter commentdelim ] [ --version | -h | --help ] [ --input-file infile | --input-string instring ] [ --line-separator linesep ] [ --output-file outfile ]

    DESCRIPTION

    Gravity reads in positions on standard input and prints out the gravitational field on standard output.

    -

    The input line is of the form lat lon h. lat and lon are the latitude and longitude expressed as decimal degrees or degrees, minutes, and seconds; see GeoConvert(1) for details. h is the height above the ellipsoid in meters; this quantity is optional and defaults to 0. Alternatively, the gravity field can be computed at various points on a circle of latitude (constant lat and h) via the -c option; in this case only the longitude should be given on the input lines. The quantities printed out are governed by the -G (default), -D, -A, or -H options.

    +

    The input line is of the form lat lon h. lat and lon are the latitude and longitude expressed as decimal degrees or degrees, minutes, and seconds; for details on the allowed formats for latitude and longitude, see the GEOGRAPHIC COORDINATES section of GeoConvert(1). h is the height above the ellipsoid in meters; this quantity is optional and defaults to 0. Alternatively, the gravity field can be computed at various points on a circle of latitude (constant lat and h) via the -c option; in this case only the longitude should be given on the input lines. The quantities printed out are governed by the -G (default), -D, -A, or -H options.

    -

    All the supported gravity models use WGS84 as the reference ellipsoid a = 6378137 m, f = 1/298.257223563, omega = 7292115e-11 rad/s, and GM = 3986004.418e8 m^3/s^2.

    +

    All the supported gravity models, except for grs80, use WGS84 as the reference ellipsoid a = 6378137 m, f = 1/298.257223563, omega = 7292115e-11 rad/s, and GM = 3986004.418e8 m^3/s^2.

    OPTIONS

    -
    -n
    +
    -n name

    use gravity field model name instead of the default egm96. See "MODELS".

    -
    -d
    +
    -d dir

    read gravity models from dir instead of the default. See "MODELS".

    @@ -67,13 +67,19 @@

    compute the height of the geoid above the reference ellipsoid (in meters). In this case, h should be zero. The results accurately match the results of the NGA's synthesis programs. GeoidEval(1) can compute geoid heights much more quickly by interpolating on a grid of precomputed results; however the results from GeoidEval(1) are only accurate to a few millimeters.

    -
    -c
    +
    -c lat h

    evaluate the field on a circle of latitude given by lat and h instead of reading these quantities from the input lines. In this case, Gravity can calculate the field considerably more quickly. If geoid heights are being computed (the -H option), then h must be zero.

    -
    -p
    +
    -w
    +
    + +

    toggle the longitude first flag (it starts off); if the flag is on, then on input and output, longitude precedes latitude (except that, on input, this can be overridden by a hemisphere designator, N, S, E, W).

    + +
    +
    -p prec

    set the output precision to prec. By default prec is 5 for acceleration due to gravity, 3 for the gravity disturbance and anomaly, and 4 for the geoid height.

    @@ -85,7 +91,7 @@

    print information about the gravity model on standard error before processing the input.

    -
    --comment-delimiter
    +
    --comment-delimiter commentdelim

    set the comment delimiter to commentdelim (e.g., "#" or "//"). If set, the input lines will be scanned for this delimiter and, if found, the delimiter and the rest of the line will be removed prior to processing and subsequently appended to the output line (separated by a space).

    @@ -109,25 +115,25 @@

    print full documentation and exit.

    -
    --input-file
    +
    --input-file infile

    read input from the file infile instead of from standard input; a file name of "-" stands for standard input.

    -
    --input-string
    +
    --input-string instring

    read input from the string instring instead of from standard input. All occurrences of the line separator character (default is a semicolon) in instring are converted to newlines before the reading begins.

    -
    --line-separator
    +
    --line-separator linesep

    set the line separator character to linesep. By default this is a semicolon.

    -
    --output-file
    +
    --output-file outfile

    write output to the file outfile instead of to standard output; a file name of "-" stands for standard output.

    @@ -146,34 +152,36 @@ egm2008, earth gravity model 2008. See http://earth-info.nga.mil/GandG/wgs84/gravitymod/egm2008 wgs84, world geodetic system 1984. This returns the normal - gravity for the WGS84 ellipsoid.
    + gravity for the WGS84 ellipsoid. + grs80, geodetic reference system 1980. This returns the normal + gravity for the GRS80 ellipsoid.
    -

    These models approximate the gravitation field above the surface of the earth. By default, the egm96 gravity model is used. This may changed by setting the environment variable GRAVITY_NAME or with the -n option.

    +

    These models approximate the gravitation field above the surface of the earth. By default, the egm96 gravity model is used. This may changed by setting the environment variable GEOGRAPHICLIB_GRAVITY_NAME or with the -n option.

    -

    The gravity models will be loaded from a directory specified at compile time. This may changed by setting the environment variables GRAVITY_PATH or GEOGRAPHICLIB_DATA, or with the -d option. The -h option prints the default gravity path and name. Use the -v option to ascertain the full path name of the data file.

    +

    The gravity models will be loaded from a directory specified at compile time. This may changed by setting the environment variables GEOGRAPHICLIB_GRAVITY_PATH or GEOGRAPHICLIB_DATA, or with the -d option. The -h option prints the default gravity path and name. Use the -v option to ascertain the full path name of the data file.

    -

    Instructions for downloading and installing gravity models are available at http://geographiclib.sf.net/html/gravity.html#gravityinst.

    +

    Instructions for downloading and installing gravity models are available at https://geographiclib.sourceforge.io/html/gravity.html#gravityinst.

    ENVIRONMENT

    -
    GRAVITY_NAME
    +
    GEOGRAPHICLIB_GRAVITY_NAME
    -

    Override the compile-time default gravity name of egm96. The -h option reports the value of GRAVITY_NAME, if defined, otherwise it reports the compile-time value. If the -n name option is used, then name takes precedence.

    +

    Override the compile-time default gravity name of egm96. The -h option reports the value of GEOGRAPHICLIB_GRAVITY_NAME, if defined, otherwise it reports the compile-time value. If the -n name option is used, then name takes precedence.

    -
    GRAVITY_PATH
    +
    GEOGRAPHICLIB_GRAVITY_PATH
    -

    Override the compile-time default gravity path. This is typically /usr/local/share/GeographicLib/gravity on Unix-like systems and C:/Documents and Settings/All Users/Application Data/GeographicLib/gravity on Windows systems. The -h option reports the value of GRAVITY_PATH, if defined, otherwise it reports the compile-time value. If the -d dir option is used, then dir takes precedence.

    +

    Override the compile-time default gravity path. This is typically /usr/local/share/GeographicLib/gravity on Unix-like systems and C:/ProgramData/GeographicLib/gravity on Windows systems. The -h option reports the value of GEOGRAPHICLIB_GRAVITY_PATH, if defined, otherwise it reports the compile-time value. If the -d dir option is used, then dir takes precedence.

    GEOGRAPHICLIB_DATA
    -

    Another way of overriding the compile-time default gravity path. If it is set (and if GRAVITY_PATH is not set), then $GEOGRAPHICLIB_DATA/gravity is used.

    +

    Another way of overriding the compile-time default gravity path. If it is set (and if GEOGRAPHICLIB_GRAVITY_PATH is not set), then $GEOGRAPHICLIB_DATA/gravity is used.

    @@ -191,7 +199,7 @@

    SEE ALSO

    -

    GeoConvert(1), GeoidEval(1).

    +

    GeoConvert(1), GeoidEval(1), geographiclib-get-gravity(8).

    AUTHOR

    @@ -199,7 +207,7 @@

    HISTORY

    -

    Gravity was added to GeographicLib, http://geographiclib.sf.net, in version 1.16.

    +

    Gravity was added to GeographicLib, https://geographiclib.sourceforge.io, in version 1.16.

    diff --git a/gtsam/3rdparty/GeographicLib/man/Gravity.pod b/gtsam/3rdparty/GeographicLib/man/Gravity.pod index 90f0c8ec8..c21cddb7b 100644 --- a/gtsam/3rdparty/GeographicLib/man/Gravity.pod +++ b/gtsam/3rdparty/GeographicLib/man/Gravity.pod @@ -6,7 +6,7 @@ Gravity -- compute the earth's gravity field B [ B<-n> I ] [ B<-d> I ] [ B<-G> | B<-D> | B<-A> | B<-H> ] [ B<-c> I I ] -[ B<-p> I ] +[ B<-w> ] [ B<-p> I ] [ B<-v> ] [ B<--comment-delimiter> I ] [ B<--version> | B<-h> | B<--help> ] @@ -21,28 +21,29 @@ gravitational field on standard output. The input line is of the form I I I. I and I are the latitude and longitude expressed as decimal degrees or degrees, -minutes, and seconds; see GeoConvert(1) for details. I is the height -above the ellipsoid in meters; this quantity is optional and defaults to -0. Alternatively, the gravity field can be computed at various points -on a circle of latitude (constant I and I) via the B<-c> option; -in this case only the longitude should be given on the input lines. The -quantities printed out are governed by the B<-G> (default), B<-D>, -B<-A>, or B<-H> options. +minutes, and seconds; for details on the allowed formats for latitude +and longitude, see the C section of +GeoConvert(1). I is the height above the ellipsoid in meters; this +quantity is optional and defaults to 0. Alternatively, the gravity +field can be computed at various points on a circle of latitude +(constant I and I) via the B<-c> option; in this case only the +longitude should be given on the input lines. The quantities printed +out are governed by the B<-G> (default), B<-D>, B<-A>, or B<-H> options. -All the supported gravity models use WGS84 as the reference ellipsoid -I = 6378137 m, I = 1/298.257223563, I = 7292115e-11 rad/s, -and I = 3986004.418e8 m^3/s^2. +All the supported gravity models, except for grs80, use WGS84 as the +reference ellipsoid I = 6378137 m, I = 1/298.257223563, I = +7292115e-11 rad/s, and I = 3986004.418e8 m^3/s^2. =head1 OPTIONS =over -=item B<-n> +=item B<-n> I use gravity field model I instead of the default C. See L. -=item B<-d> +=item B<-d> I read gravity models from I instead of the default. See L. @@ -86,14 +87,21 @@ compute geoid heights much more quickly by interpolating on a grid of precomputed results; however the results from GeoidEval(1) are only accurate to a few millimeters. -=item B<-c> +=item B<-c> I I evaluate the field on a circle of latitude given by I and I instead of reading these quantities from the input lines. In this case, B can calculate the field considerably more quickly. If geoid heights are being computed (the B<-H> option), then I must be zero. -=item B<-p> +=item B<-w> + +toggle the longitude first flag (it starts off); if the flag is on, then +on input and output, longitude precedes latitude (except that, on input, +this can be overridden by a hemisphere designator, I, I, I, +I). + +=item B<-p> I set the output precision to I. By default I is 5 for acceleration due to gravity, 3 for the gravity disturbance and anomaly, @@ -104,7 +112,7 @@ and 4 for the geoid height. print information about the gravity model on standard error before processing the input. -=item B<--comment-delimiter> +=item B<--comment-delimiter> I set the comment delimiter to I (e.g., "#" or "//"). If set, the input lines will be scanned for this delimiter and, if found, @@ -124,23 +132,23 @@ print usage, the default gravity path and name, and exit. print full documentation and exit. -=item B<--input-file> +=item B<--input-file> I read input from the file I instead of from standard input; a file name of "-" stands for standard input. -=item B<--input-string> +=item B<--input-string> I read input from the string I instead of from standard input. All occurrences of the line separator character (default is a semicolon) in I are converted to newlines before the reading begins. -=item B<--line-separator> +=item B<--line-separator> I set the line separator character to I. By default this is a semicolon. -=item B<--output-file> +=item B<--output-file> I write output to the file I instead of to standard output; a file name of "-" stands for standard output. @@ -159,47 +167,48 @@ B computes the gravity field using one of the following models http://earth-info.nga.mil/GandG/wgs84/gravitymod/egm2008 wgs84, world geodetic system 1984. This returns the normal gravity for the WGS84 ellipsoid. + grs80, geodetic reference system 1980. This returns the normal + gravity for the GRS80 ellipsoid. These models approximate the gravitation field above the surface of the earth. By default, the C gravity model is used. This may -changed by setting the environment variable C or with the -B<-n> option. +changed by setting the environment variable +C or with the B<-n> option. The gravity models will be loaded from a directory specified at compile time. This may changed by setting the environment variables -C or C, or with the B<-d> option. -The B<-h> option prints the default gravity path and name. Use the -B<-v> option to ascertain the full path name of the data file. +C or C, or with the +B<-d> option. The B<-h> option prints the default gravity path and +name. Use the B<-v> option to ascertain the full path name of the data +file. -Instructions for downloading and installing gravity models are -available at -L. +Instructions for downloading and installing gravity models are available +at L. =head1 ENVIRONMENT =over -=item B +=item B Override the compile-time default gravity name of C. The B<-h> -option reports the value of B, if defined, otherwise it -reports the compile-time value. If the B<-n> I option is used, -then I takes precedence. +option reports the value of B, if defined, +otherwise it reports the compile-time value. If the B<-n> I +option is used, then I takes precedence. -=item B +=item B Override the compile-time default gravity path. This is typically C on Unix-like systems and -C on Windows systems. The B<-h> option reports -the value of B, if defined, otherwise it reports the -compile-time value. If the B<-d> I option is used, then I -takes precedence. +C on Windows systems. The B<-h> +option reports the value of B, if defined, +otherwise it reports the compile-time value. If the B<-d> I option +is used, then I takes precedence. =item B Another way of overriding the compile-time default gravity path. If it -is set (and if B is not set), then +is set (and if B is not set), then $B/gravity is used. =back @@ -220,7 +229,7 @@ The gravity field from EGM2008 at the top of Mount Everest =head1 SEE ALSO -GeoConvert(1), GeoidEval(1). +GeoConvert(1), GeoidEval(1), geographiclib-get-gravity(8). =head1 AUTHOR @@ -228,5 +237,5 @@ B was written by Charles Karney. =head1 HISTORY -B was added to GeographicLib, L, +B was added to GeographicLib, L, in version 1.16. diff --git a/gtsam/3rdparty/GeographicLib/man/Gravity.usage b/gtsam/3rdparty/GeographicLib/man/Gravity.usage index d60547f09..127a90cb2 100644 --- a/gtsam/3rdparty/GeographicLib/man/Gravity.usage +++ b/gtsam/3rdparty/GeographicLib/man/Gravity.usage @@ -1,24 +1,24 @@ int usage(int retval, bool brief) { if (brief) ( retval ? std::cerr : std::cout ) << "Usage:\n" -" Gravity [ -n name ] [ -d dir ] [ -G | -D | -A | -H ] [ -c lat h ] [ -p\n" -" prec ] [ -v ] [ --comment-delimiter commentdelim ] [ --version | -h |\n" -" --help ] [ --input-file infile | --input-string instring ] [\n" +" Gravity [ -n name ] [ -d dir ] [ -G | -D | -A | -H ] [ -c lat h ] [ -w\n" +" ] [ -p prec ] [ -v ] [ --comment-delimiter commentdelim ] [ --version |\n" +" -h | --help ] [ --input-file infile | --input-string instring ] [\n" " --line-separator linesep ] [ --output-file outfile ]\n" "\n" "For full documentation type:\n" " Gravity --help\n" "or visit:\n" -" http://geographiclib.sf.net/1.35/Gravity.1.html\n"; +" https://geographiclib.sourceforge.io/1.49/Gravity.1.html\n"; else ( retval ? std::cerr : std::cout ) << "Man page:\n" "NAME\n" " Gravity -- compute the earth's gravity field\n" "\n" "SYNOPSIS\n" -" Gravity [ -n name ] [ -d dir ] [ -G | -D | -A | -H ] [ -c lat h ] [ -p\n" -" prec ] [ -v ] [ --comment-delimiter commentdelim ] [ --version | -h |\n" -" --help ] [ --input-file infile | --input-string instring ] [\n" +" Gravity [ -n name ] [ -d dir ] [ -G | -D | -A | -H ] [ -c lat h ] [ -w\n" +" ] [ -p prec ] [ -v ] [ --comment-delimiter commentdelim ] [ --version |\n" +" -h | --help ] [ --input-file infile | --input-string instring ] [\n" " --line-separator linesep ] [ --output-file outfile ]\n" "\n" "DESCRIPTION\n" @@ -27,22 +27,26 @@ int usage(int retval, bool brief) { "\n" " The input line is of the form lat lon h. lat and lon are the latitude\n" " and longitude expressed as decimal degrees or degrees, minutes, and\n" -" seconds; see GeoConvert(1) for details. h is the height above the\n" -" ellipsoid in meters; this quantity is optional and defaults to 0.\n" -" Alternatively, the gravity field can be computed at various points on a\n" -" circle of latitude (constant lat and h) via the -c option; in this case\n" -" only the longitude should be given on the input lines. The quantities\n" -" printed out are governed by the -G (default), -D, -A, or -H options.\n" +" seconds; for details on the allowed formats for latitude and longitude,\n" +" see the \"GEOGRAPHIC COORDINATES\" section of GeoConvert(1). h is the\n" +" height above the ellipsoid in meters; this quantity is optional and\n" +" defaults to 0. Alternatively, the gravity field can be computed at\n" +" various points on a circle of latitude (constant lat and h) via the -c\n" +" option; in this case only the longitude should be given on the input\n" +" lines. The quantities printed out are governed by the -G (default),\n" +" -D, -A, or -H options.\n" "\n" -" All the supported gravity models use WGS84 as the reference ellipsoid a\n" -" = 6378137 m, f = 1/298.257223563, omega = 7292115e-11 rad/s, and GM =\n" -" 3986004.418e8 m^3/s^2.\n" +" All the supported gravity models, except for grs80, use WGS84 as the\n" +" reference ellipsoid a = 6378137 m, f = 1/298.257223563, omega =\n" +" 7292115e-11 rad/s, and GM = 3986004.418e8 m^3/s^2.\n" "\n" "OPTIONS\n" -" -n use gravity field model name instead of the default \"egm96\". See\n" +" -n name\n" +" use gravity field model name instead of the default \"egm96\". See\n" " \"MODELS\".\n" "\n" -" -d read gravity models from dir instead of the default. See \"MODELS\".\n" +" -d dir\n" +" read gravity models from dir instead of the default. See \"MODELS\".\n" "\n" " -G compute the acceleration due to gravity (including the centrifugal\n" " acceleration due the the earth's rotation) g. The output consists\n" @@ -75,20 +79,27 @@ int usage(int retval, bool brief) { " grid of precomputed results; however the results from GeoidEval(1)\n" " are only accurate to a few millimeters.\n" "\n" -" -c evaluate the field on a circle of latitude given by lat and h\n" +" -c lat h\n" +" evaluate the field on a circle of latitude given by lat and h\n" " instead of reading these quantities from the input lines. In this\n" " case, Gravity can calculate the field considerably more quickly.\n" " If geoid heights are being computed (the -H option), then h must be\n" " zero.\n" "\n" -" -p set the output precision to prec. By default prec is 5 for\n" +" -w toggle the longitude first flag (it starts off); if the flag is on,\n" +" then on input and output, longitude precedes latitude (except that,\n" +" on input, this can be overridden by a hemisphere designator, N, S,\n" +" E, W).\n" +"\n" +" -p prec\n" +" set the output precision to prec. By default prec is 5 for\n" " acceleration due to gravity, 3 for the gravity disturbance and\n" " anomaly, and 4 for the geoid height.\n" "\n" " -v print information about the gravity model on standard error before\n" " processing the input.\n" "\n" -" --comment-delimiter\n" +" --comment-delimiter commentdelim\n" " set the comment delimiter to commentdelim (e.g., \"#\" or \"//\"). If\n" " set, the input lines will be scanned for this delimiter and, if\n" " found, the delimiter and the rest of the line will be removed prior\n" @@ -103,21 +114,21 @@ int usage(int retval, bool brief) { " --help\n" " print full documentation and exit.\n" "\n" -" --input-file\n" +" --input-file infile\n" " read input from the file infile instead of from standard input; a\n" " file name of \"-\" stands for standard input.\n" "\n" -" --input-string\n" +" --input-string instring\n" " read input from the string instring instead of from standard input.\n" " All occurrences of the line separator character (default is a\n" " semicolon) in instring are converted to newlines before the reading\n" " begins.\n" "\n" -" --line-separator\n" +" --line-separator linesep\n" " set the line separator character to linesep. By default this is a\n" " semicolon.\n" "\n" -" --output-file\n" +" --output-file outfile\n" " write output to the file outfile instead of to standard output; a\n" " file name of \"-\" stands for standard output.\n" "\n" @@ -132,41 +143,42 @@ int usage(int retval, bool brief) { " http://earth-info.nga.mil/GandG/wgs84/gravitymod/egm2008\n" " wgs84, world geodetic system 1984. This returns the normal\n" " gravity for the WGS84 ellipsoid.\n" +" grs80, geodetic reference system 1980. This returns the normal\n" +" gravity for the GRS80 ellipsoid.\n" "\n" " These models approximate the gravitation field above the surface of the\n" " earth. By default, the \"egm96\" gravity model is used. This may\n" -" changed by setting the environment variable \"GRAVITY_NAME\" or with the\n" -" -n option.\n" +" changed by setting the environment variable\n" +" \"GEOGRAPHICLIB_GRAVITY_NAME\" or with the -n option.\n" "\n" " The gravity models will be loaded from a directory specified at compile\n" " time. This may changed by setting the environment variables\n" -" \"GRAVITY_PATH\" or \"GEOGRAPHICLIB_DATA\", or with the -d option. The -h\n" -" option prints the default gravity path and name. Use the -v option to\n" -" ascertain the full path name of the data file.\n" +" \"GEOGRAPHICLIB_GRAVITY_PATH\" or \"GEOGRAPHICLIB_DATA\", or with the -d\n" +" option. The -h option prints the default gravity path and name. Use\n" +" the -v option to ascertain the full path name of the data file.\n" "\n" " Instructions for downloading and installing gravity models are\n" " available at\n" -" .\n" +" .\n" "\n" "ENVIRONMENT\n" -" GRAVITY_NAME\n" +" GEOGRAPHICLIB_GRAVITY_NAME\n" " Override the compile-time default gravity name of \"egm96\". The -h\n" -" option reports the value of GRAVITY_NAME, if defined, otherwise it\n" -" reports the compile-time value. If the -n name option is used,\n" -" then name takes precedence.\n" +" option reports the value of GEOGRAPHICLIB_GRAVITY_NAME, if defined,\n" +" otherwise it reports the compile-time value. If the -n name option\n" +" is used, then name takes precedence.\n" "\n" -" GRAVITY_PATH\n" +" GEOGRAPHICLIB_GRAVITY_PATH\n" " Override the compile-time default gravity path. This is typically\n" " \"/usr/local/share/GeographicLib/gravity\" on Unix-like systems and\n" -" \"C:/Documents and Settings/All Users/Application\n" -" Data/GeographicLib/gravity\" on Windows systems. The -h option\n" -" reports the value of GRAVITY_PATH, if defined, otherwise it reports\n" -" the compile-time value. If the -d dir option is used, then dir\n" -" takes precedence.\n" +" \"C:/ProgramData/GeographicLib/gravity\" on Windows systems. The -h\n" +" option reports the value of GEOGRAPHICLIB_GRAVITY_PATH, if defined,\n" +" otherwise it reports the compile-time value. If the -d dir option\n" +" is used, then dir takes precedence.\n" "\n" " GEOGRAPHICLIB_DATA\n" " Another way of overriding the compile-time default gravity path.\n" -" If it is set (and if GRAVITY_PATH is not set), then\n" +" If it is set (and if GEOGRAPHICLIB_GRAVITY_PATH is not set), then\n" " $GEOGRAPHICLIB_DATA/gravity is used.\n" "\n" "ERRORS\n" @@ -182,14 +194,14 @@ int usage(int retval, bool brief) { " => -0.00001 0.00103 -9.76782\n" "\n" "SEE ALSO\n" -" GeoConvert(1), GeoidEval(1).\n" +" GeoConvert(1), GeoidEval(1), geographiclib-get-gravity(8).\n" "\n" "AUTHOR\n" " Gravity was written by Charles Karney.\n" "\n" "HISTORY\n" -" Gravity was added to GeographicLib, , in\n" -" version 1.16.\n" +" Gravity was added to GeographicLib,\n" +" , in version 1.16.\n" ; return retval; } diff --git a/gtsam/3rdparty/GeographicLib/man/MagneticField.1 b/gtsam/3rdparty/GeographicLib/man/MagneticField.1 index 3d520cb6b..e7c29cc09 100644 --- a/gtsam/3rdparty/GeographicLib/man/MagneticField.1 +++ b/gtsam/3rdparty/GeographicLib/man/MagneticField.1 @@ -1,4 +1,4 @@ -.\" Automatically generated by Pod::Man 2.25 (Pod::Simple 3.20) +.\" Automatically generated by Pod::Man 4.09 (Pod::Simple 3.35) .\" .\" Standard preamble: .\" ======================================================================== @@ -38,26 +38,31 @@ . ds PI \(*p . ds L" `` . ds R" '' +. ds C` +. ds C' 'br\} .\" .\" Escape single quotes in literal strings from groff's Unicode transform. .ie \n(.g .ds Aq \(aq .el .ds Aq ' .\" -.\" If the F register is turned on, we'll generate index entries on stderr for +.\" If the F register is >0, we'll generate index entries on stderr for .\" titles (.TH), headers (.SH), subsections (.SS), items (.Ip), and index .\" entries marked with X<> in POD. Of course, you'll have to process the .\" output yourself in some meaningful fashion. -.ie \nF \{\ +.\" +.\" Avoid warning from groff about undefined register 'F'. +.de IX +.. +.if !\nF .nr F 0 +.if \nF>0 \{\ . de IX . tm Index:\\$1\t\\n%\t"\\$2" .. -. nr % 0 -. rr F -.\} -.el \{\ -. de IX -.. +. if !\nF==2 \{\ +. nr % 0 +. nr F 2 +. \} .\} .\" .\" Accent mark definitions (@(#)ms.acc 1.5 88/02/08 SMI; from UCB 4.2). @@ -124,7 +129,7 @@ .\" ======================================================================== .\" .IX Title "MAGNETICFIELD 1" -.TH MAGNETICFIELD 1 "2014-03-13" "GeographicLib 1.35" "GeographicLib Utilities" +.TH MAGNETICFIELD 1 "2017-10-05" "GeographicLib 1.49" "GeographicLib Utilities" .\" For nroff, turn off justification. Always turn off hyphenation; it makes .\" way too many mistakes in technical documents. .if n .ad l @@ -135,7 +140,7 @@ MagneticField \-\- compute the earth's magnetic field .IX Header "SYNOPSIS" \&\fBMagneticField\fR [ \fB\-n\fR \fIname\fR ] [ \fB\-d\fR \fIdir\fR ] [ \fB\-t\fR \fItime\fR | \fB\-c\fR \fItime\fR \fIlat\fR \fIh\fR ] -[ \fB\-r\fR ] [ \fB\-T\fR \fItguard\fR ] [ \fB\-H\fR \fIhguard\fR ] [ \fB\-p\fR \fIprec\fR ] +[ \fB\-r\fR ] [ \fB\-w\fR ] [ \fB\-T\fR \fItguard\fR ] [ \fB\-H\fR \fIhguard\fR ] [ \fB\-p\fR \fIprec\fR ] [ \fB\-v\fR ] [ \fB\-\-comment\-delimiter\fR \fIcommentdelim\fR ] [ \fB\-\-version\fR | \fB\-h\fR | \fB\-\-help\fR ] @@ -149,16 +154,18 @@ prints out the geomagnetic field on standard output and, optionally, its rate of change. .PP The input line is of the form \fItime\fR \fIlat\fR \fIlon\fR \fIh\fR. \fItime\fR is a -date of the form 2012\-07\-03 or a fractional year such as 2012.5. \fIlat\fR -and \fIlon\fR are the latitude and longitude expressed as decimal degrees -or degrees, minutes, and seconds; see \fIGeoConvert\fR\|(1) for details. \fIh\fR -is the height above the ellipsoid in meters; this is optional and -defaults to zero. Alternatively, \fItime\fR can be given on the command -line as the argument to the \fB\-t\fR option, in which case it should not be -included on the input lines. Finally, the magnetic field can be -computed at various points on a circle of latitude (constant \fItime\fR, -\&\fIlat\fR, and \fIh\fR) via the \fB\-c\fR option; in this case only the longitude -should be given on the input lines. +date of the form 2012\-07\-03, a fractional year such as 2012.5, or the +string \*(L"now\*(R". \fIlat\fR and \fIlon\fR are the latitude and longitude +expressed as decimal degrees or degrees, minutes, and seconds; for +details on the allowed formats for latitude and longitude, see the +\&\f(CW\*(C`GEOGRAPHIC COORDINATES\*(C'\fR section of \fIGeoConvert\fR\|(1). \fIh\fR is the height +above the ellipsoid in meters; this is optional and defaults to zero. +Alternatively, \fItime\fR can be given on the command line as the argument +to the \fB\-t\fR option, in which case it should not be included on the +input lines. Finally, the magnetic field can be computed at various +points on a circle of latitude (constant \fItime\fR, \fIlat\fR, and \fIh\fR) via +the \fB\-c\fR option; in this case only the longitude should be given on the +input lines. .PP The output consists of the following 7 items: .PP @@ -180,20 +187,20 @@ of change of these quantities in degrees/yr and nT/yr. The \s-1WGS84\s0 ellipsoid is used, \fIa\fR = 6378137 m, \fIf\fR = 1/298.257223563. .SH "OPTIONS" .IX Header "OPTIONS" -.IP "\fB\-n\fR" 4 -.IX Item "-n" -use magnetic field model \fIname\fR instead of the default \f(CW\*(C`wmm2010\*(C'\fR. See -\&\*(L"\s-1MODELS\s0\*(R". -.IP "\fB\-d\fR" 4 -.IX Item "-d" +.IP "\fB\-n\fR \fIname\fR" 4 +.IX Item "-n name" +use magnetic field model \fIname\fR instead of the default \f(CW\*(C`wmm2015\*(C'\fR. See +\&\*(L"\s-1MODELS\*(R"\s0. +.IP "\fB\-d\fR \fIdir\fR" 4 +.IX Item "-d dir" read magnetic models from \fIdir\fR instead of the default. See -\&\*(L"\s-1MODELS\s0\*(R". -.IP "\fB\-t\fR" 4 -.IX Item "-t" +\&\*(L"\s-1MODELS\*(R"\s0. +.IP "\fB\-t\fR \fItime\fR" 4 +.IX Item "-t time" evaluate the field at \fItime\fR instead of reading the time from the input lines. -.IP "\fB\-c\fR" 4 -.IX Item "-c" +.IP "\fB\-c\fR \fItime\fR \fIlat\fR \fIh\fR" 4 +.IX Item "-c time lat h" evaluate the field on a circle of latitude given by \fItime\fR, \fIlat\fR, \&\fIh\fR instead of reading these quantities from the input lines. In this case, \fBMagneticField\fR can calculate the field considerably more @@ -201,16 +208,22 @@ quickly. .IP "\fB\-r\fR" 4 .IX Item "-r" toggle whether to report the rates of change of the field. -.IP "\fB\-T\fR" 4 -.IX Item "-T" +.IP "\fB\-w\fR" 4 +.IX Item "-w" +toggle the longitude first flag (it starts off); if the flag is on, then +on input and output, longitude precedes latitude (except that, on input, +this can be overridden by a hemisphere designator, \fIN\fR, \fIS\fR, \fIE\fR, +\&\fIW\fR). +.IP "\fB\-T\fR \fItguard\fR" 4 +.IX Item "-T tguard" signal an error if \fItime\fR lies \fItguard\fR years (default 50 yr) beyond the range for the model. -.IP "\fB\-H\fR" 4 -.IX Item "-H" +.IP "\fB\-H\fR \fIhguard\fR" 4 +.IX Item "-H hguard" signal an error if \fIh\fR lies \fIhguard\fR meters (default 500000 m) beyond the range for the model. -.IP "\fB\-p\fR" 4 -.IX Item "-p" +.IP "\fB\-p\fR \fIprec\fR" 4 +.IX Item "-p prec" set the output precision to \fIprec\fR (default 1). Fields are printed with precision with \fIprec\fR decimal places; angles use \fIprec\fR + 1 places. @@ -218,8 +231,8 @@ places. .IX Item "-v" print information about the magnetic model on standard error before processing the input. -.IP "\fB\-\-comment\-delimiter\fR" 4 -.IX Item "--comment-delimiter" +.IP "\fB\-\-comment\-delimiter\fR \fIcommentdelim\fR" 4 +.IX Item "--comment-delimiter commentdelim" set the comment delimiter to \fIcommentdelim\fR (e.g., \*(L"#\*(R" or \*(L"//\*(R"). If set, the input lines will be scanned for this delimiter and, if found, the delimiter and the rest of the line will be removed prior to @@ -234,21 +247,21 @@ print usage, the default magnetic path and name, and exit. .IP "\fB\-\-help\fR" 4 .IX Item "--help" print full documentation and exit. -.IP "\fB\-\-input\-file\fR" 4 -.IX Item "--input-file" +.IP "\fB\-\-input\-file\fR \fIinfile\fR" 4 +.IX Item "--input-file infile" read input from the file \fIinfile\fR instead of from standard input; a file name of \*(L"\-\*(R" stands for standard input. -.IP "\fB\-\-input\-string\fR" 4 -.IX Item "--input-string" +.IP "\fB\-\-input\-string\fR \fIinstring\fR" 4 +.IX Item "--input-string instring" read input from the string \fIinstring\fR instead of from standard input. All occurrences of the line separator character (default is a semicolon) in \fIinstring\fR are converted to newlines before the reading begins. -.IP "\fB\-\-line\-separator\fR" 4 -.IX Item "--line-separator" +.IP "\fB\-\-line\-separator\fR \fIlinesep\fR" 4 +.IX Item "--line-separator linesep" set the line separator character to \fIlinesep\fR. By default this is a semicolon. -.IP "\fB\-\-output\-file\fR" 4 -.IX Item "--output-file" +.IP "\fB\-\-output\-file\fR \fIoutfile\fR" 4 +.IX Item "--output-file outfile" write output to the file \fIoutfile\fR instead of to standard output; a file name of \*(L"\-\*(R" stands for standard output. .SH "MODELS" @@ -258,56 +271,69 @@ following models .PP .Vb 10 \& wmm2010, the World Magnetic Model 2010, which approximates the -\& main magnetic field for the period 2010a\*^XX2015. See -\& http://ngdc.noaa.gov/geomag/WMM/DoDWMM.shtml +\& main magnetic field for the period 2010\-2015. See +\& https://ngdc.noaa.gov/geomag/WMM/DoDWMM.shtml +\& wmm2015, the World Magnetic Model 2015, which approximates the +\& main magnetic field for the period 2015\-2020. See +\& https://ngdc.noaa.gov/geomag/WMM/DoDWMM.shtml \& igrf11, the International Geomagnetic Reference Field (11th -\& generation) which approximates the main magnetic field for -\& the period 1900a\*^XX2015. See -\& http://ngdc.noaa.gov/IAGA/vmod/igrf.html -\& emm2010, the Enhanced Magnetic Model 2010, which approximates the -\& main and crustal magnetic fields for the period 2010a\*^XX2015. See -\& http://ngdc.noaa.gov/geomag/EMM/index.html +\& generation), which approximates the main magnetic field for +\& the period 1900\-2015. See +\& https://ngdc.noaa.gov/IAGA/vmod/igrf.html +\& igrf12, the International Geomagnetic Reference Field (12th +\& generation), which approximates the main magnetic field for +\& the period 1900\-2020. See +\& https://ngdc.noaa.gov/IAGA/vmod/igrf.html +\& emm2010, the Enhanced Magnetic Model 2010, which approximates +\& the main and crustal magnetic fields for the period 2010\-2015. +\& See https://ngdc.noaa.gov/geomag/EMM/index.html +\& emm2015, the Enhanced Magnetic Model 2015, which approximates +\& the main and crustal magnetic fields for the period 2000\-2020. +\& See https://ngdc.noaa.gov/geomag/EMM/index.html +\& emm2017, the Enhanced Magnetic Model 2017, which approximates +\& the main and crustal magnetic fields for the period 2000\-2022. +\& See https://ngdc.noaa.gov/geomag/EMM/index.html .Ve .PP These models approximate the magnetic field due to the earth's core and -(in the case of emm2010) its crust. They neglect magnetic fields due to +(in the case of emm20xx) its crust. They neglect magnetic fields due to the ionosphere, the magnetosphere, nearby magnetized materials, electrical machinery, etc. .PP -By default, the \f(CW\*(C`wmm2010\*(C'\fR magnetic model is used. This may changed by -setting the environment variable \f(CW\*(C`MAGNETIC_NAME\*(C'\fR or with the \fB\-n\fR -option. +By default, the \f(CW\*(C`wmm2015\*(C'\fR magnetic model is used. This may changed by +setting the environment variable \f(CW\*(C`GEOGRAPHICLIB_MAGNETIC_NAME\*(C'\fR or with +the \fB\-n\fR option. .PP The magnetic models will be loaded from a directory specified at compile time. This may changed by setting the environment variables -\&\f(CW\*(C`MAGNETIC_PATH\*(C'\fR or \f(CW\*(C`GEOGRAPHICLIB_DATA\*(C'\fR, or with the \fB\-d\fR option. -The \fB\-h\fR option prints the default magnetic path and name. Use the -\&\fB\-v\fR option to ascertain the full path name of the data file. +\&\f(CW\*(C`GEOGRAPHICLIB_MAGNETIC_PATH\*(C'\fR or \f(CW\*(C`GEOGRAPHICLIB_DATA\*(C'\fR, or with the +\&\fB\-d\fR option. The \fB\-h\fR option prints the default magnetic path and +name. Use the \fB\-v\fR option to ascertain the full path name of the data +file. .PP Instructions for downloading and installing magnetic models are available at -. +. .SH "ENVIRONMENT" .IX Header "ENVIRONMENT" -.IP "\fB\s-1MAGNETIC_NAME\s0\fR" 4 -.IX Item "MAGNETIC_NAME" -Override the compile-time default magnetic name of \f(CW\*(C`wmm2010\*(C'\fR. The \fB\-h\fR -option reports the value of \fB\s-1MAGNETIC_NAME\s0\fR, if defined, otherwise it -reports the compile-time value. If the \fB\-n\fR \fIname\fR option is used, -then \fIname\fR takes precedence. -.IP "\fB\s-1MAGNETIC_PATH\s0\fR" 4 -.IX Item "MAGNETIC_PATH" +.IP "\fB\s-1GEOGRAPHICLIB_MAGNETIC_NAME\s0\fR" 4 +.IX Item "GEOGRAPHICLIB_MAGNETIC_NAME" +Override the compile-time default magnetic name of \f(CW\*(C`wmm2015\*(C'\fR. The +\&\fB\-h\fR option reports the value of \fB\s-1GEOGRAPHICLIB_MAGNETIC_NAME\s0\fR, if +defined, otherwise it reports the compile-time value. If the \fB\-n\fR +\&\fIname\fR option is used, then \fIname\fR takes precedence. +.IP "\fB\s-1GEOGRAPHICLIB_MAGNETIC_PATH\s0\fR" 4 +.IX Item "GEOGRAPHICLIB_MAGNETIC_PATH" Override the compile-time default magnetic path. This is typically \&\f(CW\*(C`/usr/local/share/GeographicLib/magnetic\*(C'\fR on Unix-like systems and -\&\f(CW\*(C`C:/Documents and Settings/All Users/Application -Data/GeographicLib/magnetic\*(C'\fR on Windows systems. The \fB\-h\fR option reports -the value of \fB\s-1MAGNETIC_PATH\s0\fR, if defined, otherwise it reports the -compile-time value. If the \fB\-d\fR \fIdir\fR option is used, then \fIdir\fR -takes precedence. +\&\f(CW\*(C`C:/ProgramData/GeographicLib/magnetic\*(C'\fR on Windows systems. The \fB\-h\fR +option reports the value of \fB\s-1GEOGRAPHICLIB_MAGNETIC_PATH\s0\fR, if defined, +otherwise it reports the compile-time value. If the \fB\-d\fR \fIdir\fR option +is used, then \fIdir\fR takes precedence. .IP "\fB\s-1GEOGRAPHICLIB_DATA\s0\fR" 4 .IX Item "GEOGRAPHICLIB_DATA" Another way of overriding the compile-time default magnetic path. If it -is set (and if \fB\s-1MAGNETIC_PATH\s0\fR is not set), then +is set (and if \fB\s-1GEOGRAPHICLIB_MAGNETIC_PATH\s0\fR is not set), then $\fB\s-1GEOGRAPHICLIB_DATA\s0\fR/magnetic is used. .SH "ERRORS" .IX Header "ERRORS" @@ -321,23 +347,23 @@ error and the field (which may be inaccurate) is returned in the normal way. .SH "EXAMPLES" .IX Header "EXAMPLES" -The magnetic field from \s-1WMM2010\s0 in Timbuktu on 2012\-01\-01 +The magnetic field from \s-1WMM2015\s0 in Timbuktu on 2016\-01\-01 .PP .Vb 3 -\& echo 2012\-01\-01 16:46:33N 3:00:34W 300 | MagneticField \-r -\& => \-2.55 12.43 33771.0 33737.6 \-1500.5 7446.0 34582.1 -\& 0.10 \-0.07 34.3 36.8 54.4 \-35.3 25.9 +\& echo 2016\-01\-01 16:46:33N 3:00:34W 300 | MagneticField \-r +\& => \-2.12 12.15 33871.9 33848.7 \-1251.4 7293.9 34648.3 +\& 0.09 \-0.08 31.8 33.8 53.7 \-41.4 22.3 .Ve .PP The first two numbers returned are the declination and inclination of the field. The second line gives the annual change. .SH "SEE ALSO" .IX Header "SEE ALSO" -\&\fIGeoConvert\fR\|(1). +\&\fIGeoConvert\fR\|(1), \fIgeographiclib\-get\-magnetic\fR\|(8). .SH "AUTHOR" .IX Header "AUTHOR" \&\fBMagneticField\fR was written by Charles Karney. .SH "HISTORY" .IX Header "HISTORY" \&\fBMagneticField\fR was added to GeographicLib, -, in version 1.15. +, in version 1.15. diff --git a/gtsam/3rdparty/GeographicLib/man/MagneticField.1.html b/gtsam/3rdparty/GeographicLib/man/MagneticField.1.html index dd1884602..746f45d9f 100644 --- a/gtsam/3rdparty/GeographicLib/man/MagneticField.1.html +++ b/gtsam/3rdparty/GeographicLib/man/MagneticField.1.html @@ -7,7 +7,7 @@ - + @@ -17,13 +17,13 @@

    SYNOPSIS

    -

    MagneticField [ -n name ] [ -d dir ] [ -t time | -c time lat h ] [ -r ] [ -T tguard ] [ -H hguard ] [ -p prec ] [ -v ] [ --comment-delimiter commentdelim ] [ --version | -h | --help ] [ --input-file infile | --input-string instring ] [ --line-separator linesep ] [ --output-file outfile ]

    +

    MagneticField [ -n name ] [ -d dir ] [ -t time | -c time lat h ] [ -r ] [ -w ] [ -T tguard ] [ -H hguard ] [ -p prec ] [ -v ] [ --comment-delimiter commentdelim ] [ --version | -h | --help ] [ --input-file infile | --input-string instring ] [ --line-separator linesep ] [ --output-file outfile ]

    DESCRIPTION

    MagneticField reads in times and positions on standard input and prints out the geomagnetic field on standard output and, optionally, its rate of change.

    -

    The input line is of the form time lat lon h. time is a date of the form 2012-07-03 or a fractional year such as 2012.5. lat and lon are the latitude and longitude expressed as decimal degrees or degrees, minutes, and seconds; see GeoConvert(1) for details. h is the height above the ellipsoid in meters; this is optional and defaults to zero. Alternatively, time can be given on the command line as the argument to the -t option, in which case it should not be included on the input lines. Finally, the magnetic field can be computed at various points on a circle of latitude (constant time, lat, and h) via the -c option; in this case only the longitude should be given on the input lines.

    +

    The input line is of the form time lat lon h. time is a date of the form 2012-07-03, a fractional year such as 2012.5, or the string "now". lat and lon are the latitude and longitude expressed as decimal degrees or degrees, minutes, and seconds; for details on the allowed formats for latitude and longitude, see the GEOGRAPHIC COORDINATES section of GeoConvert(1). h is the height above the ellipsoid in meters; this is optional and defaults to zero. Alternatively, time can be given on the command line as the argument to the -t option, in which case it should not be included on the input lines. Finally, the magnetic field can be computed at various points on a circle of latitude (constant time, lat, and h) via the -c option; in this case only the longitude should be given on the input lines.

    The output consists of the following 7 items:

    @@ -45,25 +45,25 @@
    -
    -n
    +
    -n name
    -

    use magnetic field model name instead of the default wmm2010. See "MODELS".

    +

    use magnetic field model name instead of the default wmm2015. See "MODELS".

    -
    -d
    +
    -d dir

    read magnetic models from dir instead of the default. See "MODELS".

    -
    -t
    +
    -t time

    evaluate the field at time instead of reading the time from the input lines.

    -
    -c
    +
    -c time lat h

    evaluate the field on a circle of latitude given by time, lat, h instead of reading these quantities from the input lines. In this case, MagneticField can calculate the field considerably more quickly.

    @@ -75,19 +75,25 @@

    toggle whether to report the rates of change of the field.

    -
    -T
    +
    -w
    +
    + +

    toggle the longitude first flag (it starts off); if the flag is on, then on input and output, longitude precedes latitude (except that, on input, this can be overridden by a hemisphere designator, N, S, E, W).

    + +
    +
    -T tguard

    signal an error if time lies tguard years (default 50 yr) beyond the range for the model.

    -
    -H
    +
    -H hguard

    signal an error if h lies hguard meters (default 500000 m) beyond the range for the model.

    -
    -p
    +
    -p prec

    set the output precision to prec (default 1). Fields are printed with precision with prec decimal places; angles use prec + 1 places.

    @@ -99,7 +105,7 @@

    print information about the magnetic model on standard error before processing the input.

    -
    --comment-delimiter
    +
    --comment-delimiter commentdelim

    set the comment delimiter to commentdelim (e.g., "#" or "//"). If set, the input lines will be scanned for this delimiter and, if found, the delimiter and the rest of the line will be removed prior to processing and subsequently appended to the output line (separated by a space).

    @@ -123,25 +129,25 @@

    print full documentation and exit.

    -
    --input-file
    +
    --input-file infile

    read input from the file infile instead of from standard input; a file name of "-" stands for standard input.

    -
    --input-string
    +
    --input-string instring

    read input from the string instring instead of from standard input. All occurrences of the line separator character (default is a semicolon) in instring are converted to newlines before the reading begins.

    -
    --line-separator
    +
    --line-separator linesep

    set the line separator character to linesep. By default this is a semicolon.

    -
    --output-file
    +
    --output-file outfile

    write output to the file outfile instead of to standard output; a file name of "-" stands for standard output.

    @@ -154,44 +160,57 @@

    MagneticField computes the geomagnetic field using one of the following models

        wmm2010, the World Magnetic Model 2010, which approximates the
    -      main magnetic field for the period 2010–2015.  See
    -      http://ngdc.noaa.gov/geomag/WMM/DoDWMM.shtml
    +      main magnetic field for the period 2010-2015.  See
    +      https://ngdc.noaa.gov/geomag/WMM/DoDWMM.shtml
    +    wmm2015, the World Magnetic Model 2015, which approximates the
    +      main magnetic field for the period 2015-2020.  See
    +      https://ngdc.noaa.gov/geomag/WMM/DoDWMM.shtml
         igrf11, the International Geomagnetic Reference Field (11th
    -      generation) which approximates the main magnetic field for
    -      the period 1900–2015.  See
    -      http://ngdc.noaa.gov/IAGA/vmod/igrf.html
    -    emm2010, the Enhanced Magnetic Model 2010, which approximates the
    -      main and crustal magnetic fields for the period 2010–2015.  See
    -      http://ngdc.noaa.gov/geomag/EMM/index.html
    + generation), which approximates the main magnetic field for + the period 1900-2015. See + https://ngdc.noaa.gov/IAGA/vmod/igrf.html + igrf12, the International Geomagnetic Reference Field (12th + generation), which approximates the main magnetic field for + the period 1900-2020. See + https://ngdc.noaa.gov/IAGA/vmod/igrf.html + emm2010, the Enhanced Magnetic Model 2010, which approximates + the main and crustal magnetic fields for the period 2010-2015. + See https://ngdc.noaa.gov/geomag/EMM/index.html + emm2015, the Enhanced Magnetic Model 2015, which approximates + the main and crustal magnetic fields for the period 2000-2020. + See https://ngdc.noaa.gov/geomag/EMM/index.html + emm2017, the Enhanced Magnetic Model 2017, which approximates + the main and crustal magnetic fields for the period 2000-2022. + See https://ngdc.noaa.gov/geomag/EMM/index.html
  • -

    These models approximate the magnetic field due to the earth's core and (in the case of emm2010) its crust. They neglect magnetic fields due to the ionosphere, the magnetosphere, nearby magnetized materials, electrical machinery, etc.

    +

    These models approximate the magnetic field due to the earth's core and (in the case of emm20xx) its crust. They neglect magnetic fields due to the ionosphere, the magnetosphere, nearby magnetized materials, electrical machinery, etc.

    -

    By default, the wmm2010 magnetic model is used. This may changed by setting the environment variable MAGNETIC_NAME or with the -n option.

    +

    By default, the wmm2015 magnetic model is used. This may changed by setting the environment variable GEOGRAPHICLIB_MAGNETIC_NAME or with the -n option.

    -

    The magnetic models will be loaded from a directory specified at compile time. This may changed by setting the environment variables MAGNETIC_PATH or GEOGRAPHICLIB_DATA, or with the -d option. The -h option prints the default magnetic path and name. Use the -v option to ascertain the full path name of the data file.

    +

    The magnetic models will be loaded from a directory specified at compile time. This may changed by setting the environment variables GEOGRAPHICLIB_MAGNETIC_PATH or GEOGRAPHICLIB_DATA, or with the -d option. The -h option prints the default magnetic path and name. Use the -v option to ascertain the full path name of the data file.

    -

    Instructions for downloading and installing magnetic models are available at http://geographiclib.sf.net/html/magnetic.html#magneticinst.

    +

    Instructions for downloading and installing magnetic models are available at https://geographiclib.sourceforge.io/html/magnetic.html#magneticinst.

    ENVIRONMENT

    -
    MAGNETIC_NAME
    +
    GEOGRAPHICLIB_MAGNETIC_NAME
    -

    Override the compile-time default magnetic name of wmm2010. The -h option reports the value of MAGNETIC_NAME, if defined, otherwise it reports the compile-time value. If the -n name option is used, then name takes precedence.

    +

    Override the compile-time default magnetic name of wmm2015. The -h option reports the value of GEOGRAPHICLIB_MAGNETIC_NAME, if defined, otherwise it reports the compile-time value. If the -n name option is used, then name takes precedence.

    -
    MAGNETIC_PATH
    +
    GEOGRAPHICLIB_MAGNETIC_PATH
    -

    Override the compile-time default magnetic path. This is typically /usr/local/share/GeographicLib/magnetic on Unix-like systems and C:/Documents and Settings/All Users/Application Data/GeographicLib/magnetic on Windows systems. The -h option reports the value of MAGNETIC_PATH, if defined, otherwise it reports the compile-time value. If the -d dir option is used, then dir takes precedence.

    +

    Override the compile-time default magnetic path. This is typically /usr/local/share/GeographicLib/magnetic on Unix-like systems and C:/ProgramData/GeographicLib/magnetic on Windows systems. The -h option reports the value of GEOGRAPHICLIB_MAGNETIC_PATH, if defined, otherwise it reports the compile-time value. If the -d dir option is used, then dir takes precedence.

    GEOGRAPHICLIB_DATA
    -

    Another way of overriding the compile-time default magnetic path. If it is set (and if MAGNETIC_PATH is not set), then $GEOGRAPHICLIB_DATA/magnetic is used.

    +

    Another way of overriding the compile-time default magnetic path. If it is set (and if GEOGRAPHICLIB_MAGNETIC_PATH is not set), then $GEOGRAPHICLIB_DATA/magnetic is used.

    @@ -202,17 +221,17 @@

    EXAMPLES

    -

    The magnetic field from WMM2010 in Timbuktu on 2012-01-01

    +

    The magnetic field from WMM2015 in Timbuktu on 2016-01-01

    -
        echo 2012-01-01 16:46:33N 3:00:34W 300 | MagneticField -r
    -    => -2.55 12.43 33771.0 33737.6 -1500.5 7446.0 34582.1
    -       0.10 -0.07 34.3 36.8 54.4 -35.3 25.9
    +
        echo 2016-01-01 16:46:33N 3:00:34W 300 | MagneticField -r
    +    => -2.12 12.15 33871.9 33848.7 -1251.4 7293.9 34648.3
    +       0.09 -0.08 31.8 33.8 53.7 -41.4 22.3

    The first two numbers returned are the declination and inclination of the field. The second line gives the annual change.

    SEE ALSO

    -

    GeoConvert(1).

    +

    GeoConvert(1), geographiclib-get-magnetic(8).

    AUTHOR

    @@ -220,7 +239,7 @@

    HISTORY

    -

    MagneticField was added to GeographicLib, http://geographiclib.sf.net, in version 1.15.

    +

    MagneticField was added to GeographicLib, https://geographiclib.sourceforge.io, in version 1.15.

    diff --git a/gtsam/3rdparty/GeographicLib/man/MagneticField.pod b/gtsam/3rdparty/GeographicLib/man/MagneticField.pod index 519e2ac51..58fe0f1bf 100644 --- a/gtsam/3rdparty/GeographicLib/man/MagneticField.pod +++ b/gtsam/3rdparty/GeographicLib/man/MagneticField.pod @@ -6,7 +6,7 @@ MagneticField -- compute the earth's magnetic field B [ B<-n> I ] [ B<-d> I ] [ B<-t> I