Showing preview only (380K chars total). Download the full file or copy to clipboard to get everything.
Repository: tum-vision/online_photometric_calibration
Branch: master
Commit: 3ede3f960ad0
Files: 33
Total size: 366.0 KB
Directory structure:
gitextract_g6ru51pt/
├── .gitignore
├── .gitlab-ci.yml
├── .travis.yml
├── AUTHORS.txt
├── CHANGELOG.md
├── CMakeLists.txt
├── LICENSE.txt
├── README.md
└── src/
├── CLI11.hpp
├── Database.cpp
├── Database.h
├── Feature.h
├── Frame.h
├── GainRobustTracker.cpp
├── GainRobustTracker.h
├── ImageReader.cpp
├── ImageReader.h
├── JacobianGenerator.cpp
├── JacobianGenerator.h
├── NonlinearOptimizer.cpp
├── NonlinearOptimizer.h
├── OptimizationBlock.cpp
├── OptimizationBlock.h
├── OptimizedPoint.h
├── RapidExposureTimeEstimator.cpp
├── RapidExposureTimeEstimator.h
├── ResponseModel.h
├── StandardIncludes.h
├── Tracker.cpp
├── Tracker.h
├── VignetteModel.cpp
├── VignetteModel.h
└── main.cpp
================================================
FILE CONTENTS
================================================
================================================
FILE: .gitignore
================================================
# IDE files
.idea/*
# Compiled Object files
*.slo
*.lo
*.o
*.obj
# Precompiled Headers
*.gch
*.pch
# Compiled Dynamic libraries
*.so
*.dylib
*.dll
# Fortran module files
*.mod
*.smod
# Compiled Static libraries
*.lai
*.la
*.a
*.lib
# Executables
*.exe
*.out
*.app
# Ignored by Rui
CMakeLists.txt.user*
build/
*/build/
*/bin/
*/lib/
*~
cmake-build-*/
================================================
FILE: .gitlab-ci.yml
================================================
# defaults
image: nikolausdemmel/ubuntu-dev-cv:16.04
variables:
BUILD_TYPE: Release
# template definition
.compile_template: &compile_definition
stage: build
before_script:
- mkdir -p ccache
- export CCACHE_BASEDIR=${PWD}
- export CCACHE_DIR=${PWD}/ccache
cache:
paths:
- ccache/
script:
- mkdir build
- cd build
- cmake .. -DCMAKE_BUILD_TYPE=${BUILD_TYPE}
- make -j3
release-16.04:
<<: *compile_definition
debug-16.04:
variables:
BUILD_TYPE: Debug
<<: *compile_definition
clang-16.04:
variables:
CC: /usr/bin/clang-5.0
CXX: /usr/bin/clang++-5.0
<<: *compile_definition
release-14.04:
image: nikolausdemmel/ubuntu-dev-cv:14.04
variables:
CC: /usr/lib/ccache/gcc
CXX: /usr/lib/ccache/g++
<<: *compile_definition
================================================
FILE: .travis.yml
================================================
sudo: required
language: cpp
services:
- docker
cache: ccache
env:
global:
- DOCKER_CONTAINER_NAME=nikolausdemmel/ubuntu-dev-cv-gui
- CC=/usr/bin/gcc
- CXX=/usr/bin/g++
- BUILD_TYPE=Release
matrix:
include:
- os: linux
env: DIST_VERS=16.04
- os: linux
env: DIST_VERS=16.04 CC=/usr/bin/clang-5.0 CXX=/usr/bin/clang++-5.0
- os: linux
env: DIST_VERS=16.04 BUILD_TYPE=Debug
- os: linux
env: DIST_VERS=14.04
- os: osx
before_install:
- if [[ "$TRAVIS_OS_NAME" == "osx" ]]; then brew update; fi
install: |
if [[ "$TRAVIS_OS_NAME" == "linux" ]]; then
docker pull $DOCKER_CONTAINER_NAME:$DIST_VERS
fi
if [[ "$TRAVIS_OS_NAME" == "osx" ]]; then
# upgrade python first, else linking python@2 fails (dependency of opencv@2)
brew upgrade python
# removing pip numpy, else installing brew numpy fails (dependency of opencv@2)
brew install python@2
/usr/bin/yes | pip uninstall numpy
# upgrade already installed
brew upgrade cmake
# install additional dependencies
brew install opencv@2 ccache
fi
script: |
if [[ "$TRAVIS_OS_NAME" == "linux" ]]; then
docker run --name ci -it \
-v ${TRAVIS_BUILD_DIR}:/repo \
-v $HOME/.ccache:/root/.ccache \
-e BUILD_TYPE -e CC -e CXX \
$DOCKER_CONTAINER_NAME:$DIST_VERS \
/bin/bash -c '
export PS4='\''+ \e[33;1m($0 @ line $LINENO) \$\e[0m '\'' # quotes must be escaped
set -e # exit on failure
set -x # trace for debug
mkdir build && cd build
cmake -DCMAKE_BUILD_TYPE=$BUILD_TYPE /repo
cmake --build .'
fi
if [[ "$TRAVIS_OS_NAME" == "osx" ]]; then
mkdir build && cd build
cmake -DCMAKE_BUILD_TYPE=$BUILD_TYPE ..
cmake --build .
fi
# TODO: try w/o docker, just installing from apt; compare speed.
#jobs:
# foo:
================================================
FILE: AUTHORS.txt
================================================
Authors ordered by first contribution.
Paul Bergmann <bergmann@in.tum.de>
Rui Wang <wangr@in.tum.de>
Nikolaus Demmel <demmeln@in.tum.de>
================================================
FILE: CHANGELOG.md
================================================
# Changelog
## [0.1.0] - 2018-05-22
### Added
- Initial release
================================================
FILE: CMakeLists.txt
================================================
cmake_minimum_required(VERSION 3.2)
set(PROJECT_NAME online_photometric_calibration)
project(${PROJECT_NAME})
# Set default build type if not specified otherwise.
# See https://cmake.org/pipermail/cmake/2012-May/050243.html
if(NOT CMAKE_BUILD_TYPE AND NOT CMAKE_CONFIGURATION_TYPES)
set(CMAKE_BUILD_TYPE Release CACHE STRING "Choose the type of build." FORCE)
message(STATUS "Setting build type to '${CMAKE_BUILD_TYPE}' as none was specified.")
# Set the possible values of build type for cmake-gui
set_property(CACHE CMAKE_BUILD_TYPE PROPERTY STRINGS "Debug" "Release"
"MinSizeRel" "RelWithDebInfo")
endif()
# We need at least C++11
set(CMAKE_CXX_STANDARD 11)
set(CMAKE_CXX_STANDARD_REQUIRED ON)
set(CMAKE_CXX_EXTENSIONS OFF)
# set march=native unless specified
if(NOT CXX_MARCH)
set(CXX_MARCH native)
endif()
SET(CMAKE_CXX_FLAGS_RELEASE "-march=${CXX_MARCH} ${CMAKE_CXX_FLAGS_RELEASE}")
SET(CMAKE_CXX_FLAGS_RELWITHDEBINFO "-march=${CXX_MARCH} ${CMAKE_CXX_FLAGS_RELWITHDEBINFO}")
# warnings
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -Wextra -Wno-sign-compare")
# Required libraries
if(APPLE)
# give the homebrew path as hint, since the formula is keg-only
find_package(OpenCV 2.4 REQUIRED HINTS /usr/local/opt/opencv@2)
else()
find_package(OpenCV 2.4 REQUIRED)
endif()
find_package(Threads REQUIRED)
# Configure CCache if available (requires cmake 3.4 or newer)
find_program(CCACHE_PROGRAM ccache)
if(CCACHE_PROGRAM)
message(STATUS "Found ccache: ${CCACHE_PROGRAM}")
set(CMAKE_C_COMPILER_LAUNCHER ${CCACHE_PROGRAM})
set(CMAKE_CXX_COMPILER_LAUNCHER ${CCACHE_PROGRAM})
endif()
# output paths in the build directory
set(CMAKE_ARCHIVE_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/lib)
set(CMAKE_LIBRARY_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/lib)
set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/bin)
# include path
include_directories(${PROJECT_SOURCE_DIR}/src)
# Source files
set(ONLINE_CALIB_SOURCE_FILES
src/Database.cpp
src/GainRobustTracker.cpp
src/ImageReader.cpp
src/JacobianGenerator.cpp
src/NonlinearOptimizer.cpp
src/OptimizationBlock.cpp
src/RapidExposureTimeEstimator.cpp
src/Tracker.cpp
src/VignetteModel.cpp
)
# add include files to custom target so they show up in IDEs like
# QtCreator in the project view
file(GLOB_RECURSE _INCLUDE_FILES "src/*.h" "src/*.hpp")
add_custom_target(_include_files_fix_target SOURCES ${_INCLUDE_FILES})
# main library
add_library(online_pcalib SHARED ${ONLINE_CALIB_SOURCE_FILES})
target_link_libraries(online_pcalib
${OpenCV_LIBS}
${CMAKE_THREAD_LIBS_INIT})
# demo executable for online calibration
add_executable(online_pcalib_demo src/main.cpp)
target_link_libraries(online_pcalib_demo
online_pcalib)
# install rules
install (TARGETS online_pcalib online_pcalib_demo
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin)
================================================
FILE: LICENSE.txt
================================================
3-Clause BSD License
Copyright 2017-2018 Paul Bergmann and co-authors (see AUTHORS.txt)
Redistribution and use in source and binary forms, with or without
modification, are permitted provided that the following conditions are
met:
1. Redistributions of source code must retain the above copyright
notice, this list of conditions and the following disclaimer.
2. Redistributions in binary form must reproduce the above copyright
notice, this list of conditions and the following disclaimer in the
documentation and/or other materials provided with the distribution.
3. Neither the name of the copyright holder nor the names of its
contributors may be used to endorse or promote products derived from
this software without specific prior written permission.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
"AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
================================================
FILE: README.md
================================================
# Online Photometric Calibration
Recent direct visual odometry and SLAM algorithms have demonstrated
impressive levels of precision. However, they require a photometric
camera calibration in order to achieve competitive results. Hence, the
respective algorithm cannot be directly applied to an
off-the-shelf-camera or to a video sequence acquired with an unknown
camera. In this work we propose a method for online photometric
calibration which enables to process auto exposure videos with visual
odometry precisions that are on par with those of photometrically
calibrated videos. Our algorithm recovers the exposure times of
consecutive frames, the camera response function, and the attenuation
factors of the sensor irradiance due to vignetting. Gain robust KLT
feature tracks are used to obtain scene point correspondences as input
to a nonlinear optimization framework. We show that our approach can
reliably calibrate arbitrary video sequences by evaluating it on
datasets for which full photometric ground truth is available. We
further show that our calibration can improve the performance of a
state-of-the-art direct visual odometry method that works solely on
pixel intensities, calibrating for photometric parameters in an online
fashion in realtime. For more details please refer to our paper.
If you use this code in your research, we would appreciate if you cite
the respective publication.
**Online Photometric Calibration of Auto Exposure Video for Realtime Visual Odometry and SLAM**
(P. Bergmann, R. Wang, D. Cremers),
*In IEEE Robotics and Automation Letters (RA-L)*, volume 3, 2018.
[[pdf](https://vision.in.tum.de/_media/spezial/bib/bergmann17calibration.pdf)]
[[video](https://youtu.be/nQHMG0c6Iew)]
For more information on photometric calibration, see
https://vision.in.tum.de/research/vslam/photometric-calibration.
**Note:** *This is a preliminary release. You should consider this
research code in beta. All interfaces are subject to change.*
## Install
We support Ubuntu 14.04 and 16.04, and macOS, but it might work on a
variety of other platforms that meet the dependency requirements.
### Dependencies
The main dependencies are cmake 3.2 or later, a C++11 compiler, and
OpenCV 2.4.
#### Ubuntu 14.04
On Ubuntu 14.04 you need to get a more recent version of cmake.
```
sudo add-apt-repository ppa:george-edison55/cmake-3.x
```
Now continue to install dependencies like for Ubuntu 16.04.
#### Ubuntu 16.04
**Required:**
```
sudo apt-get update
sudo apt-get install \
build-essential \
g++ \
cmake \
libopencv-dev
```
**Optional:**
CCache can help you speed up repeated builds.
*Note:* You need at least cmake version 3.4 for ccache to work
automatically.
```
sudo apt-get install ccache
```
### macOS
We assume you have installed [Homebrew](https://brew.sh).
**Required:**
```
brew install cmake opencv@2
```
**Optional:**
```
brew install ccache
```
### Compile
Start in the package directory.
```
mkdir build
cd build
cmake ..
make -j4
```
Optionally you can install the built libraries and executables.
```
sudo make install
```
## Usage
### Online calibration
**Example usage:**
Download sequence of the TUMmono VO dataset.
```
SEQ=30
wget http://vision.in.tum.de/mono/dataset/sequence_$SEQ.zip
unzip sequence_$SEQ.zip
unzip -d sequence_$SEQ/images sequence_$SEQ/images.zip
```
Run online calibration.
```
build/bin/online_pcalib_demo -i sequence_$SEQ/images --exposure-gt-file sequence_$SEQ/times.txt
```
*Note:* Currently the implementation is not suitable for
fisheye-lenses with black borders around the image, which includes
some of the TUMmono VO dataset sequences as well as the TUM VI
dataset sequences.
### Batch calibration
Online calibration runs the code in a multithreaded way in parallel on the CPU.
If tracking and backend optimization should be performed sequentially and real time
performance is not required, the system can be run in batch calibration mode.
For running in batch mode, simply add the command line option
```
--calibration-mode batch
```
For batch calibration you might want to use the exposure times from the optimization
backend rather than the rapidly estimated exposure times from the frontend. In order
to extract more keyframes to the backend optimizer, the run_settings parameters have to
be adjusted.
These parameters can be changed by manually setting:
```
--nr-active-frames INT Maximum number of frames to be stored in the database.
--keyframe-spacing INT Number of frames that keyframes are apart in the backend optimizer.
--min-keyframes-valid INT Minimum number of frames a feature has to be tracked to be considered for optimization.
```
### Command line options
```
Photometric Calibration
Usage: online_pcalib_demo [OPTIONS]
Options:
-h,--help Print this help message and exit
-i,--image-folder TEXT=images
Folder with image files to read.
--start-image-index INT=0 Start reading from this image index.
--end-image-index INT=-1 Stop reading at this image index.
--image-width INT=640 Resize image to this width.
--image-height INT=480 Resize image to this height.
--exposure-gt-file TEXT=times.txt
Textfile containing ground truth exposure times for each frame for visualization.
--calibration-mode TEXT=online
Choose 'online' or 'batch'
--nr-active-frames INT=200 Maximum number of frames to be stored in the database.
--keyframe-spacing INT=15 Number of frames that keyframes are apart in the backend optimizer.
--min-keyframes-valid INT=3 Minimum number of frames a feature has to be tracked to be considered for optimization.
```
## License
This project was originally developed at the [TUM computer vision
group](https://vision.in.tum.de) in 2017 by Paul Bergmann.
It is currently maintained by Paul Bermann,
[Rui Wang](https://vision.in.tum.de/members/wangr) and
[Nikolaus Demmel](https://vision.in.tum.de/members/demmeln). See
[AUTHROS.txt](AUTHORS.txt) for a list of contributors.
This project is available under a BSD 3-Clause license.
See [LICENSE.txt](LICENSE.txt)
Among others, we make use of the following libraries:
* OpenCV ([BSD](https://opencv.org/license.html))
* CLI11 ([BSD](https://github.com/CLIUtils/CLI11/blob/master/LICENSE))
================================================
FILE: src/CLI11.hpp
================================================
#pragma once
// CLI11: Version 1.5.3
// Originally designed by Henry Schreiner
// https://github.com/CLIUtils/CLI11
//
// This is a standalone header file generated by MakeSingleHeader.py in CLI11/scripts
// from: v1.5.3
//
// From LICENSE:
//
// CLI11 1.5 Copyright (c) 2017-2018 University of Cincinnati, developed by Henry
// Schreiner under NSF AWARD 1414736. All rights reserved.
//
// Redistribution and use in source and binary forms of CLI11, with or without
// modification, are permitted provided that the following conditions are met:
//
// 1. Redistributions of source code must retain the above copyright notice, this
// list of conditions and the following disclaimer.
// 2. Redistributions in binary form must reproduce the above copyright notice,
// this list of conditions and the following disclaimer in the documentation
// and/or other materials provided with the distribution.
// 3. Neither the name of the copyright holder nor the names of its contributors
// may be used to endorse or promote products derived from this software without
// specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
// ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
// WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
// DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
// ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
// ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
// Standard combined includes:
#include <algorithm>
#include <deque>
#include <exception>
#include <fstream>
#include <functional>
#include <iomanip>
#include <iostream>
#include <istream>
#include <iterator>
#include <locale>
#include <memory>
#include <numeric>
#include <set>
#include <sstream>
#include <stdexcept>
#include <string>
#include <sys/stat.h>
#include <sys/types.h>
#include <tuple>
#include <type_traits>
#include <utility>
#include <vector>
// Verbatim copy from CLI/Optional.hpp:
#ifdef __has_include
#if defined(CLI11_CPP17) && __has_include(<optional>) && \
defined(__cpp_lib_optional) && !defined(CLI11_STD_OPTIONAL)
#define CLI11_STD_OPTIONAL
#endif
#if defined(CLI11_CPP14) && __has_include(<experimental/optional>) && \
!defined(CLI11_EXPERIMENTAL_OPTIONAL)
#define CLI11_EXPERIMENTAL_OPTIONAL
#endif
#if __has_include(<boost/optional.hpp>) && !defined(CLI11_BOOST_OPTIONAL)
#include <boost/version.hpp>
#if BOOST_VERSION >= 105800
#define CLI11_BOOST_OPTIONAL
#endif
#endif
#endif
#ifdef CLI11_STD_OPTIONAL
#include <optional>
#endif
#ifdef CLI11_EXPERIMENTAL_OPTIONAL
#include <experimental/optional>
#endif
#ifdef CLI11_BOOST_OPTIONAL
#include <boost/optional.hpp>
#endif
// From CLI/Version.hpp:
namespace CLI {
// Note that all code in CLI11 must be in a namespace, even if it just a define.
#define CLI11_VERSION_MAJOR 1
#define CLI11_VERSION_MINOR 5
#define CLI11_VERSION_PATCH 3
#define CLI11_VERSION "1.5.3"
} // namespace CLI
// From CLI/Macros.hpp:
namespace CLI {
// Note that all code in CLI11 must be in a namespace, even if it just a define.
// The following version macro is very similar to the one in PyBind11
#if !(defined(_MSC_VER) && __cplusplus == 199711L) && !defined(__INTEL_COMPILER)
#if __cplusplus >= 201402L
#define CLI11_CPP14
#if __cplusplus >= 201703L
#define CLI11_CPP17
#if __cplusplus > 201703L
#define CLI11_CPP20
#endif
#endif
#endif
#elif defined(_MSC_VER) && __cplusplus == 199711L
// MSVC sets _MSVC_LANG rather than __cplusplus (supposedly until the standard is fully implemented)
// Unless you use the /Zc:__cplusplus flag on Visual Studio 2017 15.7 Preview 3 or newer
#if _MSVC_LANG >= 201402L
#define CLI11_CPP14
#if _MSVC_LANG > 201402L && _MSC_VER >= 1910
#define CLI11_CPP17
#if __MSVC_LANG > 201703L && _MSC_VER >= 1910
#define CLI11_CPP20
#endif
#endif
#endif
#endif
#if defined(PYBIND11_CPP14)
#define CLI11_DEPRECATED(reason) [[deprecated(reason)]]
#elif defined(_MSC_VER)
#define CLI11_DEPRECATED(reason) __declspec(deprecated(reason))
#else
#define CLI11_DEPRECATED(reason) __attribute__((deprecated(reason)))
#endif
} // namespace CLI
// From CLI/Optional.hpp:
namespace CLI {
#ifdef CLI11_STD_OPTIONAL
template <typename T> std::istream &operator>>(std::istream &in, std::optional<T> &val) {
T v;
in >> v;
val = v;
return in;
}
#endif
#ifdef CLI11_EXPERIMENTAL_OPTIONAL
template <typename T> std::istream &operator>>(std::istream &in, std::experimental::optional<T> &val) {
T v;
in >> v;
val = v;
return in;
}
#endif
#ifdef CLI11_BOOST_OPTIONAL
template <typename T> std::istream &operator>>(std::istream &in, boost::optional<T> &val) {
T v;
in >> v;
val = v;
return in;
}
#endif
// Export the best optional to the CLI namespace
#if defined(CLI11_STD_OPTIONAL)
using std::optional;
#elif defined(CLI11_EXPERIMENTAL_OPTIONAL)
using std::experimental::optional;
#elif defined(CLI11_BOOST_OPTIONAL)
using boost::optional;
#endif
// This is true if any optional is found
#if defined(CLI11_STD_OPTIONAL) || defined(CLI11_EXPERIMENTAL_OPTIONAL) || defined(CLI11_BOOST_OPTIONAL)
#define CLI11_OPTIONAL
#endif
} // namespace CLI
// From CLI/StringTools.hpp:
namespace CLI {
namespace detail {
// Based on http://stackoverflow.com/questions/236129/split-a-string-in-c
/// Split a string by a delim
inline std::vector<std::string> split(const std::string &s, char delim) {
std::vector<std::string> elems;
// Check to see if empty string, give consistent result
if(s.empty())
elems.emplace_back("");
else {
std::stringstream ss;
ss.str(s);
std::string item;
while(std::getline(ss, item, delim)) {
elems.push_back(item);
}
}
return elems;
}
/// Simple function to join a string
template <typename T> std::string join(const T &v, std::string delim = ",") {
std::ostringstream s;
size_t start = 0;
for(const auto &i : v) {
if(start++ > 0)
s << delim;
s << i;
}
return s.str();
}
/// Join a string in reverse order
template <typename T> std::string rjoin(const T &v, std::string delim = ",") {
std::ostringstream s;
for(size_t start = 0; start < v.size(); start++) {
if(start > 0)
s << delim;
s << v[v.size() - start - 1];
}
return s.str();
}
// Based roughly on http://stackoverflow.com/questions/25829143/c-trim-whitespace-from-a-string
/// Trim whitespace from left of string
inline std::string <rim(std::string &str) {
auto it = std::find_if(str.begin(), str.end(), [](char ch) { return !std::isspace<char>(ch, std::locale()); });
str.erase(str.begin(), it);
return str;
}
/// Trim anything from left of string
inline std::string <rim(std::string &str, const std::string &filter) {
auto it = std::find_if(str.begin(), str.end(), [&filter](char ch) { return filter.find(ch) == std::string::npos; });
str.erase(str.begin(), it);
return str;
}
/// Trim whitespace from right of string
inline std::string &rtrim(std::string &str) {
auto it = std::find_if(str.rbegin(), str.rend(), [](char ch) { return !std::isspace<char>(ch, std::locale()); });
str.erase(it.base(), str.end());
return str;
}
/// Trim anything from right of string
inline std::string &rtrim(std::string &str, const std::string &filter) {
auto it =
std::find_if(str.rbegin(), str.rend(), [&filter](char ch) { return filter.find(ch) == std::string::npos; });
str.erase(it.base(), str.end());
return str;
}
/// Trim whitespace from string
inline std::string &trim(std::string &str) { return ltrim(rtrim(str)); }
/// Trim anything from string
inline std::string &trim(std::string &str, const std::string filter) { return ltrim(rtrim(str, filter), filter); }
/// Make a copy of the string and then trim it
inline std::string trim_copy(const std::string &str) {
std::string s = str;
return trim(s);
}
/// Make a copy of the string and then trim it, any filter string can be used (any char in string is filtered)
inline std::string trim_copy(const std::string &str, const std::string &filter) {
std::string s = str;
return trim(s, filter);
}
/// Print a two part "help" string
inline void format_help(std::stringstream &out, std::string name, std::string description, size_t wid) {
name = " " + name;
out << std::setw(static_cast<int>(wid)) << std::left << name;
if(!description.empty()) {
if(name.length() >= wid)
out << std::endl << std::setw(static_cast<int>(wid)) << "";
out << description;
}
out << std::endl;
}
/// Verify the first character of an option
template <typename T> bool valid_first_char(T c) { return std::isalpha(c, std::locale()) || c == '_'; }
/// Verify following characters of an option
template <typename T> bool valid_later_char(T c) {
return std::isalnum(c, std::locale()) || c == '_' || c == '.' || c == '-';
}
/// Verify an option name
inline bool valid_name_string(const std::string &str) {
if(str.empty() || !valid_first_char(str[0]))
return false;
for(auto c : str.substr(1))
if(!valid_later_char(c))
return false;
return true;
}
/// Return a lower case version of a string
inline std::string to_lower(std::string str) {
std::transform(std::begin(str), std::end(str), std::begin(str), [](const std::string::value_type &x) {
return std::tolower(x, std::locale());
});
return str;
}
/// Split a string '"one two" "three"' into 'one two', 'three'
inline std::vector<std::string> split_up(std::string str) {
std::vector<char> delims = {'\'', '\"'};
auto find_ws = [](char ch) { return std::isspace<char>(ch, std::locale()); };
trim(str);
std::vector<std::string> output;
while(!str.empty()) {
if(str[0] == '\'') {
auto end = str.find('\'', 1);
if(end != std::string::npos) {
output.push_back(str.substr(1, end - 1));
str = str.substr(end + 1);
} else {
output.push_back(str.substr(1));
str = "";
}
} else if(str[0] == '\"') {
auto end = str.find('\"', 1);
if(end != std::string::npos) {
output.push_back(str.substr(1, end - 1));
str = str.substr(end + 1);
} else {
output.push_back(str.substr(1));
str = "";
}
} else {
auto it = std::find_if(std::begin(str), std::end(str), find_ws);
if(it != std::end(str)) {
std::string value = std::string(str.begin(), it);
output.push_back(value);
str = std::string(it, str.end());
} else {
output.push_back(str);
str = "";
}
}
trim(str);
}
return output;
}
/// Add a leader to the beginning of all new lines (nothing is added
/// at the start of the first line). `"; "` would be for ini files
///
/// Can't use Regex, or this would be a subs.
inline std::string fix_newlines(std::string leader, std::string input) {
std::string::size_type n = 0;
while(n != std::string::npos && n < input.size()) {
n = input.find('\n', n);
if(n != std::string::npos) {
input = input.substr(0, n + 1) + leader + input.substr(n + 1);
n += leader.size();
}
}
return input;
}
} // namespace detail
} // namespace CLI
// From CLI/Error.hpp:
namespace CLI {
// Use one of these on all error classes
#define CLI11_ERROR_DEF(parent, name) \
protected: \
name(std::string name, std::string msg, int exit_code) : parent(std::move(name), std::move(msg), exit_code) {} \
name(std::string name, std::string msg, ExitCodes exit_code) \
: parent(std::move(name), std::move(msg), exit_code) {} \
\
public: \
name(std::string msg, ExitCodes exit_code) : parent(#name, std::move(msg), exit_code) {} \
name(std::string msg, int exit_code) : parent(#name, std::move(msg), exit_code) {}
// This is added after the one above if a class is used directly and builds its own message
#define CLI11_ERROR_SIMPLE(name) \
explicit name(std::string msg) : name(#name, msg, ExitCodes::name) {}
/// These codes are part of every error in CLI. They can be obtained from e using e.exit_code or as a quick shortcut,
/// int values from e.get_error_code().
enum class ExitCodes {
Success = 0,
IncorrectConstruction = 100,
BadNameString,
OptionAlreadyAdded,
FileError,
ConversionError,
ValidationError,
RequiredError,
RequiresError,
ExcludesError,
ExtrasError,
INIError,
InvalidError,
HorribleError,
OptionNotFound,
ArgumentMismatch,
BaseClass = 127
};
// Error definitions
/// @defgroup error_group Errors
/// @brief Errors thrown by CLI11
///
/// These are the errors that can be thrown. Some of them, like CLI::Success, are not really errors.
/// @{
/// All errors derive from this one
class Error : public std::runtime_error {
int exit_code;
std::string name{"Error"};
public:
int get_exit_code() const { return exit_code; }
std::string get_name() const { return name; }
Error(std::string name, std::string msg, int exit_code = static_cast<int>(ExitCodes::BaseClass))
: runtime_error(msg), exit_code(exit_code), name(std::move(name)) {}
Error(std::string name, std::string msg, ExitCodes exit_code) : Error(name, msg, static_cast<int>(exit_code)) {}
};
// Note: Using Error::Error constructors does not work on GCC 4.7
/// Construction errors (not in parsing)
class ConstructionError : public Error {
CLI11_ERROR_DEF(Error, ConstructionError)
};
/// Thrown when an option is set to conflicting values (non-vector and multi args, for example)
class IncorrectConstruction : public ConstructionError {
CLI11_ERROR_DEF(ConstructionError, IncorrectConstruction)
CLI11_ERROR_SIMPLE(IncorrectConstruction)
static IncorrectConstruction PositionalFlag(std::string name) {
return IncorrectConstruction(name + ": Flags cannot be positional");
}
static IncorrectConstruction Set0Opt(std::string name) {
return IncorrectConstruction(name + ": Cannot set 0 expected, use a flag instead");
}
static IncorrectConstruction SetFlag(std::string name) {
return IncorrectConstruction(name + ": Cannot set an expected number for flags");
}
static IncorrectConstruction ChangeNotVector(std::string name) {
return IncorrectConstruction(name + ": You can only change the expected arguments for vectors");
}
static IncorrectConstruction AfterMultiOpt(std::string name) {
return IncorrectConstruction(
name + ": You can't change expected arguments after you've changed the multi option policy!");
}
static IncorrectConstruction MissingOption(std::string name) {
return IncorrectConstruction("Option " + name + " is not defined");
}
static IncorrectConstruction MultiOptionPolicy(std::string name) {
return IncorrectConstruction(name + ": multi_option_policy only works for flags and exact value options");
}
};
/// Thrown on construction of a bad name
class BadNameString : public ConstructionError {
CLI11_ERROR_DEF(ConstructionError, BadNameString)
CLI11_ERROR_SIMPLE(BadNameString)
static BadNameString OneCharName(std::string name) { return BadNameString("Invalid one char name: " + name); }
static BadNameString BadLongName(std::string name) { return BadNameString("Bad long name: " + name); }
static BadNameString DashesOnly(std::string name) {
return BadNameString("Must have a name, not just dashes: " + name);
}
static BadNameString MultiPositionalNames(std::string name) {
return BadNameString("Only one positional name allowed, remove: " + name);
}
};
/// Thrown when an option already exists
class OptionAlreadyAdded : public ConstructionError {
CLI11_ERROR_DEF(ConstructionError, OptionAlreadyAdded)
explicit OptionAlreadyAdded(std::string name)
: OptionAlreadyAdded(name + " is already added", ExitCodes::OptionAlreadyAdded) {}
static OptionAlreadyAdded Requires(std::string name, std::string other) {
return OptionAlreadyAdded(name + " requires " + other, ExitCodes::OptionAlreadyAdded);
}
static OptionAlreadyAdded Excludes(std::string name, std::string other) {
return OptionAlreadyAdded(name + " excludes " + other, ExitCodes::OptionAlreadyAdded);
}
};
// Parsing errors
/// Anything that can error in Parse
class ParseError : public Error {
CLI11_ERROR_DEF(Error, ParseError)
};
// Not really "errors"
/// This is a successful completion on parsing, supposed to exit
class Success : public ParseError {
CLI11_ERROR_DEF(ParseError, Success)
Success() : Success("Successfully completed, should be caught and quit", ExitCodes::Success) {}
};
/// -h or --help on command line
class CallForHelp : public ParseError {
CLI11_ERROR_DEF(ParseError, CallForHelp)
CallForHelp() : CallForHelp("This should be caught in your main function, see examples", ExitCodes::Success) {}
};
/// Does not output a diagnostic in CLI11_PARSE, but allows to return from main() with a specific error code.
class RuntimeError : public ParseError {
CLI11_ERROR_DEF(ParseError, RuntimeError)
explicit RuntimeError(int exit_code = 1) : RuntimeError("Runtime error", exit_code) {}
};
/// Thrown when parsing an INI file and it is missing
class FileError : public ParseError {
CLI11_ERROR_DEF(ParseError, FileError)
CLI11_ERROR_SIMPLE(FileError)
static FileError Missing(std::string name) { return FileError(name + " was not readable (missing?)"); }
};
/// Thrown when conversion call back fails, such as when an int fails to coerce to a string
class ConversionError : public ParseError {
CLI11_ERROR_DEF(ParseError, ConversionError)
CLI11_ERROR_SIMPLE(ConversionError)
ConversionError(std::string member, std::string name)
: ConversionError("The value " + member + " is not an allowed value for " + name) {}
ConversionError(std::string name, std::vector<std::string> results)
: ConversionError("Could not convert: " + name + " = " + detail::join(results)) {}
static ConversionError TooManyInputsFlag(std::string name) {
return ConversionError(name + ": too many inputs for a flag");
}
static ConversionError TrueFalse(std::string name) {
return ConversionError(name + ": Should be true/false or a number");
}
};
/// Thrown when validation of results fails
class ValidationError : public ParseError {
CLI11_ERROR_DEF(ParseError, ValidationError)
CLI11_ERROR_SIMPLE(ValidationError)
explicit ValidationError(std::string name, std::string msg) : ValidationError(name + ": " + msg) {}
};
/// Thrown when a required option is missing
class RequiredError : public ParseError {
CLI11_ERROR_DEF(ParseError, RequiredError)
explicit RequiredError(std::string name) : RequiredError(name + " is required", ExitCodes::RequiredError) {}
static RequiredError Subcommand(size_t min_subcom) {
if(min_subcom == 1)
return RequiredError("A subcommand");
else
return RequiredError("Requires at least " + std::to_string(min_subcom) + " subcommands",
ExitCodes::RequiredError);
}
};
/// Thrown when the wrong number of arguments has been received
class ArgumentMismatch : public ParseError {
CLI11_ERROR_DEF(ParseError, ArgumentMismatch)
CLI11_ERROR_SIMPLE(ArgumentMismatch)
ArgumentMismatch(std::string name, int expected, size_t recieved)
: ArgumentMismatch(expected > 0 ? ("Expected exactly " + std::to_string(expected) + " arguments to " + name +
", got " + std::to_string(recieved))
: ("Expected at least " + std::to_string(-expected) + " arguments to " + name +
", got " + std::to_string(recieved)),
ExitCodes::ArgumentMismatch) {}
static ArgumentMismatch AtLeast(std::string name, int num) {
return ArgumentMismatch(name + ": At least " + std::to_string(num) + " required");
}
static ArgumentMismatch TypedAtLeast(std::string name, int num, std::string type) {
return ArgumentMismatch(name + ": " + std::to_string(num) + " required " + type + " missing");
}
};
/// Thrown when a requires option is missing
class RequiresError : public ParseError {
CLI11_ERROR_DEF(ParseError, RequiresError)
RequiresError(std::string curname, std::string subname)
: RequiresError(curname + " requires " + subname, ExitCodes::RequiresError) {}
};
/// Thrown when an excludes option is present
class ExcludesError : public ParseError {
CLI11_ERROR_DEF(ParseError, ExcludesError)
ExcludesError(std::string curname, std::string subname)
: ExcludesError(curname + " excludes " + subname, ExitCodes::ExcludesError) {}
};
/// Thrown when too many positionals or options are found
class ExtrasError : public ParseError {
CLI11_ERROR_DEF(ParseError, ExtrasError)
explicit ExtrasError(std::vector<std::string> args)
: ExtrasError((args.size() > 1 ? "The following arguments were not expected: "
: "The following argument was not expected: ") +
detail::rjoin(args, " "),
ExitCodes::ExtrasError) {}
};
/// Thrown when extra values are found in an INI file
class INIError : public ParseError {
CLI11_ERROR_DEF(ParseError, INIError)
CLI11_ERROR_SIMPLE(INIError)
static INIError Extras(std::string item) { return INIError("INI was not able to parse " + item); }
static INIError NotConfigurable(std::string item) {
return INIError(item + ": This option is not allowed in a configuration file");
}
};
/// Thrown when validation fails before parsing
class InvalidError : public ParseError {
CLI11_ERROR_DEF(ParseError, InvalidError)
explicit InvalidError(std::string name)
: InvalidError(name + ": Too many positional arguments with unlimited expected args", ExitCodes::InvalidError) {
}
};
/// This is just a safety check to verify selection and parsing match - you should not ever see it
/// Strings are directly added to this error, but again, it should never be seen.
class HorribleError : public ParseError {
CLI11_ERROR_DEF(ParseError, HorribleError)
CLI11_ERROR_SIMPLE(HorribleError)
};
// After parsing
/// Thrown when counting a non-existent option
class OptionNotFound : public Error {
CLI11_ERROR_DEF(Error, OptionNotFound)
explicit OptionNotFound(std::string name) : OptionNotFound(name + " not found", ExitCodes::OptionNotFound) {}
};
/// @}
} // namespace CLI
// From CLI/TypeTools.hpp:
namespace CLI {
// Type tools
// We could check to see if C++14 is being used, but it does not hurt to redefine this
// (even Google does this: https://github.com/google/skia/blob/master/include/private/SkTLogic.h)
// It is not in the std namespace anyway, so no harm done.
template <bool B, class T = void> using enable_if_t = typename std::enable_if<B, T>::type;
template <typename T> struct is_vector { static const bool value = false; };
template <class T, class A> struct is_vector<std::vector<T, A>> { static bool const value = true; };
template <typename T> struct is_bool { static const bool value = false; };
template <> struct is_bool<bool> { static bool const value = true; };
namespace detail {
// Based generally on https://rmf.io/cxx11/almost-static-if
/// Simple empty scoped class
enum class enabler {};
/// An instance to use in EnableIf
constexpr enabler dummy = {};
// Type name print
/// Was going to be based on
/// http://stackoverflow.com/questions/1055452/c-get-name-of-type-in-template
/// But this is cleaner and works better in this case
template <typename T,
enable_if_t<std::is_integral<T>::value && std::is_signed<T>::value, detail::enabler> = detail::dummy>
constexpr const char *type_name() {
return "INT";
}
template <typename T,
enable_if_t<std::is_integral<T>::value && std::is_unsigned<T>::value, detail::enabler> = detail::dummy>
constexpr const char *type_name() {
return "UINT";
}
template <typename T, enable_if_t<std::is_floating_point<T>::value, detail::enabler> = detail::dummy>
constexpr const char *type_name() {
return "FLOAT";
}
/// This one should not be used, since vector types print the internal type
template <typename T, enable_if_t<is_vector<T>::value, detail::enabler> = detail::dummy>
constexpr const char *type_name() {
return "VECTOR";
}
template <typename T,
enable_if_t<!std::is_floating_point<T>::value && !std::is_integral<T>::value && !is_vector<T>::value,
detail::enabler> = detail::dummy>
constexpr const char *type_name() {
return "TEXT";
}
// Lexical cast
/// Signed integers / enums
template <typename T,
enable_if_t<(std::is_integral<T>::value && std::is_signed<T>::value), detail::enabler> = detail::dummy>
bool lexical_cast(std::string input, T &output) {
try {
size_t n = 0;
long long output_ll = std::stoll(input, &n, 0);
output = static_cast<T>(output_ll);
return n == input.size() && static_cast<long long>(output) == output_ll;
} catch(const std::invalid_argument &) {
return false;
} catch(const std::out_of_range &) {
return false;
}
}
/// Unsigned integers
template <typename T,
enable_if_t<std::is_integral<T>::value && std::is_unsigned<T>::value, detail::enabler> = detail::dummy>
bool lexical_cast(std::string input, T &output) {
if(!input.empty() && input.front() == '-')
return false; // std::stoull happily converts negative values to junk without any errors.
try {
size_t n = 0;
unsigned long long output_ll = std::stoull(input, &n, 0);
output = static_cast<T>(output_ll);
return n == input.size() && static_cast<unsigned long long>(output) == output_ll;
} catch(const std::invalid_argument &) {
return false;
} catch(const std::out_of_range &) {
return false;
}
}
/// Floats
template <typename T, enable_if_t<std::is_floating_point<T>::value, detail::enabler> = detail::dummy>
bool lexical_cast(std::string input, T &output) {
try {
size_t n = 0;
output = static_cast<T>(std::stold(input, &n));
return n == input.size();
} catch(const std::invalid_argument &) {
return false;
} catch(const std::out_of_range &) {
return false;
}
}
/// String and similar
template <typename T,
enable_if_t<!std::is_floating_point<T>::value && !std::is_integral<T>::value &&
std::is_assignable<T &, std::string>::value,
detail::enabler> = detail::dummy>
bool lexical_cast(std::string input, T &output) {
output = input;
return true;
}
/// Non-string parsable
template <typename T,
enable_if_t<!std::is_floating_point<T>::value && !std::is_integral<T>::value &&
!std::is_assignable<T &, std::string>::value,
detail::enabler> = detail::dummy>
bool lexical_cast(std::string input, T &output) {
std::istringstream is;
is.str(input);
is >> output;
return !is.fail() && !is.rdbuf()->in_avail();
}
} // namespace detail
} // namespace CLI
// From CLI/Split.hpp:
namespace CLI {
namespace detail {
// Returns false if not a short option. Otherwise, sets opt name and rest and returns true
inline bool split_short(const std::string ¤t, std::string &name, std::string &rest) {
if(current.size() > 1 && current[0] == '-' && valid_first_char(current[1])) {
name = current.substr(1, 1);
rest = current.substr(2);
return true;
} else
return false;
}
// Returns false if not a long option. Otherwise, sets opt name and other side of = and returns true
inline bool split_long(const std::string ¤t, std::string &name, std::string &value) {
if(current.size() > 2 && current.substr(0, 2) == "--" && valid_first_char(current[2])) {
auto loc = current.find("=");
if(loc != std::string::npos) {
name = current.substr(2, loc - 2);
value = current.substr(loc + 1);
} else {
name = current.substr(2);
value = "";
}
return true;
} else
return false;
}
// Splits a string into multiple long and short names
inline std::vector<std::string> split_names(std::string current) {
std::vector<std::string> output;
size_t val;
while((val = current.find(",")) != std::string::npos) {
output.push_back(trim_copy(current.substr(0, val)));
current = current.substr(val + 1);
}
output.push_back(trim_copy(current));
return output;
}
/// Get a vector of short names, one of long names, and a single name
inline std::tuple<std::vector<std::string>, std::vector<std::string>, std::string>
get_names(const std::vector<std::string> &input) {
std::vector<std::string> short_names;
std::vector<std::string> long_names;
std::string pos_name;
for(std::string name : input) {
if(name.length() == 0)
continue;
else if(name.length() > 1 && name[0] == '-' && name[1] != '-') {
if(name.length() == 2 && valid_first_char(name[1]))
short_names.emplace_back(1, name[1]);
else
throw BadNameString::OneCharName(name);
} else if(name.length() > 2 && name.substr(0, 2) == "--") {
name = name.substr(2);
if(valid_name_string(name))
long_names.push_back(name);
else
throw BadNameString::BadLongName(name);
} else if(name == "-" || name == "--") {
throw BadNameString::DashesOnly(name);
} else {
if(pos_name.length() > 0)
throw BadNameString::MultiPositionalNames(name);
pos_name = name;
}
}
return std::tuple<std::vector<std::string>, std::vector<std::string>, std::string>(
short_names, long_names, pos_name);
}
} // namespace detail
} // namespace CLI
// From CLI/Ini.hpp:
namespace CLI {
namespace detail {
inline std::string inijoin(std::vector<std::string> args) {
std::ostringstream s;
size_t start = 0;
for(const auto &arg : args) {
if(start++ > 0)
s << " ";
auto it = std::find_if(arg.begin(), arg.end(), [](char ch) { return std::isspace<char>(ch, std::locale()); });
if(it == arg.end())
s << arg;
else if(arg.find(R"(")") == std::string::npos)
s << R"(")" << arg << R"(")";
else
s << R"(')" << arg << R"(')";
}
return s.str();
}
struct ini_ret_t {
/// This is the full name with dots
std::string fullname;
/// Listing of inputs
std::vector<std::string> inputs;
/// Current parent level
size_t level = 0;
/// Return parent or empty string, based on level
///
/// Level 0, a.b.c would return a
/// Level 1, a.b.c could return b
std::string parent() const {
std::vector<std::string> plist = detail::split(fullname, '.');
if(plist.size() > (level + 1))
return plist[level];
else
return "";
}
/// Return name
std::string name() const {
std::vector<std::string> plist = detail::split(fullname, '.');
return plist.at(plist.size() - 1);
}
};
/// Internal parsing function
inline std::vector<ini_ret_t> parse_ini(std::istream &input) {
std::string name, line;
std::string section = "default";
std::vector<ini_ret_t> output;
while(getline(input, line)) {
std::vector<std::string> items;
detail::trim(line);
size_t len = line.length();
if(len > 1 && line[0] == '[' && line[len - 1] == ']') {
section = line.substr(1, len - 2);
} else if(len > 0 && line[0] != ';') {
output.emplace_back();
ini_ret_t &out = output.back();
// Find = in string, split and recombine
auto pos = line.find("=");
if(pos != std::string::npos) {
name = detail::trim_copy(line.substr(0, pos));
std::string item = detail::trim_copy(line.substr(pos + 1));
items = detail::split_up(item);
} else {
name = detail::trim_copy(line);
items = {"ON"};
}
if(detail::to_lower(section) == "default")
out.fullname = name;
else
out.fullname = section + "." + name;
out.inputs.insert(std::end(out.inputs), std::begin(items), std::end(items));
}
}
return output;
}
/// Parse an INI file, throw an error (ParseError:INIParseError or FileError) on failure
inline std::vector<ini_ret_t> parse_ini(const std::string &name) {
std::ifstream input{name};
if(!input.good())
throw FileError::Missing(name);
return parse_ini(input);
}
} // namespace detail
} // namespace CLI
// From CLI/Validators.hpp:
namespace CLI {
/// @defgroup validator_group Validators
/// @brief Some validators that are provided
///
/// These are simple `void(std::string&)` validators that are useful. They throw
/// a ValidationError if they fail (or the normally expected error if the cast fails)
/// @{
/// Check for an existing file
inline std::string ExistingFile(const std::string &filename) {
struct stat buffer;
bool exist = stat(filename.c_str(), &buffer) == 0;
bool is_dir = (buffer.st_mode & S_IFDIR) != 0;
if(!exist) {
return "File does not exist: " + filename;
} else if(is_dir) {
return "File is actually a directory: " + filename;
}
return std::string();
}
/// Check for an existing directory
inline std::string ExistingDirectory(const std::string &filename) {
struct stat buffer;
bool exist = stat(filename.c_str(), &buffer) == 0;
bool is_dir = (buffer.st_mode & S_IFDIR) != 0;
if(!exist) {
return "Directory does not exist: " + filename;
} else if(!is_dir) {
return "Directory is actually a file: " + filename;
}
return std::string();
}
/// Check for an existing path
inline std::string ExistingPath(const std::string &filename) {
struct stat buffer;
bool const exist = stat(filename.c_str(), &buffer) == 0;
if(!exist) {
return "Path does not exist: " + filename;
}
return std::string();
}
/// Check for a non-existing path
inline std::string NonexistentPath(const std::string &filename) {
struct stat buffer;
bool exist = stat(filename.c_str(), &buffer) == 0;
if(exist) {
return "Path already exists: " + filename;
}
return std::string();
}
/// Produce a range validator function
template <typename T> std::function<std::string(const std::string &)> Range(T min, T max) {
return [min, max](std::string input) {
T val;
detail::lexical_cast(input, val);
if(val < min || val > max)
return "Value " + input + " not in range " + std::to_string(min) + " to " + std::to_string(max);
return std::string();
};
}
/// Range of one value is 0 to value
template <typename T> std::function<std::string(const std::string &)> Range(T max) {
return Range(static_cast<T>(0), max);
}
/// @}
} // namespace CLI
// From CLI/Option.hpp:
namespace CLI {
using results_t = std::vector<std::string>;
using callback_t = std::function<bool(results_t)>;
class Option;
class App;
using Option_p = std::unique_ptr<Option>;
enum class MultiOptionPolicy { Throw, TakeLast, TakeFirst, Join };
template <typename CRTP> class OptionBase {
friend App;
protected:
/// The group membership
std::string group_ = std::string("Options");
/// True if this is a required option
bool required_{false};
/// Ignore the case when matching (option, not value)
bool ignore_case_{false};
/// Allow this option to be given in a configuration file
bool configurable_{true};
/// Policy for multiple arguments when `expected_ == 1` (can be set on bool flags, too)
MultiOptionPolicy multi_option_policy_{MultiOptionPolicy::Throw};
template <typename T> void copy_to(T *other) const {
other->group(group_);
other->required(required_);
other->ignore_case(ignore_case_);
other->configurable(configurable_);
other->multi_option_policy(multi_option_policy_);
}
public:
// setters
/// Changes the group membership
CRTP *group(std::string name) {
group_ = name;
return static_cast<CRTP *>(this);
;
}
/// Set the option as required
CRTP *required(bool value = true) {
required_ = value;
return static_cast<CRTP *>(this);
}
/// Support Plumbum term
CRTP *mandatory(bool value = true) { return required(value); }
// Getters
/// Get the group of this option
const std::string &get_group() const { return group_; }
/// True if this is a required option
bool get_required() const { return required_; }
/// The status of ignore case
bool get_ignore_case() const { return ignore_case_; }
/// The status of configurable
bool get_configurable() const { return configurable_; }
/// The status of the multi option policy
MultiOptionPolicy get_multi_option_policy() const { return multi_option_policy_; }
// Shortcuts for multi option policy
/// Set the multi option policy to take last
CRTP *take_last() {
auto self = static_cast<CRTP *>(this);
self->multi_option_policy(MultiOptionPolicy::TakeLast);
return self;
}
/// Set the multi option policy to take last
CRTP *take_first() {
auto self = static_cast<CRTP *>(this);
self->multi_option_policy(MultiOptionPolicy::TakeFirst);
return self;
}
/// Set the multi option policy to take last
CRTP *join() {
auto self = static_cast<CRTP *>(this);
self->multi_option_policy(MultiOptionPolicy::Join);
return self;
}
/// Allow in a configuration file
CRTP *configurable(bool value = true) {
configurable_ = value;
return static_cast<CRTP *>(this);
}
};
class OptionDefaults : public OptionBase<OptionDefaults> {
public:
OptionDefaults() = default;
// Methods here need a different implementation if they are Option vs. OptionDefault
/// Take the last argument if given multiple times
OptionDefaults *multi_option_policy(MultiOptionPolicy value = MultiOptionPolicy::Throw) {
multi_option_policy_ = value;
return this;
}
/// Ignore the case of the option name
OptionDefaults *ignore_case(bool value = true) {
ignore_case_ = value;
return this;
}
};
class Option : public OptionBase<Option> {
friend App;
protected:
/// @name Names
///@{
/// A list of the short names (`-a`) without the leading dashes
std::vector<std::string> snames_;
/// A list of the long names (`--a`) without the leading dashes
std::vector<std::string> lnames_;
/// A positional name
std::string pname_;
/// If given, check the environment for this option
std::string envname_;
///@}
/// @name Help
///@{
/// The description for help strings
std::string description_;
/// A human readable default value, usually only set if default is true in creation
std::string defaultval_;
/// A human readable type value, set when App creates this
std::string typeval_;
/// True if this option has a default
bool default_{false};
///@}
/// @name Configuration
///@{
/// The number of arguments that make up one option. -1=unlimited (vector-like), 0=flag, 1=normal option,
/// 2=complex/pair, etc. Set only when the option is created; this is intrinsic to the type. Eventually, -2 may mean
/// vector of pairs.
int type_size_{1};
/// The number of expected values, type_size_ must be < 0. Ignored for flag. N < 0 means at least -N values.
int expected_{1};
/// A list of validators to run on each value parsed
std::vector<std::function<std::string(std::string &)>> validators_;
/// A list of options that are required with this option
std::set<Option *> requires_;
/// A list of options that are excluded with this option
std::set<Option *> excludes_;
///@}
/// @name Other
///@{
/// Remember the parent app
App *parent_;
/// Options store a callback to do all the work
callback_t callback_;
///@}
/// @name Parsing results
///@{
/// Results of parsing
results_t results_;
/// Whether the callback has run (needed for INI parsing)
bool callback_run_{false};
///@}
/// Making an option by hand is not defined, it must be made by the App class
Option(std::string name,
std::string description = "",
std::function<bool(results_t)> callback = [](results_t) { return true; },
bool default_ = true,
App *parent = nullptr)
: description_(std::move(description)), default_(default_), parent_(parent), callback_(std::move(callback)) {
std::tie(snames_, lnames_, pname_) = detail::get_names(detail::split_names(name));
}
public:
/// @name Basic
///@{
/// Count the total number of times an option was passed
size_t count() const { return results_.size(); }
/// This class is true if option is passed.
operator bool() const { return count() > 0; }
/// Clear the parsed results (mostly for testing)
void clear() { results_.clear(); }
///@}
/// @name Setting options
///@{
/// Set the number of expected arguments (Flags don't use this)
Option *expected(int value) {
// Break if this is a flag
if(type_size_ == 0)
throw IncorrectConstruction::SetFlag(single_name());
// Setting 0 is not allowed
else if(value == 0)
throw IncorrectConstruction::Set0Opt(single_name());
// No change is okay, quit now
else if(expected_ == value)
return this;
// Type must be a vector
else if(type_size_ >= 0)
throw IncorrectConstruction::ChangeNotVector(single_name());
// TODO: Can support multioption for non-1 values (except for join)
else if(value != 1 && multi_option_policy_ != MultiOptionPolicy::Throw)
throw IncorrectConstruction::AfterMultiOpt(single_name());
expected_ = value;
return this;
}
/// Adds a validator
Option *check(std::function<std::string(const std::string &)> validator) {
validators_.emplace_back(validator);
return this;
}
/// Adds a validator-like function that can change result
Option *transform(std::function<std::string(std::string)> func) {
validators_.emplace_back([func](std::string &inout) {
try {
inout = func(inout);
} catch(const ValidationError &e) {
return std::string(e.what());
}
return std::string();
});
return this;
}
/// Sets required options
Option *needs(Option *opt) {
auto tup = requires_.insert(opt);
if(!tup.second)
throw OptionAlreadyAdded::Requires(single_name(), opt->single_name());
return this;
}
/// Can find a string if needed
template <typename T = App> Option *needs(std::string opt_name) {
for(const Option_p &opt : dynamic_cast<T *>(parent_)->options_)
if(opt.get() != this && opt->check_name(opt_name))
return needs(opt.get());
throw IncorrectConstruction::MissingOption(opt_name);
}
/// Any number supported, any mix of string and Opt
template <typename A, typename B, typename... ARG> Option *needs(A opt, B opt1, ARG... args) {
needs(opt);
return needs(opt1, args...);
}
#ifndef CLI11_CPP20
/// Sets required options \deprecated
CLI11_DEPRECATED("Use needs instead of requires (eventual keyword clash)")
Option *requires(Option *opt) { return needs(opt); }
/// Can find a string if needed \deprecated
template <typename T = App> Option *requires(std::string opt_name) {
for(const Option_p &opt : dynamic_cast<T *>(parent_)->options_)
if(opt.get() != this && opt->check_name(opt_name))
return needs(opt.get());
throw IncorrectConstruction::MissingOption(opt_name);
}
/// Any number supported, any mix of string and Opt \deprecated
template <typename A, typename B, typename... ARG> Option *requires(A opt, B opt1, ARG... args) {
requires(opt);
return requires(opt1, args...);
}
#endif
/// Sets excluded options
Option *excludes(Option *opt) {
excludes_.insert(opt);
// Help text should be symmetric - excluding a should exclude b
opt->excludes_.insert(this);
// Ignoring the insert return value, excluding twice is now allowed.
// (Mostly to allow both directions to be excluded by user, even though the library does it for you.)
return this;
}
/// Can find a string if needed
template <typename T = App> Option *excludes(std::string opt_name) {
for(const Option_p &opt : dynamic_cast<T *>(parent_)->options_)
if(opt.get() != this && opt->check_name(opt_name))
return excludes(opt.get());
throw IncorrectConstruction::MissingOption(opt_name);
}
/// Any number supported, any mix of string and Opt
template <typename A, typename B, typename... ARG> Option *excludes(A opt, B opt1, ARG... args) {
excludes(opt);
return excludes(opt1, args...);
}
/// Sets environment variable to read if no option given
Option *envname(std::string name) {
envname_ = name;
return this;
}
/// Ignore case
///
/// The template hides the fact that we don't have the definition of App yet.
/// You are never expected to add an argument to the template here.
template <typename T = App> Option *ignore_case(bool value = true) {
ignore_case_ = value;
auto *parent = dynamic_cast<T *>(parent_);
for(const Option_p &opt : parent->options_)
if(opt.get() != this && *opt == *this)
throw OptionAlreadyAdded(opt->get_name());
return this;
}
/// Take the last argument if given multiple times (or another policy)
Option *multi_option_policy(MultiOptionPolicy value = MultiOptionPolicy::Throw) {
if(get_items_expected() < 0)
throw IncorrectConstruction::MultiOptionPolicy(single_name());
multi_option_policy_ = value;
return this;
}
///@}
/// @name Accessors
///@{
/// The number of arguments the option expects
int get_type_size() const { return type_size_; }
/// The number of times the option expects to be included
int get_expected() const { return expected_; }
/// \breif The total number of expected values (including the type)
/// This is positive if exactly this number is expected, and negitive for at least N values
///
/// v = fabs(size_type*expected)
/// !MultiOptionPolicy::Throw
/// | Expected < 0 | Expected == 0 | Expected > 0
/// Size < 0 | -v | 0 | -v
/// Size == 0 | 0 | 0 | 0
/// Size > 0 | -v | 0 | -v // Expected must be 1
///
/// MultiOptionPolicy::Throw
/// | Expected < 0 | Expected == 0 | Expected > 0
/// Size < 0 | -v | 0 | v
/// Size == 0 | 0 | 0 | 0
/// Size > 0 | v | 0 | v // Expected must be 1
///
int get_items_expected() const {
return std::abs(type_size_ * expected_) *
((multi_option_policy_ != MultiOptionPolicy::Throw || (expected_ < 0 && type_size_ < 0) ? -1 : 1));
}
/// True if this has a default value
int get_default() const { return default_; }
/// True if the argument can be given directly
bool get_positional() const { return pname_.length() > 0; }
/// True if option has at least one non-positional name
bool nonpositional() const { return (snames_.size() + lnames_.size()) > 0; }
/// True if option has description
bool has_description() const { return description_.length() > 0; }
/// Get the description
const std::string &get_description() const { return description_; }
// Just the pname
std::string get_pname() const { return pname_; }
///@}
/// @name Help tools
///@{
/// Gets a , sep list of names. Does not include the positional name if opt_only=true.
std::string get_name(bool opt_only = false) const {
std::vector<std::string> name_list;
if(!opt_only && pname_.length() > 0)
name_list.push_back(pname_);
for(const std::string &sname : snames_)
name_list.push_back("-" + sname);
for(const std::string &lname : lnames_)
name_list.push_back("--" + lname);
return detail::join(name_list);
}
/// The name and any extras needed for positionals
std::string help_positional() const {
std::string out = pname_;
if(get_expected() > 1)
out = out + "(" + std::to_string(get_expected()) + "x)";
else if(get_expected() == -1)
out = out + "...";
out = get_required() ? out : "[" + out + "]";
return out;
}
/// The most descriptive name available
std::string single_name() const {
if(!lnames_.empty())
return std::string("--") + lnames_[0];
else if(!snames_.empty())
return std::string("-") + snames_[0];
else
return pname_;
}
/// The first half of the help print, name plus default, etc. Setting opt_only to true avoids the positional name.
std::string help_name(bool opt_only = false) const {
std::stringstream out;
out << get_name(opt_only) << help_aftername();
return out.str();
}
/// pname with type info
std::string help_pname() const {
std::stringstream out;
out << get_pname() << help_aftername();
return out.str();
}
/// This is the part after the name is printed but before the description
std::string help_aftername() const {
std::stringstream out;
if(get_type_size() != 0) {
if(!typeval_.empty())
out << " " << typeval_;
if(!defaultval_.empty())
out << "=" << defaultval_;
if(get_expected() > 1)
out << " x " << get_expected();
if(get_expected() == -1)
out << " ...";
if(get_required())
out << " (REQUIRED)";
}
if(!envname_.empty())
out << " (env:" << envname_ << ")";
if(!requires_.empty()) {
out << " Needs:";
for(const Option *opt : requires_)
out << " " << opt->single_name();
}
if(!excludes_.empty()) {
out << " Excludes:";
for(const Option *opt : excludes_)
out << " " << opt->single_name();
}
return out.str();
}
///@}
/// @name Parser tools
///@{
/// Process the callback
void run_callback() {
// Run the validators (can change the string)
if(!validators_.empty()) {
for(std::string &result : results_)
for(const std::function<std::string(std::string &)> &vali : validators_) {
std::string err_msg = vali(result);
if(!err_msg.empty())
throw ValidationError(single_name(), err_msg);
}
}
bool local_result;
// Num items expected or length of vector, always at least 1
// Only valid for a trimming policy
int trim_size = std::min(std::max(std::abs(get_items_expected()), 1), static_cast<int>(results_.size()));
// Operation depends on the policy setting
if(multi_option_policy_ == MultiOptionPolicy::TakeLast) {
// Allow multi-option sizes (including 0)
results_t partial_result{results_.end() - trim_size, results_.end()};
local_result = !callback_(partial_result);
} else if(multi_option_policy_ == MultiOptionPolicy::TakeFirst) {
results_t partial_result{results_.begin(), results_.begin() + trim_size};
local_result = !callback_(partial_result);
} else if(multi_option_policy_ == MultiOptionPolicy::Join) {
results_t partial_result = {detail::join(results_, "\n")};
local_result = !callback_(partial_result);
} else {
// For now, vector of non size 1 types are not supported but possibility included here
if((get_items_expected() > 0 && results_.size() != static_cast<size_t>(get_items_expected())) ||
(get_items_expected() < 0 && results_.size() < static_cast<size_t>(-get_items_expected())))
throw ArgumentMismatch(single_name(), get_items_expected(), results_.size());
else
local_result = !callback_(results_);
}
if(local_result)
throw ConversionError(get_name(), results_);
}
/// If options share any of the same names, they are equal (not counting positional)
bool operator==(const Option &other) const {
for(const std::string &sname : snames_)
if(other.check_sname(sname))
return true;
for(const std::string &lname : lnames_)
if(other.check_lname(lname))
return true;
// We need to do the inverse, just in case we are ignore_case
for(const std::string &sname : other.snames_)
if(check_sname(sname))
return true;
for(const std::string &lname : other.lnames_)
if(check_lname(lname))
return true;
return false;
}
/// Check a name. Requires "-" or "--" for short / long, supports positional name
bool check_name(std::string name) const {
if(name.length() > 2 && name.substr(0, 2) == "--")
return check_lname(name.substr(2));
else if(name.length() > 1 && name.substr(0, 1) == "-")
return check_sname(name.substr(1));
else {
std::string local_pname = pname_;
if(ignore_case_) {
local_pname = detail::to_lower(local_pname);
name = detail::to_lower(name);
}
return name == local_pname;
}
}
/// Requires "-" to be removed from string
bool check_sname(std::string name) const {
if(ignore_case_) {
name = detail::to_lower(name);
return std::find_if(std::begin(snames_), std::end(snames_), [&name](std::string local_sname) {
return detail::to_lower(local_sname) == name;
}) != std::end(snames_);
} else
return std::find(std::begin(snames_), std::end(snames_), name) != std::end(snames_);
}
/// Requires "--" to be removed from string
bool check_lname(std::string name) const {
if(ignore_case_) {
name = detail::to_lower(name);
return std::find_if(std::begin(lnames_), std::end(lnames_), [&name](std::string local_sname) {
return detail::to_lower(local_sname) == name;
}) != std::end(lnames_);
} else
return std::find(std::begin(lnames_), std::end(lnames_), name) != std::end(lnames_);
}
/// Puts a result at the end, unless last_ is set, in which case it just keeps the last one
void add_result(std::string s) {
results_.push_back(s);
callback_run_ = false;
}
/// Get a copy of the results
std::vector<std::string> results() const { return results_; }
/// See if the callback has been run already
bool get_callback_run() const { return callback_run_; }
///@}
/// @name Custom options
///@{
/// Set a custom option, typestring, type_size
void set_custom_option(std::string typeval, int type_size = 1) {
typeval_ = typeval;
type_size_ = type_size;
if(type_size_ == 0)
required_ = false;
if(type_size < 0)
expected_ = -1;
}
/// Set the default value string representation
void set_default_str(std::string val) { defaultval_ = val; }
/// Set the default value string representation and evaluate
void set_default_val(std::string val) {
set_default_str(val);
auto old_results = results_;
results_ = {val};
run_callback();
results_ = std::move(old_results);
}
/// Set the type name displayed on this option
void set_type_name(std::string val) { typeval_ = val; }
/// Get the typename for this option
std::string get_type_name() const { return typeval_; }
///@}
protected:
/// @name App Helpers
///@{
/// Can print positional name detailed option if true
bool _has_help_positional() const {
return get_positional() && (has_description() || !requires_.empty() || !excludes_.empty());
}
///@}
};
} // namespace CLI
// From CLI/App.hpp:
namespace CLI {
#ifndef CLI11_PARSE
#define CLI11_PARSE(app, argc, argv) \
try { \
(app).parse((argc), (argv)); \
} catch(const CLI::ParseError &e) { \
return (app).exit(e); \
}
#endif
namespace detail {
enum class Classifer { NONE, POSITIONAL_MARK, SHORT, LONG, SUBCOMMAND };
struct AppFriend;
} // namespace detail
namespace FailureMessage {
std::string simple(const App *app, const Error &e);
std::string help(const App *app, const Error &e);
} // namespace FailureMessage
class App;
using App_p = std::unique_ptr<App>;
/// Creates a command line program, with very few defaults.
/** To use, create a new `Program()` instance with `argc`, `argv`, and a help description. The templated
* add_option methods make it easy to prepare options. Remember to call `.start` before starting your
* program, so that the options can be evaluated and the help option doesn't accidentally run your program. */
class App {
friend Option;
friend detail::AppFriend;
protected:
// This library follows the Google style guide for member names ending in underscores
/// @name Basics
///@{
/// Subcommand name or program name (from parser if name is empty)
std::string name_;
/// Description of the current program/subcommand
std::string description_;
/// If true, allow extra arguments (ie, don't throw an error). INHERITABLE
bool allow_extras_{false};
/// If true, allow extra arguments in the ini file (ie, don't throw an error). INHERITABLE
bool allow_ini_extras_{false};
/// If true, return immediately on an unrecognised option (implies allow_extras) INHERITABLE
bool prefix_command_{false};
/// This is a function that runs when complete. Great for subcommands. Can throw.
std::function<void()> callback_;
///@}
/// @name Options
///@{
/// The default values for options, customizable and changeable INHERITABLE
OptionDefaults option_defaults_;
/// The list of options, stored locally
std::vector<Option_p> options_;
///@}
/// @name Help
///@{
/// Footer to put after all options in the help output INHERITABLE
std::string footer_;
/// A pointer to the help flag if there is one INHERITABLE
Option *help_ptr_{nullptr};
/// The error message printing function INHERITABLE
std::function<std::string(const App *, const Error &e)> failure_message_ = FailureMessage::simple;
///@}
/// @name Parsing
///@{
using missing_t = std::vector<std::pair<detail::Classifer, std::string>>;
/// Pair of classifier, string for missing options. (extra detail is removed on returning from parse)
///
/// This is faster and cleaner than storing just a list of strings and reparsing. This may contain the -- separator.
missing_t missing_;
/// This is a list of pointers to options with the original parse order
std::vector<Option *> parse_order_;
/// This is a list of the subcommands collected, in order
std::vector<App *> parsed_subcommands_;
///@}
/// @name Subcommands
///@{
/// Storage for subcommand list
std::vector<App_p> subcommands_;
/// If true, the program name is not case sensitive INHERITABLE
bool ignore_case_{false};
/// Allow subcommand fallthrough, so that parent commands can collect commands after subcommand. INHERITABLE
bool fallthrough_{false};
/// A pointer to the parent if this is a subcommand
App *parent_{nullptr};
/// True if this command/subcommand was parsed
bool parsed_{false};
/// Minimum required subcommands
size_t require_subcommand_min_ = 0;
/// Max number of subcommands allowed (parsing stops after this number). 0 is unlimited INHERITABLE
size_t require_subcommand_max_ = 0;
/// The group membership INHERITABLE
std::string group_{"Subcommands"};
///@}
/// @name Config
///@{
/// The name of the connected config file
std::string config_name_;
/// True if ini is required (throws if not present), if false simply keep going.
bool config_required_{false};
/// Pointer to the config option
Option *config_ptr_{nullptr};
///@}
/// Special private constructor for subcommand
App(std::string description_, std::string name, App *parent)
: name_(std::move(name)), description_(std::move(description_)), parent_(parent) {
// Inherit if not from a nullptr
if(parent_ != nullptr) {
if(parent_->help_ptr_ != nullptr)
set_help_flag(parent_->help_ptr_->get_name(), parent_->help_ptr_->get_description());
/// OptionDefaults
option_defaults_ = parent_->option_defaults_;
// INHERITABLE
failure_message_ = parent_->failure_message_;
allow_extras_ = parent_->allow_extras_;
allow_ini_extras_ = parent_->allow_ini_extras_;
prefix_command_ = parent_->prefix_command_;
ignore_case_ = parent_->ignore_case_;
fallthrough_ = parent_->fallthrough_;
group_ = parent_->group_;
footer_ = parent_->footer_;
require_subcommand_max_ = parent_->require_subcommand_max_;
}
}
public:
/// @name Basic
///@{
/// Create a new program. Pass in the same arguments as main(), along with a help string.
explicit App(std::string description_ = "", std::string name = "") : App(description_, name, nullptr) {
set_help_flag("-h,--help", "Print this help message and exit");
}
/// virtual destructor
virtual ~App() = default;
/// Set a callback for the end of parsing.
///
/// Due to a bug in c++11,
/// it is not possible to overload on std::function (fixed in c++14
/// and backported to c++11 on newer compilers). Use capture by reference
/// to get a pointer to App if needed.
App *set_callback(std::function<void()> callback) {
callback_ = callback;
return this;
}
/// Set a name for the app (empty will use parser to set the name)
App *set_name(std::string name = "") {
name_ = name;
return this;
}
/// Remove the error when extras are left over on the command line.
App *allow_extras(bool allow = true) {
allow_extras_ = allow;
return this;
}
/// Remove the error when extras are left over on the command line.
/// Will also call App::allow_extras().
App *allow_ini_extras(bool allow = true) {
allow_extras(allow);
allow_ini_extras_ = allow;
return this;
}
/// Do not parse anything after the first unrecognised option and return
App *prefix_command(bool allow = true) {
prefix_command_ = allow;
return this;
}
/// Ignore case. Subcommand inherit value.
App *ignore_case(bool value = true) {
ignore_case_ = value;
if(parent_ != nullptr) {
for(const auto &subc : parent_->subcommands_) {
if(subc.get() != this && (this->check_name(subc->name_) || subc->check_name(this->name_)))
throw OptionAlreadyAdded(subc->name_);
}
}
return this;
}
/// Check to see if this subcommand was parsed, true only if received on command line.
bool parsed() const { return parsed_; }
/// Get the OptionDefault object, to set option defaults
OptionDefaults *option_defaults() { return &option_defaults_; }
///@}
/// @name Adding options
///@{
/// Add an option, will automatically understand the type for common types.
///
/// To use, create a variable with the expected type, and pass it in after the name.
/// After start is called, you can use count to see if the value was passed, and
/// the value will be initialized properly. Numbers, vectors, and strings are supported.
///
/// ->required(), ->default, and the validators are options,
/// The positional options take an optional number of arguments.
///
/// For example,
///
/// std::string filename;
/// program.add_option("filename", filename, "description of filename");
///
Option *add_option(std::string name, callback_t callback, std::string description = "", bool defaulted = false) {
Option myopt{name, description, callback, defaulted, this};
if(std::find_if(std::begin(options_), std::end(options_), [&myopt](const Option_p &v) {
return *v == myopt;
}) == std::end(options_)) {
options_.emplace_back();
Option_p &option = options_.back();
option.reset(new Option(name, description, callback, defaulted, this));
option_defaults_.copy_to(option.get());
return option.get();
} else
throw OptionAlreadyAdded(myopt.get_name());
}
/// Add option for non-vectors (duplicate copy needed without defaulted to avoid `iostream << value`)
template <typename T, enable_if_t<!is_vector<T>::value, detail::enabler> = detail::dummy>
Option *add_option(std::string name,
T &variable, ///< The variable to set
std::string description = "") {
std::string simple_name = CLI::detail::split(name, ',').at(0);
CLI::callback_t fun = [&variable, simple_name](CLI::results_t res) {
return detail::lexical_cast(res[0], variable);
};
Option *opt = add_option(name, fun, description, false);
opt->set_custom_option(detail::type_name<T>());
return opt;
}
/// Add option for non-vectors with a default print
template <typename T, enable_if_t<!is_vector<T>::value, detail::enabler> = detail::dummy>
Option *add_option(std::string name,
T &variable, ///< The variable to set
std::string description,
bool defaulted) {
std::string simple_name = CLI::detail::split(name, ',').at(0);
CLI::callback_t fun = [&variable, simple_name](CLI::results_t res) {
return detail::lexical_cast(res[0], variable);
};
Option *opt = add_option(name, fun, description, defaulted);
opt->set_custom_option(detail::type_name<T>());
if(defaulted) {
std::stringstream out;
out << variable;
opt->set_default_str(out.str());
}
return opt;
}
/// Add option for vectors (no default)
template <typename T>
Option *add_option(std::string name,
std::vector<T> &variable, ///< The variable vector to set
std::string description = "") {
CLI::callback_t fun = [&variable](CLI::results_t res) {
bool retval = true;
variable.clear();
for(const auto &a : res) {
variable.emplace_back();
retval &= detail::lexical_cast(a, variable.back());
}
return (!variable.empty()) && retval;
};
Option *opt = add_option(name, fun, description, false);
opt->set_custom_option(detail::type_name<T>(), -1);
return opt;
}
/// Add option for vectors
template <typename T>
Option *add_option(std::string name,
std::vector<T> &variable, ///< The variable vector to set
std::string description,
bool defaulted) {
CLI::callback_t fun = [&variable](CLI::results_t res) {
bool retval = true;
variable.clear();
for(const auto &a : res) {
variable.emplace_back();
retval &= detail::lexical_cast(a, variable.back());
}
return (!variable.empty()) && retval;
};
Option *opt = add_option(name, fun, description, defaulted);
opt->set_custom_option(detail::type_name<T>(), -1);
if(defaulted)
opt->set_default_str("[" + detail::join(variable) + "]");
return opt;
}
/// Set a help flag, replaced the existing one if present
Option *set_help_flag(std::string name = "", std::string description = "") {
if(help_ptr_ != nullptr) {
remove_option(help_ptr_);
help_ptr_ = nullptr;
}
// Empty name will simply remove the help flag
if(!name.empty()) {
help_ptr_ = add_flag(name, description);
help_ptr_->configurable(false);
}
return help_ptr_;
}
/// Add option for flag
Option *add_flag(std::string name, std::string description = "") {
CLI::callback_t fun = [](CLI::results_t) { return true; };
Option *opt = add_option(name, fun, description, false);
if(opt->get_positional())
throw IncorrectConstruction::PositionalFlag(name);
opt->set_custom_option("", 0);
return opt;
}
/// Add option for flag integer
template <typename T,
enable_if_t<std::is_integral<T>::value && !is_bool<T>::value, detail::enabler> = detail::dummy>
Option *add_flag(std::string name,
T &count, ///< A variable holding the count
std::string description = "") {
count = 0;
CLI::callback_t fun = [&count](CLI::results_t res) {
count = static_cast<T>(res.size());
return true;
};
Option *opt = add_option(name, fun, description, false);
if(opt->get_positional())
throw IncorrectConstruction::PositionalFlag(name);
opt->set_custom_option("", 0);
return opt;
}
/// Bool version - defaults to allowing multiple passings, but can be forced to one if
/// `multi_option_policy(CLI::MultiOptionPolicy::Throw)` is used.
template <typename T, enable_if_t<is_bool<T>::value, detail::enabler> = detail::dummy>
Option *add_flag(std::string name,
T &count, ///< A variable holding true if passed
std::string description = "") {
count = false;
CLI::callback_t fun = [&count](CLI::results_t res) {
count = true;
return res.size() == 1;
};
Option *opt = add_option(name, fun, description, false);
if(opt->get_positional())
throw IncorrectConstruction::PositionalFlag(name);
opt->set_custom_option("", 0);
opt->multi_option_policy(CLI::MultiOptionPolicy::TakeLast);
return opt;
}
/// Add option for callback
Option *add_flag_function(std::string name,
std::function<void(size_t)> function, ///< A function to call, void(size_t)
std::string description = "") {
CLI::callback_t fun = [function](CLI::results_t res) {
auto count = static_cast<size_t>(res.size());
function(count);
return true;
};
Option *opt = add_option(name, fun, description, false);
if(opt->get_positional())
throw IncorrectConstruction::PositionalFlag(name);
opt->set_custom_option("", 0);
return opt;
}
#ifdef CLI11_CPP14
/// Add option for callback (C++14 or better only)
Option *add_flag(std::string name,
std::function<void(size_t)> function, ///< A function to call, void(size_t)
std::string description = "") {
return add_flag_function(name, function, description);
}
#endif
/// Add set of options (No default)
template <typename T>
Option *add_set(std::string name,
T &member, ///< The selected member of the set
std::set<T> options, ///< The set of possibilities
std::string description = "") {
std::string simple_name = CLI::detail::split(name, ',').at(0);
CLI::callback_t fun = [&member, options, simple_name](CLI::results_t res) {
bool retval = detail::lexical_cast(res[0], member);
if(!retval)
throw ConversionError(res[0], simple_name);
return std::find(std::begin(options), std::end(options), member) != std::end(options);
};
Option *opt = add_option(name, fun, description, false);
std::string typeval = detail::type_name<T>();
typeval += " in {" + detail::join(options) + "}";
opt->set_custom_option(typeval);
return opt;
}
/// Add set of options
template <typename T>
Option *add_set(std::string name,
T &member, ///< The selected member of the set
std::set<T> options, ///< The set of posibilities
std::string description,
bool defaulted) {
std::string simple_name = CLI::detail::split(name, ',').at(0);
CLI::callback_t fun = [&member, options, simple_name](CLI::results_t res) {
bool retval = detail::lexical_cast(res[0], member);
if(!retval)
throw ConversionError(res[0], simple_name);
return std::find(std::begin(options), std::end(options), member) != std::end(options);
};
Option *opt = add_option(name, fun, description, defaulted);
std::string typeval = detail::type_name<T>();
typeval += " in {" + detail::join(options) + "}";
opt->set_custom_option(typeval);
if(defaulted) {
std::stringstream out;
out << member;
opt->set_default_str(out.str());
}
return opt;
}
/// Add set of options, string only, ignore case (no default)
Option *add_set_ignore_case(std::string name,
std::string &member, ///< The selected member of the set
std::set<std::string> options, ///< The set of possibilities
std::string description = "") {
std::string simple_name = CLI::detail::split(name, ',').at(0);
CLI::callback_t fun = [&member, options, simple_name](CLI::results_t res) {
member = detail::to_lower(res[0]);
auto iter = std::find_if(std::begin(options), std::end(options), [&member](std::string val) {
return detail::to_lower(val) == member;
});
if(iter == std::end(options))
throw ConversionError(member, simple_name);
else {
member = *iter;
return true;
}
};
Option *opt = add_option(name, fun, description, false);
std::string typeval = detail::type_name<std::string>();
typeval += " in {" + detail::join(options) + "}";
opt->set_custom_option(typeval);
return opt;
}
/// Add set of options, string only, ignore case
Option *add_set_ignore_case(std::string name,
std::string &member, ///< The selected member of the set
std::set<std::string> options, ///< The set of posibilities
std::string description,
bool defaulted) {
std::string simple_name = CLI::detail::split(name, ',').at(0);
CLI::callback_t fun = [&member, options, simple_name](CLI::results_t res) {
member = detail::to_lower(res[0]);
auto iter = std::find_if(std::begin(options), std::end(options), [&member](std::string val) {
return detail::to_lower(val) == member;
});
if(iter == std::end(options))
throw ConversionError(member, simple_name);
else {
member = *iter;
return true;
}
};
Option *opt = add_option(name, fun, description, defaulted);
std::string typeval = detail::type_name<std::string>();
typeval += " in {" + detail::join(options) + "}";
opt->set_custom_option(typeval);
if(defaulted) {
opt->set_default_str(member);
}
return opt;
}
/// Add a complex number
template <typename T>
Option *add_complex(std::string name,
T &variable,
std::string description = "",
bool defaulted = false,
std::string label = "COMPLEX") {
std::string simple_name = CLI::detail::split(name, ',').at(0);
CLI::callback_t fun = [&variable, simple_name, label](results_t res) {
if(res[1].back() == 'i')
res[1].pop_back();
double x, y;
bool worked = detail::lexical_cast(res[0], x) && detail::lexical_cast(res[1], y);
if(worked)
variable = T(x, y);
return worked;
};
CLI::Option *opt = add_option(name, fun, description, defaulted);
opt->set_custom_option(label, 2);
if(defaulted) {
std::stringstream out;
out << variable;
opt->set_default_str(out.str());
}
return opt;
}
/// Set a configuration ini file option, or clear it if no name passed
Option *set_config(std::string name = "",
std::string default_filename = "",
std::string help = "Read an ini file",
bool required = false) {
// Remove existing config if present
if(config_ptr_ != nullptr)
remove_option(config_ptr_);
// Only add config if option passed
if(!name.empty()) {
config_name_ = default_filename;
config_required_ = required;
config_ptr_ = add_option(name, config_name_, help, !default_filename.empty());
config_ptr_->configurable(false);
}
return config_ptr_;
}
/// Removes an option from the App. Takes an option pointer. Returns true if found and removed.
bool remove_option(Option *opt) {
auto iterator =
std::find_if(std::begin(options_), std::end(options_), [opt](const Option_p &v) { return v.get() == opt; });
if(iterator != std::end(options_)) {
options_.erase(iterator);
return true;
}
return false;
}
///@}
/// @name Subcommmands
///@{
/// Add a subcommand. Inherits INHERITABLE and OptionDefaults, and help flag
App *add_subcommand(std::string name, std::string description = "") {
subcommands_.emplace_back(new App(description, name, this));
for(const auto &subc : subcommands_)
if(subc.get() != subcommands_.back().get())
if(subc->check_name(subcommands_.back()->name_) || subcommands_.back()->check_name(subc->name_))
throw OptionAlreadyAdded(subc->name_);
return subcommands_.back().get();
}
/// Check to see if a subcommand is part of this command (doesn't have to be in command line)
App *get_subcommand(App *subcom) const {
for(const App_p &subcomptr : subcommands_)
if(subcomptr.get() == subcom)
return subcom;
throw OptionNotFound(subcom->get_name());
}
/// Check to see if a subcommand is part of this command (text version)
App *get_subcommand(std::string subcom) const {
for(const App_p &subcomptr : subcommands_)
if(subcomptr->check_name(subcom))
return subcomptr.get();
throw OptionNotFound(subcom);
}
/// Changes the group membership
App *group(std::string name) {
group_ = name;
return this;
}
/// The argumentless form of require subcommand requires 1 or more subcommands
App *require_subcommand() {
require_subcommand_min_ = 1;
require_subcommand_max_ = 0;
return this;
}
/// Require a subcommand to be given (does not affect help call)
/// The number required can be given. Negative values indicate maximum
/// number allowed (0 for any number). Max number inheritable.
App *require_subcommand(int value) {
if(value < 0) {
require_subcommand_min_ = 0;
require_subcommand_max_ = static_cast<size_t>(-value);
} else {
require_subcommand_min_ = static_cast<size_t>(value);
require_subcommand_max_ = static_cast<size_t>(value);
}
return this;
}
/// Explicitly control the number of subcommands required. Setting 0
/// for the max means unlimited number allowed. Max number inheritable.
App *require_subcommand(size_t min, size_t max) {
require_subcommand_min_ = min;
require_subcommand_max_ = max;
return this;
}
/// Stop subcommand fallthrough, so that parent commands cannot collect commands after subcommand.
/// Default from parent, usually set on parent.
App *fallthrough(bool value = true) {
fallthrough_ = value;
return this;
}
/// Check to see if this subcommand was parsed, true only if received on command line.
/// This allows the subcommand to be directly checked.
operator bool() const { return parsed_; }
///@}
/// @name Extras for subclassing
///@{
/// This allows subclasses to inject code before callbacks but after parse.
///
/// This does not run if any errors or help is thrown.
virtual void pre_callback() {}
///@}
/// @name Parsing
///@{
/// Parses the command line - throws errors
/// This must be called after the options are in but before the rest of the program.
void parse(int argc, char **argv) {
// If the name is not set, read from command line
if(name_.empty())
name_ = argv[0];
std::vector<std::string> args;
for(int i = argc - 1; i > 0; i--)
args.emplace_back(argv[i]);
parse(args);
}
/// The real work is done here. Expects a reversed vector.
/// Changes the vector to the remaining options.
void parse(std::vector<std::string> &args) {
_validate();
_parse(args);
run_callback();
}
/// Provide a function to print a help message. The function gets access to the App pointer and error.
void set_failure_message(std::function<std::string(const App *, const Error &e)> function) {
failure_message_ = function;
}
/// Print a nice error message and return the exit code
int exit(const Error &e, std::ostream &out = std::cout, std::ostream &err = std::cerr) const {
/// Avoid printing anything if this is a CLI::RuntimeError
if(dynamic_cast<const CLI::RuntimeError *>(&e) != nullptr)
return e.get_exit_code();
if(dynamic_cast<const CLI::CallForHelp *>(&e) != nullptr) {
out << help();
return e.get_exit_code();
}
if(e.get_exit_code() != static_cast<int>(ExitCodes::Success)) {
if(failure_message_)
err << failure_message_(this, e) << std::flush;
}
return e.get_exit_code();
}
/// Reset the parsed data
void reset() {
parsed_ = false;
missing_.clear();
parsed_subcommands_.clear();
for(const Option_p &opt : options_) {
opt->clear();
}
for(const App_p &app : subcommands_) {
app->reset();
}
}
///@}
/// @name Post parsing
///@{
/// Counts the number of times the given option was passed.
size_t count(std::string name) const {
for(const Option_p &opt : options_) {
if(opt->check_name(name)) {
return opt->count();
}
}
throw OptionNotFound(name);
}
/// Get a subcommand pointer list to the currently selected subcommands (after parsing by default, in command line
/// order)
std::vector<App *> get_subcommands(bool parsed = true) const {
if(parsed) {
return parsed_subcommands_;
} else {
std::vector<App *> subcomms(subcommands_.size());
std::transform(std::begin(subcommands_), std::end(subcommands_), std::begin(subcomms), [](const App_p &v) {
return v.get();
});
return subcomms;
}
}
/// Check to see if given subcommand was selected
bool got_subcommand(App *subcom) const {
// get subcom needed to verify that this was a real subcommand
return get_subcommand(subcom)->parsed_;
}
/// Check with name instead of pointer to see if subcommand was selected
bool got_subcommand(std::string name) const { return get_subcommand(name)->parsed_; }
///@}
/// @name Help
///@{
/// Set footer.
App *set_footer(std::string footer) {
footer_ = footer;
return this;
}
/// Produce a string that could be read in as a config of the current values of the App. Set default_also to include
/// default arguments. Prefix will add a string to the beginning of each option.
std::string
config_to_str(bool default_also = false, std::string prefix = "", bool write_description = false) const {
std::stringstream out;
for(const Option_p &opt : options_) {
// Only process option with a long-name and configurable
if(!opt->lnames_.empty() && opt->get_configurable()) {
std::string name = prefix + opt->lnames_[0];
std::string value;
// Non-flags
if(opt->get_type_size() != 0) {
// If the option was found on command line
if(opt->count() > 0)
value = detail::inijoin(opt->results());
// If the option has a default and is requested by optional argument
else if(default_also && !opt->defaultval_.empty())
value = opt->defaultval_;
// Flag, one passed
} else if(opt->count() == 1) {
value = "true";
// Flag, multiple passed
} else if(opt->count() > 1) {
value = std::to_string(opt->count());
// Flag, not present
} else if(opt->count() == 0 && default_also) {
value = "false";
}
if(!value.empty()) {
if(write_description && opt->has_description()) {
if(static_cast<int>(out.tellp()) != 0) {
out << std::endl;
}
out << "; " << detail::fix_newlines("; ", opt->get_description()) << std::endl;
}
out << name << "=" << value << std::endl;
}
}
}
for(const App_p &subcom : subcommands_)
out << subcom->config_to_str(default_also, prefix + subcom->name_ + ".");
return out.str();
}
/// Makes a help message, with a column wid for column 1
std::string help(size_t wid = 30, std::string prev = "") const {
// Delegate to subcommand if needed
if(prev.empty())
prev = name_;
else
prev += " " + name_;
auto selected_subcommands = get_subcommands();
if(!selected_subcommands.empty())
return selected_subcommands.at(0)->help(wid, prev);
std::stringstream out;
out << description_ << std::endl;
out << "Usage:" << (prev.empty() ? "" : " ") << prev;
// Check for options_
bool npos = false;
std::vector<std::string> groups;
for(const Option_p &opt : options_) {
if(opt->nonpositional()) {
npos = true;
// Add group if it is not already in there
if(std::find(groups.begin(), groups.end(), opt->get_group()) == groups.end()) {
groups.push_back(opt->get_group());
}
}
}
if(npos)
out << " [OPTIONS]";
// Positionals
bool pos = false;
for(const Option_p &opt : options_)
if(opt->get_positional()) {
// A hidden positional should still show up in the usage statement
// if(detail::to_lower(opt->get_group()).empty())
// continue;
out << " " << opt->help_positional();
if(opt->_has_help_positional())
pos = true;
}
if(!subcommands_.empty()) {
if(require_subcommand_min_ > 0)
out << " SUBCOMMAND";
else
out << " [SUBCOMMAND]";
}
out << std::endl;
// Positional descriptions
if(pos) {
out << std::endl << "Positionals:" << std::endl;
for(const Option_p &opt : options_) {
if(detail::to_lower(opt->get_group()).empty())
continue; // Hidden
if(opt->_has_help_positional())
detail::format_help(out, opt->help_pname(), opt->get_description(), wid);
}
}
// Options
if(npos) {
for(const std::string &group : groups) {
if(detail::to_lower(group).empty())
continue; // Hidden
out << std::endl << group << ":" << std::endl;
for(const Option_p &opt : options_) {
if(opt->nonpositional() && opt->get_group() == group)
detail::format_help(out, opt->help_name(true), opt->get_description(), wid);
}
}
}
// Subcommands
if(!subcommands_.empty()) {
std::set<std::string> subcmd_groups_seen;
for(const App_p &com : subcommands_) {
const std::string &group_key = detail::to_lower(com->get_group());
if(group_key.empty() || subcmd_groups_seen.count(group_key) != 0)
continue; // Hidden or not in a group
subcmd_groups_seen.insert(group_key);
out << std::endl << com->get_group() << ":" << std::endl;
for(const App_p &new_com : subcommands_)
if(detail::to_lower(new_com->get_group()) == group_key)
detail::format_help(out, new_com->get_name(), new_com->description_, wid);
}
}
if(!footer_.empty()) {
out << std::endl << footer_ << std::endl;
}
return out.str();
}
///@}
/// @name Getters
///@{
/// Get the app or subcommand description
std::string get_description() const { return description_; }
/// Get the list of options (user facing function, so returns raw pointers)
std::vector<Option *> get_options() const {
std::vector<Option *> options(options_.size());
std::transform(std::begin(options_), std::end(options_), std::begin(options), [](const Option_p &val) {
return val.get();
});
return options;
}
/// Check the status of ignore_case
bool get_ignore_case() const { return ignore_case_; }
/// Check the status of fallthrough
bool get_fallthrough() const { return fallthrough_; }
/// Get the group of this subcommand
const std::string &get_group() const { return group_; }
/// Get footer.
std::string get_footer() const { return footer_; }
/// Get the required min subcommand value
size_t get_require_subcommand_min() const { return require_subcommand_min_; }
/// Get the required max subcommand value
size_t get_require_subcommand_max() const { return require_subcommand_max_; }
/// Get the prefix command status
bool get_prefix_command() const { return prefix_command_; }
/// Get the status of allow extras
bool get_allow_extras() const { return allow_extras_; }
/// Get the status of allow extras
bool get_allow_ini_extras() const { return allow_ini_extras_; }
/// Get a pointer to the help flag.
Option *get_help_ptr() { return help_ptr_; }
/// Get a pointer to the help flag. (const)
const Option *get_help_ptr() const { return help_ptr_; }
/// Get a pointer to the config option.
Option *get_config_ptr() { return config_ptr_; }
/// Get the parent of this subcommand (or nullptr if master app)
App *get_parent() { return parent_; }
/// Get a pointer to the config option. (const)
const Option *get_config_ptr() const { return config_ptr_; }
/// Get the name of the current app
std::string get_name() const { return name_; }
/// Check the name, case insensitive if set
bool check_name(std::string name_to_check) const {
std::string local_name = name_;
if(ignore_case_) {
local_name = detail::to_lower(name_);
name_to_check = detail::to_lower(name_to_check);
}
return local_name == name_to_check;
}
/// This gets a vector of pointers with the original parse order
const std::vector<Option *> &parse_order() const { return parse_order_; }
/// This returns the missing options from the current subcommand
std::vector<std::string> remaining(bool recurse = false) const {
std::vector<std::string> miss_list;
for(const std::pair<detail::Classifer, std::string> &miss : missing_) {
miss_list.push_back(std::get<1>(miss));
}
// Recurse into subcommands
if(recurse) {
for(const App *sub : parsed_subcommands_) {
std::vector<std::string> output = sub->remaining(recurse);
std::copy(std::begin(output), std::end(output), std::back_inserter(miss_list));
}
}
return miss_list;
}
/// This returns the number of remaining options, minus the -- seperator
size_t remaining_size(bool recurse = false) const {
size_t count = static_cast<size_t>(std::count_if(
std::begin(missing_), std::end(missing_), [](const std::pair<detail::Classifer, std::string> &val) {
return val.first != detail::Classifer::POSITIONAL_MARK;
}));
if(recurse) {
for(const App_p &sub : subcommands_) {
count += sub->remaining_size(recurse);
}
}
return count;
}
///@}
protected:
/// Check the options to make sure there are no conflicts.
///
/// Currently checks to see if multiple positionals exist with -1 args
void _validate() const {
auto count = std::count_if(std::begin(options_), std::end(options_), [](const Option_p &opt) {
return opt->get_items_expected() < 0 && opt->get_positional();
});
if(count > 1)
throw InvalidError(name_);
for(const App_p &app : subcommands_)
app->_validate();
}
/// Internal function to run (App) callback, top down
void run_callback() {
pre_callback();
if(callback_)
callback_();
for(App *subc : get_subcommands()) {
subc->run_callback();
}
}
/// Check to see if a subcommand is valid. Give up immediately if subcommand max has been reached.
bool _valid_subcommand(const std::string ¤t) const {
// Don't match if max has been reached - but still check parents
if(require_subcommand_max_ != 0 && parsed_subcommands_.size() >= require_subcommand_max_) {
return parent_ != nullptr && parent_->_valid_subcommand(current);
}
for(const App_p &com : subcommands_)
if(com->check_name(current) && !*com)
return true;
// Check parent if exists, else return false
return parent_ != nullptr && parent_->_valid_subcommand(current);
}
/// Selects a Classifier enum based on the type of the current argument
detail::Classifer _recognize(const std::string ¤t) const {
std::string dummy1, dummy2;
if(current == "--")
return detail::Classifer::POSITIONAL_MARK;
if(_valid_subcommand(current))
return detail::Classifer::SUBCOMMAND;
if(detail::split_long(current, dummy1, dummy2))
return detail::Classifer::LONG;
if(detail::split_short(current, dummy1, dummy2))
return detail::Classifer::SHORT;
return detail::Classifer::NONE;
}
/// Internal parse function
void _parse(std::vector<std::string> &args) {
parsed_ = true;
bool positional_only = false;
while(!args.empty()) {
_parse_single(args, positional_only);
}
if(help_ptr_ != nullptr && help_ptr_->count() > 0) {
throw CallForHelp();
}
// Process an INI file
if(config_ptr_ != nullptr) {
if(*config_ptr_) {
config_ptr_->run_callback();
config_required_ = true;
}
if(!config_name_.empty()) {
try {
std::vector<detail::ini_ret_t> values = detail::parse_ini(config_name_);
while(!values.empty()) {
if(!_parse_ini(values)) {
throw INIError::Extras(values.back().fullname);
}
}
} catch(const FileError &) {
if(config_required_)
throw;
}
}
}
// Get envname options if not yet passed
for(const Option_p &opt : options_) {
if(opt->count() == 0 && !opt->envname_.empty()) {
char *buffer = nullptr;
std::string ename_string;
#ifdef _MSC_VER
// Windows version
size_t sz = 0;
if(_dupenv_s(&buffer, &sz, opt->envname_.c_str()) == 0 && buffer != nullptr) {
ename_string = std::string(buffer);
free(buffer);
}
#else
// This also works on Windows, but gives a warning
buffer = std::getenv(opt->envname_.c_str());
if(buffer != nullptr)
ename_string = std::string(buffer);
#endif
if(!ename_string.empty()) {
opt->add_result(ename_string);
}
}
}
// Process callbacks
for(const Option_p &opt : options_) {
if(opt->count() > 0 && !opt->get_callback_run()) {
opt->run_callback();
}
}
// Verify required options
for(const Option_p &opt : options_) {
// Required or partially filled
if(opt->get_required() || opt->count() != 0) {
// Make sure enough -N arguments parsed (+N is already handled in parsing function)
if(opt->get_items_expected() < 0 && opt->count() < static_cast<size_t>(-opt->get_items_expected()))
throw ArgumentMismatch::AtLeast(opt->single_name(), -opt->get_items_expected());
// Required but empty
if(opt->get_required() && opt->count() == 0)
throw RequiredError(opt->single_name());
}
// Requires
for(const Option *opt_req : opt->requires_)
if(opt->count() > 0 && opt_req->count() == 0)
throw RequiresError(opt->single_name(), opt_req->single_name());
// Excludes
for(const Option *opt_ex : opt->excludes_)
if(opt->count() > 0 && opt_ex->count() != 0)
throw ExcludesError(opt->single_name(), opt_ex->single_name());
}
auto selected_subcommands = get_subcommands();
if(require_subcommand_min_ > selected_subcommands.size())
throw RequiredError::Subcommand(require_subcommand_min_);
// Convert missing (pairs) to extras (string only)
if(!(allow_extras_ || prefix_command_)) {
size_t num_left_over = remaining_size();
if(num_left_over > 0) {
args = remaining(false);
std::reverse(std::begin(args), std::end(args));
throw ExtrasError(args);
}
}
}
/// Parse one ini param, return false if not found in any subcommand, remove if it is
///
/// If this has more than one dot.separated.name, go into the subcommand matching it
/// Returns true if it managed to find the option, if false you'll need to remove the arg manually.
bool _parse_ini(std::vector<detail::ini_ret_t> &args) {
detail::ini_ret_t ¤t = args.back();
std::string parent = current.parent(); // respects current.level
std::string name = current.name();
// If a parent is listed, go to a subcommand
if(!parent.empty()) {
current.level++;
for(const App_p &com : subcommands_)
if(com->check_name(parent))
return com->_parse_ini(args);
return false;
}
auto op_ptr = std::find_if(
std::begin(options_), std::end(options_), [name](const Option_p &v) { return v->check_lname(name); });
if(op_ptr == std::end(options_)) {
if(allow_ini_extras_) {
// Should we worry about classifying the extras properly?
missing_.emplace_back(detail::Classifer::NONE, current.fullname);
args.pop_back();
return true;
}
return false;
}
// Let's not go crazy with pointer syntax
Option_p &op = *op_ptr;
if(!op->get_configurable())
throw INIError::NotConfigurable(current.fullname);
if(op->results_.empty()) {
// Flag parsing
if(op->get_type_size() == 0) {
if(current.inputs.size() == 1) {
std::string val = current.inputs.at(0);
val = detail::to_lower(val);
if(val == "true" || val == "on" || val == "yes")
op->results_ = {""};
else if(val == "false" || val == "off" || val == "no")
;
else
try {
size_t ui = std::stoul(val);
for(size_t i = 0; i < ui; i++)
op->results_.emplace_back("");
} catch(const std::invalid_argument &) {
throw ConversionError::TrueFalse(current.fullname);
}
} else
throw ConversionError::TooManyInputsFlag(current.fullname);
} else {
op->results_ = current.inputs;
op->run_callback();
}
}
args.pop_back();
return true;
}
/// Parse "one" argument (some may eat more than one), delegate to parent if fails, add to missing if missing from
/// master
void _parse_single(std::vector<std::string> &args, bool &positional_only) {
detail::Classifer classifer = positional_only ? detail::Classifer::NONE : _recognize(args.back());
switch(classifer) {
case detail::Classifer::POSITIONAL_MARK:
missing_.emplace_back(classifer, args.back());
args.pop_back();
positional_only = true;
break;
case detail::Classifer::SUBCOMMAND:
_parse_subcommand(args);
break;
case detail::Classifer::LONG:
// If already parsed a subcommand, don't accept options_
_parse_arg(args, true);
break;
case detail::Classifer::SHORT:
// If already parsed a subcommand, don't accept options_
_parse_arg(args, false);
break;
case detail::Classifer::NONE:
// Probably a positional or something for a parent (sub)command
_parse_positional(args);
}
}
/// Count the required remaining positional arguments
size_t _count_remaining_positionals(bool required = false) const {
size_t retval = 0;
for(const Option_p &opt : options_)
if(opt->get_positional() && (!required || opt->get_required()) && opt->get_items_expected() > 0 &&
static_cast<int>(opt->count()) < opt->get_items_expected())
retval = static_cast<size_t>(opt->get_items_expected()) - opt->count();
return retval;
}
/// Parse a positional, go up the tree to check
void _parse_positional(std::vector<std::string> &args) {
std::string positional = args.back();
for(const Option_p &opt : options_) {
// Eat options, one by one, until done
if(opt->get_positional() &&
(static_cast<int>(opt->count()) < opt->get_items_expected() || opt->get_items_expected() < 0)) {
opt->add_result(positional);
parse_order_.push_back(opt.get());
args.pop_back();
return;
}
}
if(parent_ != nullptr && fallthrough_)
return parent_->_parse_positional(args);
else {
args.pop_back();
missing_.emplace_back(detail::Classifer::NONE, positional);
if(prefix_command_) {
while(!args.empty()) {
missing_.emplace_back(detail::Classifer::NONE, args.back());
args.pop_back();
}
}
}
}
/// Parse a subcommand, modify args and continue
///
/// Unlike the others, this one will always allow fallthrough
void _parse_subcommand(std::vector<std::string> &args) {
if(_count_remaining_positionals(/* required */ true) > 0)
return _parse_positional(args);
for(const App_p &com : subcommands_) {
if(com->check_name(args.back())) {
args.pop_back();
if(std::find(std::begin(parsed_subcommands_), std::end(parsed_subcommands_), com.get()) ==
std::end(parsed_subcommands_))
parsed_subcommands_.push_back(com.get());
com->_parse(args);
return;
}
}
if(parent_ != nullptr)
return parent_->_parse_subcommand(args);
else
throw HorribleError("Subcommand " + args.back() + " missing");
}
/// Parse a short (false) or long (true) argument, must be at the top of the list
void _parse_arg(std::vector<std::string> &args, bool second_dash) {
detail::Classifer current_type = second_dash ? detail::Classifer::LONG : detail::Classifer::SHORT;
std::string current = args.back();
std::string name;
std::string value;
std::string rest;
if(second_dash) {
if(!detail::split_long(current, name, value))
throw HorribleError("Long parsed but missing (you should not see this):" + args.back());
} else {
if(!detail::split_short(current, name, rest))
throw HorribleError("Short parsed but missing! You should not see this");
}
auto op_ptr = std::find_if(std::begin(options_), std::end(options_), [name, second_dash](const Option_p &opt) {
return second_dash ? opt->check_lname(name) : opt->check_sname(name);
});
// Option not found
if(op_ptr == std::end(options_)) {
// If a subcommand, try the master command
if(parent_ != nullptr && fallthrough_)
return parent_->_parse_arg(args, second_dash);
// Otherwise, add to missing
else {
args.pop_back();
missing_.emplace_back(current_type, current);
return;
}
}
args.pop_back();
// Get a reference to the pointer to make syntax bearable
Option_p &op = *op_ptr;
int num = op->get_items_expected();
// Make sure we always eat the minimum for unlimited vectors
int collected = 0;
// --this=value
if(!value.empty()) {
// If exact number expected
if(num > 0)
num--;
op->add_result(value);
parse_order_.push_back(op.get());
collected += 1;
} else if(num == 0) {
op->add_result("");
parse_order_.push_back(op.get());
// -Trest
} else if(!rest.empty()) {
if(num > 0)
num--;
op->add_result(rest);
parse_order_.push_back(op.get());
rest = "";
collected += 1;
}
// Unlimited vector parser
if(num < 0) {
while(!args.empty() && _recognize(args.back()) == detail::Classifer::NONE) {
if(collected >= -num) {
// We could break here for allow extras, but we don't
// If any positionals remain, don't keep eating
if(_count_remaining_positionals() > 0)
break;
}
op->add_result(args.back());
parse_order_.push_back(op.get());
args.pop_back();
collected++;
}
// Allow -- to end an unlimited list and "eat" it
if(!args.empty() && _recognize(args.back()) == detail::Classifer::POSITIONAL_MARK)
args.pop_back();
} else {
while(num > 0 && !args.empty()) {
num--;
std::string current_ = args.back();
args.pop_back();
op->add_result(current_);
parse_order_.push_back(op.get());
}
if(num > 0) {
throw ArgumentMismatch::TypedAtLeast(op->single_name(), num, op->get_type_name());
}
}
if(!rest.empty()) {
rest = "-" + rest;
args.push_back(rest);
}
}
};
namespace FailureMessage {
inline std::string simple(const App *app, const Error &e) {
std::string header = std::string(e.what()) + "\n";
if(app->get_help_ptr() != nullptr)
header += "Run with " + app->get_help_ptr()->single_name() + " for more information.\n";
return header;
}
inline std::string help(const App *app, const Error &e) {
std::string header = std::string("ERROR: ") + e.get_name() + ": " + e.what() + "\n";
header += app->help();
return header;
}
} // namespace FailureMessage
namespace detail {
/// This class is simply to allow tests access to App's protected functions
struct AppFriend {
/// Wrap _parse_short, perfectly forward arguments and return
template <typename... Args>
static auto parse_arg(App *app, Args &&... args) ->
typename std::result_of<decltype (&App::_parse_arg)(App, Args...)>::type {
return app->_parse_arg(std::forward<Args>(args)...);
}
/// Wrap _parse_subcommand, perfectly forward arguments and return
template <typename... Args>
static auto parse_subcommand(App *app, Args &&... args) ->
typename std::result_of<decltype (&App::_parse_subcommand)(App, Args...)>::type {
return app->_parse_subcommand(std::forward<Args>(args)...);
}
};
} // namespace detail
} // namespace CLI
================================================
FILE: src/Database.cpp
================================================
//
// Database.cpp
// OnlinePhotometricCalibration
//
// Created by Paul on 16.11.17.
// Copyright (c) 2017-2018 Paul Bergmann and co-authors. All rights reserved.
//
// See LICENSE.txt
//
#include "Database.h"
/**
* Initialize vignette model with some vignetting
*/
Database::Database(int image_width,int image_height) :
m_vignette_estimate(-0.3,0,0,image_width,image_height),
m_response_estimate()
{
m_image_width = image_width;
m_image_height = image_height;
}
void Database::visualizeTracking()
{
// Fetch tracking information and create a canvas
Frame last_frame = m_tracked_frames.at(m_tracked_frames.size()-1);
// Todo: change to class member
cv::Mat draw_image = last_frame.m_image.clone();
// Draw features on the canvas
for(int i = 0;i < last_frame.m_features.size();i++)
{
cv::circle(draw_image, last_frame.m_features.at(i)->m_xy_location, 3, cv::Scalar(255,0,0));
}
// Correct the frame based on the current estimate
// Todo: change to class member
cv::Mat corrected_frame = last_frame.m_image.clone();
for(int r = 0; r < corrected_frame.rows;r++)
{
for(int c = 0;c < corrected_frame.cols;c++)
{
// Apply rsponse and vignette for each pixel
int o_value = corrected_frame.at<uchar>(r,c);
double new_o_value = m_response_estimate.removeResponse(o_value);
double v_factor = m_vignette_estimate.getVignetteFactor(cv::Point2f(c,r));
new_o_value /= v_factor;
// Correct by exposure time
new_o_value /= last_frame.m_exp_time;
if(new_o_value > 255)new_o_value = 255;
corrected_frame.at<uchar>(r,c) = (uchar)new_o_value;
}
}
//resize drawing images to an acceptable size
int image_width = 640;
int image_height = 480;
cv::resize(draw_image, draw_image, cv::Size(image_width,image_height));
cv::resize(corrected_frame, corrected_frame, cv::Size(image_width,image_height));
// Display
cv::imshow("Tracked frame", draw_image);
cv::imshow("Corrected frame", corrected_frame);
cv::waitKey(1);
}
void Database::visualizeRapidExposureTimeEstimates(double exponent)
{
// Visualize exposure times
// If GT data is available, the estimated exposure times will be aligned
// to the GT by computing an optimal alignment factor alignment_alpha
// If no GT data is available, the estimated exposure is simply scaled between [0,1]
int nr_frames_to_vis = int(fmin(m_tracked_frames.size(),40));
int exp_image_height = 150;
int draw_spacing = 8;
std::vector<double> estimated_exp_times;
std::vector<double> gt_exp_times;
double alignment_alpha = 1.0;
double max_exp = -10000.0;
double min_exp = 10000.0;
double top = 0;
double bot = 0;
for(int i = 0;i < nr_frames_to_vis;i++)
{
// Fetch estimated and GT exposure time data, pow estimates with alignment exponent
Frame current_frame = m_tracked_frames.at(m_tracked_frames.size()-nr_frames_to_vis+i);
double frame_exp_time = pow(current_frame.m_exp_time,exponent);
double frame_time_gt = current_frame.m_gt_exp_time;
// Keep track of max and min exposure to scale between [0,1]
if(frame_exp_time > max_exp)
max_exp = frame_exp_time;
if(frame_exp_time < min_exp)
min_exp = frame_exp_time;
// Accumulate information for least square fit between GT and estimated exposure
top += frame_exp_time*frame_time_gt;
bot += frame_exp_time*frame_exp_time;
// Push back estimated exposure values
estimated_exp_times.push_back(frame_exp_time);
// Push gt exposure time if available
if(!(frame_time_gt < 0))
gt_exp_times.push_back(frame_time_gt);
}
// Set alignment factor only if GT exposure is available
if(gt_exp_times.size() == estimated_exp_times.size())
alignment_alpha = top/bot;
else
{
// Normalize estimated exposures between [0,1]
for(int k = 0;k < estimated_exp_times.size();k++)
{
estimated_exp_times.at(k) = (estimated_exp_times.at(k)-min_exp)/(max_exp-min_exp);
}
}
// Create exposure time canvas
cv::Mat exposure_vis_image(exp_image_height,draw_spacing*nr_frames_to_vis,CV_8UC3,cv::Scalar(0,0,0));
// Draw estimated exposure times as lines to graph
for(int i = 0;i < nr_frames_to_vis-1;i++)
{
int drawing_y_exp_1 = exp_image_height - exp_image_height*(alignment_alpha * estimated_exp_times.at(i));
drawing_y_exp_1 = int(fmax(0,drawing_y_exp_1));
drawing_y_exp_1 = int(fmin(exp_image_height-1,drawing_y_exp_1));
int drawing_y_exp_2 = exp_image_height - exp_image_height*(alignment_alpha * estimated_exp_times.at(i+1));
drawing_y_exp_2 = int(fmax(0,drawing_y_exp_2));
drawing_y_exp_2 = int(fmin(exp_image_height-1,drawing_y_exp_2));
// Draw exposure lines
cv::line(exposure_vis_image, cv::Point(draw_spacing*i,drawing_y_exp_1), cv::Point(draw_spacing*(i+1),drawing_y_exp_2), cv::Scalar(0,0,255));
}
// Draw GT exposure line only if GT exposure data is available
if(gt_exp_times.size() == estimated_exp_times.size())
{
for(int i = 0;i < nr_frames_to_vis-1;i++)
{
int drawing_y_gt_exp_1 = exp_image_height - exp_image_height * gt_exp_times.at(i);
drawing_y_gt_exp_1 = int(fmax(0,drawing_y_gt_exp_1));
drawing_y_gt_exp_1 = int(fmin(exp_image_height-1,drawing_y_gt_exp_1));
int drawing_y_gt_exp_2 = exp_image_height - exp_image_height * gt_exp_times.at(i+1);
drawing_y_gt_exp_2 = int(fmax(0,drawing_y_gt_exp_2));
drawing_y_gt_exp_2 = int(fmin(exp_image_height-1,drawing_y_gt_exp_2));
cv::line(exposure_vis_image, cv::Point(draw_spacing*i,drawing_y_gt_exp_1), cv::Point(draw_spacing*(i+1),drawing_y_gt_exp_2), cv::Scalar(255,255,0));
}
}
cv::imshow("Estimated Exposure (Rapid)", exposure_vis_image);
cv::moveWindow("Estimated Exposure (Rapid)", 20+20+256,20);
}
// Todo: change the return to parameter passed by reference
std::vector<cv::Point2f> Database::fetchActiveFeatureLocations()
{
std::vector<cv::Point2f> point_locations;
Frame last_frame = m_tracked_frames.at(m_tracked_frames.size()-1);
for(int i = 0;i < last_frame.m_features.size();i++)
{
point_locations.push_back(last_frame.m_features.at(i)->m_xy_location);
}
return point_locations;
}
void Database::removeLastFrame()
{
// Erase the information about the first frame
m_tracked_frames.erase(m_tracked_frames.begin());
// Let all pointers of the new first frame point to NULL
for(int i = 0;i < m_tracked_frames.at(0).m_features.size();i++)
{
m_tracked_frames.at(0).m_features.at(i)->m_prev_feature = NULL;
}
}
================================================
FILE: src/Database.h
================================================
//
// Database.h
// OnlinePhotometricCalibration
//
// Created by Paul on 16.11.17.
// Copyright (c) 2017-2018 Paul Bergmann and co-authors. All rights reserved.
//
// See LICENSE.txt
//
#ifndef OnlinePhotometricCalibration_Database_h_
#define OnlinePhotometricCalibration_Database_h_
#include "StandardIncludes.h"
#include "Frame.h"
#include "VignetteModel.h"
#include "ResponseModel.h"
class Database
{
public:
/**
* Initialize database
*
* @param image_width Width of input images in pixels
* @param image_height Height of input images in pixels
*/
Database(int image_width,int image_height);
/**
* Tracked frames, exposure time estimates + radiance estimates of tracked points
* Frames also include the tracking information + output intensities
*/
std::vector<Frame> m_tracked_frames;
/**
* Vignette and response estimates
*/
VignetteModel m_vignette_estimate;
ResponseModel m_response_estimate;
/**
* Information about stored image size
*/
int m_image_width;
int m_image_height;
/**
* Fetch current active feature locations
*
* @returns Vector of feature locations active in the most current frame
*/
std::vector<cv::Point2f> fetchActiveFeatureLocations();
/**
* Fetch most current image
*
* @returns Most current image in the databse
*/
// Todo: change return type to reference
cv::Mat fetchActiveImage()
{
return m_tracked_frames.at(m_tracked_frames.size()-1).m_image;
}
/**
* Remove last frame and tracking information from the database
*/
void removeLastFrame();
/**
* Visualize the current tracking state
* Shows current active image with feature locations
* And corrected image based on current photometric estimates
* Calling this method slows down performance of the system significantly
*/
void visualizeTracking();
/**
* Visualize the rapid exposure time estimates
*/
void visualizeRapidExposureTimeEstimates(double exponent);
};
#endif // include guard
================================================
FILE: src/Feature.h
================================================
//
// Feature.h
// OnlinePhotometricCalibration
//
// Created by Paul on 16.11.17.
// Copyright (c) 2017-2018 Paul Bergmann and co-authors. All rights reserved.
//
// See LICENSE.txt
//
#ifndef OnlinePhotometricCalibration_Feature_h_
#define OnlinePhotometricCalibration_Feature_h_
#include <stdio.h>
#include "StandardIncludes.h"
/**
* Stores tracking information of one feature in one particular image
*/
class Feature
{
public:
/**
* Location of the feature in the image
*/
cv::Point2f m_xy_location;
/**
* Output values of the image patch centered around the feature location
*/
std::vector<double> m_output_values;
/**
* Radiance estimates of the image patch centered around the feature location
*/
std::vector<double> m_radiance_estimates;
/**
* Gradient values of the image patch centered around the feature location
*/
std::vector<double> m_gradient_values;
/*
* Link to the feature in the previous image corresponding to the same scene point
* (Obtained from tracking)
*/
Feature* m_prev_feature;
/*
* Link to the feature in the previous image corresponding to the same scene point
* (Obtained from tracking)
*/
Feature* m_next_feature;
};
#endif // include guard
================================================
FILE: src/Frame.h
================================================
//
// Frame.h
// OnlinePhotometricCalibration
//
// Created by Paul on 16.11.17.
// Copyright (c) 2017-2018 Paul Bergmann and co-authors. All rights reserved.
//
// See LICENSE.txt
//
#ifndef OnlinePhotometricCalibration_Frame_h_
#define OnlinePhotometricCalibration_Frame_h_
#include "StandardIncludes.h"
#include "Feature.h"
/**
* Stores tracking information for one entire image
*/
class Frame
{
public:
/**
* Original input image
*/
cv::Mat m_image;
/**
* Photometrically corrected image
*/
cv::Mat m_image_corrected;
/**
* Gradient information
*/
cv::Mat m_gradient_image;
/**
* List of features present in this frame
*/
std::vector<Feature*> m_features;
/**
* Exposure time estimate (from rapid exposure time estimation)
*/
double m_exp_time;
/**
* Ground truth exposure time if available
*/
double m_gt_exp_time;
};
#endif // include guard
================================================
FILE: src/GainRobustTracker.cpp
================================================
//
// GainRobustTracker.cpp
// OnlinePhotometricCalibration
//
// Created by Paul on 17.11.17.
// Copyright (c) 2017-2018 Paul Bergmann and co-authors. All rights reserved.
//
// See LICENSE.txt
//
#include "GainRobustTracker.h"
GainRobustTracker::GainRobustTracker(int patch_size,int pyramid_levels)
{
// Initialize patch size and pyramid levels
m_patch_size = patch_size;
m_pyramid_levels = pyramid_levels;
}
// Todo: change frame_1 frame 2 to ref (or const ref), pts_1 to ref
double GainRobustTracker::trackImagePyramids(cv::Mat frame_1,
cv::Mat frame_2,
std::vector<cv::Point2f> pts_1,
std::vector<cv::Point2f>& pts_2,
std::vector<int>& point_status)
{
// All points valid in the beginning of tracking
std::vector<int> point_validity;
for(int i = 0;i < pts_1.size();i++)
{
point_validity.push_back(1);
}
// Calculate image pyramid of frame 1 and frame 2
std::vector<cv::Mat> new_pyramid;
cv::buildPyramid(frame_2, new_pyramid, m_pyramid_levels);
std::vector<cv::Mat> old_pyramid;
cv::buildPyramid(frame_1, old_pyramid, m_pyramid_levels);
// Temporary vector to update tracking estiamtes over time
std::vector<cv::Point2f> tracking_estimates = pts_1;
double all_exp_estimates = 0.0;
int nr_estimates = 0;
// Iterate all pyramid levels and perform gain robust KLT on each level (coarse to fine)
for(int level = (int)new_pyramid.size()-1;level >= 0;level--)
{
// Scale the input points and tracking estimates to the current pyramid level
std::vector<cv::Point2f> scaled_tracked_points;
std::vector<cv::Point2f> scaled_tracking_estimates;
for(int i = 0;i < pts_1.size();i++)
{
cv::Point2f scaled_point;
scaled_point.x = (float)(pts_1.at(i).x/pow(2,level));
scaled_point.y = (float)(pts_1.at(i).y/pow(2,level));
scaled_tracked_points.push_back(scaled_point);
cv::Point2f scaled_estimate;
scaled_estimate.x = (float)(tracking_estimates.at(i).x/pow(2,level));
scaled_estimate.y = (float)(tracking_estimates.at(i).y/pow(2,level));
scaled_tracking_estimates.push_back(scaled_estimate);
}
// Perform tracking on current level
double exp_estimate = trackImageExposurePyr(old_pyramid.at(level),
new_pyramid.at(level),
scaled_tracked_points,
scaled_tracking_estimates,
point_validity);
// Optional: Do something with the estimated exposure ratio
// std::cout << "Estimated exposure ratio of current level: " << exp_estimate << std::endl;
// Average estimates of each level later
all_exp_estimates += exp_estimate;
nr_estimates++;
// Update the current tracking result by scaling down to pyramid level 0
for(int i = 0;i < scaled_tracking_estimates.size();i++)
{
if(point_validity.at(i) == 0)
continue;
cv::Point2f scaled_point;
scaled_point.x = (float)(scaled_tracking_estimates.at(i).x*pow(2,level));
scaled_point.y = (float)(scaled_tracking_estimates.at(i).y*pow(2,level));
tracking_estimates.at(i) = scaled_point;
}
}
// Write result to output vectors passed by reference
pts_2 = tracking_estimates;
point_status = point_validity;
// Average exposure ratio estimate
double overall_exp_estimate = all_exp_estimates / nr_estimates;
return overall_exp_estimate;
}
/**
* For a reference on the meaning of the optimization variables and the overall concept of this function
* refer to the photometric calibration paper
* introducing gain robust KLT tracking by Kim et al.
*/
// Todo: change Mat and vector to ref
double GainRobustTracker::trackImageExposurePyr(cv::Mat old_image,
cv::Mat new_image,
std::vector<cv::Point2f> input_points,
std::vector<cv::Point2f>& output_points,
std::vector<int>& point_validity)
{
// Number of points to track
int nr_points = static_cast<int>(input_points.size());
// Updated point locations which are updated throughout the iterations
if(output_points.size() == 0)
{
output_points = input_points;
}
else if(output_points.size() != input_points.size())
{
std::cout << "ERROR - OUTPUT POINT SIZE != INPUT POINT SIZE!" << std::endl;
return -1;
}
// Input image dimensions
int image_rows = new_image.rows;
int image_cols = new_image.cols;
// Final exposure time estimate
double K_total = 0.0;
for(int round = 0;round < 1;round++)
{
// Get the currently valid points
int nr_valid_points = getNrValidPoints(point_validity);
// Allocate space for W,V matrices
cv::Mat W(2*nr_valid_points,1,CV_64F,0.0);
cv::Mat V(2*nr_valid_points,1,CV_64F,0.0);
// Allocate space for U_INV and the original Us
cv::Mat U_INV(2*nr_valid_points,2*nr_valid_points,CV_64F,0.0);
std::vector<cv::Mat> Us;
double lambda = 0;
double m = 0;
int absolute_point_index = -1;
for(int p = 0;p < input_points.size();p++)
{
if(point_validity.at(p) == 0)
{
continue;
}
absolute_point_index++;
// Build U matrix
cv::Mat U(2,2, CV_64F, 0.0);
// Bilinear image interpolation
cv::Mat patch_intensities_1;
cv::Mat patch_intensities_2;
int absolute_patch_size = ((m_patch_size+1)*2+1); // Todo: why m_patch_size+1?
cv::getRectSubPix(new_image, cv::Size(absolute_patch_size,absolute_patch_size), output_points.at(p), patch_intensities_2,CV_32F);
cv::getRectSubPix(old_image, cv::Size(absolute_patch_size,absolute_patch_size), input_points.at(p), patch_intensities_1,CV_32F);
// Go through image patch around this point
for(int r = 0; r < 2*m_patch_size+1;r++)
{
for(int c = 0; c < 2*m_patch_size+1;c++)
{
// Fetch patch intensity values
double i_frame_1 = patch_intensities_1.at<float>(1+r,1+c);
double i_frame_2 = patch_intensities_2.at<float>(1+r,1+c);
if(i_frame_1 < 1)
i_frame_1 = 1;
if(i_frame_2 < 1)
i_frame_2 = 1;
// Estimate patch gradient values
double grad_1_x = (patch_intensities_1.at<float>(1+r,1+c+1) - patch_intensities_1.at<float>(1+r,1+c-1))/2;
double grad_1_y = (patch_intensities_1.at<float>(1+r+1,1+c) - patch_intensities_1.at<float>(1+r-1,1+c))/2;
double grad_2_x = (patch_intensities_2.at<float>(1+r,1+c+1) - patch_intensities_2.at<float>(1+r,1+c-1))/2;
double grad_2_y = (patch_intensities_2.at<float>(1+r+1,1+c) - patch_intensities_2.at<float>(1+r-1,1+c))/2;
double a = (1.0/i_frame_2)*grad_2_x + (1.0/i_frame_1)*grad_1_x;
double b = (1.0/i_frame_2)*grad_2_y + (1.0/i_frame_1)*grad_1_y;
double beta = log(i_frame_2/255.0) - log(i_frame_1/255.0);
U.at<double>(0,0) += 0.5*a*a;
U.at<double>(1,0) += 0.5*a*b;
U.at<double>(0,1) += 0.5*a*b;
U.at<double>(1,1) += 0.5*b*b;
W.at<double>(2*absolute_point_index,0) -= a;
W.at<double>(2*absolute_point_index+1,0) -= b;
V.at<double>(2*absolute_point_index,0) -= beta*a;
V.at<double>(2*absolute_point_index+1,0) -= beta*b;
lambda += 2;
m += 2*beta;
}
}
//Back up U for re-substitution
Us.push_back(U);
//Invert matrix U for this point and write it to diagonal of overall U_INV matrix
cv::Mat U_INV_p = U.inv();
//std::cout << cv::determinant(U_INV_p) << std::endl;
//std::cout << U_INV_p << std::endl;
//std::cout << U << std::endl;
U_INV.at<double>(2*absolute_point_index,2*absolute_point_index) = U_INV_p.at<double>(0,0);
U_INV.at<double>(2*absolute_point_index+1,2*absolute_point_index) = U_INV_p.at<double>(1,0);
U_INV.at<double>(2*absolute_point_index,2*absolute_point_index+1) = U_INV_p.at<double>(0,1);
U_INV.at<double>(2*absolute_point_index+1,2*absolute_point_index+1) = U_INV_p.at<double>(1,1);
}
// Todo: check if opencv utilizes the sparsity of U
//solve for the exposure
cv::Mat K_MAT;
cv::solve(-W.t()*U_INV*W+lambda, -W.t()*U_INV*V+m, K_MAT);
double K = K_MAT.at<double>(0,0);
//std::cout << -W.t()*U_INV*W+lambda << std::endl;
//std::cout << -W.t()*U_INV*V+m << std::endl;
//std::cout << K_MAT << std::endl;
// Solve for the displacements
absolute_point_index = -1;
for(int p = 0;p < nr_points;p++)
{
if(point_validity.at(p) == 0)
continue;
absolute_point_index++;
cv::Mat U_p = Us.at(absolute_point_index);
cv::Mat V_p = V(cv::Rect(0,2*absolute_point_index,1,2));
cv::Mat W_p = W(cv::Rect(0,2*absolute_point_index,1,2));
cv::Mat displacement;
cv::solve(U_p, V_p - K*W_p, displacement);
//std::cout << displacement << std::endl;
output_points.at(p).x += displacement.at<double>(0,0);
output_points.at(p).y += displacement.at<double>(1,0);
// Filter out this point if too close at the boundaries
int filter_margin = 2;
double x = output_points.at(p).x;
double y = output_points.at(p).y;
// Todo: the latter two should be ">=" ?
if(x < filter_margin || y < filter_margin || x > image_cols-filter_margin || y > image_rows-filter_margin)
{
point_validity.at(p) = 0;
}
}
K_total += K;
}
return exp(K_total);
}
int GainRobustTracker::getNrValidPoints(std::vector<int> validity_vector)
{
// Simply sum up the validity vector
int result = 0;
for(int i = 0;i < validity_vector.size();i++)
{
result += validity_vector.at(i);
}
return result;
}
================================================
FILE: src/GainRobustTracker.h
================================================
//
// GainRobustTracker.h
// OnlinePhotometricCalibration
//
// Created by Paul on 17.11.17.
// Copyright (c) 2017-2018 Paul Bergmann and co-authors. All rights reserved.
//
// See LICENSE.txt
//
#ifndef OnlinePhotometricCalibration_GainRobustTracker_h_
#define OnlinePhotometricCalibration_GainRobustTracker_h_
#include "StandardIncludes.h"
/**
* This class implements gain robust KLT tracking
* optimizing jointly for displacements of features and an exposure ratio between input frames
*/
class GainRobustTracker
{
public:
/**
* Constructor
*
* @param patch_size Size of tracking patches
* @param pyramid_levels Number of pyramid levels used for KLT tracking
*/
GainRobustTracker(int patch_size,int pyramid_levels);
/*
* Track a new image using exposure estimation + image pyramids
*
* @param frame_1 Frame to track points from
* @param frame_2 Frame to track points to
* @param pts_1 Given point locations in frame_1
* @param pts_2 Output point locations in frame_2 (tracked from frame_1 to frame_2)
* @param point_status Vector indicating point validity (set to 0 by tracker if e.g. tracked patches leave input images)
* @returns Exposure ratio estimate between frame_1 and frame_2 based on KLT optimization
*/
double trackImagePyramids(cv::Mat frame_1,
cv::Mat frame_2,
std::vector<cv::Point2f> pts_1,
std::vector<cv::Point2f>& pts_2,
std::vector<int>& point_status);
private:
/*
* Patch size used for tracking of image patches
*/
int m_patch_size;
/*
* Number of pyramid levels used for tracking
*/
int m_pyramid_levels;
/**
* Get number of valid points inside the specified validity vector
*
* @param validity_vector Vector of validity flags corresponding to tracking points
* @returns Number of valid flags inside the input vector
*/
int getNrValidPoints(std::vector<int> validity_vector);
/**
* Track points on a specific pyramid layer
*
* @param old_image First input image
* @param new_image Second input image, track new features to this image
* @param input_points Original points in first input image
* @param output_points Tracked point locations in second input image
* @returns Exposure ratio estimate between first and second input image
*/
double trackImageExposurePyr(cv::Mat old_image,
cv::Mat new_image,
std::vector<cv::Point2f> input_points,
std::vector<cv::Point2f>& output_points,
std::vector<int>& point_validity);
};
#endif // include guard
================================================
FILE: src/ImageReader.cpp
================================================
//
// ImageReader.cpp
// OnlinePhotometricCalibration
//
// Created by Paul on 16.11.17.
// Copyright (c) 2017-2018 Paul Bergmann and co-authors. All rights reserved.
//
// See LICENSE.txt
//
#include "ImageReader.h"
ImageReader::ImageReader(std::string image_folder,
cv::Size new_img_size)
{
m_img_new_size = new_img_size;
getDir(image_folder, m_files);
printf("ImageReader: got %d files in %s!\n", (int)m_files.size(), image_folder.c_str());
}
cv::Mat ImageReader::readImage(int image_index)
{
// Read image from disk
cv::Mat image = cv::imread(m_files.at(image_index), CV_LOAD_IMAGE_GRAYSCALE);
if(!image.data)
{
std::cout << "ERROR READING IMAGE " << m_files.at(image_index) << std::endl;
return cv::Mat();
}
// Resize input image
cv::resize(image, image, m_img_new_size);
return image;
}
int ImageReader::getDir(std::string dir, std::vector<std::string> &files)
{
DIR *dp;
struct dirent *dirp;
if((dp = opendir(dir.c_str())) == NULL)
{
return -1;
}
while ((dirp = readdir(dp)) != NULL)
{
std::string name = std::string(dirp->d_name);
if(name != "." && name != "..")
files.push_back(name);
}
closedir(dp);
std::sort(files.begin(), files.end());
if(dir.at(dir.length() - 1) != '/')
dir = dir+"/";
for(unsigned int i = 0; i < files.size(); i++)
{
if(files[i].at(0) != '/')
files[i] = dir + files[i];
}
return (int)files.size();
}
================================================
FILE: src/ImageReader.h
================================================
//
// ImageReader.h
// OnlinePhotometricCalibration
//
// Created by Paul on 16.11.17.
// Copyright (c) 2017-2018 Paul Bergmann and co-authors. All rights reserved.
//
// See LICENSE.txt
//
#ifndef OnlinePhotometricCalibration_ImageReader_h_
#define OnlinePhotometricCalibration_ImageReader_h_
#include <stdio.h>
#include <iostream>
#include <dirent.h>
#include "StandardIncludes.h"
/**
* Read input images from image files
* Resizes the images if requested
*/
class ImageReader
{
public:
/**
* Initialize the image reader
* @param image_folder Image folder
* @param new_size Resize input images to new_size
*/
ImageReader(std::string image_folder,
cv::Size new_size);
/**
* Read a new input image from the hard drive and return it
*
* @param Input image index to read
* @return Read input image
*/
cv::Mat readImage(int image_index);
int getNumImages() { return (int)m_files.size(); }
int getDir(std::string dir, std::vector<std::string> &files);
private:
/**
* Resize images to this size
*/
cv::Size m_img_new_size;
std::vector<std::string> m_files;
};
#endif // include guard
================================================
FILE: src/JacobianGenerator.cpp
================================================
//
// JacobianGenerator.cpp
// OnlinePhotometricCalibration
//
// Created by Paul on 16.11.17.
// Copyright (c) 2017-2018 Paul Bergmann and co-authors. All rights reserved.
//
// See LICENSE.txt
//
#include "JacobianGenerator.h"
JacobianGenerator::JacobianGenerator()
{
// Nothing to initialize
}
void JacobianGenerator::getRawJacobianRow(double I,
double r,
double e,
std::vector<double>& j_res,
std::vector<double>& j_vig,
double& j_e,
double& j_I)
{
j_res.clear();
j_vig.clear();
// Get the vignetting value
double a2 = m_vignetting_params.at(0);
double a4 = m_vignetting_params.at(1);
double a6 = m_vignetting_params.at(2);
double r2 = r * r;
double r4 = r2 * r2;
double r6 = r4 * r2;
double v = 1 + a2*r2 + a4*r4 + a6*r6;
// Evaluate the Grossberg base functions at the derivatives for the other derivatives
double eIv = e * I * v;
double h_0_d = evaluateGrossbergBaseFunction(0, true, eIv);
double h_1_d = evaluateGrossbergBaseFunction(1, true, eIv);
double h_2_d = evaluateGrossbergBaseFunction(2, true, eIv);
double h_3_d = evaluateGrossbergBaseFunction(3, true, eIv);
double h_4_d = evaluateGrossbergBaseFunction(4, true, eIv);
double deriv_value = h_0_d +
m_response_params.at(0)*h_1_d +
m_response_params.at(1)*h_2_d +
m_response_params.at(2)*h_3_d +
m_response_params.at(3)*h_4_d;
// Derive by the 4 Grossberg parameters
double j_res_1 = 255*evaluateGrossbergBaseFunction(1, false, eIv);
double j_res_2 = 255*evaluateGrossbergBaseFunction(2, false, eIv);
double j_res_3 = 255*evaluateGrossbergBaseFunction(3, false, eIv);
double j_res_4 = 255*evaluateGrossbergBaseFunction(4, false, eIv);
j_res.push_back(j_res_1);
j_res.push_back(j_res_2);
j_res.push_back(j_res_3);
j_res.push_back(j_res_4);
// Derive by the 3 vignetting parameters
double j_vig_1 = 255 * deriv_value * e * I * r2;
double j_vig_2 = 255 * deriv_value * e * I * r4;
double j_vig_3 = 255 * deriv_value * e * I * r6;
j_vig.push_back(j_vig_1);
j_vig.push_back(j_vig_2);
j_vig.push_back(j_vig_3);
// Derive by exposure time
j_e = 255 * deriv_value * (I*v);
double j_I_temp;
getJacobianRadiance(I, r, e, j_I_temp);
j_I = j_I_temp;
}
void JacobianGenerator::getJacobianRow_eca(double I,
double r,
double e,
cv::Mat jacobian,
int image_index,
int residual_index)
{
// Get the vignetting value
double a2 = m_vignetting_params.at(0);
double a4 = m_vignetting_params.at(1);
double a6 = m_vignetting_params.at(2);
double r2 = r * r;
double r4 = r2 * r2;
double r6 = r4 * r2;
double v = 1 + a2*r2 + a4*r4 + a6*r6;
// Evaluate the grossberg base functions' derivatives for the other derivatives
double eIv = e * I * v;
double h_0_d = evaluateGrossbergBaseFunction(0, true, eIv);
double h_1_d = evaluateGrossbergBaseFunction(1, true, eIv);
double h_2_d = evaluateGrossbergBaseFunction(2, true, eIv);
double h_3_d = evaluateGrossbergBaseFunction(3, true, eIv);
double h_4_d = evaluateGrossbergBaseFunction(4, true, eIv);
double deriv_value = h_0_d +
m_response_params.at(0)*h_1_d +
m_response_params.at(1)*h_2_d +
m_response_params.at(2)*h_3_d +
m_response_params.at(3)*h_4_d;
// Derive by the 4 Grossberg parameters
jacobian.at<double>(residual_index,0) = 255*evaluateGrossbergBaseFunction(1, false, eIv);
jacobian.at<double>(residual_index,1) = 255*evaluateGrossbergBaseFunction(2, false, eIv);
jacobian.at<double>(residual_index,2) = 255*evaluateGrossbergBaseFunction(3, false, eIv);
jacobian.at<double>(residual_index,3) = 255*evaluateGrossbergBaseFunction(4, false, eIv);
// Derive by the 3 vignetting parameters
jacobian.at<double>(residual_index,4) = 255 * deriv_value * e * I * r2;
jacobian.at<double>(residual_index,5) = 255 * deriv_value * e * I * r4;
jacobian.at<double>(residual_index,6) = 255 * deriv_value * e * I * r6;
// Derive by exposure time
jacobian.at<double>(residual_index,7+image_index) = 255 * deriv_value * (I*v);
}
void JacobianGenerator::getJacobianRadiance(double I,double r,double e,double& j_I)
{
double a2 = m_vignetting_params.at(0);
double a4 = m_vignetting_params.at(1);
double a6 = m_vignetting_params.at(2);
// Get the vignetting value
double r2 = r * r;
double r4 = r2 * r2;
double r6 = r4 * r2;
double v = 1 + a2*r2 + a4*r4 + a6*r6;
// Evaluate the Grossberg base functions' derivatives for the other derivatives
double h_0_d = evaluateGrossbergBaseFunction(0, true, e*I*v);
double h_1_d = evaluateGrossbergBaseFunction(1, true, e*I*v);
double h_2_d = evaluateGrossbergBaseFunction(2, true, e*I*v);
double h_3_d = evaluateGrossbergBaseFunction(3, true, e*I*v);
double h_4_d = evaluateGrossbergBaseFunction(4, true, e*I*v);
double deriv_value = h_0_d +
m_response_params.at(0)*h_1_d +
m_response_params.at(1)*h_2_d +
m_response_params.at(2)*h_3_d +
m_response_params.at(3)*h_4_d;
j_I = 255 * deriv_value * (e*v);
}
double JacobianGenerator::evaluateGrossbergBaseFunction(int base_function_index,bool is_derivative,double x)
{
if(x < 0)x = 0.0;
else if(x > 1)x = 1.0;
int x_int = round(x*1023);
int x_der_int = round(x*1021);
if(base_function_index == 0)
{
if(!is_derivative)
{
return m_f_0[x_int];
}
else
{
return m_f_0_der[x_der_int];
}
}
if(base_function_index == 1)
{
if(!is_derivative)
{
return m_h_1[x_int];
}
else
{
return m_h_1_der[x_der_int];
}
}
if(base_function_index == 2)
{
if(!is_derivative)
{
return m_h_2[x_int];
}
else
{
return m_h_2_der[x_der_int];
}
}
if(base_function_index == 3)
{
if(!is_derivative)
{
return m_h_3[x_int];
}
else
{
return m_h_3_der[x_der_int];
}
}
if(base_function_index == 4)
{
if(!is_derivative)
{
return m_h_4[x_int];
}
else
{
return m_h_4_der[x_der_int];
}
}
// Error code
return -1.0;
}
double JacobianGenerator::applyGrossbergResponse(double x)
{
double v0 = evaluateGrossbergBaseFunction(0, false, x);
double v1 = evaluateGrossbergBaseFunction(1, false, x);
double v2 = evaluateGrossbergBaseFunction(2, false, x);
double v3 = evaluateGrossbergBaseFunction(3, false, x);
double v4 = evaluateGrossbergBaseFunction(4, false, x);
double c1 = m_response_params.at(0);
double c2 = m_response_params.at(1);
double c3 = m_response_params.at(2);
double c4 = m_response_params.at(3);
return v0 + c1*v1 + c2*v2 + c3*v3 + c4*v4;
}
std::vector<double> JacobianGenerator::fitGrossbergModelToResponseVector(double* response)
{
// Given a response vector, find Grossberg parameters that fit well
cv::Mat LeftSide(4,4,CV_64F,0.0);
cv::Mat RightSide(4,1,CV_64F,0.0);
for(int i = 10;i < 240;i++)
{
response[i] /= 255.0;
double input = i/256.0;
double f0 = evaluateGrossbergBaseFunction(0, false, input);
double f1 = evaluateGrossbergBaseFunction(1, false, input);
double f2 = evaluateGrossbergBaseFunction(2, false, input);
double f3 = evaluateGrossbergBaseFunction(3, false, input);
double f4 = evaluateGrossbergBaseFunction(4, false, input);
// For equation 1
LeftSide.at<double>(0,0) += f1*f1;
LeftSide.at<double>(0,1) += f1*f2;
LeftSide.at<double>(0,2) += f1*f3;
LeftSide.at<double>(0,3) += f1*f4;
RightSide.at<double>(0,0) += (response[i]*f1 - f0*f1);
// For equation 2
LeftSide.at<double>(1,0) += f2*f1;
LeftSide.at<double>(1,1) += f2*f2;
LeftSide.at<double>(1,2) += f2*f3;
LeftSide.at<double>(1,3) += f2*f4;
RightSide.at<double>(1,0) += (response[i]*f2 - f0*f2);
// For equation 3
LeftSide.at<double>(2,0) += f3*f1;
LeftSide.at<double>(2,1) += f3*f2;
LeftSide.at<double>(2,2) += f3*f3;
LeftSide.at<double>(2,3) += f3*f4;
RightSide.at<double>(2,0) += (response[i]*f3 - f0*f3);
// For equation 4
LeftSide.at<double>(3,0) += f4*f1;
LeftSide.at<double>(3,1) += f4*f2;
LeftSide.at<double>(3,2) += f4*f3;
LeftSide.at<double>(3,3) += f4*f4;
RightSide.at<double>(3,0) += (response[i]*f4 - f0*f4);
}
cv::Mat Solution;
cv::solve(LeftSide, RightSide, Solution,cv::DECOMP_SVD);
std::vector<double> solution_response;
solution_response.push_back(Solution.at<double>(0,0));
solution_response.push_back(Solution.at<double>(1,0));
solution_response.push_back(Solution.at<double>(2,0));
solution_response.push_back(Solution.at<double>(3,0));
return solution_response;
}
================================================
FILE: src/JacobianGenerator.h
================================================
//
// JacobianGenerator.h
// OnlinePhotometricCalibration
//
// Created by Paul on 16.11.17.
// Copyright (c) 2017-2018 Paul Bergmann and co-authors. All rights reserved.
//
// See LICENSE.txt
//
#ifndef OnlinePhotometricCalibration_JacobianGenerator_h_
#define OnlinePhotometricCalibration_JacobianGenerator_h_
#include "StandardIncludes.h"
class JacobianGenerator
{
public:
/**
* Constructor
*/
JacobianGenerator();
/**
* Initialize Grossberg response parameters
*/
void setResponseParameters(std::vector<double> response_params)
{
m_response_params = response_params;
};
/**
* Initialize vignette parameters
*/
void setVignettingParameters(std::vector<double> vignetting_params)
{
m_vignetting_params = vignetting_params;
};
/**
* Get the raw Jacobian row to construct the Hessian directly
*/
void getRawJacobianRow(double I,
double r,
double e,
std::vector<double>& j_res,
std::vector<double>& j_vig,
double& j_e,
double& j_I);
/**
* Apply the Grossberg response to a value x
*/
double applyGrossbergResponse(double x);
/**
* Get the Jacobian information, passing the irradiance, radius of the point and exposure time
* of the image
*/
// Todo: what does eca mean? Term for evf from old version.
void getJacobianRow_eca(double I, double r, double e,cv::Mat jacobian,int image_index,int residual_index);
/**
* Get the Jacobian entry for the irradiance
*/
void getJacobianRadiance(double I,double r,double e, double& j_I);
/**
* Get 4 least squares parameters for an input response vector
*/
std::vector<double> fitGrossbergModelToResponseVector(double* response);
private:
/**
* Response and vignette parameters
*/
std::vector<double> m_response_params;
std::vector<double> m_vignetting_params;
//Evaluate one of the Grossberg base functions or their derivatives (f0,h0,h1,h2,h3,..) at location x
//Base functions are approximated by polynomials (of max. degree 10)
double evaluateGrossbergBaseFunction(int base_function_index,bool is_derivative,double x);
/**
* Here follow the PCA components of the first 4 basis functions of the Grossberg model as discrete 1024 component vectors
* The derivatives have 1023 components, obtained by symmetric differences
*/
double m_f_0[1024] = {0,0.0088337,0.014976,0.020237,0.024986,0.029375,0.033483,0.037402,0.041166,0.044812,0.048351,0.05179,0.055148,0.058435,0.061671,0.064858,0.067999,0.071094,0.074141,0.077147,0.080112,0.083033,0.085917,0.08876,0.091569,0.094344,0.097087,0.099801,0.10249,0.10515,0.10778,0.1104,0.11299,0.11557,0.11813,0.12068,0.1232,0.12572,0.12823,0.13072,0.13319,0.13566,0.13811,0.14055,0.14298,0.14539,0.14778,0.15016,0.15253,0.15489,0.15723,0.15957,0.1619,0.16423,0.16654,0.16885,0.17114,0.17343,0.1757,0.17797,0.18023,0.18247,0.1847,0.18693,0.18914,0.19135,0.19355,0.19575,0.19793,0.20011,0.20228,0.20445,0.2066,0.20875,0.2109,0.21303,0.21516,0.21729,0.21941,0.22152,0.22363,0.22574,0.22784,0.22994,0.23204,0.23413,0.23621,0.2383,0.24038,0.24246,0.24453,0.2466,0.24867,0.25073,0.25279,0.25484,0.25689,0.25893,0.26097,0.263,0.26502,0.26705,0.26906,0.27107,0.27308,0.27508,0.27708,0.27908,0.28107,0.28305,0.28503,0.28701,0.28898,0.29094,0.2929,0.29485,0.2968,0.29874,0.30068,0.30261,0.30453,0.30645,0.30836,0.31026,0.31216,0.31406,0.31595,0.31783,0.31971,0.32159,0.32345,0.32532,0.32717,0.32903,0.33087,0.33271,0.33455,0.33638,0.33821,0.34003,0.34184,0.34365,0.34546,0.34726,0.34905,0.35084,0.35262,0.35439,0.35616,0.35792,0.35968,0.36143,0.36318,0.36492,0.36665,0.36838,0.3701,0.37182,0.37354,0.37525,0.37695,0.37865,0.38035,0.38204,0.38372,0.3854,0.38707,0.38874,0.39041,0.39207,0.39372,0.39537,0.39702,0.39866,0.4003,0.40193,0.40356,0.40519,0.40681,0.40842,0.41003,0.41164,0.41324,0.41484,0.41644,0.41803,0.41961,0.4212,0.42278,0.42435,0.42593,0.42749,0.42906,0.43062,0.43217,0.43372,0.43527,0.43681,0.43835,0.43989,0.44142,0.44294,0.44446,0.44598,0.44749,0.449,0.4505,0.452,0.4535,0.45499,0.45647,0.45795,0.45943,0.4609,0.46236,0.46382,0.46528,0.46673,0.46817,0.46962,0.47105,0.47249,0.47392,0.47535,0.47677,0.47819,0.4796,0.48101,0.48242,0.48382,0.48521,0.48661,0.488,0.48938,0.49076,0.49214,0.49351,0.49487,0.49624,0.49759,0.49895,0.50029,0.50164,0.50298,0.50431,0.50564,0.50697,0.50829,0.50961,0.51092,0.51223,0.51354,0.51484,0.51614,0.51743,0.51872,0.52001,0.5213,0.52258,0.52385,0.52513,0.5264,0.52766,0.52893,0.53019,0.53145,0.5327,0.53395,0.5352,0.53644,0.53768,0.53891,0.54014,0.54137,0.54259,0.54382,0.54503,0.54625,0.54746,0.54867,0.54987,0.55107,0.55226,0.55346,0.55465,0.55583,0.55702,0.5582,0.55937,0.56055,0.56172,0.56289,0.56405,0.56521,0.56637,0.56753,0.56868,0.56983,0.57098,0.57213,0.57327,0.57441,0.57554,0.57667,0.5778,0.57892,0.58004,0.58116,0.58228,0.58339,0.58449,0.5856,0.58669,0.58779,0.58888,0.58997,0.59106,0.59214,0.59322,0.5943,0.59537,0.59644,0.5975,0.59856,0.59962,0.60068,0.60173,0.60278,0.60383,0.60487,0.60591,0.60695,0.60799,0.60902,0.61005,0.61108,0.6121,0.61312,0.61414,0.61515,0.61617,0.61717,0.61818,0.61918,0.62018,0.62117,0.62217,0.62316,0.62414,0.62513,0.62611,0.62709,0.62807,0.62904,0.63001,0.63098,0.63195,0.63291,0.63388,0.63484,0.6358,0.63675,0.63771,0.63866,0.63961,0.64056,0.6415,0.64245,0.64339,0.64433,0.64526,0.6462,0.64713,0.64806,0.64898,0.64991,0.65083,0.65175,0.65266,0.65358,0.65449,0.6554,0.6563,0.65721,0.65811,0.65901,0.65991,0.6608,0.6617,0.66259,0.66347,0.66436,0.66524,0.66613,0.66701,0.66788,0.66876,0.66963,0.67051,0.67137,0.67224,0.67311,0.67397,0.67483,0.67568,0.67654,0.67739,0.67824,0.67909,0.67994,0.68078,0.68162,0.68246,0.6833,0.68414,0.68497,0.6858,0.68663,0.68746,0.68828,0.68911,0.68993,0.69075,0.69157,0.69239,0.69321,0.69402,0.69483,0.69564,0.69645,0.69726,0.69807,0.69888,0.69968,0.70048,0.70128,0.70208,0.70288,0.70367,0.70447,0.70526,0.70604,0.70683,0.70762,0.7084,0.70918,0.70996,0.71074,0.71152,0.71229,0.71306,0.71384,0.71461,0.71537,0.71614,0.71691,0.71767,0.71843,0.71919,0.71996,0.72071,0.72147,0.72223,0.72298,0.72374,0.72449,0.72524,0.72599,0.72674,0.72748,0.72823,0.72897,0.72971,0.73046,0.7312,0.73193,0.73267,0.73341,0.73414,0.73487,0.7356,0.73633,0.73706,0.73778,0.73851,0.73923,0.73995,0.74067,0.74138,0.7421,0.74281,0.74352,0.74423,0.74494,0.74565,0.74635,0.74705,0.74775,0.74846,0.74915,0.74985,0.75055,0.75124,0.75194,0.75263,0.75332,0.75401,0.7547,0.75539,0.75608,0.75676,0.75745,0.75813,0.75881,0.75949,0.76016,0.76084,0.76151,0.76218,0.76286,0.76352,0.76419,0.76486,0.76552,0.76619,0.76685,0.76751,0.76817,0.76883,0.76949,0.77014,0.7708,0.77146,0.77211,0.77276,0.77342,0.77407,0.77472,0.77537,0.77602,0.77667,0.77732,0.77796,0.77861,0.77925,0.77989,0.78053,0.78117,0.78181,0.78244,0.78308,0.78371,0.78435,0.78498,0.78561,0.78624,0.78687,0.7875,0.78813,0.78876,0.78939,0.79001,0.79064,0.79126,0.79189,0.79251,0.79313,0.79375,0.79438,0.795,0.79562,0.79623,0.79685,0.79747,0.79808,0.7987,0.79931,0.79992,0.80053,0.80114,0.80175,0.80236,0.80296,0.80357,0.80417,0.80477,0.80537,0.80598,0.80657,0.80717,0.80777,0.80837,0.80896,0.80956,0.81016,0.81075,0.81134,0.81194,0.81253,0.81312,0.81371,0.8143,0.81489,0.81547,0.81606,0.81665,0.81724,0.81782,0.81841,0.81899,0.81957,0.82015,0.82073,0.82131,0.82188,0.82246,0.82303,0.82361,0.82418,0.82475,0.82532,0.82589,0.82646,0.82703,0.82759,0.82816,0.82872,0.82928,0.82985,0.83041,0.83097,0.83153,0.83209,0.83265,0.8332,0.83376,0.83432,0.83488,0.83543,0.83599,0.83654,0.8371,0.83765,0.8382,0.83875,0.8393,0.83985,0.8404,0.84094,0.84149,0.84203,0.84257,0.84311,0.84365,0.84419,0.84473,0.84526,0.8458,0.84633,0.84687,0.8474,0.84793,0.84846,0.84899,0.84952,0.85005,0.85058,0.8511,0.85163,0.85215,0.85268,0.8532,0.85373,0.85425,0.85477,0.85529,0.85581,0.85633,0.85685,0.85737,0.85789,0.85841,0.85892,0.85944,0.85995,0.86047,0.86098,0.86149,0.862,0.86251,0.86301,0.86352,0.86402,0.86453,0.86503,0.86553,0.86604,0.86654,0.86704,0.86753,0.86803,0.86853,0.86903,0.86952,0.87001,0.87051,0.871,0.87149,0.87198,0.87248,0.87297,0.87346,0.87395,0.87443,0.87492,0.87541,0.8759,0.87639,0.87687,0.87736,0.87784,0.87832,0.8788,0.87928,0.87976,0.88024,0.88072,0.8812,0.88167,0.88215,0.88263,0.8831,0.88358,0.88405,0.88452,0.885,0.88547,0.88594,0.88641,0.88689,0.88736,0.88783,0.8883,0.88877,0.88924,0.88971,0.89017,0.89064,0.89111,0.89157,0.89204,0.8925,0.89296,0.89342,0.89388,0.89434,0.89481,0.89526,0.89572,0.89618,0.89664,0.8971,0.89755,0.89801,0.89847,0.89892,0.89938,0.89983,0.90029,0.90074,0.9012,0.90165,0.90211,0.90256,0.90301,0.90346,0.90392,0.90437,0.90482,0.90527,0.90572,0.90617,0.90662,0.90706,0.90751,0.90795,0.9084,0.90884,0.90929,0.90973,0.91017,0.91061,0.91105,0.91149,0.91193,0.91237,0.91281,0.91325,0.91369,0.91413,0.91456,0.915,0.91544,0.91587,0.91631,0.91675,0.91718,0.91762,0.91806,0.91849,0.91893,0.91936,0.9198,0.92023,0.92067,0.9211,0.92153,0.92196,0.92239,0.92282,0.92325,0.92368,0.9241,0.92453,0.92495,0.92538,0.9258,0.92623,0.92665,0.92707,0.9275,0.92792,0.92834,0.92876,0.92918,0.9296,0.93002,0.93044,0.93086,0.93129,0.93171,0.93212,0.93254,0.93296,0.93338,0.9338,0.93422,0.93463,0.93505,0.93546,0.93588,0.93629,0.9367,0.93711,0.93753,0.93794,0.93835,0.93876,0.93917,0.93957,0.93998,0.94039,0.94079,0.9412,0.94161,0.94202,0.94242,0.94283,0.94324,0.94364,0.94405,0.94445,0.94485,0.94526,0.94566,0.94607,0.94647,0.94687,0.94728,0.94768,0.94808,0.94848,0.94888,0.94928,0.94967,0.95007,0.95047,0.95086,0.95125,0.95165,0.95204,0.95243,0.95282,0.95322,0.95361,0.954,0.95439,0.95478,0.95516,0.95555,0.95594,0.95633,0.95671,0.9571,0.95749,0.95787,0.95826,0.95865,0.95903,0.95941,0.9598,0.96018,0.96057,0.96095,0.96133,0.96172,0.9621,0.96248,0.96287,0.96325,0.96363,0.96401,0.96439,0.96477,0.96515,0.96553,0.96591,0.96629,0.96667,0.96705,0.96742,0.9678,0.96818,0.96856,0.96893,0.96931,0.96969,0.97006,0.97044,0.97081,0.97118,0.97156,0.97193,0.9723,0.97268,0.97305,0.97342,0.97379,0.97416,0.97452,0.97489,0.97526,0.97562,0.97599,0.97636,0.97672,0.97709,0.97745,0.97781,0.97818,0.97854,0.9789,0.97926,0.97962,0.97998,0.98034,0.9807,0.98105,0.98141,0.98177,0.98213,0.98248,0.98284,0.9832,0.98355,0.98391,0.98426,0.98462,0.98497,0.98533,0.98568,0.98603,0.98638,0.98673,0.98707,0.98742,0.98777,0.98811,0.98846,0.9888,0.98915,0.98949,0.98983,0.99017,0.99051,0.99086,0.9912,0.99153,0.99187,0.9922,0.99254,0.99287,0.99321,0.99354,0.99387,0.99421,0.99454,0.99487,0.9952,0.99553,0.99586,0.99618,0.99651,0.99683,0.99715,0.99747,0.99779,0.9981,0.99842,0.99874,0.99905,0.99937,0.99968,1
};
double m_h_1[1024] = {0,-0.0014523,-0.0021332,-0.0026743,-0.0031499,-0.0035824,-0.0039809,-0.0043598,-0.0047252,-0.0050806,-0.0054271,-0.0057658,-0.0060988,-0.0064263,-0.0067504,-0.0070713,-0.0073899,-0.0077059,-0.0080188,-0.0083293,-0.0086366,-0.0089397,-0.0092394,-0.0095354,-0.0098288,-0.010119,-0.010407,-0.010692,-0.010976,-0.011259,-0.011539,-0.011819,-0.012097,-0.012375,-0.012651,-0.012926,-0.0132,-0.013474,-0.013747,-0.014019,-0.01429,-0.014561,-0.014831,-0.015099,-0.015367,-0.015633,-0.015897,-0.016161,-0.016424,-0.016685,-0.016947,-0.017208,-0.017468,-0.017728,-0.017987,-0.018244,-0.018501,-0.018757,-0.019011,-0.019264,-0.019516,-0.019766,-0.020016,-0.020264,-0.020512,-0.020759,-0.021005,-0.02125,-0.021494,-0.021738,-0.02198,-0.022221,-0.022462,-0.022701,-0.02294,-0.023177,-0.023414,-0.02365,-0.023884,-0.024118,-0.02435,-0.024582,-0.024813,-0.025043,-0.025271,-0.025499,-0.025726,-0.025951,-0.026175,-0.026398,-0.02662,-0.026839,-0.027058,-0.027275,-0.027491,-0.027705,-0.027918,-0.028129,-0.028339,-0.028548,-0.028755,-0.028961,-0.029167,-0.02937,-0.029573,-0.029775,-0.029975,-0.030174,-0.030371,-0.030567,-0.030762,-0.030955,-0.031147,-0.031337,-0.031526,-0.031713,-0.031899,-0.032083,-0.032265,-0.032445,-0.032624,-0.032801,-0.032976,-0.033149,-0.033321,-0.03349,-0.033658,-0.033824,-0.033989,-0.034151,-0.034313,-0.034472,-0.034631,-0.034787,-0.034942,-0.035096,-0.035248,-0.035399,-0.035548,-0.035696,-0.035843,-0.035988,-0.036132,-0.036275,-0.036415,-0.036555,-0.036692,-0.036829,-0.036963,-0.037096,-0.037228,-0.037358,-0.037486,-0.037614,-0.037739,-0.037863,-0.037986,-0.038107,-0.038227,-0.038346,-0.038463,-0.03858,-0.038695,-0.038809,-0.038922,-0.039034,-0.039146,-0.039256,-0.039365,-0.039472,-0.039579,-0.039685,-0.03979,-0.039893,-0.039995,-0.040097,-0.040197,-0.040296,-0.040393,-0.04049,-0.040585,-0.040678,-0.040771,-0.040862,-0.040951,-0.041039,-0.041126,-0.041211,-0.041295,-0.041377,-0.041458,-0.041538,-0.041616,-0.041693,-0.041768,-0.041842,-0.041915,-0.041987,-0.042057,-0.042127,-0.042195,-0.042263,-0.042329,-0.042395,-0.04246,-0.042524,-0.042588,-0.04265,-0.042711,-0.042772,-0.042831,-0.04289,-0.042948,-0.043004,-0.04306,-0.043115,-0.043169,-0.043222,-0.043274,-0.043326,-0.043376,-0.043426,-0.043475,-0.043522,-0.043568,-0.043614,-0.043658,-0.043702,-0.043745,-0.043787,-0.043828,-0.043869,-0.043909,-0.043948,-0.043986,-0.044023,-0.04406,-0.044096,-0.044131,-0.044165,-0.044199,-0.044232,-0.044265,-0.044296,-0.044327,-0.044358,-0.044387,-0.044416,-0.044444,-0.044471,-0.044497,-0.044523,-0.044547,-0.044571,-0.044594,-0.044617,-0.044638,-0.044659,-0.044679,-0.044698,-0.044717,-0.044734,-0.04475,-0.044765,-0.04478,-0.044793,-0.044806,-0.044819,-0.044831,-0.044842,-0.044853,-0.044864,-0.044875,-0.044885,-0.044894,-0.044903,-0.044912,-0.04492,-0.044928,-0.044935,-0.044942,-0.044948,-0.044954,-0.044959,-0.044964,-0.044969,-0.044973,-0.044976,-0.044978,-0.04498,-0.044982,-0.044983,-0.044983,-0.044983,-0.044982,-0.04498,-0.044978,-0.044975,-0.044971,-0.044967,-0.044962,-0.044957,-0.044951,-0.044945,-0.044938,-0.044931,-0.044924,-0.044916,-0.044908,-0.0449,-0.044891,-0.044882,-0.044873,-0.044863,-0.044852,-0.044842,-0.044831,-0.044819,-0.044807,-0.044795,-0.044781,-0.044768,-0.044754,-0.04474,-0.044725,-0.044709,-0.044694,-0.044678,-0.044661,-0.044643,-0.044625,-0.044606,-0.044587,-0.044567,-0.044547,-0.044527,-0.044507,-0.044486,-0.044465,-0.044443,-0.044422,-0.0444,-0.044378,-0.044356,-0.044333,-0.044311,-0.044288,-0.044265,-0.044242,-0.044218,-0.044194,-0.04417,-0.044145,-0.04412,-0.044094,-0.044068,-0.044042,-0.044015,-0.043987,-0.043959,-0.043931,-0.043901,-0.043872,-0.043842,-0.043811,-0.043781,-0.04375,-0.043719,-0.043687,-0.043656,-0.043624,-0.043592,-0.043559,-0.043527,-0.043494,-0.043461,-0.043428,-0.043394,-0.043361,-0.043327,-0.043293,-0.043259,-0.043224,-0.04319,-0.043155,-0.04312,-0.043085,-0.043049,-0.043013,-0.042977,-0.042941,-0.042904,-0.042866,-0.042829,-0.042791,-0.042753,-0.042715,-0.042676,-0.042637,-0.042598,-0.042558,-0.042519,-0.042479,-0.042439,-0.042398,-0.042358,-0.042317,-0.042277,-0.042236,-0.042195,-0.042154,-0.042113,-0.042072,-0.042031,-0.041989,-0.041947,-0.041905,-0.041863,-0.041821,-0.041778,-0.041735,-0.041692,-0.041648,-0.041604,-0.04156,-0.041516,-0.041472,-0.041427,-0.041382,-0.041336,-0.04129,-0.041244,-0.041197,-0.041151,-0.041104,-0.041057,-0.04101,-0.040963,-0.040917,-0.04087,-0.040823,-0.040777,-0.04073,-0.040683,-0.040636,-0.040588,-0.040541,-0.040494,-0.040446,-0.040399,-0.040352,-0.040305,-0.040257,-0.04021,-0.040162,-0.040114,-0.040066,-0.040018,-0.039969,-0.03992,-0.039871,-0.039821,-0.039771,-0.039721,-0.039671,-0.039621,-0.03957,-0.039519,-0.039468,-0.039417,-0.039366,-0.039315,-0.039264,-0.039212,-0.03916,-0.039108,-0.039056,-0.039004,-0.038951,-0.038899,-0.038847,-0.038794,-0.038742,-0.03869,-0.038638,-0.038585,-0.038533,-0.038481,-0.038429,-0.038377,-0.038324,-0.038272,-0.03822,-0.038167,-0.038115,-0.038062,-0.038009,-0.037956,-0.037903,-0.03785,-0.037796,-0.037743,-0.037689,-0.037635,-0.037581,-0.037526,-0.037472,-0.037417,-0.037362,-0.037307,-0.037252,-0.037198,-0.037142,-0.037088,-0.037033,-0.036978,-0.036923,-0.036869,-0.036814,-0.03676,-0.036705,-0.03665,-0.036595,-0.03654,-0.036485,-0.03643,-0.036375,-0.036319,-0.036264,-0.036208,-0.036152,-0.036096,-0.03604,-0.035984,-0.035927,-0.03587,-0.035812,-0.035755,-0.035697,-0.035639,-0.035581,-0.035523,-0.035465,-0.035407,-0.035349,-0.035291,-0.035234,-0.035176,-0.035119,-0.035062,-0.035004,-0.034947,-0.034889,-0.034832,-0.034774,-0.034716,-0.034658,-0.0346,-0.034542,-0.034484,-0.034426,-0.034367,-0.034308,-0.034249,-0.03419,-0.03413,-0.03407,-0.034011,-0.03395,-0.03389,-0.03383,-0.033769,-0.033709,-0.033648,-0.033588,-0.033527,-0.033466,-0.033406,-0.033345,-0.033285,-0.033224,-0.033164,-0.033104,-0.033044,-0.032984,-0.032924,-0.032864,-0.032804,-0.032743,-0.032683,-0.032622,-0.032561,-0.0325,-0.032439,-0.032378,-0.032316,-0.032254,-0.032193,-0.032131,-0.032069,-0.032007,-0.031944,-0.031881,-0.031818,-0.031755,-0.031692,-0.031628,-0.031564,-0.031501,-0.031437,-0.031373,-0.031309,-0.031246,-0.031182,-0.031119,-0.031056,-0.030993,-0.03093,-0.030867,-0.030804,-0.030741,-0.030678,-0.030616,-0.030553,-0.03049,-0.030427,-0.030364,-0.0303,-0.030237,-0.030173,-0.030109,-0.030045,-0.029981,-0.029917,-0.029852,-0.029788,-0.029723,-0.029657,-0.029591,-0.029526,-0.02946,-0.029393,-0.029327,-0.029261,-0.029195,-0.029128,-0.029062,-0.028995,-0.028929,-0.028863,-0.028797,-0.028731,-0.028665,-0.028599,-0.028534,-0.028468,-0.028402,-0.028337,-0.028271,-0.028205,-0.02814,-0.028074,-0.028008,-0.027942,-0.027876,-0.02781,-0.027745,-0.027678,-0.027612,-0.027545,-0.027479,-0.027411,-0.027344,-0.027276,-0.027208,-0.02714,-0.027072,-0.027004,-0.026935,-0.026867,-0.026798,-0.026729,-0.02666,-0.026592,-0.026523,-0.026454,-0.026386,-0.026317,-0.026249,-0.02618,-0.026112,-0.026044,-0.025976,-0.025908,-0.02584,-0.025772,-0.025704,-0.025636,-0.025568,-0.025499,-0.025431,-0.025362,-0.025294,-0.025226,-0.025157,-0.025089,-0.02502,-0.024951,-0.024881,-0.024812,-0.024742,-0.024672,-0.024601,-0.024531,-0.024461,-0.024391,-0.024321,-0.024251,-0.024181,-0.024111,-0.024041,-0.023971,-0.023901,-0.023831,-0.023761,-0.02369,-0.02362,-0.02355,-0.02348,-0.02341,-0.02334,-0.023269,-0.023198,-0.023128,-0.023057,-0.022986,-0.022915,-0.022844,-0.022772,-0.0227,-0.022629,-0.022557,-0.022484,-0.022412,-0.02234,-0.022268,-0.022196,-0.022123,-0.022051,-0.021978,-0.021906,-0.021834,-0.021762,-0.02169,-0.021618,-0.021546,-0.021473,-0.0214,-0.021328,-0.021255,-0.021182,-0.021109,-0.021035,-0.020962,-0.020888,-0.020814,-0.02074,-0.020666,-0.020592,-0.020518,-0.020443,-0.020368,-0.020292,-0.020216,-0.020141,-0.020065,-0.019989,-0.019913,-0.019837,-0.019762,-0.019686,-0.019611,-0.019535,-0.01946,-0.019385,-0.01931,-0.019235,-0.01916,-0.019085,-0.019009,-0.018934,-0.018859,-0.018784,-0.018709,-0.018633,-0.018558,-0.018482,-0.018407,-0.018331,-0.018254,-0.018178,-0.018101,-0.018024,-0.017947,-0.01787,-0.017793,-0.017715,-0.017637,-0.017558,-0.01748,-0.017401,-0.017323,-0.017244,-0.017166,-0.017087,-0.017008,-0.01693,-0.016852,-0.016774,-0.016697,-0.016619,-0.016542,-0.016464,-0.016387,-0.01631,-0.016232,-0.016154,-0.016077,-0.015999,-0.015921,-0.015844,-0.015766,-0.015689,-0.015611,-0.015533,-0.015455,-0.015376,-0.015298,-0.015219,-0.01514,-0.015061,-0.014982,-0.014902,-0.014823,-0.014744,-0.014665,-0.014586,-0.014507,-0.014428,-0.01435,-0.014271,-0.014193,-0.014115,-0.014036,-0.013958,-0.01388,-0.013801,-0.013723,-0.013644,-0.013566,-0.013488,-0.013409,-0.01333,-0.013251,-0.013171,-0.013092,-0.013012,-0.012933,-0.012853,-0.012772,-0.012692,-0.012611,-0.01253,-0.012449,-0.012368,-0.012286,-0.012205,-0.012124,-0.012042,-0.011961,-0.01188,-0.011798,-0.011717,-0.011636,-0.011556,-0.011475,-0.011395,-0.011315,-0.011235,-0.011155,-0.011076,-0.010996,-0.010916,-0.010836,-0.010756,-0.010676,-0.010597,-0.010517,-0.010437,-0.010358,-0.010278,-0.010198,-0.010118,-0.010038,-0.0099572,-0.0098768,-0.0097964,-0.0097162,-0.009636,-0.0095558,-0.0094755,-0.009395,-0.0093142,-0.0092332,-0.0091522,-0.0090711,-0.0089901,-0.0089092,-0.0088283,-0.0087475,-0.0086667,-0.0085857,-0.0085044,-0.0084229,-0.0083413,-0.0082596,-0.0081778,-0.0080958,-0.0080136,-0.0079313,-0.0078489,-0.0077663,-0.0076835,-0.0076005,-0.0075175,-0.0074344,-0.0073511,-0.0072679,-0.0071848,-0.0071016,-0.0070185,-0.0069354,-0.006852,-0.0067684,-0.006685,-0.0066018,-0.0065188,-0.0064358,-0.006353,-0.0062704,-0.0061877,-0.006105,-0.0060221,-0.005939,-0.005856,-0.0057731,-0.0056902,-0.0056076,-0.0055251,-0.0054426,-0.0053602,-0.0052777,-0.005195,-0.0051119,-0.0050288,-0.0049455,-0.0048622,-0.0047786,-0.0046949,-0.0046111,-0.0045274,-0.0044436,-0.0043596,-0.0042749,-0.00419,-0.0041049,-0.0040198,-0.0039347,-0.0038496,-0.0037645,-0.0036794,-0.0035945,-0.0035096,-0.0034243,-0.0033393,-0.0032545,-0.0031698,-0.0030852,-0.0030005,-0.0029159,-0.0028313,-0.0027468,-0.0026623,-0.0025773,-0.002492,-0.0024067,-0.0023215,-0.0022367,-0.0021519,-0.0020668,-0.0019817,-0.0018966,-0.0018116,-0.0017261,-0.0016399,-0.0015535,-0.0014668,-0.0013798,-0.0012927,-0.0012056,-0.001119,-0.0010326,-0.00094644,-0.00086078,-0.00077461,-0.00068832,-0.00060193,-0.0005156,-0.00042937,-0.00034323,-0.00025723,-0.00017134,-8.5608e-05,-1.7347e-18
};
double m_h_2[1024] = {0,-0.0068347,-0.010307,-0.013097,-0.015503,-0.017653,-0.019616,-0.021445,-0.023169,-0.02481,-0.026374,-0.02787,-0.029302,-0.030675,-0.031995,-0.033266,-0.034488,-0.035667,-0.036804,-0.037904,-0.038969,-0.04,-0.040994,-0.041958,-0.042891,-0.043794,-0.04467,-0.045518,-0.04634,-0.047138,-0.047913,-0.048664,-0.049394,-0.050103,-0.050793,-0.051466,-0.052121,-0.052758,-0.05338,-0.053986,-0.054576,-0.05515,-0.055709,-0.056253,-0.056783,-0.057298,-0.057798,-0.058284,-0.058756,-0.059215,-0.05966,-0.060092,-0.060511,-0.060917,-0.06131,-0.061691,-0.062059,-0.062413,-0.062753,-0.063078,-0.06339,-0.063689,-0.063975,-0.064249,-0.06451,-0.064758,-0.064995,-0.06522,-0.065435,-0.065637,-0.065827,-0.066007,-0.066177,-0.066336,-0.066485,-0.066622,-0.06675,-0.066867,-0.066974,-0.067073,-0.067162,-0.067241,-0.06731,-0.067371,-0.067423,-0.067465,-0.067499,-0.067524,-0.067538,-0.067544,-0.06754,-0.067528,-0.067507,-0.067477,-0.067438,-0.06739,-0.067334,-0.06727,-0.067196,-0.067114,-0.067025,-0.066928,-0.066822,-0.066708,-0.066588,-0.066461,-0.066327,-0.066185,-0.066038,-0.065885,-0.065724,-0.065559,-0.065389,-0.065212,-0.065029,-0.064842,-0.064649,-0.064451,-0.064249,-0.064041,-0.06383,-0.063614,-0.063393,-0.063169,-0.062939,-0.062705,-0.062467,-0.062225,-0.06198,-0.061731,-0.061479,-0.061223,-0.060964,-0.060702,-0.060437,-0.060169,-0.0599,-0.059626,-0.059352,-0.059075,-0.058795,-0.058513,-0.058227,-0.057939,-0.057649,-0.057357,-0.057063,-0.056766,-0.056468,-0.056167,-0.055864,-0.055559,-0.055251,-0.054943,-0.054634,-0.054323,-0.054009,-0.053694,-0.053376,-0.053058,-0.052738,-0.052417,-0.052093,-0.051768,-0.051441,-0.051113,-0.050783,-0.050453,-0.050119,-0.049785,-0.04945,-0.049114,-0.048775,-0.048434,-0.048092,-0.047749,-0.047404,-0.047058,-0.046711,-0.046363,-0.046011,-0.04566,-0.045308,-0.044954,-0.044597,-0.044241,-0.043882,-0.043521,-0.043161,-0.042797,-0.042432,-0.042066,-0.041697,-0.041326,-0.040954,-0.040581,-0.040207,-0.039831,-0.039455,-0.039078,-0.038699,-0.038319,-0.037939,-0.037559,-0.037178,-0.036798,-0.036419,-0.036039,-0.035662,-0.035285,-0.034908,-0.034532,-0.034158,-0.033784,-0.033412,-0.03304,-0.032669,-0.032299,-0.031929,-0.031562,-0.031194,-0.030827,-0.030462,-0.030098,-0.029735,-0.029373,-0.029011,-0.028651,-0.028292,-0.027933,-0.027575,-0.027219,-0.026863,-0.026508,-0.026154,-0.0258,-0.025447,-0.025096,-0.024746,-0.024397,-0.024048,-0.023702,-0.023355,-0.02301,-0.022668,-0.022325,-0.021983,-0.021642,-0.021302,-0.020963,-0.020624,-0.020287,-0.019952,-0.019618,-0.019284,-0.018952,-0.018621,-0.018291,-0.017962,-0.017634,-0.017309,-0.016984,-0.016661,-0.016338,-0.016017,-0.015699,-0.015381,-0.015063,-0.014747,-0.014432,-0.014119,-0.013807,-0.013496,-0.013185,-0.012877,-0.012569,-0.012262,-0.011957,-0.011652,-0.011349,-0.011047,-0.010746,-0.010446,-0.010148,-0.0098508,-0.0095548,-0.0092602,-0.0089671,-0.0086748,-0.0083839,-0.0080947,-0.007806,-0.0075181,-0.0072313,-0.0069458,-0.0066611,-0.0063777,-0.0060952,-0.0058141,-0.0055343,-0.0052557,-0.0049783,-0.0047019,-0.0044267,-0.0041522,-0.003879,-0.0036074,-0.0033367,-0.003067,-0.002798,-0.0025299,-0.0022637,-0.0019984,-0.0017338,-0.0014707,-0.0012081,-0.00094708,-0.00068784,-0.00043029,-0.00017447,8.0061e-05,0.00033373,0.00058625,0.00083738,0.0010864,0.0013345,0.0015814,0.0018269,0.0020714,0.0023141,0.0025552,0.0027949,0.0030335,0.0032705,0.0035057,0.00374,0.0039728,0.0042041,0.0044347,0.004664,0.0048907,0.0051161,0.0053408,0.0055642,0.0057866,0.0060076,0.0062269,0.0064447,0.0066615,0.006877,0.0070915,0.0073043,0.0075159,0.0077268,0.0079358,0.008143,0.0083492,0.0085539,0.0087573,0.0089598,0.0091611,0.0093613,0.0095593,0.0097565,0.0099527,0.010148,0.010341,0.010533,0.010725,0.010916,0.011105,0.011294,0.011482,0.011668,0.011853,0.012037,0.012221,0.012403,0.012583,0.012763,0.012943,0.01312,0.013297,0.013472,0.013647,0.013821,0.013993,0.014164,0.014334,0.014504,0.014671,0.014837,0.015001,0.015166,0.015329,0.01549,0.015651,0.015811,0.01597,0.016126,0.016282,0.016437,0.016591,0.016745,0.016897,0.017047,0.017198,0.017346,0.017493,0.017639,0.017785,0.01793,0.018073,0.018216,0.018358,0.0185,0.01864,0.01878,0.018918,0.019054,0.01919,0.019325,0.019458,0.01959,0.019722,0.019852,0.019981,0.02011,0.020237,0.020363,0.020488,0.020613,0.020736,0.020857,0.020977,0.021097,0.021216,0.021334,0.021451,0.021567,0.021682,0.021796,0.021908,0.022019,0.02213,0.022239,0.022348,0.022455,0.022562,0.022668,0.022773,0.022877,0.02298,0.023083,0.023184,0.023285,0.023384,0.023482,0.023579,0.023675,0.023771,0.023865,0.02396,0.024053,0.024145,0.024237,0.024327,0.024417,0.024506,0.024594,0.024681,0.024768,0.024853,0.024937,0.025021,0.025104,0.025187,0.025269,0.02535,0.02543,0.02551,0.025589,0.025667,0.025744,0.02582,0.025895,0.02597,0.026044,0.026117,0.026189,0.02626,0.026331,0.026401,0.02647,0.026538,0.026605,0.026672,0.026738,0.026803,0.026867,0.02693,0.026992,0.027054,0.027116,0.027177,0.027237,0.027296,0.027354,0.027413,0.027471,0.027527,0.027583,0.027638,0.027693,0.027747,0.0278,0.027853,0.027904,0.027955,0.028006,0.028055,0.028104,0.028152,0.028198,0.028243,0.028289,0.028334,0.028378,0.02842,0.028463,0.028504,0.028545,0.028586,0.028626,0.028665,0.028703,0.02874,0.028776,0.028813,0.028848,0.028883,0.028916,0.028949,0.028982,0.029015,0.029047,0.029078,0.029108,0.029138,0.029168,0.029197,0.029226,0.029254,0.02928,0.029306,0.029332,0.029357,0.029382,0.029406,0.029429,0.029451,0.029474,0.029495,0.029516,0.029536,0.029556,0.029575,0.029594,0.029613,0.02963,0.029647,0.029663,0.029679,0.029694,0.029709,0.029724,0.029738,0.029751,0.029763,0.029775,0.029787,0.029799,0.02981,0.029821,0.02983,0.02984,0.029849,0.029857,0.029865,0.029872,0.029878,0.029884,0.029889,0.029895,0.0299,0.029905,0.029909,0.029912,0.029914,0.029916,0.029918,0.029919,0.029919,0.029919,0.029917,0.029916,0.029914,0.029911,0.029909,0.029906,0.029902,0.029898,0.029893,0.029888,0.029883,0.029878,0.029872,0.029866,0.029859,0.029853,0.029846,0.029838,0.02983,0.029822,0.029813,0.029803,0.029792,0.029781,0.02977,0.029759,0.029747,0.029735,0.029721,0.029708,0.029694,0.029679,0.029665,0.029649,0.029632,0.029615,0.029598,0.02958,0.029562,0.029544,0.029524,0.029504,0.029483,0.029461,0.029439,0.029418,0.029396,0.029374,0.029351,0.029328,0.029304,0.02928,0.029257,0.029233,0.029209,0.029183,0.029158,0.029131,0.029105,0.029078,0.02905,0.029022,0.028994,0.028965,0.028936,0.028906,0.028876,0.028845,0.028814,0.028782,0.028749,0.028716,0.028683,0.028649,0.028615,0.028581,0.028546,0.02851,0.028474,0.028438,0.028402,0.028365,0.028327,0.028289,0.028251,0.028212,0.028172,0.028131,0.028091,0.02805,0.028009,0.027968,0.027927,0.027884,0.02784,0.027797,0.027753,0.027709,0.027665,0.02762,0.027574,0.027527,0.02748,0.027433,0.027386,0.027338,0.027289,0.027241,0.027191,0.027141,0.027091,0.027041,0.02699,0.02694,0.026889,0.026839,0.026787,0.026735,0.026682,0.026629,0.026576,0.026523,0.02647,0.026415,0.02636,0.026305,0.02625,0.026195,0.026139,0.026083,0.026027,0.02597,0.025913,0.025855,0.025797,0.025738,0.02568,0.025621,0.025562,0.025503,0.025443,0.025383,0.025323,0.025261,0.025201,0.02514,0.025079,0.025018,0.024956,0.024895,0.024833,0.024772,0.02471,0.024647,0.024584,0.02452,0.024456,0.024392,0.024328,0.024264,0.024199,0.024134,0.024069,0.024003,0.023938,0.023871,0.023804,0.023737,0.023669,0.023602,0.023535,0.023467,0.023399,0.023331,0.023262,0.023193,0.023124,0.023056,0.022987,0.022918,0.022848,0.022779,0.022709,0.022639,0.022568,0.022497,0.022426,0.022354,0.022283,0.022211,0.02214,0.022068,0.021995,0.021922,0.021849,0.021775,0.021701,0.021626,0.021551,0.021476,0.021399,0.021322,0.021246,0.021168,0.021091,0.021014,0.020937,0.020859,0.020781,0.020702,0.020623,0.020543,0.020464,0.020384,0.020305,0.020225,0.020146,0.020066,0.019985,0.019904,0.019823,0.019741,0.01966,0.019578,0.019497,0.019415,0.019332,0.019249,0.019165,0.019082,0.018998,0.018915,0.018831,0.018747,0.018662,0.018577,0.018491,0.018405,0.018318,0.018232,0.018145,0.018058,0.017971,0.017885,0.017798,0.017711,0.017624,0.017536,0.017448,0.017359,0.017271,0.017183,0.017095,0.017007,0.016918,0.016828,0.016737,0.016647,0.016557,0.016467,0.016376,0.016285,0.016194,0.016102,0.016009,0.015916,0.015823,0.01573,0.015636,0.015543,0.015449,0.015355,0.015261,0.015167,0.015072,0.014976,0.014881,0.014784,0.014688,0.014593,0.014497,0.014402,0.014306,0.014209,0.014112,0.014015,0.013918,0.01382,0.013723,0.013625,0.013528,0.01343,0.013332,0.013234,0.013136,0.013037,0.012939,0.01
gitextract_g6ru51pt/
├── .gitignore
├── .gitlab-ci.yml
├── .travis.yml
├── AUTHORS.txt
├── CHANGELOG.md
├── CMakeLists.txt
├── LICENSE.txt
├── README.md
└── src/
├── CLI11.hpp
├── Database.cpp
├── Database.h
├── Feature.h
├── Frame.h
├── GainRobustTracker.cpp
├── GainRobustTracker.h
├── ImageReader.cpp
├── ImageReader.h
├── JacobianGenerator.cpp
├── JacobianGenerator.h
├── NonlinearOptimizer.cpp
├── NonlinearOptimizer.h
├── OptimizationBlock.cpp
├── OptimizationBlock.h
├── OptimizedPoint.h
├── RapidExposureTimeEstimator.cpp
├── RapidExposureTimeEstimator.h
├── ResponseModel.h
├── StandardIncludes.h
├── Tracker.cpp
├── Tracker.h
├── VignetteModel.cpp
├── VignetteModel.h
└── main.cpp
SYMBOL INDEX (45 symbols across 16 files)
FILE: src/CLI11.hpp
type CLI (line 101) | namespace CLI {
type detail (line 204) | namespace detail {
function split (line 208) | inline std::vector<std::string> split(const std::string &s, char del...
function join (line 225) | std::string join(const T &v, std::string delim = ",") {
function rjoin (line 237) | std::string rjoin(const T &v, std::string delim = ",") {
function trim_copy (line 285) | inline std::string trim_copy(const std::string &str) {
function trim_copy (line 291) | inline std::string trim_copy(const std::string &str, const std::stri...
function format_help (line 296) | inline void format_help(std::stringstream &out, std::string name, st...
function valid_first_char (line 308) | bool valid_first_char(T c) { return std::isalpha(c, std::locale()) |...
function valid_later_char (line 311) | bool valid_later_char(T c) {
function valid_name_string (line 316) | inline bool valid_name_string(const std::string &str) {
function to_lower (line 326) | inline std::string to_lower(std::string str) {
function split_up (line 334) | inline std::vector<std::string> split_up(std::string str) {
function fix_newlines (line 383) | inline std::string fix_newlines(std::string leader, std::string inpu...
type ExitCodes (line 419) | enum class ExitCodes {
class Error (line 448) | class Error : public std::runtime_error {
method get_exit_code (line 453) | int get_exit_code() const { return exit_code; }
method get_name (line 455) | std::string get_name() const { return name; }
method Error (line 457) | Error(std::string name, std::string msg, int exit_code = static_cast...
method Error (line 460) | Error(std::string name, std::string msg, ExitCodes exit_code) : Erro...
function namespace (line 466) | class ConstructionError : public Error {
type CLI (line 114) | namespace CLI {
type detail (line 204) | namespace detail {
function split (line 208) | inline std::vector<std::string> split(const std::string &s, char del...
function join (line 225) | std::string join(const T &v, std::string delim = ",") {
function rjoin (line 237) | std::string rjoin(const T &v, std::string delim = ",") {
function trim_copy (line 285) | inline std::string trim_copy(const std::string &str) {
function trim_copy (line 291) | inline std::string trim_copy(const std::string &str, const std::stri...
function format_help (line 296) | inline void format_help(std::stringstream &out, std::string name, st...
function valid_first_char (line 308) | bool valid_first_char(T c) { return std::isalpha(c, std::locale()) |...
function valid_later_char (line 311) | bool valid_later_char(T c) {
function valid_name_string (line 316) | inline bool valid_name_string(const std::string &str) {
function to_lower (line 326) | inline std::string to_lower(std::string str) {
function split_up (line 334) | inline std::vector<std::string> split_up(std::string str) {
function fix_newlines (line 383) | inline std::string fix_newlines(std::string leader, std::string inpu...
type ExitCodes (line 419) | enum class ExitCodes {
class Error (line 448) | class Error : public std::runtime_error {
method get_exit_code (line 453) | int get_exit_code() const { return exit_code; }
method get_name (line 455) | std::string get_name() const { return name; }
method Error (line 457) | Error(std::string name, std::string msg, int exit_code = static_cast...
method Error (line 460) | Error(std::string name, std::string msg, ExitCodes exit_code) : Erro...
function namespace (line 466) | class ConstructionError : public Error {
type CLI (line 156) | namespace CLI {
type detail (line 204) | namespace detail {
function split (line 208) | inline std::vector<std::string> split(const std::string &s, char del...
function join (line 225) | std::string join(const T &v, std::string delim = ",") {
function rjoin (line 237) | std::string rjoin(const T &v, std::string delim = ",") {
function trim_copy (line 285) | inline std::string trim_copy(const std::string &str) {
function trim_copy (line 291) | inline std::string trim_copy(const std::string &str, const std::stri...
function format_help (line 296) | inline void format_help(std::stringstream &out, std::string name, st...
function valid_first_char (line 308) | bool valid_first_char(T c) { return std::isalpha(c, std::locale()) |...
function valid_later_char (line 311) | bool valid_later_char(T c) {
function valid_name_string (line 316) | inline bool valid_name_string(const std::string &str) {
function to_lower (line 326) | inline std::string to_lower(std::string str) {
function split_up (line 334) | inline std::vector<std::string> split_up(std::string str) {
function fix_newlines (line 383) | inline std::string fix_newlines(std::string leader, std::string inpu...
type ExitCodes (line 419) | enum class ExitCodes {
class Error (line 448) | class Error : public std::runtime_error {
method get_exit_code (line 453) | int get_exit_code() const { return exit_code; }
method get_name (line 455) | std::string get_name() const { return name; }
method Error (line 457) | Error(std::string name, std::string msg, int exit_code = static_cast...
method Error (line 460) | Error(std::string name, std::string msg, ExitCodes exit_code) : Erro...
function namespace (line 466) | class ConstructionError : public Error {
type CLI (line 203) | namespace CLI {
type detail (line 204) | namespace detail {
function split (line 208) | inline std::vector<std::string> split(const std::string &s, char del...
function join (line 225) | std::string join(const T &v, std::string delim = ",") {
function rjoin (line 237) | std::string rjoin(const T &v, std::string delim = ",") {
function trim_copy (line 285) | inline std::string trim_copy(const std::string &str) {
function trim_copy (line 291) | inline std::string trim_copy(const std::string &str, const std::stri...
function format_help (line 296) | inline void format_help(std::stringstream &out, std::string name, st...
function valid_first_char (line 308) | bool valid_first_char(T c) { return std::isalpha(c, std::locale()) |...
function valid_later_char (line 311) | bool valid_later_char(T c) {
function valid_name_string (line 316) | inline bool valid_name_string(const std::string &str) {
function to_lower (line 326) | inline std::string to_lower(std::string str) {
function split_up (line 334) | inline std::vector<std::string> split_up(std::string str) {
function fix_newlines (line 383) | inline std::string fix_newlines(std::string leader, std::string inpu...
type ExitCodes (line 419) | enum class ExitCodes {
class Error (line 448) | class Error : public std::runtime_error {
method get_exit_code (line 453) | int get_exit_code() const { return exit_code; }
method get_name (line 455) | std::string get_name() const { return name; }
method Error (line 457) | Error(std::string name, std::string msg, int exit_code = static_cast...
method Error (line 460) | Error(std::string name, std::string msg, ExitCodes exit_code) : Erro...
function namespace (line 466) | class ConstructionError : public Error {
type CLI (line 400) | namespace CLI {
type detail (line 204) | namespace detail {
function split (line 208) | inline std::vector<std::string> split(const std::string &s, char del...
function join (line 225) | std::string join(const T &v, std::string delim = ",") {
function rjoin (line 237) | std::string rjoin(const T &v, std::string delim = ",") {
function trim_copy (line 285) | inline std::string trim_copy(const std::string &str) {
function trim_copy (line 291) | inline std::string trim_copy(const std::string &str, const std::stri...
function format_help (line 296) | inline void format_help(std::stringstream &out, std::string name, st...
function valid_first_char (line 308) | bool valid_first_char(T c) { return std::isalpha(c, std::locale()) |...
function valid_later_char (line 311) | bool valid_later_char(T c) {
function valid_name_string (line 316) | inline bool valid_name_string(const std::string &str) {
function to_lower (line 326) | inline std::string to_lower(std::string str) {
function split_up (line 334) | inline std::vector<std::string> split_up(std::string str) {
function fix_newlines (line 383) | inline std::string fix_newlines(std::string leader, std::string inpu...
type ExitCodes (line 419) | enum class ExitCodes {
class Error (line 448) | class Error : public std::runtime_error {
method get_exit_code (line 453) | int get_exit_code() const { return exit_code; }
method get_name (line 455) | std::string get_name() const { return name; }
method Error (line 457) | Error(std::string name, std::string msg, int exit_code = static_cast...
method Error (line 460) | Error(std::string name, std::string msg, ExitCodes exit_code) : Erro...
function namespace (line 466) | class ConstructionError : public Error {
FILE: src/Database.h
function class (line 19) | class Database
FILE: src/Feature.h
function class (line 22) | class Feature
FILE: src/Frame.h
function class (line 20) | class Frame
FILE: src/GainRobustTracker.h
function class (line 21) | class GainRobustTracker
FILE: src/ImageReader.cpp
type dirent (line 41) | struct dirent
FILE: src/ImageReader.h
function class (line 25) | class ImageReader
FILE: src/JacobianGenerator.h
function class (line 16) | class JacobianGenerator
FILE: src/NonlinearOptimizer.h
function class (line 28) | class NonlinearOptimizer
FILE: src/OptimizationBlock.h
function class (line 23) | class OptimizationBlock
FILE: src/OptimizedPoint.h
function class (line 19) | class OptimizedPoint
FILE: src/RapidExposureTimeEstimator.h
function class (line 18) | class RapidExposureTimeEstimator
FILE: src/ResponseModel.h
function class (line 19) | class ResponseModel
FILE: src/Tracker.h
function class (line 36) | class Tracker
FILE: src/VignetteModel.h
function class (line 23) | class VignetteModel
FILE: src/main.cpp
type Settings (line 29) | struct Settings{
function run_batch_optimization_task (line 47) | void run_batch_optimization_task(NonlinearOptimizer *optimizer)
function split (line 110) | std::vector<string> split(const string &s, char delim) {
function run_batch_calibration (line 120) | int run_batch_calibration(Settings *run_settings,std::vector<double> gt_...
function run_online_calibration (line 221) | int run_online_calibration(Settings *run_settings,std::vector<double> gt...
function main (line 353) | int main(int argc, char** argv)
Condensed preview — 33 files, each showing path, character count, and a content snippet. Download the .json file or copy for the full structured content (385K chars).
[
{
"path": ".gitignore",
"chars": 357,
"preview": "# IDE files\n.idea/*\n\n# Compiled Object files\n*.slo\n*.lo\n*.o\n*.obj\n\n# Precompiled Headers\n*.gch\n*.pch\n\n# Compiled Dynamic"
},
{
"path": ".gitlab-ci.yml",
"chars": 802,
"preview": "# defaults\nimage: nikolausdemmel/ubuntu-dev-cv:16.04\nvariables:\n BUILD_TYPE: Release\n\n\n# template definition\n.compile_t"
},
{
"path": ".travis.yml",
"chars": 1834,
"preview": "sudo: required\n\nlanguage: cpp\n\nservices:\n - docker\n\ncache: ccache\n\nenv:\n global:\n - DOCKER_CONTAINER_NAME=nikolausd"
},
{
"path": "AUTHORS.txt",
"chars": 138,
"preview": "Authors ordered by first contribution.\n\nPaul Bergmann <bergmann@in.tum.de>\nRui Wang <wangr@in.tum.de>\nNikolaus Demmel <d"
},
{
"path": "CHANGELOG.md",
"chars": 65,
"preview": "# Changelog\n\n## [0.1.0] - 2018-05-22\n### Added\n- Initial release\n"
},
{
"path": "CMakeLists.txt",
"chars": 2860,
"preview": "cmake_minimum_required(VERSION 3.2)\nset(PROJECT_NAME online_photometric_calibration)\n\nproject(${PROJECT_NAME})\n\n# Set de"
},
{
"path": "LICENSE.txt",
"chars": 1518,
"preview": "3-Clause BSD License\n\nCopyright 2017-2018 Paul Bergmann and co-authors (see AUTHORS.txt)\n\nRedistribution and use in sour"
},
{
"path": "README.md",
"chars": 6386,
"preview": "# Online Photometric Calibration\n\nRecent direct visual odometry and SLAM algorithms have demonstrated\nimpressive levels "
},
{
"path": "src/CLI11.hpp",
"chars": 115371,
"preview": "#pragma once\n\n// CLI11: Version 1.5.3\n// Originally designed by Henry Schreiner\n// https://github.com/CLIUtils/CLI11\n//\n"
},
{
"path": "src/Database.cpp",
"chars": 7042,
"preview": "//\n// Database.cpp\n// OnlinePhotometricCalibration\n//\n// Created by Paul on 16.11.17.\n// Copyright (c) 2017-2018 Pau"
},
{
"path": "src/Database.h",
"chars": 2171,
"preview": "//\n// Database.h\n// OnlinePhotometricCalibration\n//\n// Created by Paul on 16.11.17.\n// Copyright (c) 2017-2018 Paul "
},
{
"path": "src/Feature.h",
"chars": 1344,
"preview": "//\n// Feature.h\n// OnlinePhotometricCalibration\n//\n// Created by Paul on 16.11.17.\n// Copyright (c) 2017-2018 Paul B"
},
{
"path": "src/Frame.h",
"chars": 995,
"preview": "//\n// Frame.h\n// OnlinePhotometricCalibration\n//\n// Created by Paul on 16.11.17.\n// Copyright (c) 2017-2018 Paul Ber"
},
{
"path": "src/GainRobustTracker.cpp",
"chars": 11544,
"preview": "//\n// GainRobustTracker.cpp\n// OnlinePhotometricCalibration\n//\n// Created by Paul on 17.11.17.\n// Copyright (c) 2017"
},
{
"path": "src/GainRobustTracker.h",
"chars": 2880,
"preview": "//\n// GainRobustTracker.h\n// OnlinePhotometricCalibration\n//\n// Created by Paul on 17.11.17.\n// Copyright (c) 2017-2"
},
{
"path": "src/ImageReader.cpp",
"chars": 1575,
"preview": "//\n// ImageReader.cpp\n// OnlinePhotometricCalibration\n//\n// Created by Paul on 16.11.17.\n// Copyright (c) 2017-2018 "
},
{
"path": "src/ImageReader.h",
"chars": 1220,
"preview": "//\n// ImageReader.h\n// OnlinePhotometricCalibration\n//\n// Created by Paul on 16.11.17.\n// Copyright (c) 2017-2018 Pa"
},
{
"path": "src/JacobianGenerator.cpp",
"chars": 10055,
"preview": "//\n// JacobianGenerator.cpp\n// OnlinePhotometricCalibration\n//\n// Created by Paul on 16.11.17.\n// Copyright (c) 2017"
},
{
"path": "src/JacobianGenerator.h",
"chars": 94282,
"preview": "//\n// JacobianGenerator.h\n// OnlinePhotometricCalibration\n//\n// Created by Paul on 16.11.17.\n// Copyright (c) 2017-2"
},
{
"path": "src/NonlinearOptimizer.cpp",
"chars": 43351,
"preview": "//\n// NonlinearOptimizer.cpp\n// OnlinePhotometricCalibration\n//\n// Created by Paul on 16.11.17.\n// Copyright (c) 201"
},
{
"path": "src/NonlinearOptimizer.h",
"chars": 5850,
"preview": "//\n// NonlinearOptimizer.h\n// OnlinePhotometricCalibration\n//\n// Created by Paul on 16.11.17.\n// Copyright (c) 2017-"
},
{
"path": "src/OptimizationBlock.cpp",
"chars": 3723,
"preview": "//\n// OptimizationBlock.cpp\n// OnlinePhotometricCalibration\n//\n// Created by Paul on 17.11.17.\n// Copyright (c) 2017"
},
{
"path": "src/OptimizationBlock.h",
"chars": 3736,
"preview": "//\n// OptimizationBlock.h\n// OnlinePhotometricCalibration\n//\n// Created by Paul on 17.11.17.\n// Copyright (c) 2017-2"
},
{
"path": "src/OptimizedPoint.h",
"chars": 1326,
"preview": "//\n// OptimizedPoint.h\n// OnlinePhotometricCalibration\n//\n// Created by Paul on 17.11.17.\n// Copyright (c) 2017-2018"
},
{
"path": "src/RapidExposureTimeEstimator.cpp",
"chars": 6150,
"preview": "//\n// RapidExposureTimeEstimator.cpp\n// OnlinePhotometricCalibration\n//\n// Created by Paul on 16.11.17.\n// Copyright"
},
{
"path": "src/RapidExposureTimeEstimator.h",
"chars": 1238,
"preview": "//\n// RapidExposureTimeEstimator.h\n// OnlinePhotometricCalibration\n//\n// Created by Paul on 16.11.17.\n// Copyright ("
},
{
"path": "src/ResponseModel.h",
"chars": 2614,
"preview": "//\n// ResponseModel.h\n// OnlinePhotometricCalibration\n//\n// Created by Paul on 16.11.17.\n// Copyright (c) 2017-2018 "
},
{
"path": "src/StandardIncludes.h",
"chars": 762,
"preview": "//\n// OpencvIncludes.h\n// OnlinePhotometricCalibration\n//\n// Created by Paul on 16.11.17.\n// Copyright (c) 2017-2018"
},
{
"path": "src/Tracker.cpp",
"chars": 17160,
"preview": "//\n// Tracker.cpp\n// OnlinePhotometricCalibration\n//\n// Created by Paul on 16.11.17.\n// Copyright (c) 2017-2018 Paul"
},
{
"path": "src/Tracker.h",
"chars": 3726,
"preview": "//\n// Tracker.h\n// OnlinePhotometricCalibration\n//\n// Created by Paul on 16.11.17.\n// Copyright (c) 2017-2018 Paul B"
},
{
"path": "src/VignetteModel.cpp",
"chars": 1762,
"preview": "//\n// VignetteModel.cpp\n// OnlinePhotometricCalibration\n//\n// Created by Paul on 16.11.17.\n// Copyright (c) 2017-201"
},
{
"path": "src/VignetteModel.h",
"chars": 2128,
"preview": "//\n// VignetteModel.h\n// OnlinePhotometricCalibration\n//\n// Created by Paul on 16.11.17.\n// Copyright (c) 2017-2018 "
},
{
"path": "src/main.cpp",
"chars": 18868,
"preview": "//\n// main.cpp\n// OnlinePhotometricCalibration\n//\n// Created by Paul on 16.11.17.\n// Copyright (c) 2017-2018 Paul Be"
}
]
About this extraction
This page contains the full source code of the tum-vision/online_photometric_calibration GitHub repository, extracted and formatted as plain text for AI agents and large language models (LLMs). The extraction includes 33 files (366.0 KB), approximately 119.2k tokens, and a symbol index with 45 extracted functions, classes, methods, constants, and types. Use this with OpenClaw, Claude, ChatGPT, Cursor, Windsurf, or any other AI tool that accepts text input. You can copy the full output to your clipboard or download it as a .txt file.
Extracted by GitExtract — free GitHub repo to text converter for AI. Built by Nikandr Surkov.