diff --git a/.github/scripts/python_wheels/cibw_before_all.sh b/.github/scripts/python_wheels/cibw_before_all.sh index 2398877a89..acc389e0e2 100644 --- a/.github/scripts/python_wheels/cibw_before_all.sh +++ b/.github/scripts/python_wheels/cibw_before_all.sh @@ -14,19 +14,42 @@ export PYTHON="python${PYTHON_VERSION}" if [ "$(uname)" == "Linux" ]; then # manylinux2014 is based on CentOS 7, so use yum to install dependencies - yum install -y wget - - # Install Boost from source - wget https://archives.boost.io/release/1.87.0/source/boost_1_87_0.tar.gz --quiet - tar -xzf boost_1_87_0.tar.gz - cd boost_1_87_0 - ./bootstrap.sh --prefix=/opt/boost - ./b2 install --prefix=/opt/boost --with=all - cd .. + yum install -y wget doxygen elif [ "$(uname)" == "Darwin" ]; then - brew install wget cmake boost + brew install wget cmake doxygen fi +# Install Boost from source +wget https://archives.boost.io/release/1.87.0/source/boost_1_87_0.tar.gz --quiet +tar -xzf boost_1_87_0.tar.gz +cd boost_1_87_0 + +BOOST_PREFIX="$HOME/opt/boost" +./bootstrap.sh --prefix=${BOOST_PREFIX} + +if [ "$(uname)" == "Linux" ]; then + ./b2 install --prefix=${BOOST_PREFIX} --with=all -d0 +elif [ "$(uname)" == "Darwin" ]; then + # Default to macOS 10.15 if MACOSX_DEPLOYMENT_TARGET is not set + if [[ -z "${MACOSX_DEPLOYMENT_TARGET}" ]]; then + export MACOSX_DEPLOYMENT_TARGET="10.15" + fi + + ./b2 install --prefix=${BOOST_PREFIX} --with=all -d0 \ + cxxflags="-mmacosx-version-min=${MACOSX_DEPLOYMENT_TARGET}" \ + linkflags="-mmacosx-version-min=${MACOSX_DEPLOYMENT_TARGET}" +fi +cd .. + +# Export paths so CMake or build system can find Boost +export BOOST_ROOT="${BOOST_PREFIX}" +export BOOST_INCLUDEDIR="${BOOST_PREFIX}/include" +export BOOST_LIBRARYDIR="${BOOST_PREFIX}/lib" + +# Ensure runtime linker can find Boost libraries +export LD_LIBRARY_PATH="${BOOST_LIBRARYDIR}:$LD_LIBRARY_PATH" # For Linux +export REPAIR_LIBRARY_PATH="${BOOST_LIBRARYDIR}:$DYLD_LIBRARY_PATH" # For macOS + $(which $PYTHON) -m pip install -r $PROJECT_DIR/python/dev_requirements.txt # Remove build/cache files that were generated on host @@ -48,11 +71,14 @@ cmake $PROJECT_DIR \ -DGTSAM_PYTHON_VERSION=$PYTHON_VERSION \ -DPYTHON_EXECUTABLE:FILEPATH=$(which $PYTHON) \ -DGTSAM_ALLOW_DEPRECATED_SINCE_V43=OFF \ - -DCMAKE_INSTALL_PREFIX=$PROJECT_DIR/gtsam_install + -DCMAKE_INSTALL_PREFIX=$PROJECT_DIR/gtsam_install \ + -DGTSAM_GENERATE_DOC_XML=0 -cd $PROJECT_DIR/build/python +# Generate Doxygen XML documentation +doxygen build/doc/Doxyfile # Install the Python wrapper module and generate Python stubs +cd $PROJECT_DIR/build/python if [ "$(uname)" == "Linux" ]; then make -j $(nproc) install make -j $(nproc) python-stubs diff --git a/.github/workflows/build-cibw.yml b/.github/workflows/build-cibw.yml index f0b93aef17..826f24bd35 100644 --- a/.github/workflows/build-cibw.yml +++ b/.github/workflows/build-cibw.yml @@ -76,22 +76,22 @@ jobs: manylinux_image: manylinux2014 # MacOS x86_64 - # - os: macos-13 - # python_version: "3.10" - # cibw_python_version: 310 - # platform_id: macosx_x86_64 - # - os: macos-13 - # python_version: "3.11" - # cibw_python_version: 311 - # platform_id: macosx_x86_64 - # - os: macos-13 - # python_version: "3.12" - # cibw_python_version: 312 - # platform_id: macosx_x86_64 - # - os: macos-13 - # python_version: "3.13" - # cibw_python_version: 313 - # platform_id: macosx_x86_64 + - os: macos-13 + python_version: "3.10" + cibw_python_version: 310 + platform_id: macosx_x86_64 + - os: macos-13 + python_version: "3.11" + cibw_python_version: 311 + platform_id: macosx_x86_64 + - os: macos-13 + python_version: "3.12" + cibw_python_version: 312 + platform_id: macosx_x86_64 + - os: macos-13 + python_version: "3.13" + cibw_python_version: 313 + platform_id: macosx_x86_64 steps: - name: Checkout @@ -130,6 +130,14 @@ jobs: run: | cmake . -B build -DGTSAM_BUILD_PYTHON=1 -DGTSAM_PYTHON_VERSION=${{ matrix.python_version }} + # If on macOS, we previously installed boost using homebrew for the first build. + # We need to uninstall it before building the wheels with cibuildwheel, which will + # install boost from source. + - name: Uninstall Boost (MacOS) + if: runner.os == 'macOS' + run: | + brew uninstall boost + - name: Build and test wheels env: # Generate the platform identifier. See https://cibuildwheel.pypa.io/en/stable/options/#build-skip. @@ -138,6 +146,8 @@ jobs: CIBW_MANYLINUX_AARCH64_IMAGE: ${{ matrix.manylinux_image }} CIBW_ARCHS: all CIBW_ENVIRONMENT_PASS_LINUX: DEVELOP TIMESTAMP + MACOSX_DEPLOYMENT_TARGET: 10.15 + CIBW_REPAIR_WHEEL_COMMAND_MACOS: DYLD_LIBRARY_PATH=$REPAIR_LIBRARY_PATH delocate-wheel --require-archs {delocate_archs} -w {dest_dir} -v {wheel} # Use build instead of pip wheel to build the wheels. This is recommended by PyPA. # See https://cibuildwheel.pypa.io/en/stable/options/#build-frontend. diff --git a/CMakeLists.txt b/CMakeLists.txt index cabde7653d..4d06cf2562 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -124,6 +124,10 @@ if(GTSAM_BUILD_PYTHON OR GTSAM_INSTALL_MATLAB_TOOLBOX) # Set the include directory for matlab.h set(GTWRAP_INCLUDE_NAME "wrap") + if (GTSAM_GENERATE_DOC_XML) + set(GTWRAP_ADD_DOCSTRINGS ON) + endif() + # Copy matlab.h to the correct folder. configure_file(${PROJECT_SOURCE_DIR}/wrap/matlab.h ${PROJECT_BINARY_DIR}/wrap/matlab.h COPYONLY) diff --git a/doc/CMakeLists.txt b/doc/CMakeLists.txt index 05e0a13ef5..ba3d75e90e 100644 --- a/doc/CMakeLists.txt +++ b/doc/CMakeLists.txt @@ -4,6 +4,7 @@ option(GTSAM_BUILD_DOCS "Enable/Disable building of doxygen doc # configure doxygen option(GTSAM_BUILD_DOC_HTML "Enable/Disable doxygen HTML output" ON) option(GTSAM_BUILD_DOC_LATEX "Enable/Disable doxygen LaTeX output" OFF) +option(GTSAM_GENERATE_DOC_XML "Enable/Disable doxygen XML output" OFF) # add a target to generate API documentation with Doxygen if (GTSAM_BUILD_DOCS) @@ -20,6 +21,12 @@ if (GTSAM_BUILD_DOCS) set(GTSAM_BUILD_DOC_LATEX_YN "NO") endif() + if (GTSAM_GENERATE_DOC_XML) + set(GTSAM_GENERATE_XML_YN "YES") + else() + set(GTSAM_GENERATE_XML_YN "NO") + endif() + # GTSAM core subfolders set(gtsam_doc_subdirs gtsam/base diff --git a/doc/Doxyfile.in b/doc/Doxyfile.in index 0f789be66f..3461127ae1 100644 --- a/doc/Doxyfile.in +++ b/doc/Doxyfile.in @@ -2120,7 +2120,7 @@ MAN_LINKS = NO # captures the structure of the code including all documentation. # The default value is: NO. -GENERATE_XML = NO +GENERATE_XML = @GTSAM_GENERATE_XML_YN@ # The XML_OUTPUT tag is used to specify where the XML pages will be put. If a # relative path is entered the value of OUTPUT_DIRECTORY will be put in front of diff --git a/doc/examples.md b/doc/examples.md new file mode 100644 index 0000000000..14300a03cb --- /dev/null +++ b/doc/examples.md @@ -0,0 +1,3 @@ +# Examples + +This section contains python examples in interactive Python notebooks (`*.ipynb`). Python notebooks with an Open In Colab button near the top can be opened in your browser, where you can run the files yourself and make edits to play with and understand GTSAM. \ No newline at end of file diff --git a/doc/expressions.md b/doc/expressions.md new file mode 100644 index 0000000000..6e5518f702 --- /dev/null +++ b/doc/expressions.md @@ -0,0 +1,113 @@ +# Expressions +## Motivation +GTSAM is an optimization library for objective functions expressed as a factor graph over a set of unknown variables. In the continuous case, the variables are typically vectors or elements on a manifold (such as the 3D rotation manifold). The factors compute vector-valued errors that need to be minimized, and are typically only connected to a handful of unknowns. + +In the continuous case, the main optimization methods we have implemented are variants of Gauss-Newton non-linear optimization or conjugate gradient methods. Let us assume there are m factors over n unknowns. For either optimization method, we need to evaluate the sparse Jacobian matrix of the entire factor graph, which is a sparse block-matrix of m block-rows and n-block columns. + +The sparse Jacobian is built up factor by factor, corresponding to the block-rows. A typical non-linear least-square term is $|h(x)-z|^2$ where $h(x)$ is a measurement function, which we need to be able to linearize as +$$ +h(x) \approx h(x_0+dx)+H(x_0)dx +$$ +Note the above is for vector unknowns, for Lie groups and manifold variables, see [doc/math.pdf](https://github.com/borglab/gtsam/blob/develop/doc/math.pdf) for details. + +## Expressions +In many cases one can use GTSAM 4 Expressions to implement factors. Expressions are objects of type Expression, and there are three main expression flavors: + +- constants, e.g., `Expression kExpr(Point2(3,4))` +- unknowns, e.g., `Expression pExpr(123)` where 123 is a key. +- functions, e.g., `Expression sumExpr(h, kexpr, pExpr)` + +The latter case is an example of wrapping a binary measurement function `h`. To be able to wrap `h`, it needs to be able to compute its local derivatives, i.e., it has to have the signature +```c++ +double h(const Point2& a, const Point3& b, + OptionalJacobian<1, 2> Ha, OptionalJacobian<1, 3> Hb) +``` +In this case the output type 'T' is 'double', the two arguments have type Point2 and Point3 respectively, and the two remaining arguments provide a way to compute the function Jacobians, if needed. The templated type `OptionalJacobian` behaves very much like `std::optional`. If an actual matrix is passed in, the function is expected to treat it as an output argument in which to write the Jacobian for the result wrp. the corresponding input argument. *The matrix to write in will be allocated before the call.* + +Expression constructors exist for both methods and functions with different arities. Note that an expression is templated with the output type T, not with the argument types. However, the constructor will infer the argument types from inspecting the signature of the function f, and will in this example expect two additional arguments of type Expression and Expression, respectively. + +As an example, here is the constructor declaration for wrapping unary functions: +```c++ +template +Expression(typename UnaryFunction::type function, + const Expression& expression); +``` +where (in this case) the function type is defined by +```c++ +template +struct UnaryFunction { +typedef boost::function< + T(const A1&, typename MakeOptionalJacobian::type)> type; +}; +``` +## Some measurement function examples +An example of a simple unary function is `gtsam::norm3` in [Point3.cpp](https://github.com/borglab/gtsam/blob/develop/gtsam/geometry/Point3.cpp#L41): +```c++ +double norm3(const Point3 & p, OptionalJacobian<1, 3> H = {}) { + double r = sqrt(p.x() * p.x() + p.y() * p.y() + p.z() * p.z()); + if (H) *H << p.x() / r, p.y() / r, p.z() / r; + return r; +} +``` +The key new concept here is OptionalJacobian, which acts like a std::optional: if it evaluates to true, you should write the Jacobian of the function in it. It acts as a fixed-size Eigen matrix. + +As we said above, expressions also support binary functions, ternary functions, and methods. An example of a binary function is 'Point3::cross': + +```c++ +Point3 cross(const Point3 &p, const Point3 & q, + OptionalJacobian<3, 3> H1 = {}, OptionalJacobian<3, 3> H2 = {}) { + if (H1) *H1 << skewSymmetric(-q.x(), -q.y(), -q.z()); + if (H2) *H2 << skewSymmetric(p.x(), p.y(), p.z()); + return Point3(p.y() * q.z() - p.z() * q.y(), p.z() * q.x() - p.x() * q.z(), p.x() * q.y() - p.y() * q.x()); +} +``` +Example of using cross: +```c++ +using namespace gtsam; +Matrix3 H1, H2; +Point3 p(1,2,3), q(4,5,6), r = cross(p,q,H1,H2); +``` +## Using Expressions for Inference +The way expressions are used is by creating unknown Expressions for the unknown variables we are optimizing for: +```c++ +Expression x(‘x’,1); +auto h = Expression(& norm3, x); +``` +For convenient creation of factors with expressions, we provide a new factor graph type `ExpressionFactorGraph`, which is just a `NonlinearFactorGraph` with an extra method addExpressionFactor(h, z, n) that takes a measurement expression h, an actual measurement z, and a measurement noise model R. With this, we can add a GTSAM nonlinear factor $|h(x)-z|^2$ to a `NonlinearFactorGraph` by +```c++ +graph.addExpressionFactor(h, z, R) +``` +In the above, the unknown in the example can be retrieved by the `gtsam::Symbol(‘x’,1)`, which evaluates to a uint64 identifier. + +## Composing Expressions +The key coolness behind expressions, however, is that you can compose them into expression trees, as long as the leaves know how to do their own derivatives: +```c++ +Expression x1(‘x’1), x2(‘x’,2); +auto h = Expression(& cross, x1, x2); +auto g = Expression(& norm3, h); +``` +Because we typedef Point3_ to Expression, we can write this very concisely as +```c++ +auto g = Point3_(& norm3, Point3_(& cross, x1(‘x’1), x2(‘x’,2))); +``` +## PoseSLAM Example +Using expressions, it is simple to quickly create a factor graph corresponding to a PoseSLAM problem, where our only measurements are relative poses between a series of unknown 2D or 3D poses. The following code snippet from [Pose2SLAMExampleExpressions.cpp](https://github.com/borglab/gtsam/blob/develop/examples/Pose2SLAMExampleExpressions.cpp) is used to create a simple Pose2 example (where the robot is moving on a plane): +```c++ +1 ExpressionFactorGraph graph; +2 Expression x1(1), x2(2), x3(3), x4(4), x5(5); +3 graph.addExpressionFactor(x1, Pose2(0, 0, 0), priorNoise); +4 graph.addExpressionFactor(between(x1,x2), Pose2(2, 0, 0 ), model); +5 graph.addExpressionFactor(between(x2,x3), Pose2(2, 0, M_PI_2), model); +6 graph.addExpressionFactor(between(x3,x4), Pose2(2, 0, M_PI_2), model); +7 graph.addExpressionFactor(between(x4,x5), Pose2(2, 0, M_PI_2), model); +8 graph.addExpressionFactor(between(x5,x2), Pose2(2, 0, M_PI_2), model); +``` +This is what is going on: +- In line 1, we create an empty factor graph. +- In line 2 we create the 5 unknown poses, of type `Expression`, with keys 1 to 5. These are what we will optimize over. +- Line 3 then creates a simple factor that gives a prior on `x1` (the first argument), namely that it is at the origin `Pose2(0, 0, 0)` (the second argument), with a particular probability density given by `priorNoise` (the third argument). +- Lines 4-7 adds factors for the odometry constraints, i.e., the movement between successive poses of the robot. The function `between(t1,t2)` is implemented in [nonlinear/expressions.h](https://github.com/borglab/gtsam/blob/develop/gtsam/nonlinear/expressions.h) and is equivalent to calling the constructor Expression(traits::Between, t1, t2). +- Finally, line 8 creates a loop closure constraint between poses x2 and x5. + +Another good example of its use is in +[SFMExampleExpressions.cpp](https://github.com/borglab/gtsam/blob/develop/examples/SFMExampleExpressions.cpp). \ No newline at end of file diff --git a/doc/generating/gpt_generate.py b/doc/generating/gpt_generate.py new file mode 100644 index 0000000000..3936023e64 --- /dev/null +++ b/doc/generating/gpt_generate.py @@ -0,0 +1,138 @@ +""" +GTSAM Copyright 2010-2025, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +Author: Porter Zach + +This script generates interactive Python notebooks (.ipynb) that document GTSAM +header files. Since inserting the text of the file directly into the prompt +might be too many tokens, it retrieves the header file content from the GTSAM +GitHub repository. It then sends it to OpenAI's API for processing, and saves +the generated documentation as a Jupyter notebook. + +Functions: + is_url_valid(url: str) -> bool: + Verifies that the supplied URL does not return a 404. + + save_ipynb(text: str, file_path: str) -> str: + Saves the provided text to a single Markdown cell in a new .ipynb file. + + generate_ipynb(file_path: str, openai_client): + Generates an interactive Python notebook for the given GTSAM header file + by sending a request to OpenAI's API and saving the response. + +Usage: + Run the script with paths to GTSAM header files as arguments. For example: + python gpt_generate.py gtsam/geometry/Pose3.h +""" + +import os +import time +import requests +import argparse +import nbformat as nbf +from openai import OpenAI + +_output_folder = "output" +_gtsam_gh_base = "https://raw.githubusercontent.com/borglab/gtsam/refs/heads/develop/" +_asst_id = "asst_na7wYBtXyGU0x5t2RdcnpxzP" +_request_text = "Document the file found at {}." + + +def is_url_valid(url): + """Verify that the supplied URL does not return a 404.""" + try: + response = requests.head(url, allow_redirects=True) + return response.status_code != 404 + except requests.RequestException: + return False + + +def save_ipynb(text: str, file_path: str): + """Save text to a single Markdown cell in a new .ipynb file.""" + script_dir = os.path.dirname(os.path.abspath(__file__)) + output_dir = os.path.join(script_dir, _output_folder) + os.makedirs(output_dir, exist_ok=True) + output_file = os.path.splitext(os.path.basename(file_path))[0] + ".ipynb" + output_full_path = os.path.join(output_dir, output_file) + + nb = nbf.v4.new_notebook() + new_cell = nbf.v4.new_markdown_cell(text) + nb['cells'].append(new_cell) + + with open(output_full_path, 'w', encoding='utf-8') as file: + nbf.write(nb, file) + + return output_file + + +def generate_ipynb(file_path: str, openai_client): + """Generate an interactive Python notebook for the given GTSAM header file. + + Args: + file_path (str): The fully-qualified path from the root of the gtsam + repository to the header file that will be documented. + openai_client (openai.OpenAI): The OpenAI client to use. + """ + # Create the URL to get the header file from. + url = _gtsam_gh_base + file_path + + if not is_url_valid(url): + print(f"{url} was not found on the server, or an error occurred.") + return + + print(f"Sending request to OpenAI to document {url}.") + + # Create a new thread and send the request + thread = openai_client.beta.threads.create() + openai_client.beta.threads.messages.create( + thread_id=thread.id, role="user", content=_request_text.format(url)) + + run = openai_client.beta.threads.runs.create(thread_id=thread.id, + assistant_id=_asst_id) + + print("Waiting for the assistant to process the request...") + + # Wait for request to be processed + while True: + run_status = openai_client.beta.threads.runs.retrieve( + thread_id=thread.id, run_id=run.id) + if run_status.status == "completed": + break + time.sleep(2) + + print("Request processed. Retrieving response...") + + # Fetch messages + messages = openai_client.beta.threads.messages.list(thread_id=thread.id) + # Retrieve response text and strip ```markdown ... ``` + text = messages.data[0].content[0].text.value.strip('`').strip('markdown') + + # Write output to file + output_filename = save_ipynb(text, file_path) + + print(f"Response retrieved. Find output in {output_filename}.") + + +if __name__ == "__main__": + parser = argparse.ArgumentParser( + prog="gpt_generate", + description= + "Generates .ipynb documentation files given paths to GTSAM header files." + ) + parser.add_argument( + "file_paths", + nargs='+', + help= + "The paths to the header files from the root gtsam directory, e.g. 'gtsam/geometry/Pose3.h'." + ) + args = parser.parse_args() + + # Retrieves API key from environment variable OPENAI_API_KEY + client = OpenAI() + + for file_path in args.file_paths: + generate_ipynb(file_path, client) diff --git a/gtsam/user_guide.md b/doc/user_guide.md similarity index 100% rename from gtsam/user_guide.md rename to doc/user_guide.md diff --git a/gtsam_unstable/examples/FixedLagSmootherExample.cpp b/examples/FixedLagSmootherExample.cpp similarity index 98% rename from gtsam_unstable/examples/FixedLagSmootherExample.cpp rename to examples/FixedLagSmootherExample.cpp index 7b6a7d57f8..38a63c9e9d 100644 --- a/gtsam_unstable/examples/FixedLagSmootherExample.cpp +++ b/examples/FixedLagSmootherExample.cpp @@ -22,9 +22,9 @@ * - We have measurements between each pose from multiple odometry sensors */ -// This example demonstrates the use of the Fixed-Lag Smoothers in GTSAM unstable +// This example demonstrates the use of the Fixed-Lag Smoothers in GTSAM #include -#include +#include // In GTSAM, measurement functions are represented as 'factors'. Several common factors // have been provided with the library for solving robotics/SLAM/Bundle Adjustment problems. diff --git a/examples/Hybrid_City10000.cpp b/examples/Hybrid_City10000.cpp index fc5d55d44f..f37b65ff81 100644 --- a/examples/Hybrid_City10000.cpp +++ b/examples/Hybrid_City10000.cpp @@ -109,11 +109,10 @@ class Experiment { std::cout << "Smoother update: " << newFactors_.size() << std::endl; gttic_(SmootherUpdate); clock_t beforeUpdate = clock(); - auto linearized = newFactors_.linearize(initial_); - smoother_.update(*linearized, initial_); + smoother_.update(newFactors_, initial_, maxNrHypotheses); + clock_t afterUpdate = clock(); allFactors_.push_back(newFactors_); newFactors_.resize(0); - clock_t afterUpdate = clock(); return afterUpdate - beforeUpdate; } @@ -262,10 +261,20 @@ class Experiment { std::string timeFileName = "Hybrid_City10000_time.txt"; outfileTime.open(timeFileName); for (auto accTime : timeList) { - outfileTime << accTime << std::endl; + outfileTime << accTime / CLOCKS_PER_SEC << std::endl; } outfileTime.close(); std::cout << "Output " << timeFileName << " file." << std::endl; + + std::ofstream timingFile; + std::string timingFileName = "Hybrid_City10000_timing.txt"; + timingFile.open(timingFileName); + for (size_t i = 0; i < smootherUpdateTimes.size(); i++) { + auto p = smootherUpdateTimes.at(i); + timingFile << p.first << ", " << p.second / CLOCKS_PER_SEC << std::endl; + } + timingFile.close(); + std::cout << "Wrote timing information to " << timingFileName << std::endl; } }; diff --git a/examples/ISAM2_City10000.cpp b/examples/ISAM2_City10000.cpp index 2c210ab44a..526883b821 100644 --- a/examples/ISAM2_City10000.cpp +++ b/examples/ISAM2_City10000.cpp @@ -74,6 +74,8 @@ class Experiment { // Initialize local variables size_t index = 0; + std::vector> smootherUpdateTimes; + std::list timeList; // Set up initial prior @@ -82,10 +84,15 @@ class Experiment { graph_.addPrior(X(0), priorPose, kPriorNoiseModel); // Initial update + clock_t beforeUpdate = clock(); isam2_.update(graph_, initial_); + results = isam2_.calculateBestEstimate(); + clock_t afterUpdate = clock(); + smootherUpdateTimes.push_back( + std::make_pair(index, afterUpdate - beforeUpdate)); graph_.resize(0); initial_.clear(); - results = isam2_.calculateBestEstimate(); + index += 1; // Start main loop size_t keyS = 0; @@ -127,10 +134,15 @@ class Experiment { index++; } + clock_t beforeUpdate = clock(); isam2_.update(graph_, initial_); + results = isam2_.calculateBestEstimate(); + clock_t afterUpdate = clock(); + smootherUpdateTimes.push_back( + std::make_pair(index, afterUpdate - beforeUpdate)); graph_.resize(0); initial_.clear(); - results = isam2_.calculateBestEstimate(); + index += 1; // Print loop index and time taken in processor clock ticks if (index % 50 == 0 && keyS != keyT - 1) { @@ -175,6 +187,16 @@ class Experiment { outfileTime.close(); std::cout << "Written cumulative time to: " << timeFileName << " file." << std::endl; + + std::ofstream timingFile; + std::string timingFileName = "ISAM2_City10000_timing.txt"; + timingFile.open(timingFileName); + for (size_t i = 0; i < smootherUpdateTimes.size(); i++) { + auto p = smootherUpdateTimes.at(i); + timingFile << p.first << ", " << p.second / CLOCKS_PER_SEC << std::endl; + } + timingFile.close(); + std::cout << "Wrote timing information to " << timingFileName << std::endl; } }; diff --git a/gtsam_unstable/examples/IncrementalFixedLagSmootherExample.cpp b/examples/IncrementalFixedLagSmootherExample.cpp similarity index 99% rename from gtsam_unstable/examples/IncrementalFixedLagSmootherExample.cpp rename to examples/IncrementalFixedLagSmootherExample.cpp index 73beb6a75f..fda7ad7080 100644 --- a/gtsam_unstable/examples/IncrementalFixedLagSmootherExample.cpp +++ b/examples/IncrementalFixedLagSmootherExample.cpp @@ -59,7 +59,7 @@ #include #include #include -#include +#include #include #include // for writeG2o diff --git a/gtsam/3rdparty/metis/CMakeLists.txt b/gtsam/3rdparty/metis/CMakeLists.txt index dc26aecb26..f8da7ce6fa 100644 --- a/gtsam/3rdparty/metis/CMakeLists.txt +++ b/gtsam/3rdparty/metis/CMakeLists.txt @@ -1,4 +1,4 @@ -cmake_minimum_required(VERSION 3.0) +cmake_minimum_required(VERSION 3.5) project(METIS) # Add flags for currect directory and below diff --git a/gtsam/discrete/DecisionTreeFactor.cpp b/gtsam/discrete/DecisionTreeFactor.cpp index e39339dd8e..ebc02c1b52 100644 --- a/gtsam/discrete/DecisionTreeFactor.cpp +++ b/gtsam/discrete/DecisionTreeFactor.cpp @@ -547,7 +547,9 @@ namespace gtsam { /* ************************************************************************ */ DiscreteFactor::shared_ptr DecisionTreeFactor::restrict( const DiscreteValues& assignment) const { - throw std::runtime_error("DecisionTreeFactor::restrict not implemented"); + ADT restricted_tree = ADT::restrict(assignment); + return std::make_shared(this->discreteKeys(), + restricted_tree); } /* ************************************************************************ */ diff --git a/gtsam/discrete/discrete.i b/gtsam/discrete/discrete.i index 74de7a9229..91176601c2 100644 --- a/gtsam/discrete/discrete.i +++ b/gtsam/discrete/discrete.i @@ -288,7 +288,7 @@ class DiscreteBayesTree { const DiscreteBayesTreeClique* clique(size_t j) const; size_t numCachedSeparatorMarginals() const; - gtsam::DiscreteConditional marginalFactor(size_t key) const; + gtsam::DiscreteConditional* marginalFactor(size_t key) const; gtsam::DiscreteFactorGraph* joint(size_t j1, size_t j2) const; gtsam::DiscreteBayesNet* jointBayesNet(size_t j1, size_t j2) const; @@ -369,7 +369,7 @@ class DiscreteFactorGraph { void print(string s = "") const; bool equals(const gtsam::DiscreteFactorGraph& fg, double tol = 1e-9) const; - gtsam::DecisionTreeFactor product() const; + gtsam::DiscreteFactor* product() const; double operator()(const gtsam::DiscreteValues& values) const; gtsam::DiscreteValues optimize() const; diff --git a/gtsam/geometry/geometry.i b/gtsam/geometry/geometry.i index e01394bfe5..8c6e70ef4d 100644 --- a/gtsam/geometry/geometry.i +++ b/gtsam/geometry/geometry.i @@ -1075,9 +1075,14 @@ class PinholeCamera { pair projectSafe(const gtsam::Point3& pw) const; gtsam::Point2 project(const gtsam::Point3& point); gtsam::Point2 project(const gtsam::Point3& point, - Eigen::Ref Dpose, - Eigen::Ref Dpoint, - Eigen::Ref Dcal); + Eigen::Ref Dpose); + gtsam::Point2 project(const gtsam::Point3& point, + Eigen::Ref Dpose, + Eigen::Ref Dpoint); + gtsam::Point2 project(const gtsam::Point3& point, + Eigen::Ref Dpose, + Eigen::Ref Dpoint, + Eigen::Ref Dcal); gtsam::Point3 backproject(const gtsam::Point2& p, double depth) const; gtsam::Point3 backproject(const gtsam::Point2& p, double depth, Eigen::Ref Dresult_dpose, diff --git a/gtsam/hybrid/HybridSmoother.cpp b/gtsam/hybrid/HybridSmoother.cpp index 4beaf6474e..1133f645ef 100644 --- a/gtsam/hybrid/HybridSmoother.cpp +++ b/gtsam/hybrid/HybridSmoother.cpp @@ -292,13 +292,19 @@ HybridValues HybridSmoother::optimize() const { } /* ************************************************************************* */ -void HybridSmoother::relinearize() { +void HybridSmoother::relinearize(const std::optional givenOrdering) { allFactors_ = allFactors_.restrict(fixedValues_); HybridGaussianFactorGraph::shared_ptr linearized = allFactors_.linearize(linearizationPoint_); - HybridBayesNet::shared_ptr bayesNet = linearized->eliminateSequential(); + + // Compute ordering if not given + Ordering ordering = this->maybeComputeOrdering(*linearized, givenOrdering); + + HybridBayesNet::shared_ptr bayesNet = + linearized->eliminateSequential(ordering); HybridValues delta = bayesNet->optimize(); linearizationPoint_ = linearizationPoint_.retract(delta.continuous()); + reInitialize(*bayesNet); } diff --git a/gtsam/hybrid/HybridSmoother.h b/gtsam/hybrid/HybridSmoother.h index b453272581..77b809a444 100644 --- a/gtsam/hybrid/HybridSmoother.h +++ b/gtsam/hybrid/HybridSmoother.h @@ -126,9 +126,13 @@ class GTSAM_EXPORT HybridSmoother { /// Optimize the hybrid Bayes Net, taking into accound fixed values. HybridValues optimize() const; - /// Relinearize the nonlinear factor graph - /// with the latest linearization point. - void relinearize(); + /** + * @brief Relinearize the nonlinear factor graph with + * the latest stored linearization point. + * + * @param givenOrdering An optional elimination ordering. + */ + void relinearize(const std::optional givenOrdering = {}); /// Return the current linearization point. Values linearizationPoint() const; diff --git a/gtsam/hybrid/hybrid.i b/gtsam/hybrid/hybrid.i index f76de20bef..a5902d769d 100644 --- a/gtsam/hybrid/hybrid.i +++ b/gtsam/hybrid/hybrid.i @@ -288,7 +288,8 @@ class HybridSmoother { std::optional maxNrLeaves = std::nullopt, const std::optional given_ordering = std::nullopt); - void relinearize(); + void relinearize( + const std::optional givenOrdering = std::nullopt); gtsam::Values linearizationPoint() const; gtsam::HybridNonlinearFactorGraph allFactors() const; diff --git a/gtsam/navigation/AHRSFactor.h b/gtsam/navigation/AHRSFactor.h index 496fcde3d8..deea724beb 100644 --- a/gtsam/navigation/AHRSFactor.h +++ b/gtsam/navigation/AHRSFactor.h @@ -29,7 +29,7 @@ namespace gtsam { /** - * PreintegratedAHRSMeasurements accumulates (integrates) the Gyroscope + * PreintegratedAHRSMeasurements accumulates (integrates) the gyroscope * measurements (rotation rates) and the corresponding covariance matrix. * Can be built incrementally so as to avoid costly integration at time of factor construction. */ @@ -49,7 +49,7 @@ class GTSAM_EXPORT PreintegratedAhrsMeasurements : public PreintegratedRotation /** * Default constructor, initialize with no measurements - * @param bias Current estimate of acceleration and rotation rate biases + * @param bias Current estimate of rotation rate biases */ PreintegratedAhrsMeasurements(const std::shared_ptr& p, const Vector3& biasHat) : @@ -60,7 +60,7 @@ class GTSAM_EXPORT PreintegratedAhrsMeasurements : public PreintegratedRotation /** * Non-Default constructor, initialize with measurements * @param p: Parameters for AHRS pre-integration - * @param bias_hat: Current estimate of acceleration and rotation rate biases + * @param bias_hat: Current estimate of rotation rate biases * @param deltaTij: Delta time in pre-integration * @param deltaRij: Delta rotation in pre-integration * @param delRdelBiasOmega: Jacobian of rotation wrt. to gyro bias @@ -87,11 +87,11 @@ class GTSAM_EXPORT PreintegratedAhrsMeasurements : public PreintegratedRotation /// equals bool equals(const PreintegratedAhrsMeasurements&, double tol = 1e-9) const; - /// Reset inetgrated quantities to zero + /// Reset integrated quantities to zero void resetIntegration(); /** - * Add a single Gyroscope measurement to the preintegration. + * Add a single gyroscope measurement to the preintegration. * Measurements are taken to be in the sensor * frame and conversion to the body frame is handled by `body_P_sensor` in * `PreintegratedRotationParams` (if provided). diff --git a/gtsam/navigation/ConstantVelocityFactor.h b/gtsam/navigation/ConstantVelocityFactor.h index 9fe5bef85a..49d97033ec 100644 --- a/gtsam/navigation/ConstantVelocityFactor.h +++ b/gtsam/navigation/ConstantVelocityFactor.h @@ -41,7 +41,7 @@ class ConstantVelocityFactor : public NoiseModelFactorN { ~ConstantVelocityFactor() override {} /** - * @brief Caclulate error: (x2 - x1.update(dt))) + * @brief Calculate error: (x2 - x1.update(dt))) * where X1 and X1 are NavStates and dt is * the time difference in seconds between the states. * @param x1 NavState for key a diff --git a/gtsam/navigation/GPSFactor.cpp b/gtsam/navigation/GPSFactor.cpp index f01a16d902..cb42eea775 100644 --- a/gtsam/navigation/GPSFactor.cpp +++ b/gtsam/navigation/GPSFactor.cpp @@ -37,9 +37,9 @@ bool GPSFactor::equals(const NonlinearFactor& expected, double tol) const { } //*************************************************************************** -Vector GPSFactor::evaluateError(const Pose3& p, +Vector GPSFactor::evaluateError(const Pose3& nTb, OptionalMatrixType H) const { - return p.translation(H) -nT_; + return nTb.translation(H) -nT_; } //*************************************************************************** @@ -82,9 +82,9 @@ bool GPSFactorArm::equals(const NonlinearFactor& expected, double tol) const { } //*************************************************************************** -Vector GPSFactorArm::evaluateError(const Pose3& p, +Vector GPSFactorArm::evaluateError(const Pose3& nTb, OptionalMatrixType H) const { - const Matrix3 nRb = p.rotation().matrix(); + const Matrix3 nRb = nTb.rotation().matrix(); if (H) { H->resize(3, 6); @@ -92,7 +92,7 @@ Vector GPSFactorArm::evaluateError(const Pose3& p, H->block<3, 3>(0, 3) = nRb; } - return p.translation() + nRb * bL_ - nT_; + return nTb.translation() + nRb * bL_ - nT_; } //*************************************************************************** @@ -110,9 +110,9 @@ bool GPSFactorArmCalib::equals(const NonlinearFactor& expected, double tol) cons } //*************************************************************************** -Vector GPSFactorArmCalib::evaluateError(const Pose3& p, const Point3& bL, +Vector GPSFactorArmCalib::evaluateError(const Pose3& nTb, const Point3& bL, OptionalMatrixType H1, OptionalMatrixType H2) const { - const Matrix3 nRb = p.rotation().matrix(); + const Matrix3 nRb = nTb.rotation().matrix(); if (H1) { H1->resize(3, 6); @@ -124,7 +124,7 @@ Vector GPSFactorArmCalib::evaluateError(const Pose3& p, const Point3& bL, *H2 = nRb; } - return p.translation() + nRb * bL - nT_; + return nTb.translation() + nRb * bL - nT_; } //*************************************************************************** @@ -142,9 +142,9 @@ bool GPSFactor2::equals(const NonlinearFactor& expected, double tol) const { } //*************************************************************************** -Vector GPSFactor2::evaluateError(const NavState& p, +Vector GPSFactor2::evaluateError(const NavState& nTb, OptionalMatrixType H) const { - return p.position(H) -nT_; + return nTb.position(H) -nT_; } //*************************************************************************** @@ -164,9 +164,9 @@ bool GPSFactor2Arm::equals(const NonlinearFactor& expected, double tol) const { } //*************************************************************************** -Vector GPSFactor2Arm::evaluateError(const NavState& p, +Vector GPSFactor2Arm::evaluateError(const NavState& nTb, OptionalMatrixType H) const { - const Matrix3 nRb = p.attitude().matrix(); + const Matrix3 nRb = nTb.attitude().matrix(); if (H) { H->resize(3, 9); @@ -175,7 +175,7 @@ Vector GPSFactor2Arm::evaluateError(const NavState& p, H->block<3, 3>(0, 6).setZero(); } - return p.position() + nRb * bL_ - nT_; + return nTb.position() + nRb * bL_ - nT_; } //*************************************************************************** @@ -193,9 +193,9 @@ bool GPSFactor2ArmCalib::equals(const NonlinearFactor& expected, double tol) con } //*************************************************************************** -Vector GPSFactor2ArmCalib::evaluateError(const NavState& p, const Point3& bL, +Vector GPSFactor2ArmCalib::evaluateError(const NavState& nTb, const Point3& bL, OptionalMatrixType H1, OptionalMatrixType H2) const { - const Matrix3 nRb = p.attitude().matrix(); + const Matrix3 nRb = nTb.attitude().matrix(); if (H1) { H1->resize(3, 9); @@ -208,7 +208,7 @@ Vector GPSFactor2ArmCalib::evaluateError(const NavState& p, const Point3& bL, *H2 = nRb; } - return p.position() + nRb * bL - nT_; + return nTb.position() + nRb * bL - nT_; } }/// namespace gtsam diff --git a/gtsam/navigation/GPSFactor.h b/gtsam/navigation/GPSFactor.h index 4ef7c9794d..3fc618b920 100644 --- a/gtsam/navigation/GPSFactor.h +++ b/gtsam/navigation/GPSFactor.h @@ -83,7 +83,7 @@ class GTSAM_EXPORT GPSFactor: public NoiseModelFactorN { bool equals(const NonlinearFactor& expected, double tol = 1e-9) const override; /// vector of errors - Vector evaluateError(const Pose3& p, OptionalMatrixType H) const override; + Vector evaluateError(const Pose3& nTb, OptionalMatrixType H) const override; /// return the measurement, in the navigation frame inline const Point3 & measurementIn() const { @@ -171,7 +171,7 @@ class GTSAM_EXPORT GPSFactorArm: public NoiseModelFactorN { bool equals(const NonlinearFactor& expected, double tol = 1e-9) const override; /// vector of errors - Vector evaluateError(const Pose3& p, OptionalMatrixType H) const override; + Vector evaluateError(const Pose3& nTb, OptionalMatrixType H) const override; /// return the measurement, in the navigation frame inline const Point3 & measurementIn() const { @@ -242,7 +242,7 @@ class GTSAM_EXPORT GPSFactorArmCalib: public NoiseModelFactorN { bool equals(const NonlinearFactor& expected, double tol = 1e-9) const override; /// vector of errors - Vector evaluateError(const Pose3& p, const Point3& bL, OptionalMatrixType H1, + Vector evaluateError(const Pose3& nTb, const Point3& bL, OptionalMatrixType H1, OptionalMatrixType H2) const override; /// return the measurement, in the navigation frame @@ -304,7 +304,7 @@ class GTSAM_EXPORT GPSFactor2: public NoiseModelFactorN { bool equals(const NonlinearFactor& expected, double tol = 1e-9) const override; /// vector of errors - Vector evaluateError(const NavState& p, OptionalMatrixType H) const override; + Vector evaluateError(const NavState& nTb, OptionalMatrixType H) const override; /// return the measurement, in the navigation frame inline const Point3 & measurementIn() const { @@ -384,7 +384,7 @@ class GTSAM_EXPORT GPSFactor2Arm: public NoiseModelFactorN { bool equals(const NonlinearFactor& expected, double tol = 1e-9) const override; /// vector of errors - Vector evaluateError(const NavState& p, OptionalMatrixType H) const override; + Vector evaluateError(const NavState& nTb, OptionalMatrixType H) const override; /// return the measurement, in the navigation frame inline const Point3 & measurementIn() const { @@ -453,7 +453,7 @@ class GTSAM_EXPORT GPSFactor2ArmCalib: public NoiseModelFactorN { const Point& direction, const Point& bias, const SharedNoiseModel& model, - const std::optional& body_P_sensor) + const std::optional& body_P_sensor = {}) : Base(model, pose_key), measured_(body_P_sensor ? body_P_sensor->rotation() * measured : measured), nM_(scale * direction.normalized()), diff --git a/gtsam/navigation/PreintegratedRotation.cpp b/gtsam/navigation/PreintegratedRotation.cpp index 6c8e510e53..00e41fa98a 100644 --- a/gtsam/navigation/PreintegratedRotation.cpp +++ b/gtsam/navigation/PreintegratedRotation.cpp @@ -27,7 +27,7 @@ namespace gtsam { void PreintegratedRotationParams::print(const string& s) const { cout << (s.empty() ? s : s + "\n") << endl; - cout << "gyroscopeCovariance:\n[\n" << gyroscopeCovariance << "\n]" << endl; + cout << "gyroscopeCovariance:\n" << gyroscopeCovariance << endl; if (omegaCoriolis) cout << "omegaCoriolis = (" << omegaCoriolis->transpose() << ")" << endl; if (body_P_sensor) body_P_sensor->print("body_P_sensor"); diff --git a/gtsam/navigation/PreintegratedRotation.h b/gtsam/navigation/PreintegratedRotation.h index a887ef3215..9473ec51d0 100644 --- a/gtsam/navigation/PreintegratedRotation.h +++ b/gtsam/navigation/PreintegratedRotation.h @@ -126,12 +126,12 @@ class GTSAM_EXPORT PreintegratedRotation { Rot3 deltaRij_; ///< Preintegrated relative orientation (in frame i) Matrix3 delRdelBiasOmega_; ///< Jacobian of preintegrated rotation w.r.t. angular rate bias - /// Default constructor for serialization - PreintegratedRotation() {} - - public: + public: /// @name Constructors /// @{ + + /// Default constructor for serialization + PreintegratedRotation() {} /// Default constructor, resets integration to zero explicit PreintegratedRotation(const std::shared_ptr& p) : p_(p) { @@ -149,9 +149,6 @@ class GTSAM_EXPORT PreintegratedRotation { /// @name Basic utilities /// @{ - /// Re-initialize PreintegratedMeasurements - void resetIntegration(); - /// check parameters equality: checks whether shared pointer points to same Params object. bool matchesParamsWith(const PreintegratedRotation& other) const { return p_ == other.p_; @@ -175,6 +172,9 @@ class GTSAM_EXPORT PreintegratedRotation { /// @name Main functionality /// @{ + /// Re-initialize PreintegratedMeasurements + void resetIntegration(); + /** * @brief Calculate an incremental rotation given the gyro measurement and a * time interval, and update both deltaTij_ and deltaRij_. diff --git a/gtsam/navigation/doc/AHRSFactor.ipynb b/gtsam/navigation/doc/AHRSFactor.ipynb new file mode 100644 index 0000000000..71263fa87e --- /dev/null +++ b/gtsam/navigation/doc/AHRSFactor.ipynb @@ -0,0 +1,215 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# AHRSFactor\n", + "\n", + "\"Open\n", + "\n", + "## Overview\n", + "\n", + "The `AHRSFactor` class implements a factor to implement an *Attitude and Heading Reference System* (AHRS) within GTSAM. It is a binary factor, taking preintegrated measurements from a gyroscope between two discrete time steps, typically denoted as $t_i$ and $t_j$. These preintegrated measurements encapsulate the rotational motion observed by an inertial measurement unit (IMU) between these two timestamps.\n", + "\n", + "The `AHRSFactor` thus constrains two attitude states (represented as elements of $SO(3)$) based solely on gyroscope measurements. Accelerometer or magnetometer aiding, needed to build a complete AHRS system, must be handled separately." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": { + "tags": [ + "remove-cell" + ] + }, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Note: you may need to restart the kernel to use updated packages.\n" + ] + } + ], + "source": [ + "%pip install --quiet gtsam-develop plotly" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Mathematical Formulation\n", + "\n", + "The `AHRSFactor` relies on the use of `PreintegratedRotation`, which applies successive exponential maps to each individual gyroscope measurement $\\omega$ over the interval $[t_i, t_j]$. In this approach, every measurement contributes a small rotation given by $\\exp(\\omega_k \\Delta t)$, and the overall preintegrated rotation is obtained by composing these incremental rotations:\n", + "$$\n", + "\\Delta R_{ij}^{meas} = \\prod_{k} \\exp(\\omega_k \\Delta t)\n", + "$$\n", + "\n", + "Given two estimated rotations $R_i$ at time $t_i$ and $R_j$ at time $t_j$, the factor enforces:\n", + "$$\n", + "R_j \\approx R_i \\cdot \\Delta R_{ij}^{meas}\n", + "$$\n", + "\n", + "The error term optimized by the factor graph is the rotational discrepancy captured by the logarithmic map:\n", + "$$\n", + "e = \\text{Log}\\left((\\Delta R_{ij}^{meas})^T \\cdot R_i^T R_j\\right)\n", + "$$\n", + "\n", + "Note: the reality is a bit more complicated, because the code also takes into account the effects of bias, and if desired, coriolis forces." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Key Functionality\n", + "\n", + "### Constructor\n", + "\n", + "The constructor initializes the factor using a preintegrated AHRS measurement object, relating orientation states at discrete time instances $t_i$ and $t_j$.\n", + "\n", + "### Core Methods\n", + "\n", + "- `evaluateError`: calculates the error between two estimated orientations at times $t_i$ and $t_j$, relative to the preintegrated gyroscopic measurements. The error is computed as:\n", + "\n", + " $$\n", + " \\text{error} = \\text{Log}\\left((\\Delta R_{ij}^{meas})^T \\cdot R_i^T R_j\\right)\n", + " $$\n", + "\n", + " Here:\n", + "\n", + " - $R_i, R_j$ are the estimated rotation matrices at times $t_i$ and $t_j$.\n", + " - $\\Delta R_{ij}^{meas}$ is the rotation matrix obtained by integrating gyroscope measurements from $t_i$ to $t_j$.\n", + " - $\\text{Log}(\\cdot)$ is the logarithmic map from $SO(3)$ to $\\mathbb{R}^3$.\n", + "\n", + " The resulting 3-dimensional error vector represents the rotational discrepancy.\n", + "\n", + "- `print`: outputs a readable representation of the internal state of the factor, including the associated time steps and preintegrated measurements, aiding debugging and verification.\n", + "\n", + "- `equals` determines if another `AHRSFactor` instance is identical, useful in testing scenarios or when verifying the correctness of factor graph constructions." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Usage\n", + "\n", + "First, create a PreintegratedAhrsMeasurements (PAM) object by supplying the necessary IMU parameters. " + ] + }, + { + "cell_type": "code", + "execution_count": 2, + "metadata": {}, + "outputs": [], + "source": [ + "import numpy as np\n", + "from gtsam import PreintegrationParams, PreintegratedAhrsMeasurements\n", + "\n", + "params = PreintegrationParams.MakeSharedU(9.81)\n", + "params.setGyroscopeCovariance(np.deg2rad(1)*np.eye(3))\n", + "params.setAccelerometerCovariance(0.01*np.eye(3))\n", + "\n", + "biasHat = np.zeros(3) # Assuming no bias for simplicity\n", + "pam = PreintegratedAhrsMeasurements(params, biasHat) " + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "\n", + "Next, integrate each gyroscope measurement along with its corresponding time interval to accumulate the preintegrated rotation." + ] + }, + { + "cell_type": "code", + "execution_count": 3, + "metadata": {}, + "outputs": [], + "source": [ + "from gtsam import Point3\n", + "np.random.seed(42) # For reproducibility\n", + "for _ in range(15): # Add 15 random measurements, biased to move around z-axis\n", + " omega = Point3(0,0,-0.5) + 0.1*np.random.randn(3) # Random angular velocity vector\n", + " pam.integrateMeasurement(omega, deltaT=0.1)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Finally, construct the AHRSFactor using the accumulated PAM and the keys representing the rotation states at the two time instants." + ] + }, + { + "cell_type": "code", + "execution_count": 4, + "metadata": {}, + "outputs": [], + "source": [ + "from gtsam import AHRSFactor\n", + "bias_key = 0 # Key for the bias\n", + "i, j = 1, 2 # Indices of the two attitude unknowns\n", + "ahrs_factor = AHRSFactor(i, j, bias_key, pam)" + ] + }, + { + "cell_type": "code", + "execution_count": 5, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "AHRSFactor(1,2,0, preintegrated measurements: deltaTij [1.5]\n", + " deltaRij.ypr = ( -0.82321 -0.0142842 0.0228577)\n", + "biasHat [0 0 0]\n", + " PreintMeasCov [ 0.0261799 1.73472e-18 1.35525e-20\n", + "1.73472e-18 0.0261799 9.23266e-20\n", + "1.35525e-20 1.17738e-19 0.0261799 ]\n", + " noise model: diagonal sigmas [0.161802159; 0.161802159; 0.161802159];\n", + "\n" + ] + } + ], + "source": [ + "print(ahrs_factor)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Source\n", + "- [AHRSFactor.h](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/AHRSFactor.h)\n", + "- [AHRSFactor.cpp](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/AHRSFactor.cpp)" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "py312", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.12.6" + } + }, + "nbformat": 4, + "nbformat_minor": 2 +} diff --git a/gtsam/navigation/doc/AttitudeFactor.ipynb b/gtsam/navigation/doc/AttitudeFactor.ipynb new file mode 100644 index 0000000000..7fd9e58f3d --- /dev/null +++ b/gtsam/navigation/doc/AttitudeFactor.ipynb @@ -0,0 +1,209 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# AttitudeFactor\n", + "\n", + "\"Open\n", + "\n", + "## Introduction\n", + "\n", + "The `AttitudeFactor` family in GTSAM provides factors that constrain the orientation (attitude) of a body (`Rot3` or `Pose3`) based on directional measurements. A common use case is constraining roll and pitch using an accelerometer (measuring gravity) or constraining yaw using a magnetometer (measuring the Earth's magnetic field).\n", + "\n", + "This notebook explains the mathematical foundation and usage of these factors." + ] + }, + { + "cell_type": "code", + "execution_count": 1, + "metadata": { + "tags": [ + "remove-cell" + ] + }, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "\u001b[31mERROR: Could not find a version that satisfies the requirement gtsam-develop (from versions: none)\u001b[0m\u001b[31m\n", + "\u001b[0m\u001b[31mERROR: No matching distribution found for gtsam-develop\u001b[0m\u001b[31m\n", + "\u001b[0mNote: you may need to restart the kernel to use updated packages.\n" + ] + } + ], + "source": [ + "%pip install --quiet gtsam-develop" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Mathematical Foundation\n", + "\n", + "### Concept\n", + "\n", + "The `AttitudeFactor` constrains the rotation $R_{nb}$ (from the body frame $b$ to the navigation frame $n$) such that a known reference direction in the navigation frame (`nRef`) aligns with a measured direction in the body frame (`bMeasured`), when rotated by $R_{nb}$.\n", + "\n", + "The factor enforces that:\n", + "$$ \\text{nRef} \\approx R_{nb} \\cdot \\text{bMeasured} $$ \n", + "\n", + "where:\n", + "- $R_{nb}$ is the rotation matrix representing the orientation from body to navigation frame.\n", + "- `bMeasured` is the direction *vector* measured by the sensor in the *body* frame (e.g., the accelerometer reading, typically normalized to a `Unit3`).\n", + "- `nRef` is the known direction *vector* of the corresponding physical quantity in the *navigation* frame (e.g., the gravity vector, typically normalized to a `Unit3`).\n", + "\n", + "### Error Function\n", + "\n", + "The error function computes the angular difference between the reference direction (`nRef`) and the rotated measured direction ($R_{nb} \\cdot \\text{bMeasured}$). GTSAM uses the `Unit3::error` method, which typically calculates a 2-dimensional tangent space error.\n", + "\n", + "$$ e = \\text{nRef}.\\text{error}(R_{nb} \\cdot \\text{bMeasured}) $$ \n", + "\n", + "This error is minimal (zero) when the rotated body measurement aligns perfectly with the navigation reference direction.\n", + "\n", + "The `attitudeError` function within the base class implements this:\n", + "```cpp\n", + "Vector AttitudeFactor::attitudeError(const Rot3& nRb) const {\n", + " // measured direction in body frame rotated into nav frame\n", + " Unit3 nPredicted = nRb * bMeasured_;\n", + " // error between predicted and reference direction\n", + " return nRef_.error(nPredicted); \n", + "} \n", + "```\n", + "\n", + "### Jacobians\n", + "\n", + "For optimization, the $2 \\times 3$ Jacobian of the error function with respect to the rotation parameters ($R_{nb}$) is required. This is computed using the chain rule, involving the derivative of the rotated vector and the derivative of the `Unit3::error` function.\n", + "\n", + "**Note:** The Jacobian for this specific error function can become zero or ill-defined when the angle between the predicted and reference directions is exactly 180 degrees. The factor behaves best when the initial estimate for $R_{nb}$ is reasonably close (i.e., within the correct hemisphere)." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Available Factors\n", + "\n", + "- `Rot3AttitudeFactor`: Constrains a `Rot3` variable.\n", + "- `Pose3AttitudeFactor`: Constrains the rotational part of a `Pose3` variable." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Usage Example\n", + "\n", + "Let's constrain the roll and pitch of a `Pose3` using an accelerometer reading. We assume an ENU navigation frame (Z is up) and the accelerometer measures gravity when stationary." + ] + }, + { + "cell_type": "code", + "execution_count": 1, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Created Pose3AttitudeFactor:\n", + "Pose3AttitudeFactor on x0\n", + " reference direction in nav frame: : 0\n", + " 0\n", + "-1\n", + " measured direction in body frame: :0.0102036\n", + " 0\n", + "-0.999948\n", + "isotropic dim=2 sigma=0.1\n", + "\n", + "Error at identity pose: [ 0. -0.01020355]\n", + "Error near expected zero pose: [ 0.00999931 -0.01020355]\n" + ] + } + ], + "source": [ + "import numpy as np\n", + "from gtsam import Pose3, Unit3, Rot3, Pose3AttitudeFactor\n", + "from gtsam.symbol_shorthand import X\n", + "from gtsam.noiseModel import Isotropic\n", + "\n", + "# Define the reference direction in the navigation (ENU) frame\n", + "# Gravity points along the negative Z axis in ENU.\n", + "nRef_gravity = Unit3(np.array([0.0, 0.0, -1.0]))\n", + "\n", + "# Define the measured direction in the body frame\n", + "# Assume the accelerometer reading is [0.1, 0.0, -9.8]. \n", + "# GTSAM's Unit3 constructor normalizes this automatically.\n", + "# The factor expects the *direction* the sensor measures in the *body* frame.\n", + "bMeasured_acc = Unit3(np.array([0.1, 0.0, -9.8]))\n", + "\n", + "# Define the noise model for the measurement (2-dimensional error)\n", + "# Example: 0.1 radians standard deviation on the tangent plane error\n", + "attitude_noise_sigma = 0.1\n", + "noise_model = Isotropic.Sigma(2, attitude_noise_sigma)\n", + "\n", + "# Create the factor\n", + "attitude_factor = Pose3AttitudeFactor(X(0), nRef_gravity, \n", + " noise_model, bMeasured_acc)\n", + "\n", + "print(\"Created Pose3AttitudeFactor:\")\n", + "attitude_factor.print()\n", + "\n", + "# Example: Evaluate the error at the identity pose (likely non-zero error)\n", + "identity_pose = Pose3()\n", + "error = attitude_factor.evaluateError(identity_pose)\n", + "print(\"\\nError at identity pose:\", error)\n", + "\n", + "# For zero error, the rotated measurement should align with the reference\n", + "# nRef = R_nb * bMeas => R_nb = nRef * bMeas.inverse() (approx for Unit3)\n", + "# This is complex to solve directly, but optimization finds the R_nb where error is zero.\n", + "# Let's try a pose that should roughly align Z_body with Z_nav (small roll)\n", + "zero_error_pose = Pose3(Rot3.Roll(-0.01), np.zeros(3)) # Approx -0.1/9.8 rad\n", + "error_near_zero = attitude_factor.evaluateError(zero_error_pose)\n", + "print(\"Error near expected zero pose:\", error_near_zero)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Conclusion\n", + "\n", + "The `AttitudeFactor` is a crucial tool for incorporating absolute orientation information from sensors like accelerometers and magnetometers into GTSAM factor graphs. It helps constrain orientation estimates, particularly roll and pitch (using gravity) and potentially yaw (using magnetic north), improving navigation accuracy, especially in GPS-denied scenarios." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Source\n", + "- [AttitudeFactor.h](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/AttitudeFactor.h)\n", + "- [AttitudeFactor.cpp](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/AttitudeFactor.cpp)" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "py312", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.12.6" + } + }, + "nbformat": 4, + "nbformat_minor": 2 +} diff --git a/gtsam/navigation/doc/BarometricFactor.ipynb b/gtsam/navigation/doc/BarometricFactor.ipynb new file mode 100644 index 0000000000..f15bbaaba6 --- /dev/null +++ b/gtsam/navigation/doc/BarometricFactor.ipynb @@ -0,0 +1,169 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# BarometricFactor\n", + "\n", + "\"Open\n", + "\n", + "## Overview\n", + "\n", + "The `BarometricFactor` (contributed by [Peter Milani](https://github.com/pmmilani) in 2021) provides a way to incorporate altitude information derived from barometric pressure measurements into a GTSAM factor graph. It acts as a unary factor on a `Pose3` state variable but also connects to a `double` variable representing a slowly varying atmospheric pressure bias (or equivalently, an altitude offset).\n", + "\n", + "Barometers measure absolute atmospheric pressure. Under the assumption of a standard atmosphere model, this pressure can be converted into an estimate of altitude above sea level. However, local atmospheric pressure changes constantly due to weather, making the direct pressure-to-altitude conversion inaccurate over longer periods. The `BarometricFactor` accounts for this by simultaneously estimating the vehicle's altitude (Z-component of the `Pose3`) and a bias term that absorbs the slow variations in local atmospheric pressure relative to the standard model." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": { + "tags": [ + "remove-cell" + ] + }, + "outputs": [], + "source": [ + "%pip install --quiet gtsam-develop" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Mathematical Formulation\n", + "\n", + "### Measurement Model\n", + "\n", + "1. **Pressure to Altitude:** The factor internally converts the input barometric pressure measurement $P_{meas}$ (in kPa) to an altitude estimate $h_{std}$ (in meters) using a standard atmosphere model (approximated by the factor's `heightOut` method, based on [NASA GRC](https://www.grc.nasa.gov/www/k-12/airplane/atmosmet.html)). This $h_{std}$ becomes the factor's internal measurement `nT_`.\n", + " $$ h_{std} = \\text{heightOut}(P_{meas}) $$ \n", + "\n", + "2. **Factor Error:** The factor constrains the Z-component of the `Pose3` variable's translation ($p_z$) and the bias variable ($b$). The error is the difference between the altitude predicted by the state and bias, and the altitude derived from the measurement:\n", + " $$ e = (p_z + b) - h_{std} $$ \n", + " where:\n", + " - $p_z$ is the Z-coordinate of the `Pose3` translation.\n", + " - $b$ is the estimated altitude bias (in meters).\n", + " - $h_{std}$ is the altitude calculated from the pressure measurement.\n", + "\n", + "### Bias Modeling\n", + "\n", + "The bias $b$ is typically connected between successive time steps using a `BetweenFactor` with a very small noise model, enforcing that the bias changes slowly over time (approximating a random walk)." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Key Functionality / API\n", + "\n", + "- **Constructor**: `BarometricFactor(poseKey, biasKey, baroIn_kPa, model)`: Creates the factor, taking the `Pose3` key, the `double` bias key, the pressure measurement *in kilopascals (kPa)*, and the 1D noise model for the altitude error.\n", + "- **`evaluateError(pose, bias)`**: Calculates the 1D error $e = (pose.z() + bias) - h_{std}$.\n", + "- **`measurementIn()`**: Returns the internally stored altitude measurement $h_{std}$ (converted from the input pressure).\n", + "- **`heightOut(pressure_kPa)`**: Converts pressure (kPa) to altitude (m) using the standard atmosphere model.\n", + "- **`baroOut(altitude_m)`**: Converts altitude (m) back to pressure (kPa) using the inverse model.\n", + "- **`print` / `equals`**: Standard factor methods." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Usage Example\n", + "\n", + "Assume we have a pressure reading and want to add a factor constraining a `Pose3` and a bias." + ] + }, + { + "cell_type": "code", + "execution_count": 4, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Created BarometricFactor:\n", + "Barometric Factor on x0Barometric Bias on b0\n", + " Baro measurement: 108.939\n", + " noise model: unit (1) \n", + "\n", + "Internal altitude measurement: 108.94 m\n", + "Current Pose Z: 110.00 m\n", + "Current Bias: -1.50 m\n", + "Predicted Altitude (Pose Z + Bias): 108.50 m\n", + "Error (Predicted - Measured): -0.44 m\n" + ] + } + ], + "source": [ + "import gtsam\n", + "import numpy as np\n", + "from gtsam.symbol_shorthand import X, B # Pose key, Bias key\n", + "\n", + "# Define keys\n", + "pose_key = X(0)\n", + "bias_key = B(0)\n", + "\n", + "# Measurement\n", + "pressure_kPa = 100.1 # Example pressure reading in kilopascals\n", + "\n", + "# Noise model on the *altitude* error (e.g., +/- 1 meter sigma)\n", + "altitude_sigma = 1.0 \n", + "noise_model = gtsam.noiseModel.Isotropic.Sigma(1, altitude_sigma)\n", + "\n", + "# Create the factor\n", + "barometric_factor = gtsam.BarometricFactor(pose_key, bias_key, pressure_kPa, noise_model)\n", + "\n", + "print(\"Created BarometricFactor:\")\n", + "barometric_factor.print()\n", + "\n", + "# Internal altitude measurement (converted from pressure)\n", + "internal_altitude_measurement = barometric_factor.measurementIn()\n", + "print(f\"\\nInternal altitude measurement: {internal_altitude_measurement:.2f} m\")\n", + "\n", + "# Example: Evaluate error \n", + "# Assume current state estimate is Pose3 at z=110m and bias= -1.5m\n", + "current_pose = gtsam.Pose3(gtsam.Rot3(), np.array([0, 0, 110.0]))\n", + "current_bias = -1.5\n", + "\n", + "error = barometric_factor.evaluateError(current_pose, current_bias)\n", + "predicted_altitude = current_pose.z() + current_bias\n", + "print(f\"Current Pose Z: {current_pose.z():.2f} m\")\n", + "print(f\"Current Bias: {current_bias:.2f} m\")\n", + "print(f\"Predicted Altitude (Pose Z + Bias): {predicted_altitude:.2f} m\")\n", + "print(f\"Error (Predicted - Measured): {error[0]:.2f} m\")" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Source\n", + "- [BarometricFactor.h](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/BarometricFactor.h)\n", + "- [BarometricFactor.cpp](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/BarometricFactor.cpp)" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "py312", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.12.6" + } + }, + "nbformat": 4, + "nbformat_minor": 2 +} diff --git a/gtsam/navigation/doc/CombinedImuFactor.ipynb b/gtsam/navigation/doc/CombinedImuFactor.ipynb new file mode 100644 index 0000000000..1f7b7767a7 --- /dev/null +++ b/gtsam/navigation/doc/CombinedImuFactor.ipynb @@ -0,0 +1,238 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# CombinedImuFactor\n", + "\n", + "\"Open\n", + "\n", + "## Overview\n", + "\n", + "The `CombinedImuFactor` is an advanced IMU factor in GTSAM that offers several improvements over the standard `ImuFactor`:\n", + "1. **Bias Evolution:** It explicitly models the evolution of IMU biases between time steps $i$ and $j$ using a random walk model.\n", + "2. **6-Way Factor:** Consequently, it connects *six* variables: Pose_i, Vel_i, Bias_i, Pose_j, Vel_j, and Bias_j.\n", + "3. **Combined Preintegration:** It uses `PreintegratedCombinedMeasurements` which propagates a full 15x15 covariance matrix, accounting for correlations between the preintegrated state and the biases, as well as the bias random walk noise.\n", + "\n", + "This factor is generally preferred when bias stability is a concern or when modeling the time-varying nature of biases is important for accuracy. It eliminates the need for separate `BetweenFactor`s on bias variables." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": { + "tags": [ + "remove-cell" + ] + }, + "outputs": [], + "source": [ + "%pip install --quiet gtsam-develop" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Mathematical Formulation\n", + "\n", + "The `CombinedImuFactor` has a 15-dimensional error vector, conceptually split into two parts:\n", + "\n", + "1. **Preintegration Error (9 dimensions):** This part is identical in concept to the error in `ImuFactor`. It measures the discrepancy between the relative motion predicted by the `PreintegratedCombinedMeasurements` (using the current estimate of $b_i$) and the relative motion implied by the states $X_i = (R_i, p_i, v_i)$ and $X_j = (R_j, p_j, v_j)$.\n", + " $$ e_{imu} = \\text{NavState::Logmap}( \\text{pim.predict}(X_i, b_i)^{-1} \\otimes X_j ) $$ \n", + "\n", + "2. **Bias Random Walk Error (6 dimensions):** This part measures how much the change in bias ($b_j - b_i$) deviates from the expected zero-mean random walk. \n", + " $$ e_{bias} = b_j - b_i $$ \n", + "\n", + "The total error vector is $e = [e_{imu}; e_{bias}]$.\n", + "\n", + "The factor's noise model (derived from `pim.preintMeasCov()`) is a 15x15 matrix that correctly weights these two error components, accounting for the propagated uncertainty from IMU measurements, initial bias uncertainty, and the bias random walk process noise." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Key Functionality / API\n", + "\n", + "- **Constructor**: `CombinedImuFactor(keyPose_i, keyVel_i, keyPose_j, keyVel_j, keyBias_i, keyBias_j, pim)`: Creates the factor, linking the six state/bias keys and providing the combined preintegrated measurements.\n", + "- **`preintegratedMeasurements()`**: Returns a const reference to the stored `PreintegratedCombinedMeasurements` object.\n", + "- **`evaluateError(pose_i, vel_i, pose_j, vel_j, bias_i, bias_j)`**: Calculates the 15-dimensional error vector given the current values of the connected variables. Also computes Jacobians if requested.\n", + "- **`noiseModel()`**: Returns the 15x15 noise model associated with the preintegrated measurement and bias evolution uncertainty.\n", + "- **`print` / `equals`**: Standard factor methods." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Usage Example\n", + "\n", + "Create combined parameters, create a combined PIM object, define keys (including two bias keys), and construct the factor." + ] + }, + { + "cell_type": "code", + "execution_count": 1, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Created CombinedImuFactor:\n", + "CombinedImuFactor(x0,v0,x1,v1,b0,b1)\n", + " preintegrated measurements:\n", + " deltaTij = 0.1\n", + " deltaRij.ypr = ( 0 -0 0)\n", + " deltaPij = 0 0 -0.04905\n", + " deltaVij = 0 0 -0.981\n", + " gyrobias = 0 0 0\n", + " acc_bias = 0 0 0\n", + "\n", + " preintMeasCov [ 0.00011 0 0 0 1.53772e-06 0 0 4.85595e-05 0 0 0 0 4.5e-11 0 0\n", + " 0 0.00011 0 -1.53772e-06 0 0 -4.85595e-05 0 0 0 0 0 0 4.5e-11 0\n", + " 0 0 0.00011 0 0 0 0 0 0 0 0 0 0 0 4.5e-11\n", + " 0 -1.53772e-06 0 3.69908e-06 0 0 5.60718e-05 0 0 1.425e-10 0 0 0 -2.6487e-13 0\n", + " 1.53772e-06 0 0 0 3.69908e-06 0 0 5.60718e-05 0 0 1.425e-10 0 2.6487e-13 0 0\n", + " 0 0 0 0 0 3.6585e-06 0 0 5.5e-05 0 0 1.425e-10 0 0 0\n", + " 0 -4.85595e-05 0 5.60718e-05 0 0 0.00113017 0 0 4.5e-09 0 0 0 -1.1772e-11 0\n", + " 4.85595e-05 0 0 0 5.60718e-05 0 0 0.00113017 0 0 4.5e-09 0 1.1772e-11 0 0\n", + " 0 0 0 0 0 5.5e-05 0 0 0.0011 0 0 4.5e-09 0 0 0\n", + " 0 0 0 1.425e-10 0 0 4.5e-09 0 0 1e-07 0 0 0 0 0\n", + " 0 0 0 0 1.425e-10 0 0 4.5e-09 0 0 1e-07 0 0 0 0\n", + " 0 0 0 0 0 1.425e-10 0 0 4.5e-09 0 0 1e-07 0 0 0\n", + " 4.5e-11 0 0 0 2.6487e-13 0 0 1.1772e-11 0 0 0 0 1e-09 0 0\n", + " 0 4.5e-11 0 -2.6487e-13 0 0 -1.1772e-11 0 0 0 0 0 0 1e-09 0\n", + " 0 0 4.5e-11 0 0 0 0 0 0 0 0 0 0 0 1e-09 ]\n", + " noise model: Gaussian [\n", + "\t96.6351, 0, 0, 0, 91.8245, 0, -0, -8.70782, -0, 0, 0.261002, 0, -4.27039, 0, 0;\n", + "\t0, 96.6351, 0, -91.8245, 0, 0, 8.70782, -0, -0, -0.261002, 0, 0, 0, -4.27039, 0;\n", + "\t0, 0, 95.3463, 0, 0, 0, -0, -0, -0, 0, 0, 0, 0, 0, -4.29058;\n", + "\t0, 0, 0, 1044.19, 0, 0, -51.806, -0, -0, 0.843301, 0, 0, 0, -0.333286, 0;\n", + "\t0, 0, 0, 0, 1044.19, 0, -0, -51.806, -0, 0, 0.843301, 0, 0.333286, 0, 0;\n", + "\t0, 0, 0, 0, 0, 1049.15, -0, -0, -52.4575, 0, 0, 0.865549, 0, 0, 0;\n", + "\t0, 0, 0, 0, 0, 0, 29.746, -0, -0, -1.33857, 0, 0, 0, 0.35017, 0;\n", + "\t0, 0, 0, 0, 0, 0, 0, 29.746, -0, 0, -1.33857, 0, -0.35017, 0, 0;\n", + "\t0, 0, 0, 0, 0, 0, 0, 0, 30.1511, 0, 0, -1.3568, 0, 0, 0;\n", + "\t0, 0, 0, 0, 0, 0, 0, 0, 0, 3162.28, 0, 0, 0, 5.26625e-20, 0;\n", + "\t0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 3162.28, 0, -5.26625e-20, 0, 0;\n", + "\t0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 3162.28, 0, 0, 0;\n", + "\t0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 31622.8, 0, 0;\n", + "\t0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 31622.8, 0;\n", + "\t0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 31622.8\n", + "]\n", + "\n", + "Error vector (should be near zero): [0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0.]\n", + "Factor error (0.5 * ||error||^2_Sigma): 0.0\n" + ] + } + ], + "source": [ + "import numpy as np\n", + "from gtsam import (PreintegrationCombinedParams,\n", + " PreintegratedCombinedMeasurements, CombinedImuFactor,\n", + " NonlinearFactorGraph, Values, Pose3, NavState)\n", + "from gtsam.imuBias import ConstantBias\n", + "from gtsam.symbol_shorthand import X, V, B\n", + "\n", + "# 1. Create Combined Parameters and PIM (as in PreintegratedCombinedMeasurements example)\n", + "params = PreintegrationCombinedParams.MakeSharedU(9.81)\n", + "accel_noise_sigma = 0.1\n", + "gyro_noise_sigma = 0.01\n", + "params.setAccelerometerCovariance(np.eye(3) * accel_noise_sigma**2)\n", + "params.setGyroscopeCovariance(np.eye(3) * gyro_noise_sigma**2)\n", + "params.setIntegrationCovariance(np.eye(3) * 1e-8)\n", + "bias_acc_rw_sigma = 0.001\n", + "bias_gyro_rw_sigma = 0.0001\n", + "params.setBiasAccCovariance(np.eye(3) * bias_acc_rw_sigma**2)\n", + "params.setBiasOmegaCovariance(np.eye(3) * bias_gyro_rw_sigma**2)\n", + "initial_bias_cov = np.diag(np.full(6, 1e-3)) # Example initial bias uncertainty\n", + "params.setBiasAccOmegaInit(initial_bias_cov)\n", + "bias_hat = ConstantBias()\n", + "pim = PreintegratedCombinedMeasurements(params, bias_hat)\n", + "\n", + "# Integrate some dummy measurements\n", + "dt = 0.01\n", + "acc_meas = np.array([0.0, 0.0, -9.81]) # Stationary\n", + "gyro_meas = np.array([0.0, 0.0, 0.0]) # Stationary\n", + "for _ in range(10):\n", + " pim.integrateMeasurement(acc_meas, gyro_meas, dt)\n", + "\n", + "# 2. Define Symbolic Keys using shorthand\n", + "# Keys: X(0), V(0), B(0) for time i\n", + "# X(1), V(1), B(1) for time j\n", + "\n", + "# 3. Create the CombinedImuFactor\n", + "# The 15x15 noise model is automatically derived from pim.preintMeasCov()\n", + "combined_imu_factor = CombinedImuFactor(\n", + " X(0), V(0),\n", + " X(1), V(1),\n", + " B(0), B(1),\n", + " pim)\n", + "\n", + "print(\"Created CombinedImuFactor:\")\n", + "combined_imu_factor.print()\n", + "\n", + "# 4. Example: Evaluate error with perfect states & no bias change (should be near zero)\n", + "graph = NonlinearFactorGraph()\n", + "graph.add(combined_imu_factor)\n", + "\n", + "values = Values()\n", + "pose_i = Pose3()\n", + "vel_i = np.zeros(3)\n", + "bias_i = ConstantBias() # Matches bias_hat used in PIM\n", + "bias_j = bias_i # Assume no bias change for zero error check\n", + "\n", + "# Predict state j using the PIM\n", + "nav_state_i = NavState(pose_i, vel_i)\n", + "nav_state_j = pim.predict(nav_state_i, bias_i) # Use bias_i=bias_hat\n", + "pose_j = nav_state_j.pose()\n", + "vel_j = nav_state_j.velocity()\n", + "\n", + "values.insert(X(0), pose_i)\n", + "values.insert(V(0), vel_i)\n", + "values.insert(B(0), bias_i)\n", + "values.insert(X(1), pose_j)\n", + "values.insert(V(1), vel_j)\n", + "values.insert(B(1), bias_j)\n", + "\n", + "error_vector = combined_imu_factor.evaluateError(\n", + " pose_i, vel_i, pose_j, vel_j, bias_i, bias_j)\n", + "print(\"\\nError vector (should be near zero):\", error_vector)\n", + "print(\"Factor error (0.5 * ||error||^2_Sigma):\", graph.error(values))" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Source\n", + "- [CombinedImuFactor.h](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/CombinedImuFactor.h)\n", + "- [CombinedImuFactor.cpp](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/CombinedImuFactor.cpp)" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "py312", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.12.6" + } + }, + "nbformat": 4, + "nbformat_minor": 2 +} diff --git a/gtsam/navigation/doc/ConstantVelocityFactor.ipynb b/gtsam/navigation/doc/ConstantVelocityFactor.ipynb new file mode 100644 index 0000000000..561357221b --- /dev/null +++ b/gtsam/navigation/doc/ConstantVelocityFactor.ipynb @@ -0,0 +1,176 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# ConstantVelocityFactor\n", + "\n", + "\"Open\n", + "\n", + "## Overview\n", + "\n", + "The `ConstantVelocityFactor` (contributed by [Asa Hammond](https://www.linkedin.com/in/asahammond/) in 2021) is a simple motion model factor that connects two `NavState` variables at different times, $t_i$ and $t_j$. It enforces the assumption that the velocity remained constant between the two time steps.\n", + "\n", + "Given `NavState` $X_i$ (containing pose $T_i$ and velocity $v_i$) and `NavState` $X_j$ (containing pose $T_j$ and velocity $v_j$), and the time difference $\\Delta t = t_j - t_i$, this factor penalizes deviations from the constant velocity prediction." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": { + "tags": [ + "remove-cell" + ] + }, + "outputs": [], + "source": [ + "%pip install --quiet gtsam-develop" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Mathematical Formulation\n", + "\n", + "The factor uses the `NavState::update` method (or equivalent logic internally) to predict the state at time $t_j$ based on the state at $t_i$ and the assumption of constant velocity (and zero acceleration/angular velocity). Let this prediction be $X_{j, pred}$:\n", + "$$ X_{j, pred} = X_i . \\text{update}(\\text{accel}=0, \\text{omega}=0, \\Delta t) $$ \n", + "Essentially, this integrates the velocity $v_i$ over $\\Delta t$ to predict the change in position, while keeping orientation and velocity constant:\n", + "$$ R_{j, pred} = R_i $$ \n", + "$$ v_{j, pred} = v_i $$ \n", + "$$ p_{j, pred} = p_i + R_i (v_i^{body}) \\Delta t \\quad \\text{(using body velocity update)} $$ \n", + "\n", + "The factor's 9-dimensional error $e$ is the difference between the predicted state $X_{j, pred}$ and the actual state $X_j$, expressed in the tangent space at $X_{j,pred}$:\n", + "$$ e = \\text{localCoordinates}_{X_{j, pred}}(X_j) $$ \n", + "The noise model associated with the factor determines how strongly deviations from this constant velocity prediction are penalized." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Key Functionality / API\n", + "\n", + "- **Constructor**: `ConstantVelocityFactor(key1, key2, dt, model)`: Creates the factor connecting the `NavState` at `key1` (time $i$) and `key2` (time $j$), given the time difference `dt` and a 9D noise model.\n", + "- **`evaluateError(state1, state2)`**: Calculates the 9D error vector based on the constant velocity prediction from `state1` to `state2` over the stored `dt`." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Usage Example\n", + "\n", + "This factor is often used as a simple process model between consecutive states when higher-fidelity IMU integration is not available or needed." + ] + }, + { + "cell_type": "code", + "execution_count": 1, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Created ConstantVelocityFactor:\n", + " keys = { x0 x1 }\n", + " noise model: diagonal sigmas [0.01; 0.01; 0.01; 0.1; 0.1; 0.1; 0.05; 0.05; 0.05];\n", + "\n", + "Error for perfect prediction (should be zero): [0. 0. 0. 0. 0. 0. 0. 0. 0.]\n", + "Error for velocity change: [0. 0. 0. 0. 0. 0. 0. 0.1 0. ]\n", + "Error for position change: [0. 0. 0. 0. 0.05 0. 0. 0. 0. ]\n" + ] + } + ], + "source": [ + "import gtsam\n", + "import numpy as np\n", + "from gtsam.symbol_shorthand import X # Using X for NavState keys here\n", + "\n", + "# Define keys for two NavStates\n", + "key1 = X(0)\n", + "key2 = X(1)\n", + "\n", + "# Time difference between states\n", + "dt = 0.1 # seconds\n", + "\n", + "# Define a noise model - how much deviation from constant velocity is allowed?\n", + "# Example: Tighter on rotation/velocity, looser on position change due to velocity\n", + "rot_sigma = 0.01 # rad\n", + "pos_sigma = 0.1 # m \n", + "vel_sigma = 0.05 # m/s\n", + "sigmas = np.concatenate([\n", + " np.full(3, rot_sigma), \n", + " np.full(3, pos_sigma),\n", + " np.full(3, vel_sigma)\n", + "])\n", + "noise_model = gtsam.noiseModel.Diagonal.Sigmas(sigmas)\n", + "\n", + "# Create the factor\n", + "cv_factor = gtsam.ConstantVelocityFactor(key1, key2, dt, noise_model)\n", + "\n", + "print(\"Created ConstantVelocityFactor:\")\n", + "cv_factor.print()\n", + "\n", + "# --- Example Evaluation ---\n", + "# State 1: At origin, moving along +X at 1 m/s\n", + "pose1 = gtsam.Pose3()\n", + "vel1 = np.array([1.0, 0.0, 0.0])\n", + "state1 = gtsam.NavState(pose1, vel1)\n", + "\n", + "# State 2: Exactly matches constant velocity prediction\n", + "pose2 = gtsam.Pose3(gtsam.Rot3(), np.array([1.0*dt, 0.0, 0.0]))\n", + "vel2 = vel1 # Constant velocity\n", + "state2_perfect = gtsam.NavState(pose2, vel2)\n", + "\n", + "error_perfect = cv_factor.evaluateError(state1, state2_perfect)\n", + "print(\"\\nError for perfect prediction (should be zero):\", error_perfect)\n", + "\n", + "# State 3: Velocity changed slightly\n", + "vel3 = np.array([1.0, 0.1, 0.0]) # Added Y velocity\n", + "state3_vel_change = gtsam.NavState(pose2, vel3) # Keep predicted pose\n", + "\n", + "error_vel_change = cv_factor.evaluateError(state1, state3_vel_change)\n", + "print(\"Error for velocity change:\", error_vel_change)\n", + "\n", + "# State 4: Position is slightly off prediction\n", + "pose4 = gtsam.Pose3(gtsam.Rot3(), np.array([1.0*dt, 0.05, 0.0])) # Y pos is off\n", + "state4_pos_change = gtsam.NavState(pose4, vel2) # Keep velocity\n", + "\n", + "error_pos_change = cv_factor.evaluateError(state1, state4_pos_change)\n", + "print(\"Error for position change:\", error_pos_change)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Source\n", + "- [ConstantVelocityFactor.h](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/ConstantVelocityFactor.h)" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "py312", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.12.6" + } + }, + "nbformat": 4, + "nbformat_minor": 2 +} diff --git a/gtsam/navigation/doc/GPSFactor.ipynb b/gtsam/navigation/doc/GPSFactor.ipynb new file mode 100644 index 0000000000..658f2ad81d --- /dev/null +++ b/gtsam/navigation/doc/GPSFactor.ipynb @@ -0,0 +1,244 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# GPSFactor Family\n", + "\n", + "\"Open\n", + "\n", + "## Overview\n", + "\n", + "The `GPSFactor` family provides factors for incorporating Global Positioning System (GPS) measurements into a GTSAM factor graph. GPS typically provides measurements of position in Latitude/Longitude/Height. These GPS factors, however, assume the GPS measurement has been converted into a local Cartesian **navigation frame** (e.g., [ENU, NED, or ECEF](https://dirsig.cis.rit.edu/docs/new/coordinates.html)).\n", + "\n", + "Different variants exist to handle:\n", + "- State type: `Pose3` or `NavState`.\n", + "- Lever arm: Whether the GPS antenna is offset from the body frame origin.\n", + "- Calibration: Whether the lever arm itself is being estimated." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": { + "tags": [ + "remove-cell" + ] + }, + "outputs": [], + "source": [ + "%pip install --quiet gtsam-develop" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Factor Variants\n", + "\n", + "**For `Pose3` states:**\n", + "\n", + "- **`GPSFactor`**: \n", + " - Connects to: `Pose3` key.\n", + " - Assumes: Zero lever arm (GPS measurement corresponds directly to the `Pose3` origin).\n", + " - Measurement: 3D position (`Point3`) in the navigation frame.\n", + " - Error: $p_{pose} - p_{measured}$\n", + "\n", + "- **`GPSFactorArm`**: \n", + " - Connects to: `Pose3` key.\n", + " - Assumes: Known, fixed lever arm (`bL` vector in the body frame).\n", + " - Measurement: 3D position (`Point3`) in the navigation frame.\n", + " - Error: $(p_{pose} + R_{nb} \\cdot bL) - p_{measured}$\n", + "\n", + "- **`GPSFactorArmCalib`**: \n", + " - Connects to: `Pose3` key, `Point3` key (for the lever arm).\n", + " - Assumes: Lever arm (`bL`) is unknown and estimated.\n", + " - Measurement: 3D position (`Point3`) in the navigation frame.\n", + " - Error: $(p_{pose} + R_{nb} \\cdot bL_{estimated}) - p_{measured}$\n", + "\n", + "**For `NavState` states:**\n", + "\n", + "- **`GPSFactor2`**: Like `GPSFactor` but connects to a `NavState` key.\n", + "- **`GPSFactor2Arm`**: Like `GPSFactorArm` but connects to a `NavState` key.\n", + "- **`GPSFactor2ArmCalib`**: Like `GPSFactorArmCalib` but connects to a `NavState` key and a `Point3` lever arm key.\n", + "\n", + "(The '2' suffix historically denoted factors using `NavState`)." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Mathematical Formulation (GPSFactorArm Example)\n", + "\n", + "Let:\n", + "- $T_{nb} = (R_{nb}, p_{nb})$ be the `Pose3` state (body frame $b$ in navigation frame $n$).\n", + "- $L_b$ be the known lever arm vector from the body origin to the GPS antenna, expressed in the body frame.\n", + "- $p_{gps}$ be the measured GPS position in the navigation frame.\n", + "\n", + "The predicted position of the GPS antenna in the navigation frame is:\n", + "$$ p_{ant, pred} = p_{nb} + R_{nb} \\cdot L_b $$ \n", + "\n", + "The factor's 3D error vector is the difference between the predicted antenna position and the measured GPS position:\n", + "$$ e = p_{ant, pred} - p_{gps} $$ \n", + "\n", + "The noise model reflects the uncertainty of the $p_{gps}$ measurement in the navigation frame." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Key Functionality / API (Common Patterns)\n", + "\n", + "- **Constructor**: Takes the relevant key(s), the measured `Point3` position `gpsIn` (in nav frame), the noise model, and potentially the `leverArm` (`Point3` in body frame).\n", + "- **`evaluateError(...)`**: Calculates the 3D error vector based on the connected state variable(s) and the measurement.\n", + "- **`measurementIn()`**: Returns the stored `Point3` measurement.\n", + "- **`leverArm()`** (For Arm variants): Returns the stored `Point3` lever arm." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Usage Example (GPSFactor and GPSFactorArm)\n", + "\n", + "Assume we have a GPS reading converted to a local ENU frame." + ] + }, + { + "cell_type": "code", + "execution_count": 1, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Created GPSFactor (zero lever arm):\n", + "GPSFactor on x0\n", + " GPS measurement: 10.5\n", + "20.2\n", + " 5.1\n", + " noise model: diagonal sigmas [0.5; 0.5; 1];\n", + "\n", + "GPSFactor Error: [-0.5 -0.2 -0.1]\n", + "\n", + "Created GPSFactorArm:\n", + "GPSFactorArm on x0\n", + " GPS measurement: 10.5 20.2 5.1\n", + " Lever arm: -0.1 0 0.05\n", + " noise model: diagonal sigmas [0.5; 0.5; 1];\n", + "\n", + "GPSFactorArm Error: [-0.6 -0.2 -0.05]\n", + " ( Pose: [10. 20. 5.] )\n", + " ( Lever Arm: [-0.1 0. 0.05] )\n", + " ( Predicted Antenna Pos: [ 9.9 20. 5.05] )\n", + " ( Measured GPS Pos: [10.5 20.2 5.1] )\n", + "\n", + "Created GPSFactorArmCalib:\n", + "GPSFactorArmCalib on x0\n", + " GPS measurement: 10.5 20.2 5.1\n", + " noise model: diagonal sigmas [0.5; 0.5; 1];\n" + ] + } + ], + "source": [ + "import gtsam\n", + "import numpy as np\n", + "from gtsam.symbol_shorthand import X, L # Pose key, Lever arm key\n", + "\n", + "# --- Setup ---\n", + "pose_key = X(0)\n", + "\n", + "# GPS Measurement in local ENU frame (meters)\n", + "gps_measurement_enu = gtsam.Point3(10.5, 20.2, 5.1)\n", + "\n", + "# Noise model for GPS measurement (e.g., 0.5m horizontal, 1.0m vertical sigma)\n", + "gps_sigmas = np.array([0.5, 0.5, 1.0])\n", + "gps_noise_model = gtsam.noiseModel.Diagonal.Sigmas(gps_sigmas)\n", + "\n", + "# --- Scenario 1: GPSFactor (Zero Lever Arm) ---\n", + "gps_factor_zero_arm = gtsam.GPSFactor(pose_key, gps_measurement_enu, gps_noise_model)\n", + "print(\"Created GPSFactor (zero lever arm):\")\n", + "gps_factor_zero_arm.print()\n", + "\n", + "# Evaluate error: Error is difference between pose translation and measurement\n", + "test_pose1 = gtsam.Pose3(gtsam.Rot3(), gtsam.Point3(10.0, 20.0, 5.0))\n", + "error1 = gps_factor_zero_arm.evaluateError(test_pose1)\n", + "print(\"\\nGPSFactor Error:\", error1) # Expected: [0.5, 0.2, 0.1]\n", + "\n", + "# --- Scenario 2: GPSFactorArm (Known Lever Arm) ---\n", + "# Assume antenna is 10cm behind and 5cm above the body origin\n", + "lever_arm_body = gtsam.Point3(-0.1, 0.0, 0.05) \n", + "\n", + "gps_factor_with_arm = gtsam.GPSFactorArm(pose_key, gps_measurement_enu, \n", + " lever_arm_body, gps_noise_model)\n", + "print(\"\\nCreated GPSFactorArm:\")\n", + "gps_factor_with_arm.print()\n", + "\n", + "# Evaluate error: Error is difference between (pose + R*lever_arm) and measurement\n", + "# Use the same test pose as before\n", + "predicted_antenna_pos = test_pose1.transformFrom(lever_arm_body)\n", + "error2 = gps_factor_with_arm.evaluateError(test_pose1)\n", + "print(\"\\nGPSFactorArm Error:\", error2) \n", + "print(\" ( Pose: \", test_pose1.translation() , \")\")\n", + "print(\" ( Lever Arm: \", lever_arm_body, \")\")\n", + "print(\" ( Predicted Antenna Pos: \", predicted_antenna_pos, \")\")\n", + "print(\" ( Measured GPS Pos: \", gps_measurement_enu, \")\")\n", + "# Expected: predicted_antenna_pos - gps_measurement_enu \n", + "# = [9.9, 20.0, 5.05] - [10.5, 20.2, 5.1] = [-0.6, -0.2, -0.05]\n", + "\n", + "# --- Scenario 3: GPSFactorArmCalib (Example Setup - Not Evaluated) ---\n", + "lever_arm_key = L(0) # Key for the unknown lever arm\n", + "gps_factor_calib = gtsam.GPSFactorArmCalib(pose_key, lever_arm_key, \n", + " gps_measurement_enu, gps_noise_model)\n", + "print(\"\\nCreated GPSFactorArmCalib:\")\n", + "gps_factor_calib.print()" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Coordinate Frames\n", + "\n", + "It's crucial to ensure consistency in coordinate frames:\n", + "- **GPS Measurement (`gpsIn`)**: Must be provided in the chosen local Cartesian **navigation frame** (e.g., ENU, NED).\n", + "- **Lever Arm (`leverArm`)**: Must be provided in the **body frame**.\n", + "- **Pose/NavState Variables**: Represent the pose of the body frame in the navigation frame ($T_{nb}$)." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Source\n", + "- [GPSFactor.h](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/GPSFactor.h)\n", + "- [GPSFactor.cpp](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/GPSFactor.cpp)" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "py312", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.12.6" + } + }, + "nbformat": 4, + "nbformat_minor": 2 +} diff --git a/gtsam/navigation/doc/ImuFactor.ipynb b/gtsam/navigation/doc/ImuFactor.ipynb new file mode 100644 index 0000000000..0d0afa5265 --- /dev/null +++ b/gtsam/navigation/doc/ImuFactor.ipynb @@ -0,0 +1,309 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# ImuFactor\n", + "\n", + "\"Open\n", + "\n", + "## Overview\n", + "\n", + "### ImuFactor (5-way Factor)\n", + "\n", + "The `ImuFactor` is the standard GTSAM factor for incorporating preintegrated IMU measurements into a factor graph. It's a 5-way factor connecting:\n", + "\n", + "1. Pose at time $i$ (`Pose3`)\n", + "2. Velocity at time $i$ (`Vector3`)\n", + "3. Pose at time $j$ (`Pose3`)\n", + "4. Velocity at time $j$ (`Vector3`)\n", + "5. IMU Bias at time $i$ (`imuBias::ConstantBias`)\n", + "\n", + "It takes a `PreintegratedImuMeasurements` object, which summarizes the IMU readings between times $i$ and $j$. The factor's error function measures the discrepancy between the relative motion predicted by the preintegrated measurements (corrected for the *current* estimate of the bias at time $i$) and the relative motion implied by the state variables ($Pose_i, Vel_i, Pose_j, Vel_j$) connected to the factor.\n", + "\n", + "### ImuFactor2: NavState Variant\n", + "\n", + "The `ImuFactor2` is ternary variant of the `ImuFactor` that operates directly on `NavState` objects instead of separate `Pose3` and `Vector3` variables for pose and velocity. This simplifies the factor graph by reducing the number of connected variables and can make the graph more efficient to optimize.\n", + "\n", + "Instead of connecting five variables (`Pose_i`, `Vel_i`, `Pose_j`, `Vel_j`, `Bias_i`), the `ImuFactor2` connects three:\n", + "\n", + "1. `NavState` at time $i$ (`NavState` combines pose and velocity)\n", + "2. `NavState` at time $j`\n", + "3. IMU Bias at time $i$ (`imuBias::ConstantBias`)\n", + "\n", + "### Modeling Bias\n", + "\n", + "Both factors assume that the bias is *constant* between time $i$ and $j$ for the purpose of evaluating its error. That is typically a very good assumption, as bias evolves slowly over time.\n", + "\n", + "The factors do *not* model the evolution of bias over time; if bias is expected to change, separate `BetweenFactor`s on bias variables are typically needed, or the `CombinedImuFactor` should be used instead." + ] + }, + { + "cell_type": "code", + "execution_count": 1, + "metadata": { + "tags": [ + "remove-cell" + ] + }, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "\u001b[31mERROR: Could not find a version that satisfies the requirement gtsam-develop (from versions: none)\u001b[0m\u001b[31m\n", + "\u001b[0m\u001b[31mERROR: No matching distribution found for gtsam-develop\u001b[0m\u001b[31m\n", + "\u001b[0mNote: you may need to restart the kernel to use updated packages.\n" + ] + } + ], + "source": [ + "%pip install --quiet gtsam-develop" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Mathematical Formulation\n", + "\n", + "Let $X_i = (R_i, p_i, v_i)$ be the state (Attitude, Position, Velocity) at time $i$, and $b_i$ be the bias estimate at time $i$.\n", + "Let $X_j = (R_j, p_j, v_j)$ be the state at time $j$.\n", + "\n", + "The `PreintegratedImuMeasurements` object (`pim`) provides:\n", + "- $\\Delta \\tilde{R}_{ij}(b_{est})$, $\\Delta \\tilde{p}_{ij}(b_{est})$, $\\Delta \\tilde{v}_{ij}(b_{est})$: Preintegrated measurements calculated using the fixed bias estimate $b_{est}$ (`pim.biasHat()`).\n", + "- Jacobians of the $\\Delta$ terms with respect to the bias.\n", + "\n", + "The factor first uses the `pim` object's `predict` method (or equivalent calculations) to find the predicted state $X_{j,pred}$ based on $X_i$ and the *current* estimate of the bias $b_i$ from the factor graph values:\n", + "$$ X_{j,pred} = \\text{pim.predict}(X_i, b_i) $$ \n", + "This prediction internally applies first-order corrections to the stored $\\Delta$ values based on the difference between $b_i$ and $b_{est}$.\n", + "\n", + "The factor's 9-dimensional error vector $e$ is then calculated as the difference between the predicted state $X_{j,pred}$ and the actual state $X_j$ in the tangent space of $X_{j,pred}$:\n", + "$$ e = \\text{Logmap}_{X_{j,pred}}(X_j) = X_{j,pred}^{-1} \\otimes X_j \\quad \\text{(Conceptual Lie notation)} $$ \n", + "Or, more explicitly using the `NavState::Logmap` definition:\n", + "$$ e = \\text{NavState::Logmap}(X_{j,pred}.inverse() * X_j) $$ \n", + "This error vector has components corresponding to errors in rotation (3), position (3), and velocity (3)." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Key Functionality / API\n", + "\n", + "- **Constructor**: `ImuFactor(keyPose_i, keyVel_i, keyPose_j, keyVel_j, keyBias_i, pim)`: Creates the factor, linking the five state/bias keys and providing the preintegrated measurements.\n", + "- **`preintegratedMeasurements()`**: Returns a const reference to the stored `PreintegratedImuMeasurements` object.\n", + "- **`evaluateError(pose_i, vel_i, pose_j, vel_j, bias_i)`**: Calculates the 9-dimensional error vector given the current values of the connected variables. Also computes Jacobians if requested.\n", + "- **`noiseModel()`**: Returns the noise model associated with the preintegrated measurement uncertainty (derived from `pim.preintMeasCov()`).\n", + "- **`print` / `equals`**: Standard factor methods." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Usage Example\n", + "\n", + "Create parameters, a PIM object, define keys, and construct the factor." + ] + }, + { + "cell_type": "code", + "execution_count": 2, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Created ImuFactor:\n", + "ImuFactor(x0,v0,x1,v1,b0)\n", + "preintegrated measurements:\n", + "\n", + " deltaTij = 0.1\n", + " deltaRij.ypr = ( 0 -0 0)\n", + " deltaPij = 0 0 -0.04905\n", + " deltaVij = 0 0 -0.981\n", + " gyrobias = 0 0 0\n", + " acc_bias = 0 0 0\n", + "\n", + " preintMeasCov \n", + "[ 1e-05 0 0 0 1.39793e-07 0 0 4.4145e-06 0\n", + " 0 1e-05 0 -1.39793e-07 0 0 -4.4145e-06 0 0\n", + " 0 0 1e-05 0 0 0 0 0 0\n", + " 0 -1.39793e-07 0 3.32969e-06 0 0 5.00974e-05 0 0\n", + " 1.39793e-07 0 0 0 3.32969e-06 0 0 5.00974e-05 0\n", + " 0 0 0 0 0 3.326e-06 0 0 5e-05\n", + " 0 -4.4145e-06 0 5.00974e-05 0 0 0.00100274 0 0\n", + " 4.4145e-06 0 0 0 5.00974e-05 0 0 0.00100274 0\n", + " 0 0 0 0 0 5e-05 0 0 0.001]\n", + " noise model sigmas: 0.00316228 0.00316228 0.00316228 0.00182474 0.00182474 0.00182373 0.0316661 0.0316661 0.0316228\n", + "\n", + "Error vector (should be near zero): [0. 0. 0. 0. 0. 0. 0. 0. 0.]\n", + "Factor error (0.5 * ||error||^2_Sigma): 0.0\n" + ] + } + ], + "source": [ + "from gtsam import PreintegrationParams, PreintegratedImuMeasurements, ImuFactor\n", + "from gtsam import NonlinearFactorGraph, Values, NavState, Pose3\n", + "from gtsam.symbol_shorthand import X,V,B\n", + "from gtsam.imuBias import ConstantBias\n", + "import numpy as np\n", + "\n", + "# 1. Create Parameters and PIM (as in PreintegratedImuMeasurements example)\n", + "params = PreintegrationParams.MakeSharedU(9.81)\n", + "accel_noise_sigma = 0.1\n", + "gyro_noise_sigma = 0.01\n", + "params.setAccelerometerCovariance(np.eye(3) * accel_noise_sigma**2)\n", + "params.setGyroscopeCovariance(np.eye(3) * gyro_noise_sigma**2)\n", + "params.setIntegrationCovariance(np.eye(3) * 1e-8)\n", + "bias_hat = ConstantBias() # Assume zero bias used for preintegration\n", + "pim = PreintegratedImuMeasurements(params, bias_hat)\n", + "\n", + "# Integrate some dummy measurements\n", + "dt = 0.01\n", + "acc_meas = np.array([0.0, 0.0, -9.81]) # Stationary\n", + "gyro_meas = np.array([0.0, 0.0, 0.0]) # Stationary\n", + "for _ in range(10):\n", + " pim.integrateMeasurement(acc_meas, gyro_meas, dt)\n", + "\n", + "# 2. Symbolic Keys will be X(0), V(0), X(1), V(1), B(0)\n", + "\n", + "# 3. Create the ImuFactor\n", + "# The noise model is automatically derived from pim.preintMeasCov()\n", + "imu_factor = ImuFactor(X(0), V(0), X(1), V(1), B(0), pim)\n", + "\n", + "print(\"Created ImuFactor:\")\n", + "imu_factor.print()\n", + "\n", + "# 4. Example: Evaluate error with perfect states (should be near zero)\n", + "graph = NonlinearFactorGraph()\n", + "graph.add(imu_factor)\n", + "\n", + "values = Values()\n", + "pose_i = Pose3() # Identity\n", + "vel_i = np.zeros(3)\n", + "bias_i = ConstantBias() # Zero bias\n", + "\n", + "# Predict state j using the PIM and the *same* bias used for integration\n", + "nav_state_i = NavState(pose_i, vel_i)\n", + "nav_state_j = pim.predict(nav_state_i, bias_i) # Use bias_i=bias_hat\n", + "pose_j = nav_state_j.pose()\n", + "vel_j = nav_state_j.velocity()\n", + "\n", + "values.insert(X(0), pose_i)\n", + "values.insert(V(0), vel_i)\n", + "values.insert(X(1), pose_j)\n", + "values.insert(V(1), vel_j)\n", + "values.insert(B(0), bias_i)\n", + "\n", + "error_vector = imu_factor.evaluateError(pose_i, vel_i, pose_j, vel_j, bias_i)\n", + "print(\"\\nError vector (should be near zero):\", error_vector)\n", + "print(\"Factor error (0.5 * ||error||^2_Sigma):\", graph.error(values))" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "We can also use `ImuFactor2`, with `NavState`, giving exactly the same result:" + ] + }, + { + "cell_type": "code", + "execution_count": 3, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Created ImuFactor2:\n", + "ImuFactor2(x0,x1,b0)\n", + "preintegrated measurements:\n", + "\n", + " deltaTij = 0.1\n", + " deltaRij.ypr = ( 0 -0 0)\n", + " deltaPij = 0 0 -0.04905\n", + " deltaVij = 0 0 -0.981\n", + " gyrobias = 0 0 0\n", + " acc_bias = 0 0 0\n", + "\n", + " preintMeasCov \n", + "[ 1e-05 0 0 0 1.39793e-07 0 0 4.4145e-06 0\n", + " 0 1e-05 0 -1.39793e-07 0 0 -4.4145e-06 0 0\n", + " 0 0 1e-05 0 0 0 0 0 0\n", + " 0 -1.39793e-07 0 3.32969e-06 0 0 5.00974e-05 0 0\n", + " 1.39793e-07 0 0 0 3.32969e-06 0 0 5.00974e-05 0\n", + " 0 0 0 0 0 3.326e-06 0 0 5e-05\n", + " 0 -4.4145e-06 0 5.00974e-05 0 0 0.00100274 0 0\n", + " 4.4145e-06 0 0 0 5.00974e-05 0 0 0.00100274 0\n", + " 0 0 0 0 0 5e-05 0 0 0.001]\n", + " noise model sigmas: 0.00316228 0.00316228 0.00316228 0.00182474 0.00182474 0.00182373 0.0316661 0.0316661 0.0316228\n", + "\n", + "Error vector (should be near zero): [0. 0. 0. 0. 0. 0. 0. 0. 0.]\n", + "Factor error (0.5 * ||error||^2_Sigma): 0.0\n" + ] + } + ], + "source": [ + "from gtsam import ImuFactor2\n", + "\n", + "# 1. Create the ImuFactor2\n", + "# The noise model is automatically derived from pim.preintMeasCov()\n", + "imu_factor2 = ImuFactor2(X(0), X(1), B(0), pim)\n", + "\n", + "print(\"Created ImuFactor2:\")\n", + "imu_factor2.print()\n", + "\n", + "# 2. Example: Evaluate error with perfect states (should be near zero)\n", + "graph = NonlinearFactorGraph()\n", + "graph.add(imu_factor2)\n", + "\n", + "values = Values()\n", + "nav_state_i = NavState(pose_i, vel_i)\n", + "nav_state_j = pim.predict(nav_state_i, bias_i) # Use bias_i=bias_hat\n", + "\n", + "values.insert(X(0), nav_state_i)\n", + "values.insert(X(1), nav_state_j)\n", + "values.insert(B(0), bias_i)\n", + "\n", + "error_vector = imu_factor2.evaluateError(nav_state_i, nav_state_j, bias_i)\n", + "print(\"\\nError vector (should be near zero):\", error_vector)\n", + "print(\"Factor error (0.5 * ||error||^2_Sigma):\", graph.error(values))" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Source\n", + "- [ImuFactor.h](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/ImuFactor.h)\n", + "- [ImuFactor.cpp](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/ImuFactor.cpp)" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "py312", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.12.6" + } + }, + "nbformat": 4, + "nbformat_minor": 2 +} diff --git a/gtsam/navigation/doc/MagFactor.ipynb b/gtsam/navigation/doc/MagFactor.ipynb new file mode 100644 index 0000000000..4070c30f5f --- /dev/null +++ b/gtsam/navigation/doc/MagFactor.ipynb @@ -0,0 +1,226 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# MagFactor Family\n", + "\n", + "\"Open\n", + "\n", + "## Overview\n", + "\n", + "The `MagFactor` family provides factors for incorporating magnetometer measurements, which sense the Earth's magnetic field, into a GTSAM factor graph. These factors are primarily used to constrain the orientation (mostly \"yaw\") of a body or sensor.\n", + "\n", + "Magnetometers measure the local magnetic field vector in the sensor's own frame. The factors relate this measurement to the known (or estimated) magnetic field direction in the navigation frame via the body's rotation.\n", + "\n", + "Several variants exist depending on what is known and what is being estimated:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": { + "tags": [ + "remove-cell" + ] + }, + "outputs": [], + "source": [ + "%pip install --quiet gtsam-develop" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Measurement Model\n", + "\n", + "The general model assumed by these factors is:\n", + "$$ bM_{measured} = R_{bn} \\cdot (s \\cdot \\hat{d}_n) + b $$ \n", + "where:\n", + "- $bM_{measured}$: The 3D magnetic field vector measured by the sensor, in the **body frame**.\n", + "- $R_{bn}$: The rotation matrix from the navigation frame ($n$) to the body frame ($b$). This is the *inverse* of the rotation usually stored in `Pose3` or `NavState` ($R_{nb}$).\n", + "- $s$: A scale factor relating the magnetic field strength to the magnetometer's output units (e.g., nT).\n", + "- $\\hat{d}_n$: The unit vector representing the direction of the Earth's magnetic field in the **navigation frame**.\n", + "- $b$: A 3D additive bias vector in the **body frame**.\n", + "\n", + "The factor error is typically calculated as:\n", + "$$ e = bM_{measured} - [ R_{bn} \\cdot (s \\cdot \\hat{d}_n) + b ] $$ \n", + "Different factors treat different components ($R_{bn}$, $s$, $\\hat{d}_n$, $b$) as known constants or as variables to be estimated." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Factor Variants\n", + "\n", + "- **`MagFactor`**: \n", + " - Estimates: `Rot2` (intended for yaw $R_{nb}$).\n", + " - Assumes Known: `scale`, `direction`, `bias`.\n", + " - Note: Uses `Rot2` which might be limiting unless the sensor is always level.\n", + "\n", + "- **`MagFactor1`**: \n", + " - Estimates: `Rot3` ($R_{nb}$).\n", + " - Assumes Known: `scale`, `direction`, `bias`.\n", + " - This is often the most practical factor for direct orientation estimation when calibration is known.\n", + "\n", + "- **`MagFactor2`**: \n", + " - Estimates: `nM` (`Point3`, the scaled field vector $s \\cdot \\hat{d}_n$ in nav frame), `bias` (`Point3`).\n", + " - Assumes Known: `Rot3` ($R_{nb}$).\n", + " - Useful for calibrating the local field and bias if orientation is known (e.g., from other sensors).\n", + "\n", + "- **`MagFactor3`**: \n", + " - Estimates: `scale` (`double`), `direction` (`Unit3`), `bias` (`Point3`).\n", + " - Assumes Known: `Rot3` ($R_{nb}$).\n", + " - Provides full calibration of scale, direction, and bias when orientation is known.\n", + "\n", + "- **`MagPoseFactor`**: (Separate Header: `MagPoseFactor.h`)\n", + " - Estimates: `Pose2` or `Pose3`.\n", + " - Assumes Known: `scale`, `direction`, `bias`, optional `body_P_sensor`.\n", + " - Similar to `MagFactor1` but works directly on `Pose` types and handles sensor-to-body transforms." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Key Functionality / API (MagFactor1 Example)\n", + "\n", + "- **Constructor**: `MagFactor1(key, measured, scale, direction, bias, model)`: Creates the factor connecting the `Rot3` key, given the measurement, known calibration parameters, and noise model.\n", + "- **`evaluateError(nRb)`**: Calculates the 3D error vector $e$ based on the current `Rot3` estimate $R_{nb}$." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Usage Example (MagFactor1)\n", + "\n", + "Using a magnetometer to help estimate a `Rot3` orientation, assuming known calibration." + ] + }, + { + "cell_type": "code", + "execution_count": 1, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Created MagFactor1:\n", + " keys = { r0 }\n", + "isotropic dim=3 sigma=50\n", + "\n", + "Error at ground truth rotation (should be zero): [0. 0. 0.]\n", + "Error at test rotation: [1034.79105955 1628.05638524 0. ]\n" + ] + } + ], + "source": [ + "import gtsam\n", + "import numpy as np\n", + "from gtsam.symbol_shorthand import R # Rotation key\n", + "\n", + "# --- Assumed Known Calibration & Field ---\n", + "# Local magnetic field direction in navigation frame (e.g., NED)\n", + "# Example: From NOAA for specific location/date\n", + "# Field Strength: 48343.4 nT\n", + "# Declination: -4.94 deg -> Angle from North towards West\n", + "# Inclination: 62.78 deg -> Angle below horizontal\n", + "declination_rad = np.deg2rad(-4.94)\n", + "inclination_rad = np.deg2rad(62.78)\n", + "field_strength_nT = 48343.4\n", + "\n", + "# Convert Dec/Inc to NED vector components\n", + "north_comp = np.cos(inclination_rad) * np.cos(declination_rad)\n", + "east_comp = np.cos(inclination_rad) * np.sin(declination_rad)\n", + "down_comp = np.sin(inclination_rad)\n", + "n_direction = gtsam.Unit3(np.array([north_comp, east_comp, down_comp]))\n", + "\n", + "# Assume scale factor converts unit vector to nT (can be absorbed if field strength is used)\n", + "mag_scale = field_strength_nT\n", + "\n", + "# Assume known magnetometer bias in body frame (nT)\n", + "mag_bias_body = gtsam.Point3(10.0, -5.0, 2.0) \n", + "\n", + "# --- Simulation: Generate Measurement ---\n", + "# Assume a ground truth rotation (e.g., 30 deg yaw right in NED)\n", + "truth_nRb = gtsam.Rot3.Yaw(np.deg2rad(30)) \n", + "truth_bRn = truth_nRb.inverse()\n", + "\n", + "# Calculate the expected magnetic field in the body frame (ideal, before bias)\n", + "n_field_vector = mag_scale * n_direction.point3()\n", + "b_field_ideal = truth_bRn.rotate(n_field_vector)\n", + "\n", + "# Calculate the measured value including bias\n", + "b_measured = b_field_ideal + mag_bias_body\n", + "\n", + "# --- Factor Creation ---\n", + "rot_key = R(0)\n", + "\n", + "# Noise model for the magnetometer measurement (nT)\n", + "mag_noise_sigma = 50.0 # nT\n", + "noise_model = gtsam.noiseModel.Isotropic.Sigma(3, mag_noise_sigma)\n", + "\n", + "# Create MagFactor1\n", + "mag_factor = gtsam.MagFactor1(rot_key, b_measured, mag_scale, \n", + " n_direction, mag_bias_body, noise_model)\n", + "\n", + "print(\"Created MagFactor1:\")\n", + "mag_factor.print()\n", + "\n", + "# --- Evaluate Error ---\n", + "# Evaluate at the ground truth rotation (error should be zero)\n", + "error_at_truth = mag_factor.evaluateError(truth_nRb)\n", + "print(\"\\nError at ground truth rotation (should be zero):\", error_at_truth)\n", + "\n", + "# Evaluate at a different rotation (error should be non-zero)\n", + "test_nRb = gtsam.Rot3.Yaw(np.deg2rad(25)) # Slightly off\n", + "error_at_test = mag_factor.evaluateError(test_nRb)\n", + "print(\"Error at test rotation:\", error_at_test)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Important Notes\n", + "- **Coordinate Frames**: Be very careful with navigation frame (NED vs ENU) and body frame conventions. Ensure the `direction` vector and the `Rot3`/`Pose3` variables use the same navigation frame. The `measured` and `bias` are typically in the body frame.\n", + "- **Units**: Ensure consistency between the `scale`, `bias`, `measured` values and the noise model sigma (e.g., all in nanoTesla (nT)).\n", + "- **Calibration**: Accurate knowledge of `scale`, `direction`, and `bias` is crucial for `MagFactor1` and `MagPoseFactor`. If these are unknown, consider using `MagFactor2`/`MagFactor3` or online calibration techniques." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Source\n", + "- [MagFactor.h](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/MagFactor.h)" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "py312", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.12.6" + } + }, + "nbformat": 4, + "nbformat_minor": 2 +} diff --git a/gtsam/navigation/doc/MagPoseFactor.ipynb b/gtsam/navigation/doc/MagPoseFactor.ipynb new file mode 100644 index 0000000000..5ef0b81327 --- /dev/null +++ b/gtsam/navigation/doc/MagPoseFactor.ipynb @@ -0,0 +1,205 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# MagPoseFactor\n", + "\n", + "\"Open\n", + "\n", + "## Overview\n", + "\n", + "The `MagPoseFactor` is a templated factor designed to constrain the orientation component of a `Pose2` or `Pose3` variable using magnetometer readings. It's similar in purpose to `MagFactor1` but operates directly on pose types and explicitly handles an optional transformation between the body frame and the sensor frame.\n", + "\n", + "It assumes the magnetometer calibration parameters (scale, bias) and the local magnetic field direction are known." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": { + "tags": [ + "remove-cell" + ] + }, + "outputs": [], + "source": [ + "%pip install --quiet gtsam-develop" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Measurement Model\n", + "\n", + "The underlying model is the same as for `MagFactor`:\n", + "$$ bM_{measured} = R_{bn} \\cdot (s \\cdot \\hat{d}_n) + b $$ \n", + "However, `MagPoseFactor` allows specifying an optional `body_P_sensor` transform. If provided, the factor internally adjusts the measurement and bias to be consistent with the body frame before calculating the error.\n", + "\n", + "Let:\n", + "- $T_{nb} = (R_{nb}, p_{nb})$ be the `Pose` state.\n", + "- $T_{bs}$ be the pose of the sensor in the body frame (`body_P_sensor`). If not given, $T_{bs}$ is identity.\n", + "- $sM_{measured}$ be the raw measurement in the sensor frame.\n", + "- $sB$ be the bias in the sensor frame.\n", + "- $s$, $\\hat{d}_n$ be the known scale and nav-frame direction.\n", + "\n", + "The factor computes the predicted measurement *in the body frame*:\n", + "$$ bM_{predicted} = R_{bs} [ R_{sn} (s \\cdot \\hat{d}_n) + sB ] $$ \n", + "where $R_{sn} = R_{sb} R_{bn} = R_{bs}^T \\cdot R_{nb}^T$.\n", + "\n", + "Alternatively, and perhaps more clearly, it predicts the field in the sensor frame and compares it to the measurement:\n", + "$$ sM_{predicted} = R_{sn} (s \\cdot \\hat{d}_n) + sB $$ \n", + "$$ e = sM_{measured} - sM_{predicted} $$ \n", + "The implementation transforms the measurement and bias to the body frame first for efficiency if `body_P_sensor` is provided.\n", + "The error $e$ is calculated in the body frame." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Key Functionality / API\n", + "\n", + "- **Template Parameter**: `POSE` (must be `gtsam.Pose2` or `gtsam.Pose3`).\n", + "- **Constructor**: `MagPoseFactor(poseKey, measured, scale, direction, bias, model, body_P_sensor=None)`\n", + " - `poseKey`: Key of the `Pose2` or `Pose3` variable.\n", + " - `measured`: Measured magnetic field vector (`Point2` or `Point3`) **in the sensor frame**.\n", + " - `scale`: Known scale factor.\n", + " - `direction`: Known magnetic field direction (`Point2` or `Point3`) **in the navigation frame**.\n", + " - `bias`: Known bias vector (`Point2` or `Point3`) **in the sensor frame**.\n", + " - `model`: Noise model (2D or 3D).\n", + " - `body_P_sensor`: Optional `Pose2` or `Pose3` describing the sensor's pose relative to the body frame.\n", + "- **`evaluateError(nPb)`**: Calculates the error vector (2D or 3D) based on the current pose estimate `nPb`." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Usage Example (Pose3)\n", + "\n", + "Using a magnetometer to help estimate a `Pose3` orientation, assuming known calibration and a sensor offset." + ] + }, + { + "cell_type": "code", + "execution_count": 1, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Created MagPoseFactor:\n", + " keys = { x0 }\n", + "isotropic dim=3 sigma=50\n", + "local field (nM): [35176.3235; 5025.18908; 35176.3235];\n", + "measured field (bM): [28523.6117; 5040.18908; 40745.2206];\n", + "magnetometer bias: [-10; 15; -5];\n", + "\n", + "Error at ground truth pose (should be zero): [0. 0. 0.]\n", + "Error at test pose: [-3660.19475195 0. 2331.80122523]\n" + ] + } + ], + "source": [ + "import gtsam\n", + "import numpy as np\n", + "from gtsam.symbol_shorthand import X\n", + "\n", + "# --- Assumed Known Calibration & Field (NED Frame) ---\n", + "n_direction_point = gtsam.Point3(0.7, 0.1, 0.7) # Example simplified direction in NED\n", + "mag_scale = 50000.0 # nT\n", + "mag_bias_sensor = gtsam.Point3(15.0, 10.0, -5.0) # Bias in sensor frame (nT)\n", + "\n", + "# --- Sensor Pose --- \n", + "# Assume sensor is rotated 90 deg yaw right w.r.t body\n", + "body_P_sensor = gtsam.Pose3(gtsam.Rot3.Yaw(np.deg2rad(90)), gtsam.Point3(0.1, 0, 0))\n", + "sensor_P_body = body_P_sensor.inverse()\n", + "\n", + "# --- Simulation: Generate Measurement ---\n", + "# Assume a ground truth body pose (e.g., 10 deg pitch up in NED)\n", + "truth_nPb = gtsam.Pose3(gtsam.Rot3.Pitch(np.deg2rad(10)), gtsam.Point3(1,2,3))\n", + "truth_nRb = truth_nPb.rotation()\n", + "truth_bRn = truth_nRb.inverse()\n", + "\n", + "# Calculate field in nav frame\n", + "n_field_vector = mag_scale * (n_direction_point / np.linalg.norm(n_direction_point))\n", + "\n", + "# Calculate field in sensor frame \n", + "truth_nRs = truth_nRb * body_P_sensor.rotation()\n", + "truth_sRn = truth_nRs.inverse()\n", + "s_field_ideal = truth_sRn.rotate(n_field_vector)\n", + "\n", + "# Calculate the measured value including bias (in sensor frame)\n", + "s_measured = s_field_ideal + mag_bias_sensor\n", + "\n", + "# --- Factor Creation ---\n", + "pose_key = X(0)\n", + "\n", + "# Noise model for the magnetometer measurement (nT)\n", + "mag_noise_sigma = 50.0 # nT\n", + "noise_model = gtsam.noiseModel.Isotropic.Sigma(3, mag_noise_sigma)\n", + "\n", + "# Create MagPoseFactor (providing body_P_sensor)\n", + "# Note: measurement and bias are in SENSOR frame when body_P_sensor is specified\n", + "mag_factor = gtsam.MagPoseFactorPose3(pose_key, s_measured, mag_scale, \n", + " n_direction_point, mag_bias_sensor, \n", + " noise_model, body_P_sensor)\n", + "\n", + "print(\"Created MagPoseFactor:\")\n", + "mag_factor.print()\n", + "\n", + "# --- Evaluate Error ---\n", + "# Evaluate at the ground truth pose (error should be zero)\n", + "error_at_truth = mag_factor.evaluateError(truth_nPb)\n", + "print(\"\\nError at ground truth pose (should be zero):\", error_at_truth)\n", + "\n", + "# Evaluate at a different pose (error should be non-zero)\n", + "test_nPb = gtsam.Pose3(gtsam.Rot3.Pitch(np.deg2rad(15)), gtsam.Point3(1,2,3))\n", + "error_at_test = mag_factor.evaluateError(test_nPb)\n", + "print(\"Error at test pose:\", error_at_test)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Important Considerations\n", + "- **Frame Consistency**: Ensure `direction` is in the nav frame, while `measured` and `bias` are in the **sensor frame** when `body_P_sensor` is provided. If `body_P_sensor` is `None`, then `measured` and `bias` are assumed to be in the body frame.\n", + "- **Units**: Maintain consistent units (e.g., nT) for scale, bias, measurement, and noise sigma." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Source\n", + "- [MagPoseFactor.h](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/MagPoseFactor.h)" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "py312", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.12.6" + } + }, + "nbformat": 4, + "nbformat_minor": 2 +} diff --git a/gtsam/navigation/doc/PreintegratedCombinedMeasurements.ipynb b/gtsam/navigation/doc/PreintegratedCombinedMeasurements.ipynb new file mode 100644 index 0000000000..051a9424c8 --- /dev/null +++ b/gtsam/navigation/doc/PreintegratedCombinedMeasurements.ipynb @@ -0,0 +1,188 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# PreintegratedCombinedMeasurements\n", + "\n", + "\"Open\n", + "\n", + "## Overview\n", + "\n", + "The `PreintegratedCombinedMeasurements` class is the preintegration container specifically designed for use with the `CombinedImuFactor`. Like `PreintegratedImuMeasurements`, it accumulates IMU measurements between two time steps ($t_i, t_j$) using a fixed bias estimate (`biasHat_`).\n", + "\n", + "However, it differs significantly in its covariance propagation:\n", + "1. It uses `PreintegrationCombinedParams`, which include bias random walk parameters.\n", + "2. It propagates a larger **15x15 covariance matrix** (`preintMeasCov_`). This matrix captures the uncertainty of the preintegrated $\\Delta R, \\Delta p, \\Delta v$ (9x9 block), the uncertainty of the bias estimate itself (6x6 block), and crucially, the **cross-correlations** between the preintegrated measurements and the bias estimate.\n", + "\n", + "Accounting for these correlations and the bias evolution noise allows the `CombinedImuFactor` to properly model the relationship between the states at $t_i, t_j$ and the biases at $b_i, b_j$." + ] + }, + { + "cell_type": "code", + "execution_count": 1, + "metadata": { + "tags": [ + "remove-cell" + ] + }, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "\u001b[31mERROR: Could not find a version that satisfies the requirement gtsam-develop (from versions: none)\u001b[0m\u001b[31m\n", + "\u001b[0m\u001b[31mERROR: No matching distribution found for gtsam-develop\u001b[0m\u001b[31m\n", + "\u001b[0mNote: you may need to restart the kernel to use updated packages.\n" + ] + } + ], + "source": [ + "%pip install --quiet gtsam-develop" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Mathematical Background\n", + "\n", + "The mean propagation (calculating $\\Delta R, \\Delta p, \\Delta v$) is mathematically identical to that in `PreintegratedImuMeasurements`, using the same underlying implementation (`ManifoldPreintegration` or `TangentPreintegration`).\n", + "\n", + "The key difference lies in the covariance propagation. The update step for the 15x15 covariance matrix $\\Sigma_k \\rightarrow \\Sigma_{k+1}$ incorporates not only the IMU measurement noise (like the standard PIM) but also:\n", + "- The noise from the bias random walk process (defined in `PreintegrationCombinedParams`).\n", + "- The uncertainty of the `biasHat_` used during the integration step (via `biasAccOmegaInit` from the parameters).\n", + "\n", + "This results in a more complex but statistically more accurate propagation of uncertainty, especially when biases are expected to drift significantly or have substantial initial uncertainty. The derivation details can be found in technical reports and papers related to the `CombinedImuFactor` (e.g., Carlone et al., IJRR 2015)." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Key Functionality / API\n", + "\n", + "The API is very similar to `PreintegratedImuMeasurements`:\n", + "\n", + "- **Constructor**: `PreintegratedCombinedMeasurements(params, biasHat)`: Requires shared `PreintegrationCombinedParams`.\n", + "- **`integrateMeasurement(measuredAcc, measuredOmega, dt)`**: Adds a measurement, updating the internal state and the 15x15 covariance.\n", + "- **`resetIntegration()` / `resetIntegrationAndSetBias(newBiasHat)`**: Resets the integration.\n", + "- **Accessors**: `deltaTij()`, `deltaRij()`, `deltaPij()`, `deltaVij()`, `biasHat()`. \n", + "- **`preintMeasCov()`**: Returns the **15x15** covariance matrix.\n", + "- **`predict(state_i, current_bias)`**: Predicts state $X_j$ (same logic as standard PIM, using only the $\\Delta R, p, v$ parts).\n", + "- **`biasCorrectedDelta(current_bias)`**: Returns the 9D tangent-space vector corrected for bias difference (same logic as standard PIM).\n", + "- **Note**: There isn't a direct equivalent of `computeError` within this class, as the full error calculation (including the bias random walk part) is handled by the `CombinedImuFactor` itself." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Usage Example\n", + "\n", + "Create combined parameters, create the object, integrate measurements." + ] + }, + { + "cell_type": "code", + "execution_count": 7, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Total integration time: 0.09999999999999999\n", + "Delta R:\n", + " [[ 0.9999875 -0.00499998 0. ]\n", + " [ 0.00499998 0.9999875 0. ]\n", + " [ 0. 0. 1. ]]\n", + "Delta P: [ 4.99999147e-04 7.12499187e-07 -4.90000000e-02]\n", + "Delta V: [ 9.99996438e-03 2.24999578e-05 -9.80000000e-01]\n", + "Preintegration Covariance (15x15 shape): (15, 15)\n" + ] + } + ], + "source": [ + "from gtsam import PreintegrationCombinedParams, PreintegratedCombinedMeasurements\n", + "from gtsam.imuBias import ConstantBias\n", + "import numpy as np\n", + "\n", + "# 1. Create Combined Parameters (as in PreintegrationCombinedParams example)\n", + "params = PreintegrationCombinedParams.MakeSharedU(9.81)\n", + "accel_noise_sigma = 0.1\n", + "gyro_noise_sigma = 0.01\n", + "params.setAccelerometerCovariance(np.eye(3) * accel_noise_sigma**2)\n", + "params.setGyroscopeCovariance(np.eye(3) * gyro_noise_sigma**2)\n", + "params.setIntegrationCovariance(np.eye(3) * 1e-8)\n", + "bias_acc_rw_sigma = 0.001\n", + "bias_gyro_rw_sigma = 0.0001\n", + "params.setBiasAccCovariance(np.eye(3) * bias_acc_rw_sigma**2)\n", + "params.setBiasOmegaCovariance(np.eye(3) * bias_gyro_rw_sigma**2)\n", + "initial_bias_cov = np.diag(np.full(6, 1e-3)) # Example initial bias uncertainty\n", + "params.setBiasAccOmegaInit(initial_bias_cov)\n", + "\n", + "# 2. Define the bias estimate used for preintegration\n", + "bias_hat = ConstantBias() # Start with zero bias estimate\n", + "\n", + "# 3. Create the PreintegratedCombinedMeasurements object\n", + "pim = PreintegratedCombinedMeasurements(params, bias_hat)\n", + "\n", + "# 4. Integrate measurements\n", + "dt = 0.01 # 100 Hz\n", + "num_measurements = 10\n", + "acc_meas = np.array([0.1, 0.0, -9.8]) \n", + "gyro_meas = np.array([0.0, 0.0, 0.05])\n", + "\n", + "for _ in range(num_measurements):\n", + " pim.integrateMeasurement(acc_meas, gyro_meas, dt)\n", + "\n", + "# 5. Inspect the results\n", + "print(\"Total integration time:\", pim.deltaTij())\n", + "print(\"Delta R:\\n\", pim.deltaRij().matrix())\n", + "print(\"Delta P:\", pim.deltaPij())\n", + "print(\"Delta V:\", pim.deltaVij())\n", + "print(\"Preintegration Covariance (15x15 shape):\", pim.preintMeasCov().shape)\n", + "# print(\"Preintegration Covariance:\\n\", pim.preintMeasCov()) # Might be large" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "This `pim` object is then passed to the `CombinedImuFactor` constructor." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Source\n", + "- [CombinedImuFactor.h](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/CombinedImuFactor.h) (Contains definition)\n", + "- [CombinedImuFactor.cpp](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/CombinedImuFactor.cpp)" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "py312", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.12.6" + } + }, + "nbformat": 4, + "nbformat_minor": 2 +} diff --git a/gtsam/navigation/doc/PreintegratedImuMeasurements.ipynb b/gtsam/navigation/doc/PreintegratedImuMeasurements.ipynb new file mode 100644 index 0000000000..3491b21588 --- /dev/null +++ b/gtsam/navigation/doc/PreintegratedImuMeasurements.ipynb @@ -0,0 +1,210 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# PreintegratedImuMeasurements\n", + "\n", + "\"Open\n", + "\n", + "## Overview\n", + "\n", + "The `PreintegratedImuMeasurements` class (often abbreviated as PIM) is the standard container in GTSAM for accumulating high-rate IMU measurements (accelerometer and gyroscope) between two keyframes or time steps ($t_i$ and $t_j$). It performs *preintegration*, effectively summarizing the relative motion $(\\Delta R_{ij}, \\Delta p_{ij}, \\Delta v_{ij})$ predicted by the IMU measurements, while accounting for sensor noise and a *fixed estimate* of the IMU bias (`biasHat_`).\n", + "\n", + "This preintegrated summary allows IMU information to be incorporated into a factor graph as a single factor (`ImuFactor` or `ImuFactor2`) between states at $t_i$ and $t_j$, avoiding the need to add every single IMU measurement to the graph. It also stores the 9x9 covariance matrix (`preintMeasCov_`) associated with the uncertainty of the preintegrated state change.\n", + "\n", + "It inherits from an underlying implementation (`ManifoldPreintegration` or `TangentPreintegration`, selected at compile time) which defines the specific mathematical approach used for integration." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": { + "tags": [ + "remove-cell" + ] + }, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Note: you may need to restart the kernel to use updated packages.\n" + ] + } + ], + "source": [ + "%pip install --quiet gtsam-develop" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Mathematical Background\n", + "\n", + "The core idea is to integrate the IMU kinematic equations *relative* to the state at time $t_i$, using the bias estimate `biasHat_` held within the class. The exact integration formulas depend on the chosen implementation (manifold or tangent space), but conceptually:\n", + "\n", + "$$ \\Delta R_{ij} = \\prod_{k=i}^{j-1} \\text{Exp}((\\omega_k - b_{g, est}) \\Delta t) $$ \n", + "$$ \\Delta v_{ij} = \\sum_{k=i}^{j-1} \\Delta R_{ik} (a_k - b_{a, est}) \\Delta t $$ \n", + "$$ \\Delta p_{ij} = \\sum_{k=i}^{j-1} [ \\Delta v_{ik} \\Delta t + \\frac{1}{2} \\Delta R_{ik} (a_k - b_{a, est}) \\Delta t^2 ] $$ \n", + "\n", + "where $\\omega_k$ and $a_k$ are the measurements at step k, $b_{g, est}$ and $b_{a, est}$ are the components of `biasHat_`, and $\\Delta R_{ik}$ is the preintegrated rotation from $i$ to $k$.\n", + "\n", + "Crucially, the class also propagates the covariance of these $\\Delta$ terms based on the IMU noise specified in `PreintegrationParams`." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Key Functionality / API\n", + "\n", + "- **Constructor**: `PreintegratedImuMeasurements(params, biasHat)`: Creates an instance, requiring shared `PreintegrationParams` and the initial bias estimate (`biasHat_`) used for integration.\n", + "- **`integrateMeasurement(measuredAcc, measuredOmega, dt)`**: Adds a single IMU measurement pair and time delta, updating the internal preintegrated state and covariance.\n", + "- **`resetIntegration()`**: Resets the accumulated measurements and time to zero, keeping the `biasHat_`.\n", + "- **`resetIntegrationAndSetBias(newBiasHat)`**: Resets integration and updates the internal `biasHat_`.\n", + "- **Accessors**: `deltaTij()`, `deltaRij()`, `deltaPij()`, `deltaVij()`, `preintMeasCov()`, `biasHat()`. These return the accumulated values.\n", + "- **`predict(state_i, current_bias)`**: Predicts the state at time $t_j$ given the state at $t_i$ and the *current best estimate* of the bias (which might differ from `biasHat_`). This function applies the necessary first-order corrections for the change in bias.\n", + "- **`biasCorrectedDelta(current_bias)`**: Returns the 9D tangent-space representation of the preintegrated measurement, corrected for the difference between `current_bias` and `biasHat_`.\n", + "- **`computeError(state_i, state_j, current_bias)`**: Calculates the 9D error between the preintegrated prediction (using `current_bias`) and the actual state change (`state_i` to `state_j`). This is the core calculation used within `ImuFactor::evaluateError`." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Usage Example\n", + "\n", + "Create parameters, create the PIM object with an initial bias estimate, integrate measurements, and potentially use `predict`." + ] + }, + { + "cell_type": "code", + "execution_count": 13, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Total integration time: 0.09999999999999999\n", + "Delta R:\n", + " [[ 9.99992775e-01 -3.10098211e-03 -2.19859941e-03]\n", + " [ 3.09900212e-03 9.99994790e-01 -9.03407707e-04]\n", + " [ 2.20138940e-03 8.96587715e-04 9.99997175e-01]]\n", + "Delta P: [ 0.00047953 0.00106289 -0.04859943]\n", + "Delta V: [ 0.00993257 0.02140713 -0.97198182]\n", + "Bias Hat Used:\n", + "acc = 0.01 -0.01 0.02 gyro = 0.001 0.002 -0.001\n", + "Preintegration Covariance (9x9):\n", + " [[ 0.01 0. -0. -0. 0. 0. -0. 0. 0. ]\n", + " [ 0. 0.01 0. -0. -0. -0. -0. -0. -0. ]\n", + " [-0. 0. 0.01 -0. 0. -0. -0. 0. -0. ]\n", + " [-0. -0. -0. 0. -0. 0. 0.05 -0. 0. ]\n", + " [ 0. -0. 0. -0. 0. 0. -0. 0.05 0. ]\n", + " [ 0. -0. -0. 0. 0. 0. 0. 0. 0.05]\n", + " [-0. -0. -0. 0.05 -0. 0. 1. -0. 0. ]\n", + " [ 0. -0. 0. -0. 0.05 0. -0. 1. 0. ]\n", + " [ 0. -0. -0. 0. 0. 0.05 0. 0. 1. ]]\n", + "\n", + "Predicted State:\n", + "R: [\n", + "\t0.999993, -0.00310098, -0.0021986;\n", + "\t0.003099, 0.999995, -0.000903408;\n", + "\t0.00220139, 0.000896588, 0.999997\n", + "]\n", + "p: 0.000479535 0.00106289 -0.0976494\n", + "v: 0.00993257 0.0214071 -1.95298\n" + ] + } + ], + "source": [ + "from gtsam import PreintegrationParams, PreintegratedImuMeasurements, NavState\n", + "from gtsam.imuBias import ConstantBias\n", + "import numpy as np\n", + "\n", + "# 1. Create Parameters (as in PreintegrationParams example)\n", + "params = PreintegrationParams.MakeSharedU(9.81)\n", + "accel_noise_sigma = 0.1\n", + "gyro_noise_sigma = 0.01\n", + "params.setAccelerometerCovariance(np.eye(3) * accel_noise_sigma**2)\n", + "params.setGyroscopeCovariance(np.eye(3) * gyro_noise_sigma**2)\n", + "params.setIntegrationCovariance(np.eye(3) * 1e-8)\n", + "\n", + "# 2. Define the bias estimate used for preintegration\n", + "initial_bias_acc = np.array([0.01, -0.01, 0.02])\n", + "initial_bias_gyro = np.array([0.001, 0.002, -0.001])\n", + "bias_hat = ConstantBias(initial_bias_acc, initial_bias_gyro)\n", + "\n", + "# 3. Create the PreintegratedImuMeasurements object\n", + "pim = PreintegratedImuMeasurements(params, bias_hat)\n", + "\n", + "# 4. Integrate measurements (example loop)\n", + "dt = 0.01 # 100 Hz\n", + "num_measurements = 10\n", + "acc_meas = np.array([0.1, 0.2, -9.7]) # Example measurement (sensor frame)\n", + "gyro_meas = np.array([0.01, -0.02, 0.03]) # Example measurement (sensor frame)\n", + "\n", + "for _ in range(num_measurements):\n", + " pim.integrateMeasurement(acc_meas, gyro_meas, dt)\n", + "\n", + "# 5. Inspect the results\n", + "print(\"Total integration time:\", pim.deltaTij())\n", + "print(\"Delta R:\\n\", pim.deltaRij().matrix())\n", + "print(\"Delta P:\", pim.deltaPij())\n", + "print(\"Delta V:\", pim.deltaVij())\n", + "print(\"Bias Hat Used:\")\n", + "pim.biasHat().print()\n", + "print(\"Preintegration Covariance (9x9):\\n\", np.round(1000*pim.preintMeasCov(),2))\n", + "\n", + "# 6. Example Prediction (requires initial state)\n", + "initial_state = NavState() # Default: Identity rotation, zero pos/vel\n", + "current_best_bias = bias_hat # Assume bias estimate hasn't changed yet\n", + "predicted_state = pim.predict(initial_state, current_best_bias)\n", + "print(\"\\nPredicted State:\")\n", + "predicted_state.print()" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "The `pim` object is then passed to the `ImuFactor` or `ImuFactor2` constructor." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Source\n", + "- [ImuFactor.h](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/ImuFactor.h) (Contains PIM definition)\n", + "- [ImuFactor.cpp](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/ImuFactor.cpp)\n", + "- [ManifoldPreintegration.h/.cpp](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/ManifoldPreintegration.h) (One possible implementation)\n", + "- [TangentPreintegration.h/.cpp](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/TangentPreintegration.h) (Another possible implementation)" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "py312", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.12.6" + } + }, + "nbformat": 4, + "nbformat_minor": 2 +} diff --git a/gtsam/navigation/doc/PreintegratedRotation.ipynb b/gtsam/navigation/doc/PreintegratedRotation.ipynb new file mode 100644 index 0000000000..547e0fcf07 --- /dev/null +++ b/gtsam/navigation/doc/PreintegratedRotation.ipynb @@ -0,0 +1,9073 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# PreintegratedRotation" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "vscode": { + "languageId": "plaintext" + } + }, + "source": [ + "\"Open" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": { + "tags": [ + "remove-cell" + ] + }, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Note: you may need to restart the kernel to use updated packages.\n" + ] + } + ], + "source": [ + "%pip install --quiet gtsam-develop plotly" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "\n", + "## Overview\n", + "`PreintegratedRotation` is a class within GTSAM used primarily for pre-integrating rotation rate measurements in factor graph-based estimation problems. It facilitates efficient handling of rotation rate measurements, typically from gyroscopes in inertial measurement units (IMU). By preintegrating rotations between two time instances, it enables effective and accurate state estimation without repeatedly recalculating rotations from individual measurements.\n", + "\n", + "This is the base class for `PreintegratedAhrsMeasurements` defined in [AHRSFactor.h](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/AHRSFactor.h) and used in the `AHRSFactor`. The `IMUFactor` has its own integration classes, derived from [PreintegrationBase](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/PreintegrationBase.h).\n", + "\n", + "## Mathematical Background\n", + "The class employs exponential maps and logarithms in the Lie group $SO(3)$. The rotation integration leverages incremental updates via rotation matrices and their tangent spaces, utilizing efficient methods from Lie group theory:\n", + "\n", + "- **Exponential map**: Converts a rotation vector $\\omega$ into a rotation matrix using:\n", + " $$\n", + " R = \\exp([\\omega]_\\times)\n", + " $$\n", + "- **Logarithmic map**: Converts rotation matrices back into rotation vectors:\n", + " $$\n", + " \\omega = \\log(R)\n", + " $$\n", + "\n", + "Here, $[\\omega]_\\times$ denotes the skew-symmetric matrix associated with vector $\\omega$." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "The preintegration process updates rotations incrementally according to:\n", + "$$\n", + "R_{k+1} = R_k \\exp\\left(\\left[\\omega_{\\text{bias-corrected}}\\Delta t\\right]_\\times\\right)\n", + "$$\n", + "\n", + "Bias correction is performed as:\n", + "$$\n", + "\\omega_{\\text{bias-corrected}} = \\omega_{\\text{measured}} - b_\\omega\n", + "$$" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## PreintegratedRotation Parameters\n", + "\n", + "The `PreintegratedRotationParams` class configures the gyroscope preintegration:\n", + "\n", + "| Parameter | Description |\n", + "|-----------|-------------|\n", + "| `gyroscopeCovariance` | 3×3 continuous-time noise covariance matrix of gyroscope measurements (units: rad²/s²/Hz) |\n", + "| `omegaCoriolis` | Optional Coriolis acceleration compensation vector (for earth rotation effects) |\n", + "| `body_P_sensor` | Optional pose transformation between the IMU sensor frame and body frame |\n", + "\n", + "The covariance matrix represents the uncertainty in angular velocity measurements, which propagates into orientation uncertainty during integration. When the IMU is not located at the center of the body frame, the optional body-to-sensor transformation allows for proper handling of lever-arm effects.\n", + "\n", + "In C++ you typically create a `shared_ptr` to a single object and pass it to all `PreintegratedRotation` objects. In python this is automatic, as all objects are encapsulated in shared pointers:" + ] + }, + { + "cell_type": "code", + "execution_count": 2, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "\n", + "gyroscopeCovariance:\n", + "1 0 0\n", + "0 1 0\n", + "0 0 1\n", + "\n" + ] + } + ], + "source": [ + "from gtsam import PreintegratedRotationParams\n", + "params = PreintegratedRotationParams()\n", + "print(params)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "You can (and should) configure using your gyroscope's noise covariance matrix and the optional Coriolis acceleration compensation vector:\n", + "\n", + "### Setters\n", + "- `setGyroscopeCovariance`: Sets the 3×3 continuous-time noise covariance matrix for gyroscope measurements.\n", + "- `setOmegaCoriolis`: Sets an optional Coriolis acceleration compensation vector.\n", + "- `setBodyPSensor`: Sets an optional pose transformation between the body frame and the sensor frame.\n", + "\n", + "### Getters\n", + "- `getGyroscopeCovariance`: Returns the gyroscope covariance matrix.\n", + "- `getOmegaCoriolis`: Returns the optional Coriolis acceleration vector.\n", + "- `getBodyPSensor`: Returns the optional body-to-sensor pose transformation." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Core Methods\n", + "\n", + "Typically you use these methods between timesteps $t_i$ and $t_j$:\n", + "- `PreintegratedRotation`: Constructs the object, needs a shared pointer to parameters.\n", + "- `resetIntegration`: Clears the integrated rotation, typically used after updating state estimates or correcting biases.\n", + "- `integrateGyroMeasurement`: Integrates incremental rotation measurements, given angular velocities and integration intervals.\n", + "\n", + "You can then query:\n", + "- `deltaTij`: Accumulated time interval.\n", + "- `deltaRij`: The integrated rotation between the two timestamps as element of $SO(3)$.\n", + "- `biascorrectedDeltaRij`: A *bias corrected* version of the integrated rotation, given an increment on the estimated bias." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Internals\n", + "- `delRdelBiasOmega`: Returns Jacobian of integrated rotation with respect to gyroscope bias. This is useful for updating bias estimates during optimization." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Example" + ] + }, + { + "cell_type": "code", + "execution_count": 3, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + " deltaTij [1.5]\n", + " deltaRij.ypr = ( -0.82321 -0.0142842 0.0228577)\n", + "\n" + ] + } + ], + "source": [ + "from gtsam import PreintegratedRotation, Point3\n", + "import numpy as np\n", + "\n", + "# Create a PreintegratedRotation object using the params\n", + "preintegrated_rotation = PreintegratedRotation(params)\n", + "\n", + "# Add random omega measurements\n", + "biasHat = np.zeros(3) # Assuming no bias for simplicity\n", + "np.random.seed(42) # For reproducibility\n", + "rotations = [] # List to record integrated rotations\n", + "for _ in range(15): # Add 15 random measurements, biased to move around z-axis\n", + " omega = Point3(0,0,-0.5) + 0.1*np.random.randn(3) # Random angular velocity vector\n", + " preintegrated_rotation.integrateGyroMeasurement(omega, biasHat, deltaT=0.1)\n", + " rotations.append(preintegrated_rotation.deltaRij())\n", + "\n", + "print(preintegrated_rotation)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "We can show the evolution of the integrated rotation by showing how it transforms the point (1,0,0) on the sphere." + ] + }, + { + "cell_type": "code", + "execution_count": 4, + "metadata": {}, + "outputs": [ + { + "data": { + "application/vnd.plotly.v1+json": { + "config": { + "plotlyServerURL": "https://plot.ly" + }, + "data": [ + { + "colorscale": [ + [ + 0, + "#440154" + ], + [ + 0.1111111111111111, + "#482878" + ], + [ + 0.2222222222222222, + "#3e4989" + ], + [ + 0.3333333333333333, + "#31688e" + ], + [ + 0.4444444444444444, + "#26828e" + ], + [ + 0.5555555555555556, + "#1f9e89" + ], + [ + 0.6666666666666666, + "#35b779" + ], + [ + 0.7777777777777778, + "#6ece58" + ], + [ + 0.8888888888888888, + "#b5de2b" + ], + [ + 1, + "#fde725" + ] + ], + "opacity": 0.3, + "showscale": false, + "type": "surface", + "x": [ + [ + 0, + 0.06407021998071291, + 0.127877161684506, + 0.1911586287013723, + 0.25365458390950735, + 0.31510821802362066, + 0.3752670048793741, + 0.4338837391175581, + 0.49071755200393785, + 0.5455349012105486, + 0.5981105304912159, + 0.6482283953077884, + 0.6956825506034864, + 0.7402779970753155, + 0.7818314824680298, + 0.8201722545969559, + 0.8551427630053461, + 0.886599306373, + 0.9144126230158124, + 0.9384684220497603, + 0.9586678530366606, + 0.9749279121818236, + 0.9871817834144502, + 0.9953791129491982, + 0.9994862162006879, + 0.9994862162006879, + 0.9953791129491982, + 0.9871817834144502, + 0.9749279121818236, + 0.9586678530366607, + 0.9384684220497604, + 0.9144126230158126, + 0.8865993063730001, + 0.8551427630053462, + 0.820172254596956, + 0.7818314824680299, + 0.7402779970753157, + 0.6956825506034865, + 0.6482283953077888, + 0.5981105304912161, + 0.545534901210549, + 0.49071755200393813, + 0.43388373911755823, + 0.3752670048793745, + 0.3151082180236209, + 0.2536545839095078, + 0.19115862870137254, + 0.1278771616845065, + 0.06407021998071323, + 1.2246467991473532e-16 + ], + [ + 0, + 0.06354420436032968, + 0.12682729195475367, + 0.1895892190021668, + 0.25157208328194003, + 0.3125211839094652, + 0.3721860679567226, + 0.4303215596170847, + 0.48668876768529507, + 0.5410560672126732, + 0.5932000513037121, + 0.6429064491429322, + 0.689971006479623, + 0.7342003249523721, + 0.7754126568044163, + 0.8134386517241579, + 0.8481220527419211, + 0.8793203383233581, + 0.9069053080210033, + 0.9307636092774119, + 0.9507972032151313, + 0.9669237674994794, + 0.9790770346186743, + 0.9872070641912558, + 0.9912804481818243, + 0.9912804481818243, + 0.9872070641912558, + 0.9790770346186743, + 0.9669237674994794, + 0.9507972032151314, + 0.930763609277412, + 0.9069053080210036, + 0.8793203383233582, + 0.8481220527419212, + 0.813438651724158, + 0.7754126568044164, + 0.7342003249523723, + 0.6899710064796231, + 0.6429064491429325, + 0.5932000513037123, + 0.5410560672126736, + 0.48668876768529534, + 0.4303215596170848, + 0.372186067956723, + 0.3125211839094654, + 0.2515720832819405, + 0.18958921900216705, + 0.12682729195475417, + 0.06354420436033, + 1.2145924658549477e-16 + ], + [ + 0, + 0.06197479466112418, + 0.12369492159743405, + 0.1849067595684226, + 0.24535877600196893, + 0.30480256059563077, + 0.36299384608786095, + 0.4196935120045804, + 0.47466856725649686, + 0.5276931075494681, + 0.5785492436737019, + 0.6270279968572571, + 0.672930157504642, + 0.7160671037917743, + 0.7562615767535142, + 0.7933484086787744, + 0.8271752018200734, + 0.8576029546285695, + 0.8845066329412399, + 0.907775683773077, + 0.927314489603017, + 0.9430427612868441, + 0.9548958679825054, + 0.9628251027321053, + 0.9667978826092422, + 0.9667978826092422, + 0.9628251027321053, + 0.9548958679825054, + 0.9430427612868441, + 0.9273144896030171, + 0.9077756837730772, + 0.8845066329412401, + 0.8576029546285696, + 0.8271752018200735, + 0.7933484086787745, + 0.7562615767535144, + 0.7160671037917745, + 0.6729301575046421, + 0.6270279968572574, + 0.5785492436737021, + 0.5276931075494685, + 0.47466856725649714, + 0.4196935120045805, + 0.36299384608786134, + 0.304802560595631, + 0.24535877600196934, + 0.18490675956842284, + 0.12369492159743453, + 0.061974794661124495, + 1.1845945578524248e-16 + ], + [ + 0, + 0.059387760546968704, + 0.11853148404721524, + 0.17718813625458818, + 0.23511668440335493, + 0.2920790876635377, + 0.34784127530174314, + 0.4021741085280142, + 0.45485432207626786, + 0.505665441649164, + 0.5543986734574267, + 0.6008537621983103, + 0.6448398139475933, + 0.6861760805836592, + 0.7246927025202993, + 0.760231406696186, + 0.7926461569528329, + 0.8218037541284933, + 0.8475843834020871, + 0.8698821066380016, + 0.888605297708614, + 0.903677019005703, + 0.9150353375935849, + 0.9226335797048304, + 0.9264405225327864, + 0.9264405225327864, + 0.9226335797048304, + 0.9150353375935849, + 0.903677019005703, + 0.8886052977086141, + 0.8698821066380017, + 0.8475843834020872, + 0.8218037541284934, + 0.792646156952833, + 0.7602314066961862, + 0.7246927025202994, + 0.6861760805836594, + 0.6448398139475934, + 0.6008537621983107, + 0.5543986734574269, + 0.5056654416491644, + 0.45485432207626814, + 0.40217410852801433, + 0.3478412753017435, + 0.2920790876635379, + 0.23511668440335534, + 0.1771881362545884, + 0.1185314840472157, + 0.059387760546969, + 1.1351456399598494e-16 + ], + [ + 0, + 0.055825581046495265, + 0.11142176280592091, + 0.16656008864208385, + 0.2210139833469895, + 0.27455968418697163, + 0.3269771603917619, + 0.3780510173081215, + 0.4275713815026731, + 0.47533476317685647, + 0.5211448923501592, + 0.5648135253755664, + 0.606161218473084, + 0.6450180651027222, + 0.6812243941469122, + 0.7146314260333781, + 0.7451018841023128, + 0.7725105587056182, + 0.7967448217202071, + 0.8177050893611193, + 0.835305231392655, + 0.8494729250559881, + 0.8601499522588952, + 0.8672924388063843, + 0.8708710346891732, + 0.8708710346891732, + 0.8672924388063843, + 0.8601499522588952, + 0.8494729250559881, + 0.8353052313926551, + 0.8177050893611194, + 0.7967448217202072, + 0.7725105587056184, + 0.7451018841023129, + 0.7146314260333783, + 0.6812243941469123, + 0.6450180651027223, + 0.6061612184730841, + 0.5648135253755667, + 0.5211448923501594, + 0.47533476317685686, + 0.4275713815026733, + 0.3780510173081216, + 0.3269771603917622, + 0.2745596841869718, + 0.22101398334698988, + 0.16656008864208408, + 0.11142176280592135, + 0.05582558104649554, + 1.0670576620419285e-16 + ], + [ + 0, + 0.05134674704861986, + 0.10248249929977425, + 0.15319712897887872, + 0.20328223879432783, + 0.2525320182866676, + 0.30074408954791937, + 0.34772033883581394, + 0.39326773066565324, + 0.4371991010345237, + 0.4793339265183303, + 0.5194990660812683, + 0.5575294725494782, + 0.5932688708252852, + 0.6265704000550977, + 0.6572972171121543, + 0.6853230589142861, + 0.7105327612660042, + 0.7328227320928807, + 0.7521013771236047, + 0.7682894762704882, + 0.7813205091618005, + 0.7911409284882434, + 0.7977103800403309, + 0.8010018685324929, + 0.8010018685324929, + 0.7977103800403309, + 0.7911409284882434, + 0.7813205091618005, + 0.7682894762704883, + 0.7521013771236047, + 0.732822732092881, + 0.7105327612660042, + 0.6853230589142862, + 0.6572972171121544, + 0.6265704000550978, + 0.5932688708252855, + 0.5575294725494782, + 0.5194990660812686, + 0.47933392651833046, + 0.4371991010345241, + 0.39326773066565346, + 0.347720338835814, + 0.3007440895479197, + 0.25253201828666777, + 0.2032822387943282, + 0.1531971289788789, + 0.10248249929977465, + 0.05134674704862012, + 9.814486268136805e-17 + ], + [ + 0, + 0.04602480088376357, + 0.09186047598840694, + 0.13731867669320363, + 0.18221260550070414, + 0.226357783627721, + 0.2695728090682192, + 0.3116801020130699, + 0.35250663456357667, + 0.3918846417402257, + 0.4296523108649721, + 0.46565444648424276, + 0.499743108100344, + 0.5317782180907005, + 0.5616281373168522, + 0.5891702060579113, + 0.6142912480456656, + 0.6368880355301407, + 0.6568677134645673, + 0.6741481810666854, + 0.6886584291884691, + 0.7003388321079476, + 0.709141392544086, + 0.7150299388879092, + 0.7179802738394011, + 0.7179802738394011, + 0.7150299388879092, + 0.709141392544086, + 0.7003388321079476, + 0.6886584291884692, + 0.6741481810666855, + 0.6568677134645675, + 0.6368880355301408, + 0.6142912480456656, + 0.5891702060579114, + 0.5616281373168522, + 0.5317782180907006, + 0.4997431081003441, + 0.465654446484243, + 0.42965231086497224, + 0.39188464174022597, + 0.35250663456357684, + 0.31168010201307, + 0.26957280906821945, + 0.22635778362772116, + 0.18221260550070445, + 0.1373186766932038, + 0.09186047598840728, + 0.046024800883763796, + 8.797242322667637e-17 + ], + [ + 0, + 0.03994712876082017, + 0.07973010620092988, + 0.11918545553260583, + 0.15815104626229826, + 0.19646676041960587, + 0.23397515051636136, + 0.2705220865321328, + 0.305957389267538, + 0.34013544746278873, + 0.3729158161455902, + 0.40416379374965783, + 0.43375097563234616, + 0.4615557817168686, + 0.48746395609091187, + 0.5113690365086868, + 0.5331727918671332, + 0.5527856258585924, + 0.5701269451412537, + 0.5851254905144835, + 0.5977196297381651, + 0.607857610792794, + 0.6154977745396268, + 0.6206087259070177, + 0.6231694628995023, + 0.6231694628995023, + 0.6206087259070177, + 0.6154977745396268, + 0.607857610792794, + 0.5977196297381651, + 0.5851254905144835, + 0.5701269451412538, + 0.5527856258585925, + 0.5331727918671333, + 0.5113690365086869, + 0.4874639560909119, + 0.4615557817168688, + 0.4337509756323462, + 0.40416379374965805, + 0.3729158161455904, + 0.340135447462789, + 0.3059573892675382, + 0.27052208653213283, + 0.2339751505163616, + 0.196466760419606, + 0.15815104626229853, + 0.119185455532606, + 0.0797301062009302, + 0.03994712876082036, + 7.635547901473156e-17 + ], + [ + 0, + 0.033213525888022094, + 0.06629057027389135, + 0.09909521248722244, + 0.13149265121658713, + 0.16334975843701763, + 0.19453562646161712, + 0.22492210586932482, + 0.254384332098375, + 0.2828012385415649, + 0.31005605403491204, + 0.3360367826954148, + 0.3606366641361582, + 0.3837546121676442, + 0.4052956301826273, + 0.4251712015175499, + 0.4432996531865001, + 0.4596064914930296, + 0.474024708140731, + 0.48649505558470113, + 0.4969662904924116, + 0.5053953843135537, + 0.5117477000935814, + 0.5159971348043871, + 0.5181262266072434, + 0.5181262266072434, + 0.5159971348043871, + 0.5117477000935814, + 0.5053953843135537, + 0.49696629049241164, + 0.4864950555847012, + 0.4740247081407311, + 0.4596064914930297, + 0.44329965318650016, + 0.42517120151754995, + 0.4052956301826274, + 0.38375461216764434, + 0.36063666413615825, + 0.336036782695415, + 0.31005605403491215, + 0.28280123854156514, + 0.2543843320983752, + 0.22492210586932487, + 0.19453562646161732, + 0.16334975843701774, + 0.13149265121658735, + 0.09909521248722258, + 0.06629057027389161, + 0.03321352588802226, + 6.348477994832602e-17 + ], + [ + 0, + 0.025934557838380178, + 0.051762545015657246, + 0.07737782879243389, + 0.1026751504732102, + 0.12755055793694137, + 0.15190183279860078, + 0.17562891044644982, + 0.1986342912289912, + 0.22082344110195082, + 0.24210518008894294, + 0.26239205695955137, + 0.28160070858519326, + 0.29965220249609603, + 0.3164723612317465, + 0.3319920671519871, + 0.3461475464562251, + 0.3588806312436586, + 0.3701389985376579, + 0.3798763852920998, + 0.3880527784961474, + 0.39463457959629433, + 0.39959474256002825, + 0.4029128850137795, + 0.4045753719984663, + 0.4045753719984663, + 0.4029128850137795, + 0.39959474256002825, + 0.39463457959629433, + 0.3880527784961474, + 0.3798763852920998, + 0.37013899853765797, + 0.3588806312436586, + 0.3461475464562251, + 0.33199206715198715, + 0.31647236123174655, + 0.2996522024960961, + 0.2816007085851933, + 0.26239205695955153, + 0.24210518008894302, + 0.22082344110195098, + 0.19863429122899132, + 0.17562891044644985, + 0.15190183279860095, + 0.12755055793694148, + 0.10267515047321037, + 0.07737782879243399, + 0.05176254501565745, + 0.025934557838380307, + 4.957166255030046e-17 + ], + [ + 0, + 0.018229745066031613, + 0.03638458019931885, + 0.05438990328809911, + 0.07217172659767089, + 0.08965698080186606, + 0.10677381524058427, + 0.1234518931695674, + 0.1396226807891687, + 0.15521972886443622, + 0.17017894577927234, + 0.18443886090263206, + 0.19794087718453124, + 0.21062951194389418, + 0.22245262485879105, + 0.23336163222220474, + 0.24331170658290424, + 0.25226196095105724, + 0.26017561681164136, + 0.2670201552552517, + 0.2727674506052745, + 0.2773938859923256, + 0.2808804504010323, + 0.28321281679037347, + 0.2843814009665643, + 0.2843814009665643, + 0.28321281679037347, + 0.2808804504010323, + 0.2773938859923256, + 0.2727674506052746, + 0.26702015525525175, + 0.2601756168116414, + 0.25226196095105724, + 0.24331170658290427, + 0.23336163222220477, + 0.22245262485879108, + 0.21062951194389423, + 0.19794087718453127, + 0.18443886090263215, + 0.1701789457792724, + 0.15521972886443633, + 0.13962268078916878, + 0.12345189316956742, + 0.10677381524058438, + 0.08965698080186613, + 0.07217172659767103, + 0.05438990328809919, + 0.03638458019931899, + 0.018229745066031703, + 3.484457982368154e-17 + ], + [ + 0, + 0.010225600383687304, + 0.020409181582013634, + 0.03050889707546375, + 0.04048324496669288, + 0.05029123852072506, + 0.059892574588238746, + 0.06924779921985241, + 0.07831846979086533, + 0.08706731297024851, + 0.09545837788475688, + 0.10345718384877894, + 0.11103086205287002, + 0.11814829062874063, + 0.1247802225356889, + 0.13089940574296421, + 0.1364806952142072, + 0.14150115623379772, + 0.1459401586505207, + 0.14977946165128286, + 0.15300328871652613, + 0.1555983924493307, + 0.15755410901181044, + 0.15886240194511025, + 0.15951789519293927, + 0.15951789519293927, + 0.15886240194511025, + 0.15755410901181044, + 0.1555983924493307, + 0.15300328871652616, + 0.1497794616512829, + 0.14594015865052073, + 0.14150115623379772, + 0.13648069521420722, + 0.13089940574296424, + 0.12478022253568892, + 0.11814829062874067, + 0.11103086205287004, + 0.103457183848779, + 0.0954583778847569, + 0.08706731297024858, + 0.07831846979086539, + 0.06924779921985243, + 0.05989257458823881, + 0.0502912385207251, + 0.04048324496669295, + 0.030508897075463788, + 0.020409181582013713, + 0.010225600383687354, + 1.9545350059688153e-17 + ], + [ + 0, + 0.002053551625744841, + 0.004098664767374055, + 0.006126935616313293, + 0.008130029572581531, + 0.010099715493450158, + 0.012027899516974019, + 0.013906658321406279, + 0.015728271683827025, + 0.017485254204195225, + 0.019170386064463127, + 0.020776742696357237, + 0.02229772323591468, + 0.023727077647849114, + 0.02505893240828634, + 0.02628781464033378, + 0.02740867460330552, + 0.02841690644319002, + 0.029308367119092134, + 0.03007939342787687, + 0.0307268170570568, + 0.0312479776040677, + 0.0316407335084333, + 0.0319034708518967, + 0.03203510999035662, + 0.03203510999035662, + 0.0319034708518967, + 0.0316407335084333, + 0.0312479776040677, + 0.030726817057056804, + 0.030079393427876872, + 0.02930836711909214, + 0.028416906443190025, + 0.027408674603305525, + 0.026287814640333782, + 0.025058932408286348, + 0.02372707764784912, + 0.022297723235914682, + 0.020776742696357247, + 0.019170386064463134, + 0.01748525420419524, + 0.01572827168382703, + 0.013906658321406282, + 0.012027899516974031, + 0.010099715493450165, + 0.008130029572581545, + 0.006126935616313302, + 0.004098664767374071, + 0.0020535516257448516, + 3.92518618807508e-18 + ], + [ + 0, + -0.006152216393118851, + -0.0122791520094321, + -0.018355629956268747, + -0.024356680682344804, + -0.030257644583005488, + -0.036034273331830194, + -0.04166282952220702, + -0.047120184209428186, + -0.052383911952485, + -0.05743238296501517, + -0.062244851996734595, + -0.06680154358012054, + -0.07108373329204962, + -0.07507382469646869, + -0.07875542165192508, + -0.08211339568682872, + -0.08513394816558706, + -0.08780466699015839, + -0.09011457760402515, + -0.09205418808900069, + -0.09361552816955712, + -0.09479218196439701, + -0.09557931435068594, + -0.09597369083260925, + -0.09597369083260925, + -0.09557931435068594, + -0.09479218196439701, + -0.09361552816955712, + -0.0920541880890007, + -0.09011457760402516, + -0.0878046669901584, + -0.08513394816558707, + -0.08211339568682874, + -0.07875542165192509, + -0.0750738246964687, + -0.07108373329204964, + -0.06680154358012055, + -0.06224485199673463, + -0.05743238296501519, + -0.05238391195248504, + -0.04712018420942821, + -0.04166282952220703, + -0.03603427333183023, + -0.030257644583005512, + -0.024356680682344846, + -0.01835562995626877, + -0.012279152009432148, + -0.006152216393118882, + -1.1759429132228557e-17 + ], + [ + 0, + -0.014256965188894749, + -0.02845534544971889, + -0.04253679659243768, + -0.05644345491384388, + -0.07011817497192599, + -0.08350476440874709, + -0.09654821485689687, + -0.1091949279806725, + -0.12139293572313695, + -0.13309211385401198, + -0.144244387940892, + -0.1548039308973987, + -0.16472735129650895, + -0.17397387167523579, + -0.18250549609797065, + -0.19028716628993278, + -0.19728690569914042, + -0.20347595089492174, + -0.20882886976302126, + -0.2133236660116124, + -0.216941869558779, + -0.21966861243004346, + -0.22149268985406328, + -0.2224066063054398, + -0.2224066063054398, + -0.22149268985406328, + -0.21966861243004346, + -0.216941869558779, + -0.21332366601161243, + -0.20882886976302129, + -0.2034759508949218, + -0.19728690569914045, + -0.1902871662899328, + -0.18250549609797068, + -0.1739738716752358, + -0.16472735129650898, + -0.15480393089739872, + -0.1442443879408921, + -0.13309211385401204, + -0.12139293572313704, + -0.10919492798067257, + -0.0965482148568969, + -0.08350476440874718, + -0.07011817497192604, + -0.05644345491384398, + -0.04253679659243773, + -0.028455345449719, + -0.01425696518889482, + -2.7250954951287993e-17 + ], + [ + 0, + -0.022127615010424057, + -0.04416430290441175, + -0.06601951020455195, + -0.08760342917612111, + -0.10882736686632898, + -0.1296041095626861, + -0.14984828117285584, + -0.1694766940533308, + -0.18840869084530373, + -0.20656647591305585, + -0.22387543502291118, + -0.24026444194912708, + -0.25566615074681287, + -0.2700172724908626, + -0.28325883534372415, + -0.2953364268833286, + -0.3062004176954046, + -0.31580616531138656, + -0.32411419765389404, + -0.3310903752359643, + -0.3367060314475272, + -0.340938090352655, + -0.34376916151353265, + -0.3451876114514973, + -0.3451876114514973, + -0.34376916151353265, + -0.340938090352655, + -0.3367060314475272, + -0.33109037523596435, + -0.3241141976538941, + -0.31580616531138667, + -0.3062004176954047, + -0.2953364268833286, + -0.28325883534372415, + -0.27001727249086266, + -0.2556661507468129, + -0.2402644419491271, + -0.2238754350229113, + -0.20656647591305594, + -0.18840869084530387, + -0.16947669405333088, + -0.14984828117285587, + -0.12960410956268623, + -0.10882736686632904, + -0.08760342917612127, + -0.06601951020455205, + -0.04416430290441192, + -0.022127615010424168, + -4.2295020843440566e-17 + ], + [ + 0, + -0.02963493000523314, + -0.059148083726402234, + -0.08841818528431536, + -0.11732495755325396, + -0.14574961640548179, + -0.17357535882070482, + -0.20068784285473587, + -0.22697565749506948, + -0.25233078047263, + -0.27664902214844583, + -0.2998304536512246, + -0.32177981750651985, + -0.3424069190701263, + -0.36162699715721996, + -0.3793610723442469, + -0.3955362715123164, + -0.41008612729847777, + -0.42295085122437115, + -0.4340775793799106, + -0.44342058965242914, + -0.4509414896086477, + -0.45660937425741815, + -0.4604009530449612, + -0.46230064556074785, + -0.46230064556074785, + -0.4604009530449612, + -0.45660937425741815, + -0.4509414896086477, + -0.4434205896524292, + -0.4340775793799106, + -0.42295085122437126, + -0.4100861272984778, + -0.39553627151231646, + -0.37936107234424693, + -0.36162699715722, + -0.34240691907012644, + -0.3217798175065199, + -0.2998304536512248, + -0.27664902214844594, + -0.25233078047263025, + -0.22697565749506962, + -0.20068784285473593, + -0.173575358820705, + -0.1457496164054819, + -0.11732495755325417, + -0.08841818528431548, + -0.05914808372640246, + -0.029634930005233286, + -5.664460366265281e-17 + ], + [ + 0, + -0.03665564026865816, + -0.07316065464884222, + -0.10936503620616299, + -0.14512001337098593, + -0.18027866127272224, + -0.21469650548563737, + -0.24823211570525602, + -0.2807476869158199, + -0.3121096056606567, + -0.3421889990885334, + -0.3708622645198453, + -0.39801157735653875, + -0.42352537524865863, + -0.4472988165279737, + -0.46923421102488, + -0.4892414214982625, + -0.5072382340287528, + -0.5231506958533589, + -0.5369134192532314, + -0.5484698502458251, + -0.5577725009773447, + -0.5647831448605221, + -0.5694729736558629, + -0.5718227158508821, + -0.5718227158508821, + -0.5694729736558629, + -0.5647831448605221, + -0.5577725009773447, + -0.5484698502458251, + -0.5369134192532314, + -0.5231506958533592, + -0.5072382340287529, + -0.48924142149826255, + -0.4692342110248801, + -0.44729881652797376, + -0.42352537524865874, + -0.3980115773565388, + -0.3708622645198455, + -0.34218899908853356, + -0.312109605660657, + -0.2807476869158201, + -0.2482321157052561, + -0.2146965054856376, + -0.18027866127272238, + -0.14512001337098618, + -0.10936503620616314, + -0.07316065464884251, + -0.03665564026865834, + -7.00640836557489e-17 + ], + [ + 0, + -0.04307446593227168, + -0.0859719296445837, + -0.12851611625706505, + -0.17053220258122562, + -0.2118475355059372, + -0.252292341466101, + -0.29170042407864316, + -0.3299098470791013, + -0.3667635997524712, + -0.4021102421239128, + -0.43580452725809077, + -0.4677079981099873, + -0.4976895564745989, + -0.5256260016975813, + -0.5514025369331647, + -0.5749132408690162, + -0.5960615029796337, + -0.6147604205197164, + -0.6309331556261868, + -0.6445132510614519, + -0.6554449033004467, + -0.663683191839289, + -0.6691942637832655, + -0.6719554729556372, + -0.6719554729556372, + -0.6691942637832655, + -0.663683191839289, + -0.6554449033004467, + -0.644513251061452, + -0.6309331556261869, + -0.6147604205197165, + -0.5960615029796337, + -0.5749132408690163, + -0.5514025369331647, + -0.5256260016975814, + -0.49768955647459906, + -0.46770799810998737, + -0.43580452725809105, + -0.4021102421239129, + -0.3667635997524715, + -0.32990984707910154, + -0.2917004240786432, + -0.2522923414661013, + -0.21184753550593735, + -0.17053220258122592, + -0.12851611625706522, + -0.08597192964458404, + -0.0430744659322719, + -8.233311333224372e-17 + ], + [ + 0, + -0.04878601005613519, + -0.0973715479323834, + -0.14555696523204592, + -0.1931442577396988, + -0.23993787906298591, + -0.28574554417468956, + -0.33037901955315246, + -0.3736548966741939, + -0.4153953456760771, + -0.4554288461005551, + -0.4935908917072249, + -0.5297246664649554, + -0.5636816889425967, + -0.59532242245103, + -0.6245168484293526, + -0.6511450007190351, + -0.6750974585305987, + -0.6962757960771091, + -0.7145929870268489, + -0.7299737621131803, + -0.7423549184321078, + -0.7516855791565671, + -0.757927402600221, + -0.7610547397716725, + -0.7610547397716725, + -0.757927402600221, + -0.7516855791565671, + -0.7423549184321078, + -0.7299737621131804, + -0.7145929870268489, + -0.6962757960771092, + -0.6750974585305987, + -0.6511450007190352, + -0.6245168484293526, + -0.59532242245103, + -0.5636816889425968, + -0.5297246664649555, + -0.4935908917072252, + -0.4554288461005553, + -0.41539534567607744, + -0.3736548966741941, + -0.3303790195531525, + -0.28574554417468984, + -0.23993787906298608, + -0.19314425773969912, + -0.1455569652320461, + -0.09737154793238377, + -0.048786010056135434, + -9.32502355640449e-17 + ], + [ + 0, + -0.05369648924363901, + -0.1071723280951151, + -0.16020777286205606, + -0.2125848895258473, + -0.2640884492792611, + -0.31450681294779165, + -0.36363280066042, + -0.4112645431961434, + -0.457206311507906, + -0.5012693210152365, + -0.5432725073605832, + -0.5830432704415978, + -0.6204181836619785, + -0.6552436654864092, + -0.6873766105400307, + -0.7166849776591226, + -0.7430483324765678, + -0.7663583423124991, + -0.7865192213365194, + -0.8034481241722242, + -0.8170754863266232, + -0.8273453100455638, + -0.8342153944205147, + -0.8376575088011508, + -0.8376575088011508, + -0.8342153944205147, + -0.8273453100455638, + -0.8170754863266232, + -0.8034481241722243, + -0.7865192213365195, + -0.7663583423124992, + -0.7430483324765679, + -0.7166849776591228, + -0.6873766105400309, + -0.6552436654864093, + -0.6204181836619788, + -0.5830432704415979, + -0.5432725073605834, + -0.5012693210152366, + -0.4572063115079064, + -0.41126454319614364, + -0.36363280066042003, + -0.314506812947792, + -0.2640884492792613, + -0.2125848895258477, + -0.16020777286205629, + -0.10717232809511551, + -0.053696489243639275, + -1.0263619150592636e-16 + ], + [ + 0, + -0.05772527356228186, + -0.11521334159346397, + -0.17222797329085426, + -0.22853488330320798, + -0.2839026944594901, + -0.3381038885473012, + -0.39091574123401485, + -0.44212123728883435, + -0.491509962344926, + -0.538878967537186, + -0.5840336034626599, + -0.6267883200366905, + -0.6669674289580173, + -0.7044058256496908, + -0.7389496677091939, + -0.7704570070798733, + -0.7987983733459518, + -0.823857305754238, + -0.8455308317763421, + -0.8637298902448827, + -0.8783796973249266, + -0.8894200538168082, + -0.8968055925275532, + -0.9005059646944062, + -0.9005059646944062, + -0.8968055925275532, + -0.8894200538168082, + -0.8783796973249266, + -0.8637298902448828, + -0.8455308317763423, + -0.8238573057542382, + -0.7987983733459518, + -0.7704570070798734, + -0.738949667709194, + -0.7044058256496909, + -0.6669674289580175, + -0.6267883200366906, + -0.5840336034626602, + -0.5388789675371862, + -0.4915099623449264, + -0.44212123728883457, + -0.39091574123401496, + -0.33810388854730156, + -0.28390269445949035, + -0.2285348833032084, + -0.17222797329085449, + -0.11521334159346441, + -0.057725273562282145, + -1.103368640208112e-16 + ], + [ + 0, + -0.06080621048493336, + -0.12136255520809289, + -0.1814201951597159, + -0.24073234061491783, + -0.29905526524560794, + -0.3561493076442506, + -0.4117798561439962, + -0.46571831288834387, + -0.5177430331887685, + -0.5676402363102881, + -0.6152048839423602, + -0.660241522745279, + -0.7025650875098751, + -0.7420016616301545, + -0.7783891917639383, + -0.8115781537448059, + -0.8414321670089682, + -0.8678285550122568, + -0.8906588493343588, + -0.9098292353988218, + -0.9252609379772722, + -0.9368905448937251, + -0.944670267598818, + -0.9485681375432105, + -0.9485681375432105, + -0.944670267598818, + -0.9368905448937251, + -0.9252609379772722, + -0.9098292353988219, + -0.8906588493343588, + -0.867828555012257, + -0.8414321670089683, + -0.811578153744806, + -0.7783891917639384, + -0.7420016616301546, + -0.7025650875098753, + -0.6602415227452791, + -0.6152048839423605, + -0.5676402363102884, + -0.5177430331887689, + -0.46571831288834414, + -0.4117798561439963, + -0.35614930764425096, + -0.29905526524560816, + -0.24073234061491824, + -0.18142019515971616, + -0.12136255520809337, + -0.06080621048493366, + -1.1622580827890157e-16 + ], + [ + 0, + -0.06288871111250068, + -0.12551899902145386, + -0.18763350243968704, + -0.24897697954913547, + -0.3092973568442219, + -0.3683467649559604, + -0.42588255720036167, + -0.4816683066657045, + -0.5354747777414302, + -0.5870808680964368, + -0.6362745172359838, + -0.6828535779037522, + -0.726626646748281, + -0.7674138508403942, + -0.8050475868096494, + -0.8393732095625379, + -0.8702496677523451, + -0.8975500833893896, + -0.9211622732098981, + -0.9409892096610991, + -0.9569494196082502, + -0.9689773191252241, + -0.9770234829929294, + -0.9810548477981369, + -0.9810548477981369, + -0.9770234829929294, + -0.9689773191252241, + -0.9569494196082502, + -0.9409892096610992, + -0.9211622732098982, + -0.8975500833893898, + -0.8702496677523452, + -0.839373209562538, + -0.8050475868096495, + -0.7674138508403943, + -0.7266266467482813, + -0.6828535779037523, + -0.6362745172359842, + -0.5870808680964369, + -0.5354747777414306, + -0.48166830666570476, + -0.4258825572003618, + -0.3683467649559608, + -0.3092973568442221, + -0.24897697954913592, + -0.1876335024396873, + -0.12551899902145436, + -0.062888711112501, + -1.2020632797828825e-16 + ], + [ + 0, + -0.063938580842253, + -0.1276144243410426, + -0.19076587279700669, + -0.25313342336249645, + -0.31446079439444075, + -0.37449597857058936, + -0.432992278441656, + -0.48970932016405333, + -0.5444140412475769, + -0.5968816482591685, + -0.6468965405473512, + -0.6942531961915519, + -0.7387570165357581, + -0.7802251258361357, + -0.818487122736688, + -0.8533857804849779, + -0.8847776930105793, + -0.9125338642113802, + -0.9365402380262364, + -0.9566981671157919, + -0.9729248182255554, + -0.985153512565511, + -0.993333999807569, + -0.9974326645749431, + -0.9974326645749431, + -0.993333999807569, + -0.985153512565511, + -0.9729248182255554, + -0.956698167115792, + -0.9365402380262365, + -0.9125338642113804, + -0.8847776930105794, + -0.853385780484978, + -0.8184871227366881, + -0.7802251258361358, + -0.7387570165357583, + -0.694253196191552, + -0.6468965405473516, + -0.5968816482591687, + -0.5444140412475773, + -0.4897093201640536, + -0.4329922784416561, + -0.37449597857058975, + -0.31446079439444097, + -0.2531334233624969, + -0.19076587279700694, + -0.1276144243410431, + -0.06393858084225332, + -1.2221306309555476e-16 + ], + [ + 0, + -0.063938580842253, + -0.1276144243410426, + -0.19076587279700669, + -0.25313342336249645, + -0.31446079439444075, + -0.37449597857058936, + -0.432992278441656, + -0.48970932016405333, + -0.5444140412475769, + -0.5968816482591685, + -0.6468965405473512, + -0.6942531961915519, + -0.7387570165357581, + -0.7802251258361357, + -0.818487122736688, + -0.8533857804849779, + -0.8847776930105793, + -0.9125338642113802, + -0.9365402380262364, + -0.9566981671157919, + -0.9729248182255554, + -0.985153512565511, + -0.993333999807569, + -0.9974326645749431, + -0.9974326645749431, + -0.993333999807569, + -0.985153512565511, + -0.9729248182255554, + -0.956698167115792, + -0.9365402380262365, + -0.9125338642113804, + -0.8847776930105794, + -0.853385780484978, + -0.8184871227366881, + -0.7802251258361358, + -0.7387570165357583, + -0.694253196191552, + -0.6468965405473516, + -0.5968816482591687, + -0.5444140412475773, + -0.4897093201640536, + -0.4329922784416561, + -0.37449597857058975, + -0.31446079439444097, + -0.2531334233624969, + -0.19076587279700694, + -0.1276144243410431, + -0.06393858084225332, + -1.2221306309555476e-16 + ], + [ + 0, + -0.06288871111250069, + -0.1255189990214539, + -0.18763350243968707, + -0.2489769795491355, + -0.30929735684422194, + -0.36834676495596047, + -0.4258825572003617, + -0.48166830666570454, + -0.5354747777414303, + -0.5870808680964368, + -0.6362745172359839, + -0.6828535779037523, + -0.726626646748281, + -0.7674138508403943, + -0.8050475868096495, + -0.8393732095625379, + -0.8702496677523452, + -0.8975500833893897, + -0.9211622732098982, + -0.9409892096610992, + -0.9569494196082503, + -0.9689773191252242, + -0.9770234829929295, + -0.981054847798137, + -0.981054847798137, + -0.9770234829929295, + -0.9689773191252242, + -0.9569494196082503, + -0.9409892096610993, + -0.9211622732098983, + -0.8975500833893899, + -0.8702496677523454, + -0.839373209562538, + -0.8050475868096496, + -0.7674138508403944, + -0.7266266467482813, + -0.6828535779037525, + -0.6362745172359843, + -0.587080868096437, + -0.5354747777414307, + -0.4816683066657048, + -0.42588255720036183, + -0.36834676495596086, + -0.30929735684422216, + -0.24897697954913595, + -0.18763350243968732, + -0.12551899902145436, + -0.062888711112501, + -1.2020632797828827e-16 + ], + [ + 0, + -0.06080621048493337, + -0.12136255520809291, + -0.18142019515971597, + -0.24073234061491788, + -0.299055265245608, + -0.3561493076442507, + -0.4117798561439963, + -0.465718312888344, + -0.5177430331887687, + -0.5676402363102884, + -0.6152048839423603, + -0.6602415227452793, + -0.7025650875098753, + -0.7420016616301547, + -0.7783891917639384, + -0.8115781537448061, + -0.8414321670089684, + -0.867828555012257, + -0.8906588493343589, + -0.909829235398822, + -0.9252609379772724, + -0.9368905448937254, + -0.9446702675988182, + -0.9485681375432107, + -0.9485681375432107, + -0.9446702675988182, + -0.9368905448937254, + -0.9252609379772724, + -0.9098292353988221, + -0.890658849334359, + -0.8678285550122572, + -0.8414321670089685, + -0.8115781537448062, + -0.7783891917639385, + -0.7420016616301548, + -0.7025650875098755, + -0.6602415227452794, + -0.6152048839423606, + -0.5676402363102885, + -0.517743033188769, + -0.46571831288834425, + -0.41177985614399637, + -0.35614930764425107, + -0.2990552652456082, + -0.2407323406149183, + -0.1814201951597162, + -0.1213625552080934, + -0.060806210484933676, + -1.162258082789016e-16 + ], + [ + 0, + -0.05772527356228187, + -0.11521334159346398, + -0.1722279732908543, + -0.228534883303208, + -0.2839026944594902, + -0.3381038885473013, + -0.3909157412340149, + -0.4421212372888344, + -0.49150996234492605, + -0.5388789675371861, + -0.58403360346266, + -0.6267883200366905, + -0.6669674289580173, + -0.7044058256496909, + -0.738949667709194, + -0.7704570070798734, + -0.7987983733459518, + -0.8238573057542381, + -0.8455308317763423, + -0.8637298902448828, + -0.8783796973249267, + -0.8894200538168083, + -0.8968055925275533, + -0.9005059646944064, + -0.9005059646944064, + -0.8968055925275533, + -0.8894200538168083, + -0.8783796973249267, + -0.8637298902448829, + -0.8455308317763424, + -0.8238573057542383, + -0.7987983733459519, + -0.7704570070798735, + -0.7389496677091941, + -0.704405825649691, + -0.6669674289580175, + -0.6267883200366906, + -0.5840336034626603, + -0.5388789675371863, + -0.49150996234492644, + -0.4421212372888346, + -0.390915741234015, + -0.3381038885473016, + -0.28390269445949035, + -0.22853488330320842, + -0.1722279732908545, + -0.11521334159346443, + -0.05772527356228215, + -1.1033686402081121e-16 + ], + [ + 0, + -0.05369648924363904, + -0.10717232809511515, + -0.16020777286205615, + -0.21258488952584742, + -0.26408844927926123, + -0.3145068129477918, + -0.36363280066042014, + -0.41126454319614364, + -0.45720631150790625, + -0.5012693210152367, + -0.5432725073605834, + -0.5830432704415981, + -0.6204181836619789, + -0.6552436654864096, + -0.6873766105400311, + -0.7166849776591231, + -0.7430483324765681, + -0.7663583423124994, + -0.7865192213365199, + -0.8034481241722247, + -0.8170754863266235, + -0.8273453100455642, + -0.8342153944205151, + -0.8376575088011512, + -0.8376575088011512, + -0.8342153944205151, + -0.8273453100455642, + -0.8170754863266235, + -0.8034481241722248, + -0.78651922133652, + -0.7663583423124997, + -0.7430483324765682, + -0.7166849776591232, + -0.6873766105400312, + -0.6552436654864097, + -0.620418183661979, + -0.5830432704415982, + -0.5432725073605837, + -0.5012693210152369, + -0.45720631150790664, + -0.41126454319614386, + -0.36363280066042025, + -0.31450681294779215, + -0.2640884492792614, + -0.2125848895258478, + -0.16020777286205637, + -0.10717232809511557, + -0.0536964892436393, + -1.0263619150592641e-16 + ], + [ + 0, + -0.04878601005613522, + -0.09737154793238345, + -0.145556965232046, + -0.1931442577396989, + -0.23993787906298605, + -0.2857455441746897, + -0.33037901955315263, + -0.3736548966741941, + -0.4153953456760774, + -0.4554288461005554, + -0.4935908917072252, + -0.5297246664649558, + -0.5636816889425971, + -0.5953224224510303, + -0.624516848429353, + -0.6511450007190356, + -0.675097458530599, + -0.6962757960771095, + -0.7145929870268493, + -0.7299737621131808, + -0.7423549184321082, + -0.7516855791565675, + -0.7579274026002214, + -0.7610547397716729, + -0.7610547397716729, + -0.7579274026002214, + -0.7516855791565675, + -0.7423549184321082, + -0.7299737621131809, + -0.7145929870268494, + -0.6962757960771097, + -0.6750974585305991, + -0.6511450007190356, + -0.6245168484293531, + -0.5953224224510303, + -0.5636816889425972, + -0.5297246664649558, + -0.4935908917072255, + -0.45542884610055556, + -0.4153953456760777, + -0.3736548966741943, + -0.33037901955315274, + -0.28574554417469, + -0.23993787906298622, + -0.19314425773969923, + -0.14555696523204617, + -0.09737154793238384, + -0.04878601005613546, + -9.325023556404495e-17 + ], + [ + 0, + -0.04307446593227171, + -0.08597192964458376, + -0.12851611625706513, + -0.17053220258122573, + -0.21184753550593735, + -0.2522923414661012, + -0.29170042407864333, + -0.32990984707910154, + -0.36676359975247147, + -0.402110242123913, + -0.4358045272580911, + -0.4677079981099876, + -0.4976895564745992, + -0.5256260016975817, + -0.551402536933165, + -0.5749132408690166, + -0.596061502979634, + -0.6147604205197167, + -0.6309331556261872, + -0.6445132510614523, + -0.6554449033004471, + -0.6636831918392895, + -0.669194263783266, + -0.6719554729556376, + -0.6719554729556376, + -0.669194263783266, + -0.6636831918392895, + -0.6554449033004471, + -0.6445132510614524, + -0.6309331556261873, + -0.6147604205197169, + -0.5960615029796341, + -0.5749132408690166, + -0.5514025369331651, + -0.5256260016975818, + -0.4976895564745994, + -0.4677079981099877, + -0.4358045272580913, + -0.40211024212391316, + -0.36676359975247175, + -0.3299098470791017, + -0.29170042407864344, + -0.25229234146610147, + -0.2118475355059375, + -0.17053220258122603, + -0.1285161162570653, + -0.0859719296445841, + -0.043074465932271926, + -8.233311333224379e-17 + ], + [ + 0, + -0.036655640268658196, + -0.07316065464884229, + -0.1093650362061631, + -0.14512001337098607, + -0.1802786612727224, + -0.21469650548563757, + -0.24823211570525627, + -0.2807476869158202, + -0.31210960566065704, + -0.34218899908853373, + -0.37086226451984566, + -0.39801157735653914, + -0.423525375248659, + -0.4472988165279741, + -0.4692342110248805, + -0.48924142149826294, + -0.5072382340287533, + -0.5231506958533595, + -0.5369134192532319, + -0.5484698502458255, + -0.5577725009773452, + -0.5647831448605226, + -0.5694729736558635, + -0.5718227158508826, + -0.5718227158508826, + -0.5694729736558635, + -0.5647831448605226, + -0.5577725009773452, + -0.5484698502458256, + -0.536913419253232, + -0.5231506958533596, + -0.5072382340287533, + -0.489241421498263, + -0.46923421102488055, + -0.4472988165279742, + -0.42352537524865913, + -0.3980115773565392, + -0.37086226451984583, + -0.3421889990885339, + -0.31210960566065726, + -0.28074768691582036, + -0.24823211570525633, + -0.2146965054856378, + -0.18027866127272255, + -0.14512001337098632, + -0.10936503620616324, + -0.07316065464884258, + -0.03665564026865838, + -7.006408365574896e-17 + ], + [ + 0, + -0.029634930005233154, + -0.05914808372640226, + -0.08841818528431541, + -0.11732495755325402, + -0.14574961640548187, + -0.1735753588207049, + -0.20068784285473598, + -0.2269756574950696, + -0.25233078047263013, + -0.276649022148446, + -0.2998304536512248, + -0.32177981750651996, + -0.3424069190701265, + -0.36162699715722013, + -0.37936107234424704, + -0.39553627151231663, + -0.41008612729847793, + -0.42295085122437137, + -0.43407757937991076, + -0.44342058965242936, + -0.45094148960864794, + -0.4566093742574184, + -0.4604009530449614, + -0.46230064556074807, + -0.46230064556074807, + -0.4604009530449614, + -0.4566093742574184, + -0.45094148960864794, + -0.4434205896524294, + -0.4340775793799108, + -0.4229508512243715, + -0.410086127298478, + -0.3955362715123167, + -0.3793610723442471, + -0.3616269971572202, + -0.3424069190701266, + -0.32177981750652, + -0.2998304536512249, + -0.2766490221484461, + -0.25233078047263036, + -0.22697565749506973, + -0.200687842854736, + -0.17357535882070507, + -0.14574961640548198, + -0.11732495755325423, + -0.08841818528431553, + -0.05914808372640249, + -0.029634930005233304, + -5.664460366265284e-17 + ], + [ + 0, + -0.0221276150104241, + -0.04416430290441184, + -0.06601951020455209, + -0.08760342917612128, + -0.10882736686632918, + -0.12960410956268634, + -0.14984828117285615, + -0.1694766940533311, + -0.1884086908453041, + -0.20656647591305627, + -0.2238754350229116, + -0.24026444194912755, + -0.2556661507468133, + -0.27001727249086316, + -0.28325883534372465, + -0.2953364268833292, + -0.30620041769540524, + -0.31580616531138717, + -0.32411419765389465, + -0.3310903752359649, + -0.33670603144752786, + -0.34093809035265565, + -0.34376916151353326, + -0.34518761145149796, + -0.34518761145149796, + -0.34376916151353326, + -0.34093809035265565, + -0.33670603144752786, + -0.33109037523596496, + -0.3241141976538947, + -0.3158061653113873, + -0.30620041769540524, + -0.29533642688332923, + -0.2832588353437247, + -0.2700172724908632, + -0.2556661507468134, + -0.24026444194912758, + -0.2238754350229117, + -0.20656647591305635, + -0.18840869084530423, + -0.1694766940533312, + -0.14984828117285617, + -0.12960410956268648, + -0.10882736686632927, + -0.08760342917612143, + -0.06601951020455217, + -0.044164302904412006, + -0.02212761501042421, + -4.2295020843440646e-17 + ], + [ + 0, + -0.014256965188894764, + -0.028455345449718922, + -0.042536796592437726, + -0.05644345491384394, + -0.07011817497192607, + -0.08350476440874718, + -0.09654821485689698, + -0.10919492798067262, + -0.12139293572313709, + -0.13309211385401212, + -0.14424438794089217, + -0.15480393089739888, + -0.16472735129650912, + -0.17397387167523598, + -0.18250549609797084, + -0.190287166289933, + -0.19728690569914065, + -0.203475950894922, + -0.20882886976302148, + -0.21332366601161265, + -0.21694186955877925, + -0.2196686124300437, + -0.22149268985406353, + -0.22240660630544004, + -0.22240660630544004, + -0.22149268985406353, + -0.2196686124300437, + -0.21694186955877925, + -0.21332366601161268, + -0.2088288697630215, + -0.20347595089492201, + -0.19728690569914067, + -0.19028716628993303, + -0.18250549609797087, + -0.173973871675236, + -0.16472735129650917, + -0.1548039308973989, + -0.14424438794089225, + -0.13309211385401218, + -0.12139293572313718, + -0.10919492798067268, + -0.096548214856897, + -0.08350476440874727, + -0.07011817497192611, + -0.05644345491384404, + -0.04253679659243778, + -0.028455345449719033, + -0.014256965188894835, + -2.7250954951288024e-17 + ], + [ + 0, + -0.006152216393118909, + -0.012279152009432215, + -0.01835562995626892, + -0.024356680682345033, + -0.030257644583005772, + -0.036034273331830534, + -0.041662829522207415, + -0.04712018420942863, + -0.05238391195248549, + -0.05743238296501571, + -0.062244851996735184, + -0.06680154358012118, + -0.07108373329205028, + -0.0750738246964694, + -0.07875542165192581, + -0.08211339568682949, + -0.08513394816558786, + -0.08780466699015921, + -0.090114577604026, + -0.09205418808900157, + -0.093615528169558, + -0.09479218196439791, + -0.09557931435068683, + -0.09597369083261015, + -0.09597369083261015, + -0.09557931435068683, + -0.09479218196439791, + -0.093615528169558, + -0.09205418808900158, + -0.09011457760402601, + -0.08780466699015924, + -0.08513394816558788, + -0.0821133956868295, + -0.07875542165192582, + -0.07507382469646941, + -0.07108373329205031, + -0.06680154358012118, + -0.06224485199673521, + -0.05743238296501573, + -0.05238391195248553, + -0.04712018420942866, + -0.04166282952220742, + -0.03603427333183057, + -0.030257644583005793, + -0.024356680682345075, + -0.018355629956268944, + -0.012279152009432264, + -0.00615221639311894, + -1.1759429132228667e-17 + ], + [ + 0, + 0.0020535516257448112, + 0.004098664767373994, + 0.006126935616313203, + 0.008130029572581412, + 0.010099715493450009, + 0.012027899516973842, + 0.013906658321406074, + 0.015728271683826792, + 0.01748525420419497, + 0.019170386064462846, + 0.02077674269635693, + 0.022297723235914352, + 0.023727077647848763, + 0.025058932408285974, + 0.02628781464033339, + 0.02740867460330512, + 0.028416906443189602, + 0.029308367119091704, + 0.030079393427876425, + 0.03072681705705635, + 0.031247977604067237, + 0.031640733508432835, + 0.03190347085189623, + 0.03203510999035615, + 0.03203510999035615, + 0.03190347085189623, + 0.031640733508432835, + 0.031247977604067237, + 0.030726817057056353, + 0.030079393427876428, + 0.02930836711909171, + 0.028416906443189605, + 0.027408674603305122, + 0.026287814640333394, + 0.025058932408285977, + 0.02372707764784877, + 0.022297723235914356, + 0.02077674269635694, + 0.019170386064462853, + 0.017485254204194983, + 0.0157282716838268, + 0.013906658321406078, + 0.012027899516973854, + 0.010099715493450017, + 0.008130029572581425, + 0.006126935616313211, + 0.004098664767374011, + 0.0020535516257448212, + 3.925186188075022e-18 + ], + [ + 0, + 0.010225600383687245, + 0.020409181582013516, + 0.030508897075463573, + 0.040483244966692644, + 0.05029123852072477, + 0.059892574588238406, + 0.06924779921985201, + 0.07831846979086489, + 0.08706731297024801, + 0.09545837788475632, + 0.10345718384877835, + 0.11103086205286938, + 0.11814829062873995, + 0.12478022253568818, + 0.13089940574296346, + 0.13648069521420642, + 0.1415011562337969, + 0.14594015865051987, + 0.149779461651282, + 0.15300328871652527, + 0.1555983924493298, + 0.15755410901180955, + 0.15886240194510934, + 0.15951789519293835, + 0.15951789519293835, + 0.15886240194510934, + 0.15755410901180955, + 0.1555983924493298, + 0.15300328871652527, + 0.14977946165128203, + 0.1459401586505199, + 0.14150115623379692, + 0.13648069521420644, + 0.1308994057429635, + 0.1247802225356882, + 0.11814829062874, + 0.1110308620528694, + 0.1034571838487784, + 0.09545837788475636, + 0.08706731297024808, + 0.07831846979086493, + 0.06924779921985204, + 0.05989257458823847, + 0.050291238520724806, + 0.04048324496669272, + 0.030508897075463615, + 0.020409181582013596, + 0.010225600383687295, + 1.9545350059688042e-17 + ], + [ + 0, + 0.01822974506603157, + 0.03638458019931877, + 0.054389903288098986, + 0.07217172659767072, + 0.08965698080186585, + 0.10677381524058402, + 0.1234518931695671, + 0.13962268078916837, + 0.15521972886443586, + 0.17017894577927192, + 0.18443886090263162, + 0.19794087718453077, + 0.21062951194389368, + 0.22245262485879053, + 0.23336163222220419, + 0.2433117065829037, + 0.25226196095105663, + 0.26017561681164075, + 0.2670201552552511, + 0.2727674506052739, + 0.277393885992325, + 0.28088045040103166, + 0.2832128167903728, + 0.2843814009665636, + 0.2843814009665636, + 0.2832128167903728, + 0.28088045040103166, + 0.277393885992325, + 0.2727674506052739, + 0.26702015525525113, + 0.2601756168116408, + 0.2522619609510567, + 0.24331170658290371, + 0.23336163222220424, + 0.22245262485879055, + 0.21062951194389376, + 0.19794087718453082, + 0.18443886090263173, + 0.170178945779272, + 0.15521972886443597, + 0.13962268078916845, + 0.12345189316956715, + 0.10677381524058413, + 0.0896569808018659, + 0.07217172659767085, + 0.054389903288099055, + 0.03638458019931891, + 0.01822974506603166, + 3.4844579823681456e-17 + ], + [ + 0, + 0.025934557838380112, + 0.051762545015657115, + 0.0773778287924337, + 0.10267515047320992, + 0.12755055793694103, + 0.1519018327986004, + 0.17562891044644935, + 0.19863429122899068, + 0.22082344110195024, + 0.2421051800889423, + 0.2623920569595507, + 0.28160070858519254, + 0.29965220249609525, + 0.31647236123174566, + 0.3319920671519862, + 0.34614754645622414, + 0.35888063124365766, + 0.3701389985376569, + 0.37987638529209883, + 0.38805277849614633, + 0.3946345795962933, + 0.3995947425600272, + 0.4029128850137784, + 0.40457537199846527, + 0.40457537199846527, + 0.4029128850137784, + 0.3995947425600272, + 0.3946345795962933, + 0.3880527784961464, + 0.3798763852920989, + 0.370138998537657, + 0.3588806312436577, + 0.3461475464562242, + 0.33199206715198626, + 0.3164723612317457, + 0.2996522024960953, + 0.2816007085851926, + 0.2623920569595508, + 0.24210518008894238, + 0.2208234411019504, + 0.1986342912289908, + 0.1756289104464494, + 0.15190183279860053, + 0.12755055793694114, + 0.1026751504732101, + 0.0773778287924338, + 0.051762545015657316, + 0.02593455783838024, + 4.957166255030033e-17 + ], + [ + 0, + 0.03321352588802205, + 0.06629057027389126, + 0.09909521248722232, + 0.13149265121658696, + 0.1633497584370174, + 0.19453562646161687, + 0.22492210586932454, + 0.2543843320983747, + 0.2828012385415645, + 0.31005605403491165, + 0.33603678269541437, + 0.36063666413615775, + 0.3837546121676437, + 0.40529563018262676, + 0.42517120151754934, + 0.44329965318649955, + 0.459606491493029, + 0.4740247081407304, + 0.4864950555847005, + 0.4969662904924109, + 0.505395384313553, + 0.5117477000935807, + 0.5159971348043865, + 0.5181262266072427, + 0.5181262266072427, + 0.5159971348043865, + 0.5117477000935807, + 0.505395384313553, + 0.496966290492411, + 0.4864950555847006, + 0.4740247081407305, + 0.45960649149302907, + 0.4432996531864996, + 0.4251712015175494, + 0.4052956301826268, + 0.38375461216764384, + 0.3606366641361578, + 0.33603678269541454, + 0.31005605403491177, + 0.28280123854156475, + 0.25438433209837485, + 0.2249221058693246, + 0.19453562646161707, + 0.16334975843701754, + 0.13149265121658718, + 0.09909521248722246, + 0.06629057027389151, + 0.03321352588802221, + 6.348477994832595e-17 + ], + [ + 0, + 0.039947128760820155, + 0.07973010620092985, + 0.11918545553260579, + 0.1581510462622982, + 0.1964667604196058, + 0.23397515051636128, + 0.27052208653213267, + 0.3059573892675379, + 0.3401354474627886, + 0.3729158161455901, + 0.4041637937496577, + 0.433750975632346, + 0.46155578171686845, + 0.4874639560909117, + 0.5113690365086866, + 0.5331727918671331, + 0.5527856258585923, + 0.5701269451412535, + 0.5851254905144833, + 0.5977196297381648, + 0.6078576107927938, + 0.6154977745396266, + 0.6206087259070174, + 0.623169462899502, + 0.623169462899502, + 0.6206087259070174, + 0.6154977745396266, + 0.6078576107927938, + 0.597719629738165, + 0.5851254905144833, + 0.5701269451412536, + 0.5527856258585923, + 0.5331727918671331, + 0.5113690365086867, + 0.48746395609091175, + 0.4615557817168686, + 0.43375097563234605, + 0.4041637937496579, + 0.3729158161455902, + 0.3401354474627889, + 0.30595738926753807, + 0.2705220865321327, + 0.23397515051636153, + 0.19646676041960595, + 0.15815104626229848, + 0.11918545553260594, + 0.07973010620093017, + 0.03994712876082035, + 7.635547901473152e-17 + ], + [ + 0, + 0.046024800883763525, + 0.09186047598840684, + 0.1373186766932035, + 0.18221260550070398, + 0.22635778362772077, + 0.26957280906821895, + 0.3116801020130696, + 0.35250663456357634, + 0.3918846417402253, + 0.4296523108649717, + 0.4656544464842423, + 0.49974310810034356, + 0.5317782180906999, + 0.5616281373168517, + 0.5891702060579108, + 0.6142912480456649, + 0.6368880355301402, + 0.6568677134645667, + 0.6741481810666847, + 0.6886584291884684, + 0.7003388321079469, + 0.7091413925440854, + 0.7150299388879086, + 0.7179802738394004, + 0.7179802738394004, + 0.7150299388879086, + 0.7091413925440854, + 0.7003388321079469, + 0.6886584291884685, + 0.6741481810666848, + 0.6568677134645668, + 0.6368880355301402, + 0.614291248045665, + 0.5891702060579108, + 0.5616281373168518, + 0.5317782180907001, + 0.4997431081003436, + 0.46565444648424253, + 0.42965231086497185, + 0.39188464174022564, + 0.3525066345635765, + 0.3116801020130697, + 0.26957280906821923, + 0.22635778362772094, + 0.18221260550070428, + 0.1373186766932037, + 0.0918604759884072, + 0.046024800883763754, + 8.797242322667628e-17 + ], + [ + 0, + 0.05134674704861985, + 0.10248249929977422, + 0.15319712897887866, + 0.20328223879432777, + 0.25253201828666755, + 0.3007440895479193, + 0.3477203388358138, + 0.3932677306656531, + 0.4371991010345236, + 0.4793339265183301, + 0.5194990660812682, + 0.5575294725494779, + 0.5932688708252851, + 0.6265704000550975, + 0.6572972171121542, + 0.685323058914286, + 0.710532761266004, + 0.7328227320928805, + 0.7521013771236045, + 0.768289476270488, + 0.7813205091618003, + 0.7911409284882431, + 0.7977103800403307, + 0.8010018685324927, + 0.8010018685324927, + 0.7977103800403307, + 0.7911409284882431, + 0.7813205091618003, + 0.768289476270488, + 0.7521013771236045, + 0.7328227320928807, + 0.7105327612660041, + 0.685323058914286, + 0.6572972171121543, + 0.6265704000550976, + 0.5932688708252852, + 0.557529472549478, + 0.5194990660812684, + 0.47933392651833034, + 0.437199101034524, + 0.39326773066565335, + 0.3477203388358139, + 0.3007440895479196, + 0.2525320182866677, + 0.20328223879432814, + 0.15319712897887888, + 0.10248249929977463, + 0.051346747048620106, + 9.814486268136802e-17 + ], + [ + 0, + 0.05582558104649524, + 0.11142176280592085, + 0.16656008864208377, + 0.22101398334698938, + 0.27455968418697146, + 0.3269771603917617, + 0.3780510173081213, + 0.4275713815026729, + 0.47533476317685625, + 0.5211448923501589, + 0.5648135253755662, + 0.6061612184730837, + 0.6450180651027219, + 0.6812243941469118, + 0.7146314260333778, + 0.7451018841023125, + 0.7725105587056179, + 0.7967448217202067, + 0.8177050893611189, + 0.8353052313926546, + 0.8494729250559877, + 0.8601499522588948, + 0.8672924388063838, + 0.8708710346891727, + 0.8708710346891727, + 0.8672924388063838, + 0.8601499522588948, + 0.8494729250559877, + 0.8353052313926547, + 0.817705089361119, + 0.7967448217202069, + 0.7725105587056179, + 0.7451018841023126, + 0.7146314260333779, + 0.6812243941469119, + 0.645018065102722, + 0.6061612184730838, + 0.5648135253755664, + 0.5211448923501592, + 0.47533476317685663, + 0.4275713815026731, + 0.3780510173081214, + 0.32697716039176206, + 0.2745596841869717, + 0.22101398334698977, + 0.166560088642084, + 0.11142176280592128, + 0.055825581046495515, + 1.067057662041928e-16 + ], + [ + 0, + 0.05938776054696869, + 0.11853148404721521, + 0.17718813625458812, + 0.23511668440335487, + 0.29207908766353763, + 0.3478412753017431, + 0.4021741085280141, + 0.45485432207626775, + 0.5056654416491639, + 0.5543986734574265, + 0.6008537621983102, + 0.6448398139475932, + 0.6861760805836591, + 0.724692702520299, + 0.7602314066961859, + 0.7926461569528328, + 0.821803754128493, + 0.8475843834020869, + 0.8698821066380014, + 0.8886052977086137, + 0.9036770190057027, + 0.9150353375935847, + 0.9226335797048302, + 0.9264405225327862, + 0.9264405225327862, + 0.9226335797048302, + 0.9150353375935847, + 0.9036770190057027, + 0.8886052977086139, + 0.8698821066380015, + 0.8475843834020871, + 0.8218037541284932, + 0.7926461569528329, + 0.760231406696186, + 0.7246927025202992, + 0.6861760805836592, + 0.6448398139475933, + 0.6008537621983105, + 0.5543986734574268, + 0.5056654416491643, + 0.454854322076268, + 0.4021741085280142, + 0.3478412753017434, + 0.29207908766353785, + 0.23511668440335529, + 0.17718813625458835, + 0.11853148404721567, + 0.05938776054696899, + 1.135145639959849e-16 + ], + [ + 0, + 0.06197479466112416, + 0.123694921597434, + 0.18490675956842254, + 0.24535877600196884, + 0.30480256059563066, + 0.36299384608786084, + 0.4196935120045802, + 0.4746685672564967, + 0.5276931075494679, + 0.5785492436737018, + 0.6270279968572569, + 0.6729301575046418, + 0.7160671037917741, + 0.756261576753514, + 0.7933484086787741, + 0.8271752018200732, + 0.8576029546285693, + 0.8845066329412397, + 0.9077756837730767, + 0.9273144896030167, + 0.9430427612868437, + 0.9548958679825051, + 0.962825102732105, + 0.9667978826092418, + 0.9667978826092418, + 0.962825102732105, + 0.9548958679825051, + 0.9430427612868437, + 0.9273144896030168, + 0.9077756837730768, + 0.8845066329412398, + 0.8576029546285694, + 0.8271752018200733, + 0.7933484086787742, + 0.7562615767535141, + 0.7160671037917743, + 0.6729301575046419, + 0.6270279968572572, + 0.578549243673702, + 0.5276931075494683, + 0.474668567256497, + 0.4196935120045803, + 0.3629938460878612, + 0.3048025605956309, + 0.24535877600196926, + 0.18490675956842278, + 0.12369492159743449, + 0.061974794661124474, + 1.1845945578524243e-16 + ], + [ + 0, + 0.06354420436032968, + 0.12682729195475367, + 0.18958921900216677, + 0.25157208328194003, + 0.31252118390946515, + 0.37218606795672254, + 0.4303215596170846, + 0.486688767685295, + 0.5410560672126732, + 0.593200051303712, + 0.642906449142932, + 0.6899710064796228, + 0.7342003249523721, + 0.7754126568044162, + 0.8134386517241577, + 0.848122052741921, + 0.879320338323358, + 0.9069053080210032, + 0.9307636092774118, + 0.9507972032151312, + 0.9669237674994793, + 0.9790770346186742, + 0.9872070641912557, + 0.9912804481818241, + 0.9912804481818241, + 0.9872070641912557, + 0.9790770346186742, + 0.9669237674994793, + 0.9507972032151313, + 0.9307636092774119, + 0.9069053080210034, + 0.8793203383233581, + 0.8481220527419211, + 0.8134386517241579, + 0.7754126568044163, + 0.7342003249523723, + 0.689971006479623, + 0.6429064491429324, + 0.5932000513037122, + 0.5410560672126736, + 0.4866887676852953, + 0.43032155961708474, + 0.37218606795672293, + 0.31252118390946537, + 0.2515720832819405, + 0.18958921900216702, + 0.12682729195475417, + 0.06354420436033, + 1.2145924658549475e-16 + ], + [ + 0, + 0.06407021998071291, + 0.127877161684506, + 0.1911586287013723, + 0.25365458390950735, + 0.31510821802362066, + 0.3752670048793741, + 0.4338837391175581, + 0.49071755200393785, + 0.5455349012105486, + 0.5981105304912159, + 0.6482283953077884, + 0.6956825506034864, + 0.7402779970753155, + 0.7818314824680298, + 0.8201722545969559, + 0.8551427630053461, + 0.886599306373, + 0.9144126230158124, + 0.9384684220497603, + 0.9586678530366606, + 0.9749279121818236, + 0.9871817834144502, + 0.9953791129491982, + 0.9994862162006879, + 0.9994862162006879, + 0.9953791129491982, + 0.9871817834144502, + 0.9749279121818236, + 0.9586678530366607, + 0.9384684220497604, + 0.9144126230158126, + 0.8865993063730001, + 0.8551427630053462, + 0.820172254596956, + 0.7818314824680299, + 0.7402779970753157, + 0.6956825506034865, + 0.6482283953077888, + 0.5981105304912161, + 0.545534901210549, + 0.49071755200393813, + 0.43388373911755823, + 0.3752670048793745, + 0.3151082180236209, + 0.2536545839095078, + 0.19115862870137254, + 0.1278771616845065, + 0.06407021998071323, + 1.2246467991473532e-16 + ] + ], + "y": [ + [ + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0 + ], + [ + 0, + 0.008193117879635491, + 0.01635256848048529, + 0.02444482286983383, + 0.03243662823861217, + 0.040295144544323105, + 0.04798807945782002, + 0.055483821059414, + 0.06275156773903254, + 0.06976145476664233, + 0.07648467701283086, + 0.08289360731526192, + 0.08896191000461155, + 0.09466464912348238, + 0.09997839089360126, + 0.10488130001024074, + 0.10935322936816984, + 0.11337580285043099, + 0.11693249083974627, + 0.12000867814226042, + 0.12259172404450727, + 0.12467101425681293, + 0.1262380045296886, + 0.12728625576398478, + 0.1278114604705305, + 0.1278114604705305, + 0.12728625576398478, + 0.1262380045296886, + 0.12467101425681293, + 0.12259172404450729, + 0.12000867814226043, + 0.1169324908397463, + 0.113375802850431, + 0.10935322936816985, + 0.10488130001024075, + 0.09997839089360128, + 0.09466464912348241, + 0.08896191000461157, + 0.08289360731526198, + 0.07648467701283089, + 0.06976145476664239, + 0.06275156773903258, + 0.05548382105941401, + 0.04798807945782007, + 0.04029514454432313, + 0.03243662823861222, + 0.024444822869833866, + 0.01635256848048535, + 0.008193117879635533, + 1.5660435674097883e-17 + ], + [ + 0, + 0.01625170499019834, + 0.03243662823861217, + 0.048488262423958595, + 0.06434064793830531, + 0.07992864392924783, + 0.0951881959776447, + 0.11005659931096544, + 0.12447275647065088, + 0.1383774283746759, + 0.15171347774364408, + 0.16442610389012471, + 0.17646306790643213, + 0.18777490732550264, + 0.1983151393727814, + 0.20804045197391335, + 0.21691088173334752, + 0.22488997815250114, + 0.2319449534126771, + 0.23804681710724387, + 0.24317049536943489, + 0.24729493390624518, + 0.25040318451503774, + 0.2524824747273434, + 0.25352426029367336, + 0.25352426029367336, + 0.2524824747273434, + 0.25040318451503774, + 0.24729493390624518, + 0.2431704953694349, + 0.2380468171072439, + 0.23194495341267715, + 0.22488997815250117, + 0.21691088173334755, + 0.20804045197391338, + 0.19831513937278142, + 0.1877749073255027, + 0.17646306790643215, + 0.1644261038901248, + 0.15171347774364413, + 0.138377428374676, + 0.12447275647065095, + 0.11005659931096547, + 0.0951881959776448, + 0.07992864392924788, + 0.06434064793830542, + 0.048488262423958664, + 0.03243662823861229, + 0.01625170499019842, + 3.106372742738319e-17 + ], + [ + 0, + 0.024043439554124763, + 0.04798807945782002, + 0.07173552604961234, + 0.0951881959776447, + 0.11824971719060093, + 0.14082532495113617, + 0.16282225124450975, + 0.18415010598225626, + 0.2047212484344478, + 0.22445114736425215, + 0.24325872838491666, + 0.26106670711181396, + 0.2778019067405557, + 0.2933955587461784, + 0.3077835854677631, + 0.32090686341728863, + 0.3327114662307263, + 0.34314888626303613, + 0.3521762339164859, + 0.35975641388320756, + 0.3658582775777744, + 0.3704567511334197, + 0.3735329384359338, + 0.37507419877185066, + 0.37507419877185066, + 0.3735329384359338, + 0.3704567511334197, + 0.3658582775777744, + 0.3597564138832076, + 0.35217623391648595, + 0.3431488862630362, + 0.33271146623072634, + 0.3209068634172887, + 0.30778358546776313, + 0.29339555874617845, + 0.27780190674055577, + 0.26106670711181396, + 0.2432587283849168, + 0.22445114736425223, + 0.20472124843444797, + 0.18415010598225637, + 0.1628222512445098, + 0.1408253249511363, + 0.11824971719060101, + 0.09518819597764487, + 0.07173552604961243, + 0.04798807945782021, + 0.024043439554124885, + 4.5956953635113964e-17 + ], + [ + 0, + 0.031440381505289224, + 0.06275156773903254, + 0.09380489432076711, + 0.12447275647065088, + 0.15462913336487424, + 0.18415010598225626, + 0.21291436631408334, + 0.24080371584473745, + 0.2677035512547505, + 0.2935033353504261, + 0.31809705128487886, + 0.3413836382039985, + 0.3632674065271771, + 0.38365843115632126, + 0.40247292099736864, + 0.41963356327586704, + 0.43506984123174786, + 0.4487183238878191, + 0.4605229267012568, + 0.4704351420270209, + 0.4784142384461746, + 0.48442742814002054, + 0.4884500016222817, + 0.49046542927568015, + 0.49046542927568015, + 0.4884500016222817, + 0.48442742814002054, + 0.4784142384461746, + 0.47043514202702097, + 0.46052292670125683, + 0.44871832388781924, + 0.4350698412317479, + 0.4196335632758671, + 0.4024729209973687, + 0.3836584311563213, + 0.3632674065271772, + 0.34138363820399853, + 0.31809705128487903, + 0.29350333535042616, + 0.2677035512547507, + 0.2408037158447376, + 0.2129143663140834, + 0.18415010598225645, + 0.15462913336487435, + 0.1244727564706511, + 0.09380489432076723, + 0.06275156773903279, + 0.03144038150528938, + 6.009556793470474e-17 + ], + [ + 0, + 0.038321073261353096, + 0.07648467701283086, + 0.11433398882055115, + 0.15171347774364408, + 0.18846954344424946, + 0.22445114736425215, + 0.259510433375115, + 0.2935033353504261, + 0.32629016916451425, + 0.3577362066844837, + 0.38771222939701094, + 0.41609505939493335, + 0.4427680655416917, + 0.46762164273368706, + 0.4905536622911618, + 0.5114698916268516, + 0.530284381467899, + 0.5469198190398518, + 0.5613078457614364, + 0.573389338144632, + 0.5831146507457641, + 0.5904438201692813, + 0.5953467292859208, + 0.5978032309904515, + 0.5978032309904515, + 0.5953467292859208, + 0.5904438201692813, + 0.5831146507457641, + 0.5733893381446321, + 0.5613078457614364, + 0.5469198190398519, + 0.5302843814678991, + 0.5114698916268517, + 0.49055366229116193, + 0.4676216427336871, + 0.44276806554169185, + 0.41609505939493346, + 0.3877122293970111, + 0.3577362066844838, + 0.32629016916451453, + 0.2935033353504263, + 0.2595104333751151, + 0.22445114736425237, + 0.1884695434442496, + 0.15171347774364433, + 0.11433398882055129, + 0.07648467701283117, + 0.03832107326135329, + 7.32474146702393e-17 + ], + [ + 0, + 0.04457253405390881, + 0.08896191000461155, + 0.1329857223848355, + 0.17646306790643213, + 0.2192152888307919, + 0.26106670711181396, + 0.3018453462946805, + 0.3413836382039985, + 0.37951911151737544, + 0.41609505939493335, + 0.4509611834213273, + 0.4839742112141724, + 0.5149984851609957, + 0.5439065198654639, + 0.5705795260122223, + 0.5949078984976719, + 0.6167916668208505, + 0.6361409058836646, + 0.6528761055124064, + 0.6669284971821122, + 0.6782403366011829, + 0.6867651409950631, + 0.692467880113934, + 0.6953251201795222, + 0.6953251201795222, + 0.692467880113934, + 0.6867651409950631, + 0.6782403366011829, + 0.6669284971821123, + 0.6528761055124065, + 0.6361409058836648, + 0.6167916668208506, + 0.5949078984976719, + 0.5705795260122224, + 0.543906519865464, + 0.5149984851609959, + 0.48397421121417245, + 0.4509611834213275, + 0.4160950593949335, + 0.3795191115173757, + 0.34138363820399864, + 0.30184534629468057, + 0.26106670711181423, + 0.21921528883079205, + 0.17646306790643243, + 0.13298572238483566, + 0.0889619100046119, + 0.044572534053909034, + 8.519654088192262e-17 + ], + [ + 0, + 0.05009211506957356, + 0.09997839089360126, + 0.14945383406414958, + 0.1983151393727814, + 0.2463615252352665, + 0.2933955587461784, + 0.33922396697305235, + 0.38365843115632126, + 0.4265163605514934, + 0.46762164273368706, + 0.5068053672813603, + 0.5439065198654639, + 0.5787726438918578, + 0.6112604669781572, + 0.6412364896906844, + 0.6685775341222768, + 0.6931712500567295, + 0.7149165766399322, + 0.7337241576605968, + 0.7495167087340957, + 0.7622293348805763, + 0.7718097971923531, + 0.7782187274947842, + 0.7814297901185455, + 0.7814297901185455, + 0.7782187274947842, + 0.7718097971923531, + 0.7622293348805763, + 0.7495167087340957, + 0.7337241576605968, + 0.7149165766399325, + 0.6931712500567296, + 0.6685775341222769, + 0.6412364896906845, + 0.6112604669781573, + 0.5787726438918579, + 0.543906519865464, + 0.5068053672813605, + 0.4676216427336872, + 0.4265163605514937, + 0.3836584311563215, + 0.33922396697305246, + 0.29339555874617873, + 0.24636152523526667, + 0.19831513937278172, + 0.14945383406414978, + 0.09997839089360165, + 0.05009211506957381, + 9.574674224771027e-17 + ], + [ + 0, + 0.054789184940667174, + 0.10935322936816984, + 0.16346791792000456, + 0.21691088173334752, + 0.26946251220641, + 0.32090686341728863, + 0.3710325394920794, + 0.41963356327586704, + 0.4665102227370371, + 0.5114698916268516, + 0.5543278210220239, + 0.5949078984976719, + 0.6330433718110487, + 0.6685775341222768, + 0.701364367936365, + 0.7312691451204175, + 0.7581689805304306, + 0.7819533369727077, + 0.8025244794248994, + 0.819797876650173, + 0.833702548554198, + 0.8441813578575781, + 0.8511912448851878, + 0.854703404507615, + 0.854703404507615, + 0.8511912448851878, + 0.8441813578575781, + 0.833702548554198, + 0.8197978766501731, + 0.8025244794248994, + 0.781953336972708, + 0.7581689805304307, + 0.7312691451204176, + 0.7013643679363651, + 0.6685775341222769, + 0.633043371811049, + 0.5949078984976719, + 0.5543278210220242, + 0.5114698916268519, + 0.4665102227370374, + 0.41963356327586726, + 0.3710325394920795, + 0.32090686341728897, + 0.26946251220641015, + 0.21691088173334788, + 0.16346791792000476, + 0.10935322936817027, + 0.054789184940667444, + 1.0472478475285208e-16 + ], + [ + 0, + 0.058586617909763807, + 0.11693249083974627, + 0.1747978630829276, + 0.2319449534126771, + 0.28813893217681746, + 0.34314888626303613, + 0.39674876797039477, + 0.4487183238878191, + 0.4988439999626098, + 0.5469198190398518, + 0.5927482272667257, + 0.6361409058836646, + 0.6769195450665312, + 0.7149165766399322, + 0.7499758626507951, + 0.7819533369727077, + 0.8107175973045347, + 0.8361504451306582, + 0.8581473714240319, + 0.8766179860961901, + 0.891486389429511, + 0.902691483965435, + 0.9101872255670289, + 0.9139428126242204, + 0.9139428126242204, + 0.9101872255670289, + 0.902691483965435, + 0.891486389429511, + 0.8766179860961902, + 0.8581473714240319, + 0.8361504451306584, + 0.8107175973045349, + 0.7819533369727079, + 0.7499758626507952, + 0.7149165766399324, + 0.6769195450665313, + 0.6361409058836647, + 0.592748227266726, + 0.546919819039852, + 0.49884399996261025, + 0.4487183238878194, + 0.3967487679703949, + 0.34314888626303647, + 0.28813893217681763, + 0.23194495341267748, + 0.17479786308292783, + 0.11693249083974673, + 0.0585866179097641, + 1.11983249187625e-16 + ], + [ + 0, + 0.0614220602324966, + 0.12259172404450727, + 0.18325763216657673, + 0.24317049536943489, + 0.3020841188469124, + 0.35975641388320756, + 0.415950392647348, + 0.4704351420270209, + 0.5229867725000833, + 0.573389338144632, + 0.6214357240071172, + 0.6669284971821122, + 0.709680718106472, + 0.7495167087340957, + 0.786272774434701, + 0.819797876650173, + 0.8499542535443964, + 0.8766179860961901, + 0.8996795073091464, + 0.9190440524459202, + 0.9346320484368628, + 0.9463794408628327, + 0.9542379571685435, + 0.958175305024849, + 0.958175305024849, + 0.9542379571685435, + 0.9463794408628327, + 0.9346320484368628, + 0.9190440524459204, + 0.8996795073091465, + 0.8766179860961903, + 0.8499542535443965, + 0.8197978766501731, + 0.7862727744347011, + 0.7495167087340958, + 0.7096807181064723, + 0.6669284971821123, + 0.6214357240071176, + 0.5733893381446322, + 0.5229867725000837, + 0.4704351420270212, + 0.41595039264734807, + 0.35975641388320795, + 0.30208411884691255, + 0.2431704953694353, + 0.18325763216657698, + 0.12259172404450776, + 0.061422060232496904, + 1.1740295176668117e-16 + ], + [ + 0, + 0.06324895402431631, + 0.1262380045296886, + 0.1887083159964814, + 0.25040318451503774, + 0.31106909263710725, + 0.3704567511334197, + 0.4283221233766011, + 0.48442742814002054, + 0.5385421166918553, + 0.5904438201692813, + 0.6399192633398297, + 0.6867651409950631, + 0.730788953375287, + 0.7718097971923531, + 0.8096591090000733, + 0.8441813578575781, + 0.8752346844393126, + 0.902691483965435, + 0.9264389305572274, + 0.9463794408628327, + 0.9624310750481792, + 0.9745278735053344, + 0.9826201278946829, + 0.9866745854071558, + 0.9866745854071558, + 0.9826201278946829, + 0.9745278735053344, + 0.9624310750481792, + 0.9463794408628328, + 0.9264389305572275, + 0.9026914839654352, + 0.8752346844393127, + 0.8441813578575782, + 0.8096591090000734, + 0.7718097971923532, + 0.7307889533752873, + 0.6867651409950633, + 0.6399192633398301, + 0.5904438201692815, + 0.5385421166918557, + 0.4844274281400208, + 0.4283221233766012, + 0.3704567511334201, + 0.31106909263710747, + 0.2504031845150382, + 0.18870831599648163, + 0.1262380045296891, + 0.06324895402431663, + 1.208949011235082e-16 + ], + [ + 0, + 0.06403730173966846, + 0.1278114604705305, + 0.19106041449484681, + 0.25352426029367336, + 0.31494632052617, + 0.37507419877185066, + 0.43366081668161455, + 0.49046542927568015, + 0.5452546142163472, + 0.5978032309904515, + 0.6478953460600252, + 0.6953251201795222, + 0.739897654233431, + 0.7814297901185455, + 0.8197508633798987, + 0.854703404507615, + 0.8861437860129042, + 0.9139428126242204, + 0.9379862521783452, + 0.958175305024849, + 0.9744270100150474, + 0.9866745854071558, + 0.9948677032867913, + 0.9989726963751682, + 0.9989726963751682, + 0.9948677032867913, + 0.9866745854071558, + 0.9744270100150474, + 0.9581753050248492, + 0.9379862521783453, + 0.9139428126242206, + 0.8861437860129043, + 0.8547034045076151, + 0.8197508633798988, + 0.7814297901185456, + 0.7398976542334312, + 0.6953251201795223, + 0.6478953460600255, + 0.5978032309904517, + 0.5452546142163477, + 0.49046542927568043, + 0.43366081668161466, + 0.37507419877185105, + 0.3149463205261702, + 0.2535242602936738, + 0.19106041449484706, + 0.127811460470531, + 0.06403730173966878, + 1.2240175954620718e-16 + ], + [ + 0, + 0.06377415873086202, + 0.12728625576398478, + 0.1902753062693571, + 0.2524824747273434, + 0.3136521385393541, + 0.3735329384359338, + 0.4318788113659163, + 0.4884500016222817, + 0.5430140460497843, + 0.5953467292859208, + 0.6452330051099486, + 0.692467880113934, + 0.7368572560646367, + 0.7782187274947842, + 0.8163823312462619, + 0.8511912448851878, + 0.8825024311189311, + 0.9101872255670289, + 0.9341318654707242, + 0.9542379571685435, + 0.9704228804169575, + 0.9826201278946829, + 0.9907795784955328, + 0.9948677032867913, + 0.9948677032867913, + 0.9907795784955328, + 0.9826201278946829, + 0.9704228804169575, + 0.9542379571685436, + 0.9341318654707244, + 0.9101872255670291, + 0.8825024311189312, + 0.8511912448851879, + 0.816382331246262, + 0.7782187274947843, + 0.7368572560646369, + 0.6924678801139341, + 0.645233005109949, + 0.595346729285921, + 0.5430140460497848, + 0.48845000162228197, + 0.43187881136591644, + 0.3735329384359342, + 0.3136521385393543, + 0.2524824747273438, + 0.19027530626935735, + 0.12728625576398528, + 0.06377415873086233, + 1.2189878446113675e-16 + ], + [ + 0, + 0.0624638457988266, + 0.12467101425681293, + 0.1863658827753693, + 0.24729493390624518, + 0.3072077971091034, + 0.3658582775777744, + 0.42300536790752397, + 0.4784142384461746, + 0.5318572022595175, + 0.5831146507457641, + 0.631975956054396, + 0.6782403366011829, + 0.7217176821227794, + 0.7622293348805763, + 0.7996088238036693, + 0.833702548554198, + 0.8643704107040818, + 0.891486389429511, + 0.9149390593575433, + 0.9346320484368628, + 0.9504844339512096, + 0.9624310750481792, + 0.9704228804169575, + 0.9744270100150474, + 0.9744270100150474, + 0.9704228804169575, + 0.9624310750481792, + 0.9504844339512096, + 0.9346320484368629, + 0.9149390593575434, + 0.8914863894295112, + 0.8643704107040819, + 0.8337025485541981, + 0.7996088238036694, + 0.7622293348805764, + 0.7217176821227796, + 0.678240336601183, + 0.6319759560543963, + 0.5831146507457643, + 0.5318572022595179, + 0.47841423844617487, + 0.4230053679075241, + 0.3658582775777748, + 0.30720779710910356, + 0.24729493390624563, + 0.18636588277536956, + 0.12467101425681341, + 0.06246384579882691, + 1.1939423470528823e-16 + ], + [ + 0, + 0.06012787824568068, + 0.12000867814226043, + 0.1793963366385729, + 0.2380468171072439, + 0.2957191121435392, + 0.35217623391648595, + 0.4071861880027047, + 0.46052292670125683, + 0.5119672779121355, + 0.5613078457614364, + 0.6083418792723485, + 0.6528761055124065, + 0.6947275237934285, + 0.7337241576605968, + 0.7697057615805996, + 0.8025244794248994, + 0.8320454520422814, + 0.8581473714240319, + 0.8807229791845672, + 0.8996795073091465, + 0.9149390593575434, + 0.9264389305572275, + 0.9341318654707244, + 0.9379862521783453, + 0.9379862521783453, + 0.9341318654707244, + 0.9264389305572275, + 0.9149390593575434, + 0.8996795073091466, + 0.8807229791845673, + 0.8581473714240321, + 0.8320454520422815, + 0.8025244794248995, + 0.7697057615805997, + 0.733724157660597, + 0.6947275237934287, + 0.6528761055124066, + 0.6083418792723488, + 0.5613078457614367, + 0.5119672779121359, + 0.46052292670125705, + 0.4071861880027048, + 0.35217623391648634, + 0.29571911214353935, + 0.23804681710724432, + 0.17939633663857313, + 0.12000867814226089, + 0.06012787824568098, + 1.1492923491641064e-16 + ], + [ + 0, + 0.0568046125940656, + 0.113375802850431, + 0.16948110761385055, + 0.22488997815250117, + 0.2793747275321742, + 0.33271146623072634, + 0.38468102214815075, + 0.4350698412317479, + 0.4836708650155355, + 0.5302843814678991, + 0.5747188456511682, + 0.6167916668208506, + 0.6563299587301685, + 0.6931712500567296, + 0.7271641520320408, + 0.7581689805304307, + 0.7860583300610848, + 0.8107175973045349, + 0.8320454520422814, + 0.8499542535443965, + 0.8643704107040819, + 0.8752346844393127, + 0.8825024311189312, + 0.8861437860129043, + 0.8861437860129043, + 0.8825024311189312, + 0.8752346844393127, + 0.8643704107040819, + 0.8499542535443966, + 0.8320454520422815, + 0.8107175973045351, + 0.7860583300610849, + 0.7581689805304308, + 0.7271641520320408, + 0.6931712500567297, + 0.6563299587301687, + 0.6167916668208506, + 0.5747188456511684, + 0.5302843814678994, + 0.4836708650155359, + 0.43506984123174813, + 0.38468102214815086, + 0.33271146623072667, + 0.27937472753217435, + 0.22488997815250156, + 0.16948110761385077, + 0.11337580285043145, + 0.056804612594065884, + 1.0857710026759582e-16 + ], + [ + 0, + 0.052548616774104245, + 0.10488130001024075, + 0.15678300348766688, + 0.20804045197391338, + 0.2584430176184621, + 0.30778358546776313, + 0.3558594045450051, + 0.4024729209973687, + 0.44743258988718326, + 0.49055366229116193, + 0.5316589444733557, + 0.5705795260122224, + 0.6071554738897803, + 0.6412364896906845, + 0.6726825272106539, + 0.7013643679363651, + 0.7271641520320408, + 0.7499758626507952, + 0.7697057615805996, + 0.7862727744347011, + 0.7996088238036694, + 0.8096591090000734, + 0.816382331246262, + 0.8197508633798988, + 0.8197508633798988, + 0.816382331246262, + 0.8096591090000734, + 0.7996088238036694, + 0.7862727744347012, + 0.7697057615805997, + 0.7499758626507954, + 0.7271641520320408, + 0.7013643679363651, + 0.672682527210654, + 0.6412364896906846, + 0.6071554738897805, + 0.5705795260122224, + 0.5316589444733559, + 0.4905536622911621, + 0.44743258988718365, + 0.4024729209973689, + 0.3558594045450052, + 0.30778358546776347, + 0.2584430176184623, + 0.20804045197391377, + 0.1567830034876671, + 0.10488130001024117, + 0.05254861677410451, + 1.0044213263416301e-16 + ], + [ + 0, + 0.047429774119497024, + 0.09466464912348241, + 0.14151052677871584, + 0.1877749073255027, + 0.2332676805004978, + 0.27780190674055577, + 0.32119458535749473, + 0.3632674065271772, + 0.40384748400282516, + 0.44276806554169185, + 0.4798692181257956, + 0.5149984851609959, + 0.548011512953841, + 0.5787726438918579, + 0.6071554738897804, + 0.633043371811049, + 0.6563299587301686, + 0.6769195450665313, + 0.6947275237934286, + 0.7096807181064723, + 0.7217176821227796, + 0.7307889533752873, + 0.7368572560646369, + 0.7398976542334312, + 0.7398976542334312, + 0.7368572560646369, + 0.7307889533752873, + 0.7217176821227796, + 0.7096807181064723, + 0.6947275237934287, + 0.6769195450665315, + 0.6563299587301687, + 0.6330433718110491, + 0.6071554738897805, + 0.578772643891858, + 0.5480115129538411, + 0.514998485160996, + 0.47986921812579586, + 0.442768065541692, + 0.4038474840028255, + 0.36326740652717737, + 0.32119458535749484, + 0.27780190674055605, + 0.23326768050049795, + 0.18777490732550303, + 0.14151052677871603, + 0.09466464912348277, + 0.04742977411949726, + 9.065790795974991e-17 + ], + [ + 0, + 0.041532135885114556, + 0.08289360731526198, + 0.12391445113232798, + 0.1644261038901248, + 0.20426209451774846, + 0.2432587283849168, + 0.281255759958318, + 0.31809705128487903, + 0.353631213596107, + 0.3877122293970111, + 0.4202000524833106, + 0.4509611834213275, + 0.4798692181257957, + 0.5068053672813605, + 0.5316589444733558, + 0.5543278210220242, + 0.5747188456511684, + 0.592748227266726, + 0.6083418792723487, + 0.6214357240071176, + 0.6319759560543963, + 0.6399192633398301, + 0.645233005109949, + 0.6478953460600255, + 0.6478953460600255, + 0.645233005109949, + 0.6399192633398301, + 0.6319759560543963, + 0.6214357240071177, + 0.6083418792723488, + 0.5927482272667262, + 0.5747188456511684, + 0.5543278210220243, + 0.5316589444733559, + 0.5068053672813606, + 0.47986921812579586, + 0.45096118342132757, + 0.4202000524833108, + 0.3877122293970113, + 0.3536312135961073, + 0.3180970512848792, + 0.28125575995831803, + 0.24325872838491705, + 0.2042620945177486, + 0.16442610389012507, + 0.12391445113232813, + 0.0828936073152623, + 0.041532135885114764, + 7.938508294301087e-17 + ], + [ + 0, + 0.03495254112771636, + 0.06976145476664239, + 0.10428370362414716, + 0.138377428374676, + 0.17190253059014804, + 0.20472124843444797, + 0.2366987227563607, + 0.2677035512547507, + 0.29760832843880325, + 0.32629016916451453, + 0.3536312135961071, + 0.3795191115173757, + 0.40384748400282533, + 0.4265163605514937, + 0.4474325898871836, + 0.4665102227370374, + 0.48367086501553586, + 0.49884399996261025, + 0.5119672779121358, + 0.5229867725000837, + 0.5318572022595179, + 0.5385421166918557, + 0.5430140460497848, + 0.5452546142163477, + 0.5452546142163477, + 0.5430140460497848, + 0.5385421166918557, + 0.5318572022595179, + 0.5229867725000839, + 0.5119672779121359, + 0.49884399996261036, + 0.4836708650155359, + 0.46651022273703746, + 0.44743258988718365, + 0.4265163605514938, + 0.4038474840028255, + 0.3795191115173758, + 0.3536312135961073, + 0.32629016916451464, + 0.2976083284388035, + 0.26770355125475087, + 0.23669872275636075, + 0.20472124843444817, + 0.17190253059014815, + 0.13837742837467626, + 0.1042837036241473, + 0.06976145476664265, + 0.034952541127716535, + 6.680875705906664e-17 + ], + [ + 0, + 0.027799026611316207, + 0.05548382105941401, + 0.08294062058553639, + 0.11005659931096547, + 0.13672033186275928, + 0.1628222512445098, + 0.18825509907063329, + 0.2129143663140834, + 0.23669872275636056, + 0.2595104333751151, + 0.28125575995831786, + 0.30184534629468057, + 0.32119458535749473, + 0.33922396697305246, + 0.35585940454500514, + 0.3710325394920795, + 0.3846810221481508, + 0.3967487679703949, + 0.40718618800270473, + 0.41595039264734807, + 0.4230053679075241, + 0.4283221233766012, + 0.43187881136591644, + 0.43366081668161466, + 0.43366081668161466, + 0.43187881136591644, + 0.4283221233766012, + 0.4230053679075241, + 0.4159503926473481, + 0.4071861880027048, + 0.396748767970395, + 0.38468102214815086, + 0.37103253949207954, + 0.3558594045450052, + 0.3392239669730525, + 0.32119458535749484, + 0.3018453462946806, + 0.28125575995831803, + 0.25951043337511515, + 0.23669872275636075, + 0.2129143663140835, + 0.18825509907063334, + 0.16282225124450997, + 0.1367203318627594, + 0.11005659931096566, + 0.0829406205855365, + 0.05548382105941423, + 0.027799026611316346, + 5.3135433231240294e-17 + ], + [ + 0, + 0.020189052846503835, + 0.04029514454432313, + 0.06023565484992841, + 0.07992864392924788, + 0.09929318906602172, + 0.11824971719060101, + 0.13672033186275934, + 0.15462913336487435, + 0.171902530590148, + 0.1884695434442496, + 0.2042620945177485, + 0.21921528883079205, + 0.2332676805004979, + 0.24636152523526667, + 0.2584430176184623, + 0.26946251220641015, + 0.27937472753217435, + 0.28813893217681763, + 0.29571911214353935, + 0.30208411884691255, + 0.30720779710910356, + 0.31106909263710747, + 0.3136521385393543, + 0.3149463205261702, + 0.3149463205261702, + 0.3136521385393543, + 0.31106909263710747, + 0.30720779710910356, + 0.3020841188469126, + 0.29571911214353935, + 0.28813893217681774, + 0.27937472753217435, + 0.2694625122064102, + 0.2584430176184623, + 0.2463615252352667, + 0.23326768050049795, + 0.21921528883079208, + 0.2042620945177486, + 0.18846954344424965, + 0.17190253059014815, + 0.15462913336487447, + 0.1367203318627594, + 0.11824971719060114, + 0.09929318906602179, + 0.07992864392924802, + 0.06023565484992849, + 0.04029514454432329, + 0.020189052846503935, + 3.8589627058765365e-17 + ], + [ + 0, + 0.01224757539210836, + 0.024444822869833866, + 0.03654162132698916, + 0.048488262423958664, + 0.06023565484992845, + 0.07173552604961243, + 0.08294062058553649, + 0.09380489432076723, + 0.10428370362414721, + 0.11433398882055129, + 0.12391445113232807, + 0.13298572238483566, + 0.14151052677871598, + 0.14945383406414978, + 0.15678300348766708, + 0.16346791792000476, + 0.16948110761385074, + 0.17479786308292783, + 0.1793963366385731, + 0.18325763216657698, + 0.18636588277536956, + 0.18870831599648163, + 0.19027530626935735, + 0.19106041449484706, + 0.19106041449484706, + 0.19027530626935735, + 0.18870831599648163, + 0.18636588277536956, + 0.183257632166577, + 0.17939633663857313, + 0.17479786308292786, + 0.16948110761385077, + 0.16346791792000478, + 0.1567830034876671, + 0.14945383406414978, + 0.14151052677871603, + 0.1329857223848357, + 0.12391445113232813, + 0.11433398882055133, + 0.1042837036241473, + 0.09380489432076727, + 0.0829406205855365, + 0.0717355260496125, + 0.06023565484992849, + 0.04848826242395875, + 0.03654162132698921, + 0.02444482286983396, + 0.01224757539210842, + 2.3410180276853326e-17 + ], + [ + 0, + 0.004104993088376964, + 0.008193117879635533, + 0.012247575392108405, + 0.01625170499019842, + 0.02018905284650392, + 0.024043439554124885, + 0.02779902661131634, + 0.03144038150528938, + 0.03495254112771651, + 0.03832107326135329, + 0.04153213588511474, + 0.044572534053909034, + 0.047429774119497246, + 0.05009211506957381, + 0.0525486167741045, + 0.054789184940667444, + 0.05680461259406588, + 0.0585866179097641, + 0.06012787824568097, + 0.061422060232496904, + 0.06246384579882691, + 0.06324895402431663, + 0.06377415873086233, + 0.06403730173966878, + 0.06403730173966878, + 0.06377415873086233, + 0.06324895402431663, + 0.06246384579882691, + 0.06142206023249691, + 0.06012787824568098, + 0.05858661790976411, + 0.056804612594065884, + 0.05478918494066745, + 0.05254861677410451, + 0.05009211506957382, + 0.04742977411949726, + 0.04457253405390904, + 0.041532135885114764, + 0.038321073261353304, + 0.034952541127716535, + 0.031440381505289404, + 0.027799026611316346, + 0.02404343955412491, + 0.020189052846503935, + 0.016251704990198446, + 0.01224757539210842, + 0.008193117879635564, + 0.004104993088376985, + 7.846338982004726e-18 + ], + [ + 0, + -0.004104993088376921, + -0.008193117879635446, + -0.012247575392108275, + -0.016251704990198245, + -0.020189052846503706, + -0.024043439554124628, + -0.027799026611316044, + -0.03144038150528905, + -0.03495254112771614, + -0.03832107326135288, + -0.0415321358851143, + -0.04457253405390856, + -0.04742977411949675, + -0.05009211506957328, + -0.05254861677410394, + -0.05478918494066686, + -0.056804612594065274, + -0.05858661790976347, + -0.06012787824568033, + -0.06142206023249625, + -0.062463845798826245, + -0.06324895402431596, + -0.06377415873086166, + -0.0640373017396681, + -0.0640373017396681, + -0.06377415873086166, + -0.06324895402431596, + -0.062463845798826245, + -0.06142206023249626, + -0.06012787824568034, + -0.05858661790976349, + -0.05680461259406528, + -0.05478918494066687, + -0.05254861677410395, + -0.050092115069573284, + -0.04742977411949676, + -0.04457253405390857, + -0.04153213588511432, + -0.038321073261352895, + -0.03495254112771617, + -0.031440381505289064, + -0.02779902661131605, + -0.024043439554124652, + -0.02018905284650372, + -0.016251704990198273, + -0.01224757539210829, + -0.008193117879635477, + -0.0041049930883769415, + -7.846338982004641e-18 + ], + [ + 0, + -0.012247575392108316, + -0.02444482286983378, + -0.036541621326989036, + -0.04848826242395849, + -0.06023565484992824, + -0.07173552604961218, + -0.0829406205855362, + -0.0938048943207669, + -0.10428370362414685, + -0.1143339888205509, + -0.12391445113232763, + -0.1329857223848352, + -0.14151052677871548, + -0.14945383406414925, + -0.15678300348766652, + -0.1634679179200042, + -0.16948110761385016, + -0.17479786308292722, + -0.1793963366385725, + -0.18325763216657634, + -0.18636588277536892, + -0.188708315996481, + -0.19027530626935668, + -0.1910604144948464, + -0.1910604144948464, + -0.19027530626935668, + -0.188708315996481, + -0.18636588277536892, + -0.18325763216657637, + -0.17939633663857252, + -0.17479786308292725, + -0.16948110761385018, + -0.16346791792000423, + -0.15678300348766655, + -0.14945383406414928, + -0.14151052677871553, + -0.13298572238483522, + -0.1239144511323277, + -0.11433398882055094, + -0.10428370362414693, + -0.09380489432076695, + -0.08294062058553621, + -0.07173552604961225, + -0.06023565484992828, + -0.048488262423958574, + -0.036541621326989085, + -0.024444822869833877, + -0.012247575392108377, + -2.3410180276853242e-17 + ], + [ + 0, + -0.020189052846503793, + -0.04029514454432305, + -0.06023565484992829, + -0.07992864392924771, + -0.09929318906602151, + -0.11824971719060076, + -0.13672033186275906, + -0.15462913336487405, + -0.17190253059014765, + -0.1884695434442492, + -0.20426209451774807, + -0.21921528883079158, + -0.2332676805004974, + -0.24636152523526614, + -0.2584430176184617, + -0.2694625122064096, + -0.27937472753217374, + -0.288138932176817, + -0.2957191121435387, + -0.30208411884691194, + -0.30720779710910295, + -0.3110690926371068, + -0.31365213853935364, + -0.31494632052616955, + -0.31494632052616955, + -0.31365213853935364, + -0.3110690926371068, + -0.30720779710910295, + -0.302084118846912, + -0.29571911214353874, + -0.28813893217681713, + -0.2793747275321738, + -0.2694625122064096, + -0.2584430176184617, + -0.24636152523526617, + -0.23326768050049748, + -0.2192152888307916, + -0.20426209451774816, + -0.18846954344424927, + -0.1719025305901478, + -0.15462913336487413, + -0.1367203318627591, + -0.11824971719060089, + -0.09929318906602158, + -0.07992864392924785, + -0.06023565484992836, + -0.0402951445443232, + -0.020189052846503894, + -3.858962705876528e-17 + ], + [ + 0, + -0.027799026611316193, + -0.05548382105941398, + -0.08294062058553635, + -0.11005659931096541, + -0.13672033186275923, + -0.16282225124450972, + -0.18825509907063318, + -0.21291436631408328, + -0.23669872275636045, + -0.2595104333751149, + -0.28125575995831775, + -0.30184534629468046, + -0.32119458535749457, + -0.3392239669730523, + -0.355859404545005, + -0.3710325394920793, + -0.38468102214815064, + -0.39674876797039466, + -0.40718618800270456, + -0.4159503926473479, + -0.42300536790752385, + -0.42832212337660097, + -0.4318788113659162, + -0.43366081668161444, + -0.43366081668161444, + -0.4318788113659162, + -0.42832212337660097, + -0.42300536790752385, + -0.41595039264734796, + -0.40718618800270456, + -0.39674876797039477, + -0.38468102214815064, + -0.37103253949207937, + -0.35585940454500503, + -0.3392239669730523, + -0.3211945853574947, + -0.30184534629468046, + -0.28125575995831786, + -0.25951043337511503, + -0.23669872275636064, + -0.2129143663140834, + -0.18825509907063323, + -0.16282225124450989, + -0.1367203318627593, + -0.1100565993109656, + -0.08294062058553646, + -0.0554838210594142, + -0.027799026611316332, + -5.3135433231240263e-17 + ], + [ + 0, + -0.03495254112771633, + -0.06976145476664232, + -0.10428370362414704, + -0.13837742837467587, + -0.17190253059014787, + -0.20472124843444775, + -0.23669872275636045, + -0.2677035512547504, + -0.29760832843880297, + -0.3262901691645142, + -0.3536312135961067, + -0.37951911151737533, + -0.40384748400282494, + -0.42651636055149333, + -0.44743258988718315, + -0.46651022273703696, + -0.48367086501553536, + -0.4988439999626097, + -0.5119672779121354, + -0.5229867725000832, + -0.5318572022595174, + -0.5385421166918551, + -0.5430140460497842, + -0.5452546142163471, + -0.5452546142163471, + -0.5430140460497842, + -0.5385421166918551, + -0.5318572022595174, + -0.5229867725000833, + -0.5119672779121354, + -0.49884399996260986, + -0.4836708650155354, + -0.466510222737037, + -0.4474325898871832, + -0.4265163605514934, + -0.40384748400282505, + -0.3795191115173754, + -0.3536312135961069, + -0.3262901691645143, + -0.2976083284388032, + -0.2677035512547506, + -0.23669872275636053, + -0.20472124843444797, + -0.17190253059014798, + -0.13837742837467612, + -0.10428370362414718, + -0.06976145476664258, + -0.0349525411277165, + -6.680875705906658e-17 + ], + [ + 0, + -0.04153213588511452, + -0.0828936073152619, + -0.12391445113232787, + -0.16442610389012466, + -0.2042620945177483, + -0.24325872838491658, + -0.2812557599583177, + -0.31809705128487875, + -0.35363121359610666, + -0.3877122293970108, + -0.42020005248331027, + -0.4509611834213271, + -0.4798692181257953, + -0.50680536728136, + -0.5316589444733554, + -0.5543278210220237, + -0.5747188456511678, + -0.5927482272667255, + -0.6083418792723483, + -0.621435724007117, + -0.6319759560543958, + -0.6399192633398295, + -0.6452330051099484, + -0.647895346060025, + -0.647895346060025, + -0.6452330051099484, + -0.6399192633398295, + -0.6319759560543958, + -0.6214357240071171, + -0.6083418792723483, + -0.5927482272667257, + -0.5747188456511679, + -0.5543278210220238, + -0.5316589444733555, + -0.5068053672813602, + -0.4798692181257954, + -0.4509611834213272, + -0.4202000524833105, + -0.38771222939701094, + -0.35363121359610694, + -0.3180970512848789, + -0.2812557599583178, + -0.24325872838491683, + -0.20426209451774843, + -0.16442610389012494, + -0.12391445113232803, + -0.08289360731526223, + -0.04153213588511473, + -7.938508294301079e-17 + ], + [ + 0, + -0.047429774119497, + -0.09466464912348235, + -0.14151052677871576, + -0.1877749073255026, + -0.23326768050049765, + -0.2778019067405556, + -0.32119458535749457, + -0.363267406527177, + -0.4038474840028249, + -0.44276806554169157, + -0.4798692181257953, + -0.5149984851609956, + -0.5480115129538407, + -0.5787726438918576, + -0.60715547388978, + -0.6330433718110486, + -0.6563299587301682, + -0.676919545066531, + -0.6947275237934282, + -0.7096807181064718, + -0.7217176821227792, + -0.7307889533752868, + -0.7368572560646365, + -0.7398976542334308, + -0.7398976542334308, + -0.7368572560646365, + -0.7307889533752868, + -0.7217176821227792, + -0.7096807181064719, + -0.6947275237934283, + -0.6769195450665311, + -0.6563299587301683, + -0.6330433718110487, + -0.6071554738897801, + -0.5787726438918577, + -0.5480115129538409, + -0.5149984851609957, + -0.4798692181257956, + -0.44276806554169174, + -0.4038474840028252, + -0.3632674065271772, + -0.3211945853574946, + -0.2778019067405559, + -0.23326768050049781, + -0.18777490732550292, + -0.14151052677871595, + -0.09466464912348271, + -0.04742977411949723, + -9.065790795974986e-17 + ], + [ + 0, + -0.052548616774104225, + -0.10488130001024071, + -0.15678300348766683, + -0.2080404519739133, + -0.258443017618462, + -0.307783585467763, + -0.355859404545005, + -0.40247292099736853, + -0.4474325898871831, + -0.4905536622911617, + -0.5316589444733555, + -0.5705795260122221, + -0.6071554738897801, + -0.6412364896906843, + -0.6726825272106536, + -0.7013643679363648, + -0.7271641520320404, + -0.7499758626507949, + -0.7697057615805992, + -0.7862727744347008, + -0.799608823803669, + -0.8096591090000731, + -0.8163823312462617, + -0.8197508633798984, + -0.8197508633798984, + -0.8163823312462617, + -0.8096591090000731, + -0.799608823803669, + -0.7862727744347009, + -0.7697057615805993, + -0.7499758626507951, + -0.7271641520320405, + -0.7013643679363649, + -0.6726825272106537, + -0.6412364896906843, + -0.6071554738897802, + -0.5705795260122222, + -0.5316589444733557, + -0.4905536622911619, + -0.4474325898871835, + -0.40247292099736875, + -0.35585940454500503, + -0.3077835854677633, + -0.25844301761846217, + -0.20804045197391366, + -0.15678300348766702, + -0.10488130001024112, + -0.05254861677410449, + -1.0044213263416298e-16 + ], + [ + 0, + -0.05680461259406559, + -0.11337580285043099, + -0.16948110761385052, + -0.22488997815250114, + -0.2793747275321741, + -0.3327114662307263, + -0.3846810221481507, + -0.43506984123174786, + -0.48367086501553547, + -0.530284381467899, + -0.574718845651168, + -0.6167916668208505, + -0.6563299587301684, + -0.6931712500567295, + -0.7271641520320407, + -0.7581689805304306, + -0.7860583300610847, + -0.8107175973045347, + -0.8320454520422813, + -0.8499542535443964, + -0.8643704107040818, + -0.8752346844393126, + -0.8825024311189311, + -0.8861437860129042, + -0.8861437860129042, + -0.8825024311189311, + -0.8752346844393126, + -0.8643704107040818, + -0.8499542535443965, + -0.8320454520422814, + -0.810717597304535, + -0.7860583300610848, + -0.7581689805304307, + -0.7271641520320408, + -0.6931712500567296, + -0.6563299587301686, + -0.6167916668208506, + -0.5747188456511684, + -0.5302843814678992, + -0.48367086501553586, + -0.4350698412317481, + -0.3846810221481508, + -0.3327114662307266, + -0.27937472753217435, + -0.22488997815250153, + -0.16948110761385074, + -0.11337580285043143, + -0.05680461259406588, + -1.085771002675958e-16 + ], + [ + 0, + -0.060127878245680666, + -0.1200086781422604, + -0.17939633663857285, + -0.23804681710724385, + -0.2957191121435391, + -0.3521762339164859, + -0.4071861880027046, + -0.4605229267012567, + -0.5119672779121354, + -0.5613078457614363, + -0.6083418792723484, + -0.6528761055124064, + -0.6947275237934284, + -0.7337241576605967, + -0.7697057615805993, + -0.8025244794248992, + -0.8320454520422812, + -0.8581473714240317, + -0.880722979184567, + -0.8996795073091463, + -0.9149390593575433, + -0.9264389305572273, + -0.9341318654707241, + -0.9379862521783451, + -0.9379862521783451, + -0.9341318654707241, + -0.9264389305572273, + -0.9149390593575433, + -0.8996795073091464, + -0.8807229791845671, + -0.858147371424032, + -0.8320454520422813, + -0.8025244794248994, + -0.7697057615805994, + -0.7337241576605968, + -0.6947275237934285, + -0.6528761055124064, + -0.6083418792723487, + -0.5613078457614366, + -0.5119672779121358, + -0.46052292670125694, + -0.4071861880027047, + -0.3521762339164862, + -0.2957191121435393, + -0.23804681710724426, + -0.1793963366385731, + -0.12000867814226086, + -0.060127878245680964, + -1.1492923491641061e-16 + ], + [ + 0, + -0.0624638457988266, + -0.12467101425681293, + -0.1863658827753693, + -0.24729493390624518, + -0.3072077971091034, + -0.3658582775777744, + -0.42300536790752397, + -0.4784142384461746, + -0.5318572022595175, + -0.5831146507457641, + -0.631975956054396, + -0.6782403366011829, + -0.7217176821227794, + -0.7622293348805763, + -0.7996088238036693, + -0.833702548554198, + -0.8643704107040818, + -0.891486389429511, + -0.9149390593575433, + -0.9346320484368628, + -0.9504844339512096, + -0.9624310750481792, + -0.9704228804169575, + -0.9744270100150474, + -0.9744270100150474, + -0.9704228804169575, + -0.9624310750481792, + -0.9504844339512096, + -0.9346320484368629, + -0.9149390593575434, + -0.8914863894295112, + -0.8643704107040819, + -0.8337025485541981, + -0.7996088238036694, + -0.7622293348805764, + -0.7217176821227796, + -0.678240336601183, + -0.6319759560543963, + -0.5831146507457643, + -0.5318572022595179, + -0.47841423844617487, + -0.4230053679075241, + -0.3658582775777748, + -0.30720779710910356, + -0.24729493390624563, + -0.18636588277536956, + -0.12467101425681341, + -0.06246384579882691, + -1.1939423470528823e-16 + ], + [ + 0, + -0.06377415873086201, + -0.12728625576398475, + -0.19027530626935707, + -0.25248247472734336, + -0.31365213853935403, + -0.37353293843593377, + -0.43187881136591627, + -0.48845000162228164, + -0.5430140460497843, + -0.5953467292859208, + -0.6452330051099486, + -0.6924678801139339, + -0.7368572560646366, + -0.778218727494784, + -0.8163823312462618, + -0.8511912448851877, + -0.8825024311189311, + -0.9101872255670288, + -0.9341318654707241, + -0.9542379571685434, + -0.9704228804169573, + -0.9826201278946828, + -0.9907795784955327, + -0.9948677032867912, + -0.9948677032867912, + -0.9907795784955327, + -0.9826201278946828, + -0.9704228804169573, + -0.9542379571685435, + -0.9341318654707242, + -0.910187225567029, + -0.8825024311189312, + -0.8511912448851878, + -0.8163823312462619, + -0.7782187274947842, + -0.7368572560646368, + -0.692467880113934, + -0.6452330051099489, + -0.595346729285921, + -0.5430140460497848, + -0.4884500016222819, + -0.4318788113659164, + -0.37353293843593416, + -0.31365213853935425, + -0.2524824747273438, + -0.19027530626935732, + -0.12728625576398525, + -0.06377415873086233, + -1.2189878446113672e-16 + ], + [ + 0, + -0.06403730173966846, + -0.1278114604705305, + -0.19106041449484681, + -0.25352426029367336, + -0.31494632052617, + -0.37507419877185066, + -0.43366081668161455, + -0.49046542927568015, + -0.5452546142163472, + -0.5978032309904515, + -0.6478953460600252, + -0.6953251201795222, + -0.739897654233431, + -0.7814297901185455, + -0.8197508633798987, + -0.854703404507615, + -0.8861437860129042, + -0.9139428126242204, + -0.9379862521783452, + -0.958175305024849, + -0.9744270100150474, + -0.9866745854071558, + -0.9948677032867913, + -0.9989726963751682, + -0.9989726963751682, + -0.9948677032867913, + -0.9866745854071558, + -0.9744270100150474, + -0.9581753050248492, + -0.9379862521783453, + -0.9139428126242206, + -0.8861437860129043, + -0.8547034045076151, + -0.8197508633798988, + -0.7814297901185456, + -0.7398976542334312, + -0.6953251201795223, + -0.6478953460600255, + -0.5978032309904517, + -0.5452546142163477, + -0.49046542927568043, + -0.43366081668161466, + -0.37507419877185105, + -0.3149463205261702, + -0.2535242602936738, + -0.19106041449484706, + -0.127811460470531, + -0.06403730173966878, + -1.2240175954620718e-16 + ], + [ + 0, + -0.06324895402431632, + -0.12623800452968864, + -0.1887083159964814, + -0.2504031845150378, + -0.31106909263710725, + -0.37045675113341975, + -0.42832212337660114, + -0.4844274281400206, + -0.5385421166918554, + -0.5904438201692814, + -0.6399192633398298, + -0.6867651409950633, + -0.7307889533752872, + -0.7718097971923532, + -0.8096591090000734, + -0.8441813578575782, + -0.8752346844393127, + -0.9026914839654351, + -0.9264389305572275, + -0.9463794408628328, + -0.9624310750481793, + -0.9745278735053345, + -0.982620127894683, + -0.9866745854071559, + -0.9866745854071559, + -0.982620127894683, + -0.9745278735053345, + -0.9624310750481793, + -0.9463794408628329, + -0.9264389305572275, + -0.9026914839654353, + -0.8752346844393128, + -0.8441813578575783, + -0.8096591090000735, + -0.7718097971923533, + -0.7307889533752874, + -0.6867651409950634, + -0.6399192633398302, + -0.5904438201692817, + -0.5385421166918558, + -0.4844274281400209, + -0.42832212337660125, + -0.37045675113342014, + -0.31106909263710747, + -0.25040318451503824, + -0.18870831599648166, + -0.12623800452968914, + -0.06324895402431663, + -1.2089490112350823e-16 + ], + [ + 0, + -0.06142206023249661, + -0.1225917240445073, + -0.18325763216657678, + -0.24317049536943494, + -0.30208411884691244, + -0.35975641388320767, + -0.41595039264734807, + -0.470435142027021, + -0.5229867725000835, + -0.5733893381446322, + -0.6214357240071173, + -0.6669284971821124, + -0.7096807181064722, + -0.7495167087340958, + -0.7862727744347012, + -0.8197978766501732, + -0.8499542535443966, + -0.8766179860961903, + -0.8996795073091466, + -0.9190440524459205, + -0.934632048436863, + -0.9463794408628329, + -0.9542379571685438, + -0.9581753050248493, + -0.9581753050248493, + -0.9542379571685438, + -0.9463794408628329, + -0.934632048436863, + -0.9190440524459206, + -0.8996795073091467, + -0.8766179860961906, + -0.8499542535443967, + -0.8197978766501732, + -0.7862727744347013, + -0.7495167087340959, + -0.7096807181064724, + -0.6669284971821126, + -0.6214357240071177, + -0.5733893381446323, + -0.5229867725000839, + -0.4704351420270213, + -0.4159503926473482, + -0.35975641388320806, + -0.30208411884691266, + -0.24317049536943536, + -0.18325763216657703, + -0.12259172404450779, + -0.06142206023249692, + -1.174029517666812e-16 + ], + [ + 0, + -0.058586617909763834, + -0.11693249083974633, + -0.1747978630829277, + -0.2319449534126772, + -0.2881389321768176, + -0.3431488862630363, + -0.39674876797039493, + -0.44871832388781935, + -0.4988439999626101, + -0.546919819039852, + -0.592748227266726, + -0.6361409058836649, + -0.6769195450665315, + -0.7149165766399326, + -0.7499758626507954, + -0.7819533369727081, + -0.8107175973045352, + -0.8361504451306586, + -0.8581473714240322, + -0.8766179860961906, + -0.8914863894295113, + -0.9026914839654354, + -0.9101872255670294, + -0.9139428126242208, + -0.9139428126242208, + -0.9101872255670294, + -0.9026914839654354, + -0.8914863894295113, + -0.8766179860961907, + -0.8581473714240323, + -0.8361504451306588, + -0.8107175973045353, + -0.7819533369727082, + -0.7499758626507955, + -0.7149165766399327, + -0.6769195450665316, + -0.636140905883665, + -0.5927482272667264, + -0.5469198190398522, + -0.4988439999626105, + -0.4487183238878196, + -0.39674876797039504, + -0.34314888626303663, + -0.2881389321768178, + -0.23194495341267762, + -0.1747978630829279, + -0.11693249083974679, + -0.058586617909764126, + -1.1198324918762505e-16 + ], + [ + 0, + -0.054789184940667195, + -0.10935322936816988, + -0.16346791792000462, + -0.2169108817333476, + -0.26946251220641004, + -0.3209068634172888, + -0.37103253949207954, + -0.4196335632758672, + -0.46651022273703724, + -0.5114698916268519, + -0.5543278210220242, + -0.5949078984976721, + -0.6330433718110491, + -0.668577534122277, + -0.7013643679363653, + -0.7312691451204177, + -0.7581689805304308, + -0.7819533369727081, + -0.8025244794248996, + -0.8197978766501733, + -0.8337025485541983, + -0.8441813578575784, + -0.8511912448851882, + -0.8547034045076153, + -0.8547034045076153, + -0.8511912448851882, + -0.8441813578575784, + -0.8337025485541983, + -0.8197978766501735, + -0.8025244794248997, + -0.7819533369727082, + -0.7581689805304309, + -0.7312691451204179, + -0.7013643679363654, + -0.6685775341222772, + -0.6330433718110492, + -0.5949078984976721, + -0.5543278210220244, + -0.5114698916268521, + -0.4665102227370376, + -0.4196335632758674, + -0.37103253949207965, + -0.3209068634172891, + -0.26946251220641027, + -0.21691088173334797, + -0.16346791792000484, + -0.10935322936817031, + -0.054789184940667465, + -1.0472478475285211e-16 + ], + [ + 0, + -0.05009211506957357, + -0.09997839089360128, + -0.14945383406414958, + -0.19831513937278142, + -0.24636152523526653, + -0.29339555874617845, + -0.3392239669730524, + -0.3836584311563213, + -0.42651636055149345, + -0.4676216427336871, + -0.5068053672813604, + -0.543906519865464, + -0.5787726438918578, + -0.6112604669781573, + -0.6412364896906845, + -0.6685775341222769, + -0.6931712500567296, + -0.7149165766399324, + -0.7337241576605968, + -0.7495167087340958, + -0.7622293348805764, + -0.7718097971923532, + -0.7782187274947843, + -0.7814297901185456, + -0.7814297901185456, + -0.7782187274947843, + -0.7718097971923532, + -0.7622293348805764, + -0.7495167087340958, + -0.733724157660597, + -0.7149165766399326, + -0.6931712500567297, + -0.6685775341222769, + -0.6412364896906846, + -0.6112604669781574, + -0.578772643891858, + -0.5439065198654641, + -0.5068053672813606, + -0.4676216427336873, + -0.4265163605514938, + -0.38365843115632153, + -0.3392239669730525, + -0.2933955587461788, + -0.2463615252352667, + -0.19831513937278175, + -0.14945383406414978, + -0.09997839089360167, + -0.05009211506957382, + -9.574674224771029e-17 + ], + [ + 0, + -0.04457253405390885, + -0.08896191000461162, + -0.1329857223848356, + -0.17646306790643226, + -0.21921528883079208, + -0.2610667071118141, + -0.30184534629468074, + -0.34138363820399875, + -0.3795191115173757, + -0.4160950593949337, + -0.4509611834213276, + -0.4839742112141728, + -0.5149984851609961, + -0.5439065198654643, + -0.5705795260122227, + -0.5949078984976723, + -0.616791666820851, + -0.6361409058836651, + -0.6528761055124069, + -0.6669284971821128, + -0.6782403366011833, + -0.6867651409950637, + -0.6924678801139346, + -0.6953251201795227, + -0.6953251201795227, + -0.6924678801139346, + -0.6867651409950637, + -0.6782403366011833, + -0.6669284971821129, + -0.652876105512407, + -0.6361409058836652, + -0.6167916668208511, + -0.5949078984976723, + -0.5705795260122228, + -0.5439065198654645, + -0.5149984851609963, + -0.48397421121417283, + -0.4509611834213279, + -0.41609505939493385, + -0.37951911151737605, + -0.3413836382039989, + -0.30184534629468085, + -0.2610667071118144, + -0.21921528883079222, + -0.17646306790643257, + -0.13298572238483578, + -0.08896191000461197, + -0.04457253405390907, + -8.519654088192268e-17 + ], + [ + 0, + -0.03832107326135312, + -0.0764846770128309, + -0.11433398882055121, + -0.15171347774364416, + -0.18846954344424957, + -0.22445114736425226, + -0.25951043337511515, + -0.2935033353504262, + -0.3262901691645144, + -0.35773620668448386, + -0.38771222939701117, + -0.41609505939493363, + -0.44276806554169196, + -0.46762164273368734, + -0.4905536622911621, + -0.511469891626852, + -0.5302843814678994, + -0.5469198190398521, + -0.5613078457614368, + -0.5733893381446323, + -0.5831146507457644, + -0.5904438201692817, + -0.5953467292859211, + -0.5978032309904519, + -0.5978032309904519, + -0.5953467292859211, + -0.5904438201692817, + -0.5831146507457644, + -0.5733893381446324, + -0.5613078457614368, + -0.5469198190398522, + -0.5302843814678995, + -0.511469891626852, + -0.49055366229116215, + -0.4676216427336874, + -0.44276806554169207, + -0.4160950593949337, + -0.38771222939701133, + -0.357736206684484, + -0.3262901691645147, + -0.2935033353504264, + -0.2595104333751152, + -0.22445114736425248, + -0.1884695434442497, + -0.1517134777436444, + -0.11433398882055136, + -0.07648467701283121, + -0.03832107326135331, + -7.324741467023933e-17 + ], + [ + 0, + -0.03144038150528928, + -0.06275156773903263, + -0.09380489432076725, + -0.12447275647065109, + -0.1546291333648745, + -0.18415010598225653, + -0.21291436631408367, + -0.24080371584473784, + -0.2677035512547509, + -0.29350333535042655, + -0.31809705128487936, + -0.341383638203999, + -0.36326740652717765, + -0.38365843115632187, + -0.40247292099736925, + -0.4196335632758677, + -0.4350698412317485, + -0.44871832388781985, + -0.4605229267012575, + -0.4704351420270217, + -0.47841423844617537, + -0.4844274281400213, + -0.48845000162228247, + -0.49046542927568093, + -0.49046542927568093, + -0.48845000162228247, + -0.4844274281400213, + -0.47841423844617537, + -0.47043514202702175, + -0.46052292670125755, + -0.44871832388781996, + -0.4350698412317486, + -0.41963356327586776, + -0.4024729209973693, + -0.3836584311563219, + -0.36326740652717776, + -0.34138363820399903, + -0.31809705128487953, + -0.29350333535042666, + -0.2677035512547511, + -0.24080371584473798, + -0.21291436631408373, + -0.18415010598225673, + -0.1546291333648746, + -0.1244727564706513, + -0.09380489432076737, + -0.06275156773903288, + -0.03144038150528943, + -6.009556793470482e-17 + ], + [ + 0, + -0.024043439554124794, + -0.04798807945782008, + -0.07173552604961243, + -0.09518819597764483, + -0.11824971719060108, + -0.14082532495113637, + -0.16282225124450997, + -0.1841501059822565, + -0.20472124843444808, + -0.22445114736425242, + -0.243258728384917, + -0.2610667071118143, + -0.27780190674055605, + -0.2933955587461788, + -0.30778358546776347, + -0.3209068634172891, + -0.3327114662307267, + -0.3431488862630366, + -0.3521762339164864, + -0.35975641388320806, + -0.3658582775777749, + -0.3704567511334202, + -0.3735329384359343, + -0.37507419877185116, + -0.37507419877185116, + -0.3735329384359343, + -0.3704567511334202, + -0.3658582775777749, + -0.3597564138832081, + -0.35217623391648645, + -0.3431488862630367, + -0.3327114662307268, + -0.32090686341728913, + -0.3077835854677635, + -0.29339555874617884, + -0.27780190674055616, + -0.26106670711181434, + -0.24325872838491713, + -0.2244511473642525, + -0.20472124843444825, + -0.1841501059822566, + -0.16282225124451002, + -0.1408253249511365, + -0.11824971719060116, + -0.095188195977645, + -0.07173552604961253, + -0.04798807945782027, + -0.024043439554124916, + -4.5956953635114025e-17 + ], + [ + 0, + -0.0162517049901984, + -0.03243662823861229, + -0.04848826242395879, + -0.06434064793830556, + -0.07992864392924813, + -0.09518819597764508, + -0.11005659931096587, + -0.12447275647065138, + -0.13837742837467645, + -0.15171347774364466, + -0.16442610389012535, + -0.17646306790643282, + -0.1877749073255034, + -0.19831513937278217, + -0.2080404519739142, + -0.21691088173334838, + -0.22488997815250203, + -0.231944953412678, + -0.23804681710724482, + -0.24317049536943583, + -0.24729493390624616, + -0.25040318451503873, + -0.25248247472734436, + -0.25352426029367436, + -0.25352426029367436, + -0.25248247472734436, + -0.25040318451503873, + -0.24729493390624616, + -0.24317049536943586, + -0.23804681710724485, + -0.23194495341267807, + -0.22488997815250206, + -0.2169108817333484, + -0.20804045197391421, + -0.1983151393727822, + -0.18777490732550345, + -0.17646306790643285, + -0.16442610389012544, + -0.15171347774364471, + -0.13837742837467656, + -0.12447275647065145, + -0.1100565993109659, + -0.09518819597764518, + -0.07992864392924819, + -0.06434064793830567, + -0.04848826242395885, + -0.03243662823861242, + -0.01625170499019848, + -3.1063727427383314e-17 + ], + [ + 0, + -0.008193117879635533, + -0.01635256848048537, + -0.024444822869833956, + -0.032436628238612326, + -0.04029514454432331, + -0.047988079457820264, + -0.055483821059414275, + -0.06275156773903286, + -0.06976145476664268, + -0.07648467701283125, + -0.08289360731526234, + -0.088961910004612, + -0.09466464912348285, + -0.09997839089360176, + -0.10488130001024126, + -0.10935322936817038, + -0.11337580285043156, + -0.11693249083974686, + -0.12000867814226102, + -0.1225917240445079, + -0.12467101425681354, + -0.12623800452968925, + -0.12728625576398542, + -0.12781146047053113, + -0.12781146047053113, + -0.12728625576398542, + -0.12623800452968925, + -0.12467101425681354, + -0.12259172404450791, + -0.12000867814226103, + -0.11693249083974688, + -0.11337580285043157, + -0.1093532293681704, + -0.10488130001024128, + -0.09997839089360178, + -0.09466464912348288, + -0.08896191000461201, + -0.08289360731526238, + -0.07648467701283128, + -0.06976145476664274, + -0.06275156773903288, + -0.05548382105941429, + -0.04798807945782031, + -0.040295144544323334, + -0.03243662823861238, + -0.024444822869833988, + -0.016352568480485434, + -0.008193117879635574, + -1.566043567409796e-17 + ], + [ + 0, + -1.5692677964009372e-17, + -3.1320871348195766e-17, + -4.682036055370659e-17, + -6.212745485476638e-17, + -7.717925411753067e-17, + -9.191390727022793e-17, + -1.0627086646248056e-16, + -1.2019113586940948e-16, + -1.3361751411813318e-16, + -1.464948293404786e-16, + -1.5877016588602166e-16, + -1.7039308176384524e-16, + -1.8131581591949977e-16, + -1.9149348449542055e-16, + -2.00884265268326e-16, + -2.0944956950570415e-16, + -2.171542005351916e-16, + -2.2396649837525e-16, + -2.2985846983282128e-16, + -2.3480590353336234e-16, + -2.3878846941057645e-16, + -2.417898022470164e-16, + -2.437975689222735e-16, + -2.4480351909241436e-16, + -2.4480351909241436e-16, + -2.437975689222735e-16, + -2.417898022470164e-16, + -2.3878846941057645e-16, + -2.3480590353336234e-16, + -2.2985846983282128e-16, + -2.2396649837525006e-16, + -2.1715420053519163e-16, + -2.0944956950570418e-16, + -2.0088426526832603e-16, + -1.9149348449542057e-16, + -1.8131581591949982e-16, + -1.7039308176384526e-16, + -1.5877016588602173e-16, + -1.4649482934047864e-16, + -1.3361751411813328e-16, + -1.2019113586940952e-16, + -1.0627086646248059e-16, + -9.191390727022803e-17, + -7.717925411753073e-17, + -6.212745485476649e-17, + -4.682036055370665e-17, + -3.132087134819589e-17, + -1.5692677964009452e-17, + -2.999519565323715e-32 + ] + ], + "z": [ + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ] + ] + }, + { + "line": { + "color": "grey" + }, + "marker": { + "color": [ + 0, + 0.07142857142857142, + 0.14285714285714285, + 0.21428571428571427, + 0.2857142857142857, + 0.3571428571428571, + 0.42857142857142855, + 0.5, + 0.5714285714285714, + 0.6428571428571428, + 0.7142857142857142, + 0.7857142857142857, + 0.8571428571428571, + 0.9285714285714285, + 1 + ], + "colorbar": { + "title": { + "text": "Time" + } + }, + "colorscale": [ + [ + 0, + "rgb(0,0,0)" + ], + [ + 0.3333333333333333, + "rgb(230,0,0)" + ], + [ + 0.6666666666666666, + "rgb(255,210,0)" + ], + [ + 1, + "rgb(255,255,255)" + ] + ], + "size": 5 + }, + "mode": "markers+lines", + "type": "scatter3d", + "x": [ + 0.9990520651470387, + 0.9954014652237735, + 0.9886995029197546, + 0.9790246247183779, + 0.9628512408584392, + 0.9489091580387646, + 0.9366935523756065, + 0.9124694002414021, + 0.885755051065365, + 0.8598031278633096, + 0.8338729831594988, + 0.7981335110234895, + 0.7580315779444392, + 0.725901272367667, + 0.6798015471372526 + ], + "y": [ + -0.04351261576799146, + -0.09574551698065353, + -0.14978008762401096, + -0.20370759566074248, + -0.26974204692854686, + -0.31487004049725087, + -0.34853749714102294, + -0.4079756940746538, + -0.4633064452066913, + -0.5095938914141421, + -0.5518165248803886, + -0.6024741344027326, + -0.65187334350698, + -0.6876804874315429, + -0.7332570029999579 + ], + "z": [ + 0.0012741249798499386, + 0.0029527967204729245, + -0.006262449806102719, + -0.00374161264149299, + 0.012518629963451593, + 0.020694622186032165, + 0.03356787191108118, + 0.0309099768262718, + 0.028020123877883357, + 0.03244452418916158, + 0.012424605652090383, + 0.0027957033096463035, + 0.02119601057026094, + 0.012762835927719434, + 0.014283699146848431 + ] + } + ], + "layout": { + "margin": { + "b": 0, + "l": 0, + "r": 0, + "t": 0 + }, + "scene": { + "camera": { + "eye": { + "x": 1.1, + "y": -1.1, + "z": 0.2 + } + } + }, + "template": { + "data": { + "bar": [ + { + "error_x": { + "color": "#2a3f5f" + }, + "error_y": { + "color": "#2a3f5f" + }, + "marker": { + "line": { + "color": "#E5ECF6", + "width": 0.5 + }, + "pattern": { + "fillmode": "overlay", + "size": 10, + "solidity": 0.2 + } + }, + "type": "bar" + } + ], + "barpolar": [ + { + "marker": { + "line": { + "color": "#E5ECF6", + "width": 0.5 + }, + "pattern": { + "fillmode": "overlay", + "size": 10, + "solidity": 0.2 + } + }, + "type": "barpolar" + } + ], + "carpet": [ + { + "aaxis": { + "endlinecolor": "#2a3f5f", + "gridcolor": "white", + "linecolor": "white", + "minorgridcolor": "white", + "startlinecolor": "#2a3f5f" + }, + "baxis": { + "endlinecolor": "#2a3f5f", + "gridcolor": "white", + "linecolor": "white", + "minorgridcolor": "white", + "startlinecolor": "#2a3f5f" + }, + "type": "carpet" + } + ], + "choropleth": [ + { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "type": "choropleth" + } + ], + "contour": [ + { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1, + "#f0f921" + ] + ], + "type": "contour" + } + ], + "contourcarpet": [ + { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "type": "contourcarpet" + } + ], + "heatmap": [ + { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1, + "#f0f921" + ] + ], + "type": "heatmap" + } + ], + "heatmapgl": [ + { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1, + "#f0f921" + ] + ], + "type": "heatmapgl" + } + ], + "histogram": [ + { + "marker": { + "pattern": { + "fillmode": "overlay", + "size": 10, + "solidity": 0.2 + } + }, + "type": "histogram" + } + ], + "histogram2d": [ + { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1, + "#f0f921" + ] + ], + "type": "histogram2d" + } + ], + "histogram2dcontour": [ + { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1, + "#f0f921" + ] + ], + "type": "histogram2dcontour" + } + ], + "mesh3d": [ + { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "type": "mesh3d" + } + ], + "parcoords": [ + { + "line": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "type": "parcoords" + } + ], + "pie": [ + { + "automargin": true, + "type": "pie" + } + ], + "scatter": [ + { + "fillpattern": { + "fillmode": "overlay", + "size": 10, + "solidity": 0.2 + }, + "type": "scatter" + } + ], + "scatter3d": [ + { + "line": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "type": "scatter3d" + } + ], + "scattercarpet": [ + { + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "type": "scattercarpet" + } + ], + "scattergeo": [ + { + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "type": "scattergeo" + } + ], + "scattergl": [ + { + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "type": "scattergl" + } + ], + "scattermapbox": [ + { + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "type": "scattermapbox" + } + ], + "scatterpolar": [ + { + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "type": "scatterpolar" + } + ], + "scatterpolargl": [ + { + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "type": "scatterpolargl" + } + ], + "scatterternary": [ + { + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "type": "scatterternary" + } + ], + "surface": [ + { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1, + "#f0f921" + ] + ], + "type": "surface" + } + ], + "table": [ + { + "cells": { + "fill": { + "color": "#EBF0F8" + }, + "line": { + "color": "white" + } + }, + "header": { + "fill": { + "color": "#C8D4E3" + }, + "line": { + "color": "white" + } + }, + "type": "table" + } + ] + }, + "layout": { + "annotationdefaults": { + "arrowcolor": "#2a3f5f", + "arrowhead": 0, + "arrowwidth": 1 + }, + "autotypenumbers": "strict", + "coloraxis": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "colorscale": { + "diverging": [ + [ + 0, + "#8e0152" + ], + [ + 0.1, + "#c51b7d" + ], + [ + 0.2, + "#de77ae" + ], + [ + 0.3, + "#f1b6da" + ], + [ + 0.4, + "#fde0ef" + ], + [ + 0.5, + "#f7f7f7" + ], + [ + 0.6, + "#e6f5d0" + ], + [ + 0.7, + "#b8e186" + ], + [ + 0.8, + "#7fbc41" + ], + [ + 0.9, + "#4d9221" + ], + [ + 1, + "#276419" + ] + ], + "sequential": [ + [ + 0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1, + "#f0f921" + ] + ], + "sequentialminus": [ + [ + 0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1, + "#f0f921" + ] + ] + }, + "colorway": [ + "#636efa", + "#EF553B", + "#00cc96", + "#ab63fa", + "#FFA15A", + "#19d3f3", + "#FF6692", + "#B6E880", + "#FF97FF", + "#FECB52" + ], + "font": { + "color": "#2a3f5f" + }, + "geo": { + "bgcolor": "white", + "lakecolor": "white", + "landcolor": "#E5ECF6", + "showlakes": true, + "showland": true, + "subunitcolor": "white" + }, + "hoverlabel": { + "align": "left" + }, + "hovermode": "closest", + "mapbox": { + "style": "light" + }, + "paper_bgcolor": "white", + "plot_bgcolor": "#E5ECF6", + "polar": { + "angularaxis": { + "gridcolor": "white", + "linecolor": "white", + "ticks": "" + }, + "bgcolor": "#E5ECF6", + "radialaxis": { + "gridcolor": "white", + "linecolor": "white", + "ticks": "" + } + }, + "scene": { + "xaxis": { + "backgroundcolor": "#E5ECF6", + "gridcolor": "white", + "gridwidth": 2, + "linecolor": "white", + "showbackground": true, + "ticks": "", + "zerolinecolor": "white" + }, + "yaxis": { + "backgroundcolor": "#E5ECF6", + "gridcolor": "white", + "gridwidth": 2, + "linecolor": "white", + "showbackground": true, + "ticks": "", + "zerolinecolor": "white" + }, + "zaxis": { + "backgroundcolor": "#E5ECF6", + "gridcolor": "white", + "gridwidth": 2, + "linecolor": "white", + "showbackground": true, + "ticks": "", + "zerolinecolor": "white" + } + }, + "shapedefaults": { + "line": { + "color": "#2a3f5f" + } + }, + "ternary": { + "aaxis": { + "gridcolor": "white", + "linecolor": "white", + "ticks": "" + }, + "baxis": { + "gridcolor": "white", + "linecolor": "white", + "ticks": "" + }, + "bgcolor": "#E5ECF6", + "caxis": { + "gridcolor": "white", + "linecolor": "white", + "ticks": "" + } + }, + "title": { + "x": 0.05 + }, + "xaxis": { + "automargin": true, + "gridcolor": "white", + "linecolor": "white", + "ticks": "", + "title": { + "standoff": 15 + }, + "zerolinecolor": "white", + "zerolinewidth": 2 + }, + "yaxis": { + "automargin": true, + "gridcolor": "white", + "linecolor": "white", + "ticks": "", + "title": { + "standoff": 15 + }, + "zerolinecolor": "white", + "zerolinewidth": 2 + } + } + } + } + } + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "import plotly.graph_objects as go\n", + "phi, theta = np.meshgrid(np.linspace(0, np.pi, 50), np.linspace(0, 2 * np.pi, 50))\n", + "fig = go.Figure(go.Surface(\n", + " x=np.sin(phi) * np.cos(theta), y=np.sin(phi) * np.sin(theta), z=np.cos(phi),\n", + " opacity=0.3, colorscale='Viridis', showscale=False\n", + "))\n", + "etas_np = np.array([R.matrix()[:,0] for R in rotations])\n", + "time_steps = np.linspace(0, 1, len(etas_np)) # Normalize time steps between 0 and 1\n", + "colors = time_steps # Use time steps as color values\n", + "\n", + "fig.add_trace(go.Scatter3d(\n", + " x=etas_np[:, 0], y=etas_np[:, 1], z=etas_np[:, 2],\n", + " mode='markers+lines',\n", + " marker=dict(size=5, color=colors, colorscale='Hot', colorbar=dict(title='Time')),\n", + " line=dict(color='grey')\n", + "))\n", + "fig.update_layout(scene_camera=dict(eye=dict(x=1.1, y=-1.1, z=0.2)), margin=dict(l=0, r=0, t=0, b=0))\n", + "fig.show()" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Source\n", + "- [PreintegratedRotation.h](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/PreintegratedRotation.h)\n", + "- [PreintegratedRotation.cpp](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/PreintegratedRotation.cpp)" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "py312", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.12.6" + } + }, + "nbformat": 4, + "nbformat_minor": 2 +} diff --git a/gtsam/navigation/doc/PreintegrationCombinedParams.ipynb b/gtsam/navigation/doc/PreintegrationCombinedParams.ipynb new file mode 100644 index 0000000000..8051158a4d --- /dev/null +++ b/gtsam/navigation/doc/PreintegrationCombinedParams.ipynb @@ -0,0 +1,214 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# PreintegrationCombinedParams\n", + "\n", + "\"Open\n", + "\n", + "## Overview\n", + "\n", + "The `PreintegrationCombinedParams` class holds parameters specifically required for the `CombinedImuFactor` and its associated `PreintegratedCombinedMeasurements` class. \n", + "\n", + "It inherits from `PreintegrationParams` (and thus also `PreintegratedRotationParams`) and adds parameters that model the *evolution* of the IMU bias over time, typically as a random walk process. This is essential for the `CombinedImuFactor`, which estimates biases at both the start ($b_i$) and end ($b_j$) of the preintegration interval." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": { + "tags": [ + "remove-cell" + ] + }, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Note: you may need to restart the kernel to use updated packages.\n" + ] + } + ], + "source": [ + "%pip install --quiet gtsam-develop" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Key Parameters\n", + "\n", + "In addition to all parameters from `PreintegrationParams`, this class adds:\n", + "\n", + "- **`biasAccCovariance`**: A 3x3 matrix representing the continuous-time covariance of the *random walk process* driving the accelerometer bias. Units: (m²/s⁵)/Hz ? (Check docs, represents variance growth rate).\n", + "- **`biasOmegaCovariance`**: A 3x3 matrix representing the continuous-time covariance of the *random walk process* driving the gyroscope bias. Units: (rad²/s³)/Hz ? (Check docs, represents variance growth rate).\n", + "- **`biasAccOmegaInit`**: A 6x6 matrix representing the covariance of the uncertainty in the *initial* bias estimate provided to the preintegration. This accounts for the fact that the bias used for integration (`biasHat_`) is itself uncertain." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Mathematical Background: Bias Random Walk\n", + "\n", + "The `CombinedImuFactor` implicitly assumes that the bias evolves between time steps according to a random walk:\n", + "$$ b_{k+1} = b_k + w_k, \\quad w_k \\sim \\mathcal{N}(0, Q_b \\Delta t) $$ \n", + "where $b_k = [b_{a,k}; b_{g,k}]$ is the 6D bias vector at time $k$, $w_k$ is zero-mean Gaussian noise, and $Q_b$ is the block-diagonal continuous-time covariance matrix formed from `biasAccCovariance` and `biasOmegaCovariance`:\n", + "$$ Q_b = \\begin{bmatrix} \\text{biasAccCovariance} & 0 \\\\ 0 & \\text{biasOmegaCovariance} \\end{bmatrix} $$ \n", + "The factor uses this model (integrated over the interval $\\Delta t_{ij}$) to constrain the difference between $b_i$ and $b_j$." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Key Functionality / API\n", + "\n", + "- **Constructors**: \n", + " - `PreintegrationCombinedParams(n_gravity)`: Main constructor.\n", + " - `MakeSharedD(g=9.81)` / `MakeSharedU(g=9.81)`: Convenience static methods for NED/ENU frames.\n", + "- **Setters**: Methods like `setBiasAccCovariance`, `setBiasOmegaCovariance`, `setBiasAccOmegaInit`, plus all setters inherited from `PreintegrationParams`.\n", + "- **Getters**: Corresponding getters for the combined parameters, plus all inherited getters.\n", + "- **`print` / `equals`**: Standard methods." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Usage Example\n", + "\n", + "Create parameters, often starting from the base `PreintegrationParams` settings, and then set the bias evolution parameters." + ] + }, + { + "cell_type": "code", + "execution_count": 3, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Combined IMU Preintegration Parameters:\n", + "\n", + "gyroscopeCovariance:\n", + "[\n", + "0.0001 0 0\n", + " 0 0.0001 0\n", + " 0 0 0.0001\n", + "]\n", + "accelerometerCovariance:\n", + "[\n", + "0.01 0 0\n", + " 0 0.01 0\n", + " 0 0 0.01\n", + "]\n", + "integrationCovariance:\n", + "[\n", + "1e-08 0 0\n", + " 0 1e-08 0\n", + " 0 0 1e-08\n", + "]\n", + "n_gravity = ( 0 0 -9.81)\n", + "biasAccCovariance:\n", + "[\n", + "1e-06 0 0\n", + " 0 1e-06 0\n", + " 0 0 1e-06\n", + "]\n", + "biasOmegaCovariance:\n", + "[\n", + "1e-08 0 0\n", + " 0 1e-08 0\n", + " 0 0 1e-08\n", + "]\n", + "biasAccOmegaInt:\n", + "[\n", + " 0.01 0 0 0 0 0\n", + " 0 0.01 0 0 0 0\n", + " 0 0 0.01 0 0 0\n", + " 0 0 0 0.0025 0 0\n", + " 0 0 0 0 0.0025 0\n", + " 0 0 0 0 0 0.0025\n", + "]\n" + ] + } + ], + "source": [ + "from gtsam import PreintegrationCombinedParams\n", + "import numpy as np\n", + "\n", + "# 1. Create parameters for an ENU navigation frame (Z-up)\n", + "params = PreintegrationCombinedParams.MakeSharedU(9.81)\n", + "\n", + "# 2. Set standard noise parameters (accel, gyro, integration)\n", + "accel_noise_sigma = 0.1\n", + "gyro_noise_sigma = 0.01\n", + "params.setAccelerometerCovariance(np.eye(3) * accel_noise_sigma**2)\n", + "params.setGyroscopeCovariance(np.eye(3) * gyro_noise_sigma**2)\n", + "params.setIntegrationCovariance(np.eye(3) * 1e-8)\n", + "\n", + "# 3. Set bias random walk noise parameters (example values)\n", + "bias_acc_rw_sigma = 0.001 # m/s^2 / sqrt(s) -> Covariance = sigma^2\n", + "bias_gyro_rw_sigma = 0.0001 # rad/s / sqrt(s) -> Covariance = sigma^2\n", + "params.setBiasAccCovariance(np.eye(3) * bias_acc_rw_sigma**2)\n", + "params.setBiasOmegaCovariance(np.eye(3) * bias_gyro_rw_sigma**2)\n", + "\n", + "# 4. Set initial bias uncertainty (covariance of bias used for preintegration)\n", + "# Example: Assume bias estimate used for preintegration has some uncertainty\n", + "initial_bias_acc_sigma = 0.1\n", + "initial_bias_gyro_sigma = 0.05\n", + "initial_bias_cov = np.diag(np.concatenate([\n", + " np.full(3, initial_bias_acc_sigma**2),\n", + " np.full(3, initial_bias_gyro_sigma**2)\n", + "]))\n", + "params.setBiasAccOmegaInit(initial_bias_cov)\n", + "\n", + "print(\"Combined IMU Preintegration Parameters:\")\n", + "params.print()" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "These combined parameters are then passed to `PreintegratedCombinedMeasurements`." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Source\n", + "- [PreintegrationCombinedParams.h](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/PreintegrationCombinedParams.h)\n", + "- [CombinedImuFactor.cpp](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/CombinedImuFactor.cpp) (Contains the definition of this class)" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "py312", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.12.6" + } + }, + "nbformat": 4, + "nbformat_minor": 2 +} diff --git a/gtsam/navigation/doc/PreintegrationParams.ipynb b/gtsam/navigation/doc/PreintegrationParams.ipynb new file mode 100644 index 0000000000..cb52b66933 --- /dev/null +++ b/gtsam/navigation/doc/PreintegrationParams.ipynb @@ -0,0 +1,179 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# PreintegrationParams\n", + "\n", + "\"Open\n", + "\n", + "## Overview\n", + "\n", + "The `PreintegrationParams` class holds the parameters required for Inertial Measurement Unit (IMU) preintegration in GTSAM. It configures how IMU measurements (accelerometer and gyroscope) are handled, including noise characteristics, gravity direction, and Coriolis effects.\n", + "\n", + "This class extends `PreintegratedRotationParams` (which handles gyroscope-specific parameters) by adding parameters relevant to accelerometer measurements and the combined integration process.\n", + "\n", + "A single `PreintegrationParams` object (usually created as a `shared_ptr`) is typically shared among multiple preintegration instances (`PreintegratedImuMeasurements` or `PreintegratedCombinedMeasurements`)." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": { + "tags": [ + "remove-cell" + ] + }, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Note: you may need to restart the kernel to use updated packages.\n" + ] + } + ], + "source": [ + "%pip install --quiet gtsam-develop" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Key Parameters\n", + "\n", + "In addition to parameters inherited from `PreintegratedRotationParams` (like `gyroscopeCovariance`, `omegaCoriolis`, `body_P_sensor`), `PreintegrationParams` includes:\n", + "\n", + "- **`accelerometerCovariance`**: A 3x3 matrix representing the continuous-time noise covariance of the accelerometer. Units: (m/s²)²/Hz.\n", + "- **`integrationCovariance`**: A 3x3 matrix representing additional uncertainty introduced during the numerical integration process itself (often set to zero). Units: (m²/s⁶)/Hz ? (Consult documentation for precise interpretation).\n", + "- **`use2ndOrderCoriolis`**: A boolean flag. If true, enables a more accurate (second-order) correction for Coriolis effects, which arise from the Earth's rotation.\n", + "- **`n_gravity`**: A 3D vector specifying the direction and magnitude of gravity in the navigation frame (e.g., [0, 0, -9.81] for ENU, [0, 0, 9.81] for NED). Units: m/s²." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Key Functionality / API\n", + "\n", + "- **Constructors**: \n", + " - `PreintegrationParams(n_gravity)`: Main constructor requiring the gravity vector.\n", + " - `MakeSharedD(g=9.81)`: Convenience static method to create shared parameters for a Z-down (NED) navigation frame.\n", + " - `MakeSharedU(g=9.81)`: Convenience static method to create shared parameters for a Z-up (ENU) navigation frame.\n", + "- **Setters**: Methods like `setAccelerometerCovariance`, `setIntegrationCovariance`, `setUse2ndOrderCoriolis`, `setGyroscopeCovariance`, `setOmegaCoriolis`, `setBodyPSensor` allow configuring the parameters after creation.\n", + "- **Getters**: Corresponding methods like `getAccelerometerCovariance`, `getIntegrationCovariance`, `getGravity`, `isUsing2ndOrderCoriolis` allow retrieving parameter values.\n", + "- **`print` / `equals`**: Standard methods for displaying parameters and comparing them." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Usage Example\n", + "\n", + "Typically, you create parameters once using a convenience function and then adjust specific noise values." + ] + }, + { + "cell_type": "code", + "execution_count": 3, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "IMU Preintegration Parameters:\n", + "\n", + "gyroscopeCovariance:\n", + "[\n", + "1e-06 0 0\n", + " 0 1e-06 0\n", + " 0 0 1e-06\n", + "]\n", + "accelerometerCovariance:\n", + "[\n", + "0.0001 0 0\n", + " 0 0.0001 0\n", + " 0 0 0.0001\n", + "]\n", + "integrationCovariance:\n", + "[\n", + "1e-08 0 0\n", + " 0 1e-08 0\n", + " 0 0 1e-08\n", + "]\n", + "n_gravity = ( 0 0 -9.81)\n" + ] + } + ], + "source": [ + "from gtsam import PreintegrationParams\n", + "import numpy as np\n", + "\n", + "# Create parameters for an ENU navigation frame (Z-up)\n", + "# Using standard gravity, g=9.81 m/s^2\n", + "params = PreintegrationParams.MakeSharedU(9.81)\n", + "\n", + "# Set accelerometer noise characteristics (example values)\n", + "accel_noise_sigma = 0.01 # m/s^2 / sqrt(Hz)\n", + "params.setAccelerometerCovariance(np.eye(3) * accel_noise_sigma**2)\n", + "\n", + "# Set gyroscope noise characteristics (example values)\n", + "gyro_noise_sigma = 0.001 # rad/s / sqrt(Hz)\n", + "params.setGyroscopeCovariance(np.eye(3) * gyro_noise_sigma**2)\n", + "\n", + "# Set integration uncertainty (often zero)\n", + "params.setIntegrationCovariance(np.eye(3) * 1e-8)\n", + "\n", + "# Optionally, set sensor pose relative to body\n", + "# params.setBodyPSensor(gtsam.Pose3(...))\n", + "\n", + "# Optionally, enable 2nd order Coriolis correction\n", + "# params.setUse2ndOrderCoriolis(True)\n", + "\n", + "print(\"IMU Preintegration Parameters:\")\n", + "params.print()" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "These parameters are then passed to `PreintegratedImuMeasurements` or `PreintegratedCombinedMeasurements` when they are constructed." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Source\n", + "- [PreintegrationParams.h](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/PreintegrationParams.h)\n", + "- [PreintegrationParams.cpp](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/PreintegrationParams.cpp)" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "py312", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.12.6" + } + }, + "nbformat": 4, + "nbformat_minor": 2 +} diff --git a/gtsam/navigation/doc/Scenario.ipynb b/gtsam/navigation/doc/Scenario.ipynb new file mode 100644 index 0000000000..6d874ab299 --- /dev/null +++ b/gtsam/navigation/doc/Scenario.ipynb @@ -0,0 +1,196 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# Scenario Class Hierarchy\n", + "\n", + "\"Open\n", + "\n", + "## Overview\n", + "\n", + "The `Scenario` class hierarchy provides a simple way to define theoretical trajectories for testing navigation algorithms and factors, particularly IMU factors. \n", + "\n", + "The base `Scenario` class is abstract and defines an interface that requires subclasses to provide the ground truth pose, angular velocity (in body frame), linear velocity (in nav frame), and linear acceleration (in nav frame) at any given continuous time `t`.\n", + "\n", + "Concrete subclasses like `ConstantTwistScenario` and `AcceleratingScenario` implement specific types of motion." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": { + "tags": [ + "remove-cell" + ] + }, + "outputs": [], + "source": [ + "%pip install --quiet gtsam-develop" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Base Class: `Scenario`\n", + "\n", + "Defines the required interface for any trajectory scenario.\n", + "\n", + "**Pure Virtual Methods (must be implemented by subclasses):**\n", + "- `pose(t)`: Returns the `Pose3` of the body in the navigation frame at time `t`.\n", + "- `omega_b(t)`: Returns the angular velocity `Vector3` in the **body frame** at time `t`.\n", + "- `velocity_n(t)`: Returns the linear velocity `Vector3` in the **navigation frame** at time `t`.\n", + "- `acceleration_n(t)`: Returns the linear acceleration `Vector3` in the **navigation frame** at time `t`.\n", + "\n", + "**Derived Methods (provided by the base class):**\n", + "- `rotation(t)`: Returns the `Rot3` part of `pose(t)`.\n", + "- `navState(t)`: Returns the `NavState` (Pose + Nav Velocity) at time `t`.\n", + "- `velocity_b(t)`: Calculates linear velocity in the **body frame** using $v_b = R_{bn} v_n$.\n", + "- `acceleration_b(t)`: Calculates linear acceleration in the **body frame** using $a_b = R_{bn} a_n$." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Concrete Scenarios\n", + "\n", + "### `ConstantTwistScenario`\n", + "\n", + "- **Description**: Models motion with a constant *twist* (angular velocity $\\omega_b$ and linear velocity $v_b$) defined in the **body frame**.\n", + "- **Motion**: Results in helical or circular motion trajectories.\n", + "- **Constructors**:\n", + " - `ConstantTwistScenario(omega_b, velocity_b, initial_nTb=Pose3())`\n", + " - `ConstantTwistScenario(twist_vector_6d, initial_nTb=Pose3())`\n", + "- **Key Behavior**: `omega_b(t)` is constant. `velocity_n(t)` and `acceleration_n(t)` are calculated based on the constant body-frame velocities and the changing orientation.\n", + "\n", + "### `AcceleratingScenario`\n", + "\n", + "- **Description**: Models motion with constant linear acceleration $a_n$ defined in the **navigation frame** and constant angular velocity $\\omega_b$ defined in the **body frame**.\n", + "- **Motion**: Represents scenarios like accelerating along a straight line while potentially rotating (e.g., aircraft takeoff, car acceleration).\n", + "- **Constructor**: `AcceleratingScenario(initial_nRb, initial_p_n, initial_v_n, const_a_n, const_omega_b=zero)`\n", + "- **Key Behavior**: `acceleration_n(t)` and `omega_b(t)` are constant. `velocity_n(t)` and `pose(t)` are integrated from the initial conditions and constant rates." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Usage Example\n", + "\n", + "Instantiate a scenario and query its properties at different times." + ] + }, + { + "cell_type": "code", + "execution_count": 1, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "--- Circle Scenario ---\n", + "Pose at t=1.0:\n", + "R: [\n", + "\t0.995004, -0.0998334, 0;\n", + "\t0.0998334, 0.995004, 0;\n", + "\t0, 0, 1\n", + "]\n", + "t: 1.99667 0.0999167 0\n", + "Nav Velocity at t=1.0: [1.99000833 0.19966683 0. ]\n", + "Body Omega at t=1.0: [0. 0. 0.1]\n", + "Nav Acceleration at t=1.0: [-0.01996668 0.19900083 0. ]\n", + "\n", + "--- Accelerating Scenario ---\n", + "Pose at t=2.0:\n", + "R: [\n", + "\t1, 0, 0;\n", + "\t0, 1, 0;\n", + "\t0, 0, 1\n", + "]\n", + "t: 1 0 0\n", + "Nav Velocity at t=2.0: [1. 0. 0.]\n", + "Nav Acceleration at t=2.0: [0.5 0. 0. ]\n" + ] + } + ], + "source": [ + "import gtsam\n", + "import numpy as np\n", + "\n", + "# --- ConstantTwistScenario Example: Moving in a Circle --- \n", + "# Forward velocity 2 m/s, turning left (positive Z rot) at ~5.73 deg/s (0.1 rad/s)\n", + "omega_b_circle = np.array([0.0, 0.0, 0.1]) \n", + "vel_b_circle = np.array([2.0, 0.0, 0.0]) # Forward velocity along body X\n", + "initial_pose_circle = gtsam.Pose3() # Start at origin\n", + "\n", + "circle_scenario = gtsam.ConstantTwistScenario(omega_b_circle, vel_b_circle, initial_pose_circle)\n", + "\n", + "print(\"--- Circle Scenario ---\")\n", + "time_t = 1.0 # seconds\n", + "print(f\"Pose at t={time_t}:\")\n", + "circle_scenario.pose(time_t).print()\n", + "print(f\"Nav Velocity at t={time_t}: {circle_scenario.velocity_n(time_t)}\")\n", + "print(f\"Body Omega at t={time_t}: {circle_scenario.omega_b(time_t)}\")\n", + "print(f\"Nav Acceleration at t={time_t}: {circle_scenario.acceleration_n(time_t)}\") # Centripetal\n", + "\n", + "# --- AcceleratingScenario Example: Accelerating Straight --- \n", + "initial_pose_accel = gtsam.Pose3() \n", + "initial_vel_n = np.array([0.0, 0.0, 0.0])\n", + "const_accel_n = np.array([0.5, 0.0, 0.0]) # Accelerate along nav X\n", + "const_omega_b = np.array([0.0, 0.0, 0.0]) # No rotation\n", + "\n", + "accel_scenario = gtsam.AcceleratingScenario(\n", + " initial_pose_accel.rotation(), initial_pose_accel.translation(),\n", + " initial_vel_n, const_accel_n, const_omega_b\n", + ")\n", + "\n", + "print(\"\\n--- Accelerating Scenario ---\")\n", + "time_t = 2.0 # seconds\n", + "print(f\"Pose at t={time_t}:\")\n", + "accel_scenario.pose(time_t).print()\n", + "print(f\"Nav Velocity at t={time_t}: {accel_scenario.velocity_n(time_t)}\")\n", + "print(f\"Nav Acceleration at t={time_t}: {accel_scenario.acceleration_n(time_t)}\")" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "These `Scenario` objects are primarily used as input to the `ScenarioRunner` class for generating simulated IMU data." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Source\n", + "- [Scenario.h](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/Scenario.h)" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "py312", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.12.6" + } + }, + "nbformat": 4, + "nbformat_minor": 2 +} diff --git a/gtsam/navigation/doc/ScenarioRunner.ipynb b/gtsam/navigation/doc/ScenarioRunner.ipynb new file mode 100644 index 0000000000..d0978a77e1 --- /dev/null +++ b/gtsam/navigation/doc/ScenarioRunner.ipynb @@ -0,0 +1,224 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# ScenarioRunner\n", + "\n", + "\"Open\n", + "\n", + "## Overview\n", + "\n", + "The `ScenarioRunner` class is a utility designed for testing IMU preintegration and factors. It takes a ground truth trajectory defined by a `Scenario` object, along with IMU parameters (`PreintegrationParams` or `PreintegrationCombinedParams`) and a specified IMU bias, and simulates the measurements an IMU would produce while following that trajectory.\n", + "\n", + "Key capabilities include:\n", + "- Calculating the ideal specific force and angular velocity at any time `t` based on the scenario's motion.\n", + "- Generating noisy IMU measurements by adding the specified bias and sampling from the noise models defined in the parameters.\n", + "- Integrating these simulated measurements over a time interval `T` to produce a `PreintegratedImuMeasurements` or `PreintegratedCombinedMeasurements` object.\n", + "- Predicting the final state based on an initial state and a preintegrated measurement object.\n", + "- Estimating the covariance of the preintegrated measurements or the prediction error via Monte Carlo simulation (useful for verifying the analytical covariance propagation)." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": { + "tags": [ + "remove-cell" + ] + }, + "outputs": [], + "source": [ + "%pip install --quiet gtsam-develop" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Measurement Simulation\n", + "\n", + "- **`actualAngularVelocity(t)`**: Returns the true angular velocity $\\omega_b(t)$ from the `Scenario`.\n", + "- **`actualSpecificForce(t)`**: Calculates the true specific force (what an ideal accelerometer measures) in the body frame. This is the body-frame acceleration $a_b(t)$ *minus* the body-frame representation of gravity $g_b(t)$:\n", + " $$ f_b(t) = a_b(t) - R_{bn}(t) g_n = R_{bn}(t) (a_n(t) - g_n) $$ \n", + " where $g_n$ is the gravity vector defined in `PreintegrationParams`.\n", + "- **`measuredAngularVelocity(t)`**: Adds bias and sampled noise to `actualAngularVelocity(t)`.\n", + " $$ \\omega_{measured} = \\omega_b(t) + b_g + \\eta_{gd} $$ \n", + " where $b_g$ is the gyro bias and $\\eta_{gd}$ is sampled discrete gyro noise.\n", + "- **`measuredSpecificForce(t)`**: Adds bias and sampled noise to `actualSpecificForce(t)`.\n", + " $$ a_{measured} = f_b(t) + b_a + \\eta_{ad} $$ \n", + " where $b_a$ is the accelerometer bias and $\\eta_{ad}$ is sampled discrete accelerometer noise." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Key Functionality / API\n", + "\n", + "- **Constructor**: `ScenarioRunner(scenario, params, imuSampleTime=0.01, bias=ConstantBias())`: Takes the scenario, IMU parameters, sample rate, and the *true* bias to apply to measurements.\n", + "- **Measurement Methods**: `actual...()`, `measured...()` as described above.\n", + "- **`integrate(T, estimatedBias, corrupted=True)`**: Simulates measurements at `imuSampleTime` intervals for a duration `T`, optionally adding noise (`corrupted=True`), and integrates them into a PIM object using `estimatedBias` as the `biasHat` for the PIM.\n", + "- **`predict(pim, estimatedBias)`**: Uses the provided PIM (which contains $\\Delta R, \\Delta p, \\Delta v$) and an `estimatedBias` to predict the final `NavState` starting from the scenario's initial state at $t=0$.\n", + "- **`estimateCovariance(T, N, estimatedBias)`**: Performs Monte Carlo simulation: runs `integrate` `N` times with different noise samples, calculates the `predict`ed state for each, and computes the sample covariance of the 9D tangent space difference between the Monte Carlo predictions and the mean prediction. Used to verify `pim.preintMeasCov()`.\n", + "- **`estimateNoiseCovariance(N)`**: Samples noise `N` times and computes the sample covariance, to verify the noise samplers themselves.\n", + "\n", + "There is also a `CombinedScenarioRunner` inheriting from `ScenarioRunner` that works with `PreintegrationCombinedParams` and `PreintegratedCombinedMeasurements`." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Usage Example\n", + "\n", + "Using the `AcceleratingScenario` from the `Scenario` example to generate measurements and verify prediction." + ] + }, + { + "cell_type": "code", + "execution_count": 2, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "--- Integration Results (T=2.0s) ---\n", + "Bias Hat used in PIM:\n", + "acc = 0.04 -0.04 0.09 gyro = 0.005 -0.005 0.015\n", + "PIM Delta R:\n", + "R: [\n", + "\t0.9998, -0.00700878, -0.0187374;\n", + "\t0.00661627, 0.999759, -0.0209287;\n", + "\t0.0188796, 0.0208006, 0.999605\n", + "]\n", + "PIM Delta P: [ 0.70090612 -0.06192379 19.6232812 ]\n", + "PIM Delta V: [ 0.62536677 -0.17585342 19.47976488]\n", + "\n", + "--- Prediction vs Ground Truth (T=2.0s) ---\n", + "Predicted State:\n", + "R: [\n", + "\t0.9998, -0.00700878, -0.0187374;\n", + "\t0.00661627, 0.999759, -0.0209287;\n", + "\t0.0188796, 0.0208006, 0.999605\n", + "]\n", + "p: 0.700906 -0.0619238 0.0032812\n", + "v: 0.625367 -0.175853 -0.140235\n", + "\n", + "Ground Truth State:\n", + "R: [\n", + "\t1, 0, 0;\n", + "\t0, 1, 0;\n", + "\t0, 0, 1\n", + "]\n", + "p: 1 0 0\n", + "v: 1 0 0\n", + "\n", + "Prediction Error (Logmap(predicted^-1 * ground_truth)):\n", + " [-0.02086757 0.01881111 -0.00681348 0.29938178 0.05974434 -0.01018013\n", + " 0.37836933 0.1761023 0.12947973]\n" + ] + } + ], + "source": [ + "import gtsam\n", + "import numpy as np\n", + "\n", + "# --- 1. Define Scenario --- \n", + "initial_pose_accel = gtsam.Pose3() \n", + "initial_vel_n = np.array([0.0, 0.0, 0.0])\n", + "const_accel_n = np.array([0.5, 0.0, 0.0]) # Accelerate along nav X (ENU)\n", + "const_omega_b = np.array([0.0, 0.0, 0.0]) # No rotation\n", + "scenario = gtsam.AcceleratingScenario(\n", + " initial_pose_accel.rotation(), initial_pose_accel.translation(),\n", + " initial_vel_n, const_accel_n, const_omega_b\n", + ")\n", + "\n", + "# --- 2. Define IMU Params and Runner --- \n", + "# Use default ENU parameters (Z-up, g=-9.81)\n", + "params = gtsam.PreintegrationParams.MakeSharedU(9.81)\n", + "# Add some noise (variances)\n", + "params.setAccelerometerCovariance(np.eye(3) * 0.01)\n", + "params.setGyroscopeCovariance(np.eye(3) * 0.0001)\n", + "params.setIntegrationCovariance(np.eye(3) * 1e-9)\n", + "\n", + "imu_sample_dt = 0.01 # 100 Hz\n", + "# Define the *true* bias applied to the measurements\n", + "true_bias = gtsam.imuBias.ConstantBias(np.array([0.05, -0.05, 0.1]), \n", + " np.array([0.01, -0.01, 0.02]))\n", + "\n", + "runner = gtsam.ScenarioRunner(scenario, params, imu_sample_dt, true_bias)\n", + "\n", + "# --- 3. Integrate Measurements --- \n", + "integration_time = 2.0 # seconds\n", + "\n", + "# Define the bias *estimate* to be used during preintegration\n", + "# Let's assume we have a slightly wrong estimate\n", + "estimated_bias = gtsam.imuBias.ConstantBias(np.array([0.04, -0.04, 0.09]), \n", + " np.array([0.005, -0.005, 0.015]))\n", + "\n", + "# Integrate noisy measurements using the 'estimated_bias' as biasHat for the PIM\n", + "pim = runner.integrate(integration_time, estimatedBias=estimated_bias, corrupted=True)\n", + "\n", + "print(f\"--- Integration Results (T={integration_time}s) ---\")\n", + "print(\"Bias Hat used in PIM:\")\n", + "pim.biasHat().print()\n", + "print(\"PIM Delta R:\")\n", + "pim.deltaRij().print()\n", + "print(\"PIM Delta P:\", pim.deltaPij())\n", + "print(\"PIM Delta V:\", pim.deltaVij())\n", + "\n", + "# --- 4. Predict State --- \n", + "# Predict the state at integration_time using the PIM and the *same* estimated_bias\n", + "initial_state_actual = scenario.navState(0.0)\n", + "predicted_state = runner.predict(pim, estimated_bias)\n", + "\n", + "# Get the ground truth state at the end time\n", + "ground_truth_state = scenario.navState(integration_time)\n", + "\n", + "print(f\"\\n--- Prediction vs Ground Truth (T={integration_time}s) ---\")\n", + "print(\"Predicted State:\")\n", + "predicted_state.print()\n", + "print(\"\\nGround Truth State:\")\n", + "ground_truth_state.print()\n", + "\n", + "# Calculate the error (difference in tangent space)\n", + "prediction_error = predicted_state.localCoordinates(ground_truth_state)\n", + "print(\"\\nPrediction Error (Logmap(predicted^-1 * ground_truth)):\\n\", prediction_error)\n", + "# Note: Error is non-zero due to noise and bias estimation error used in PIM.\n" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Source\n", + "- [ScenarioRunner.h](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/ScenarioRunner.h)\n", + "- [ScenarioRunner.cpp](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/ScenarioRunner.cpp)" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "py312", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.12.6" + } + }, + "nbformat": 4, + "nbformat_minor": 2 +} diff --git a/gtsam/navigation/navigation.i b/gtsam/navigation/navigation.i index 99567509aa..6ab3eb7a97 100644 --- a/gtsam/navigation/navigation.i +++ b/gtsam/navigation/navigation.i @@ -97,6 +97,29 @@ virtual class PreintegratedRotationParams { void serialize() const; }; +class PreintegratedRotation { + // Constructors + PreintegratedRotation(const gtsam::PreintegratedRotationParams* params); + + // Standard Interface + void resetIntegration(); + void integrateGyroMeasurement(const gtsam::Vector& measuredOmega, const gtsam::Vector& biasHat, double deltaT); + gtsam::Rot3 biascorrectedDeltaRij(const gtsam::Vector& biasOmegaIncr) const; + gtsam::Vector integrateCoriolis(const gtsam::Rot3& rot_i) const; + + // Access instance variables + double deltaTij() const; + gtsam::Rot3 deltaRij() const; + gtsam::Matrix delRdelBiasOmega() const; + + // Testable + void print(string s = "") const; + bool equals(const gtsam::PreintegratedRotation& expected, double tol) const; + + // enabling serialization functionality + void serialize() const; +}; + #include virtual class PreintegrationParams : gtsam::PreintegratedRotationParams { PreintegrationParams(gtsam::Vector n_gravity); @@ -291,10 +314,7 @@ class PreintegratedAhrsMeasurements { virtual class AHRSFactor : gtsam::NonlinearFactor { AHRSFactor(size_t rot_i, size_t rot_j,size_t bias, - const gtsam::PreintegratedAhrsMeasurements& preintegratedMeasurements, gtsam::Vector omegaCoriolis); - AHRSFactor(size_t rot_i, size_t rot_j, size_t bias, - const gtsam::PreintegratedAhrsMeasurements& preintegratedMeasurements, gtsam::Vector omegaCoriolis, - const gtsam::Pose3& body_P_sensor); + const gtsam::PreintegratedAhrsMeasurements& preintegratedMeasurements); // Standard Interface gtsam::PreintegratedAhrsMeasurements preintegratedMeasurements() const; @@ -306,6 +326,13 @@ virtual class AHRSFactor : gtsam::NonlinearFactor { // enable serialization functionality void serialize() const; + + // deprecated: + AHRSFactor(size_t rot_i, size_t rot_j,size_t bias, + const gtsam::PreintegratedAhrsMeasurements& preintegratedMeasurements, gtsam::Vector omegaCoriolis); + AHRSFactor(size_t rot_i, size_t rot_j, size_t bias, + const gtsam::PreintegratedAhrsMeasurements& preintegratedMeasurements, gtsam::Vector omegaCoriolis, + const gtsam::Pose3& body_P_sensor); }; #include @@ -319,6 +346,7 @@ virtual class Rot3AttitudeFactor : gtsam::NoiseModelFactor { bool equals(const gtsam::NonlinearFactor& expected, double tol) const; gtsam::Unit3 nRef() const; gtsam::Unit3 bMeasured() const; + gtsam::Vector evaluateError(const gtsam::Rot3& nRb); // enable serialization functionality void serialize() const; @@ -336,6 +364,7 @@ virtual class Pose3AttitudeFactor : gtsam::NoiseModelFactor { bool equals(const gtsam::NonlinearFactor& expected, double tol) const; gtsam::Unit3 nRef() const; gtsam::Unit3 bMeasured() const; + gtsam::Vector evaluateError(const gtsam::Pose3& nTb); // enable serialization functionality void serialize() const; @@ -353,6 +382,42 @@ virtual class GPSFactor : gtsam::NonlinearFactor{ // Standard Interface gtsam::Point3 measurementIn() const; + gtsam::Vector evaluateError(const gtsam::Pose3& nTb); + + // enable serialization functionality + void serialize() const; +}; + +virtual class GPSFactorArm : gtsam::NonlinearFactor{ + GPSFactorArm(size_t key, const gtsam::Point3& gpsIn, + const gtsam::Point3& leverArm, + const gtsam::noiseModel::Base* model); + + // Testable + void print(string s = "", const gtsam::KeyFormatter& keyFormatter = + gtsam::DefaultKeyFormatter) const; + bool equals(const gtsam::NonlinearFactor& expected, double tol); + + // Standard Interface + gtsam::Point3 measurementIn() const; + gtsam::Vector evaluateError(const gtsam::Pose3& nTb); + + // enable serialization functionality + void serialize() const; +}; + +virtual class GPSFactorArmCalib : gtsam::NonlinearFactor{ + GPSFactorArmCalib(size_t key1, size_t key2, const gtsam::Point3& gpsIn, + const gtsam::noiseModel::Base* model); + + // Testable + void print(string s = "", const gtsam::KeyFormatter& keyFormatter = + gtsam::DefaultKeyFormatter) const; + bool equals(const gtsam::NonlinearFactor& expected, double tol); + + // Standard Interface + gtsam::Point3 measurementIn() const; + gtsam::Vector evaluateError(const gtsam::Pose3& nTb, const gtsam::Point3& leverArm); // enable serialization functionality void serialize() const; @@ -369,6 +434,42 @@ virtual class GPSFactor2 : gtsam::NonlinearFactor { // Standard Interface gtsam::Point3 measurementIn() const; + gtsam::Vector evaluateError(const gtsam::NavState& nTb); + + // enable serialization functionality + void serialize() const; +}; + +virtual class GPSFactor2Arm : gtsam::NonlinearFactor{ + GPSFactor2Arm(size_t key, const gtsam::Point3& gpsIn, + const gtsam::Point3& leverArm, + const gtsam::noiseModel::Base* model); + + // Testable + void print(string s = "", const gtsam::KeyFormatter& keyFormatter = + gtsam::DefaultKeyFormatter) const; + bool equals(const gtsam::NonlinearFactor& expected, double tol); + + // Standard Interface + gtsam::Point3 measurementIn() const; + gtsam::Vector evaluateError(const gtsam::NavState& nTb); + + // enable serialization functionality + void serialize() const; +}; + +virtual class GPSFactor2ArmCalib : gtsam::NonlinearFactor{ + GPSFactor2ArmCalib(size_t key1, size_t key2, const gtsam::Point3& gpsIn, + const gtsam::noiseModel::Base* model); + + // Testable + void print(string s = "", const gtsam::KeyFormatter& keyFormatter = + gtsam::DefaultKeyFormatter) const; + bool equals(const gtsam::NonlinearFactor& expected, double tol); + + // Standard Interface + gtsam::Point3 measurementIn() const; + gtsam::Vector evaluateError(const gtsam::NavState& nTb, const gtsam::Point3& leverArm); // enable serialization functionality void serialize() const; @@ -389,11 +490,49 @@ virtual class BarometricFactor : gtsam::NonlinearFactor { const double& measurementIn() const; double heightOut(double n) const; double baroOut(const double& meters) const; + gtsam::Vector evaluateError(const gtsam::Pose3& p, double b); // enable serialization functionality void serialize() const; }; +#include +class ConstantVelocityFactor : gtsam::NonlinearFactor { + ConstantVelocityFactor(size_t i, size_t j, double dt, const gtsam::noiseModel::Base* model); + gtsam::Vector evaluateError(const gtsam::NavState &x1, const gtsam::NavState &x2) const; +}; + +#include + +class MagFactor: gtsam::NonlinearFactor { + MagFactor(size_t key, const gtsam::Point3& measured, double scale, + const gtsam::Unit3& direction, const gtsam::Point3& bias, + const gtsam::noiseModel::Base* model); + Vector evaluateError(const gtsam::Rot2& nRb); +}; + +class MagFactor1: gtsam::NonlinearFactor { + MagFactor1(size_t key, const gtsam::Point3& measured, double scale, + const gtsam::Unit3& direction, const gtsam::Point3& bias, + const gtsam::noiseModel::Base* model); + Vector evaluateError(const gtsam::Rot3& nRb); +}; + +#include +#include +template +virtual class MagPoseFactor : gtsam::NoiseModelFactor { + MagPoseFactor(size_t pose_key, + const POSE::Translation& measured, double scale, + const POSE::Translation& direction, const POSE::Translation& bias, + const gtsam::noiseModel::Base* noiseModel); + MagPoseFactor(size_t pose_key, + const POSE::Translation& measured, double scale, + const POSE::Translation& direction, const POSE::Translation& bias, + const gtsam::noiseModel::Base* noiseModel, const POSE& body_P_sensor); + Vector evaluateError(const POSE& nRb); +}; + #include virtual class Scenario { gtsam::Pose3 pose(double t) const; diff --git a/gtsam/navigation/navigation.md b/gtsam/navigation/navigation.md new file mode 100644 index 0000000000..704b8c7ad4 --- /dev/null +++ b/gtsam/navigation/navigation.md @@ -0,0 +1,208 @@ +# Navigation + +The `navigation` module in GTSAM provides specialized tools for inertial navigation, GPS integration, and sensor fusion. Here's an overview of key components organized by category: + +## Classes +### Core Navigation Types + +- **[NavState](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/NavState.h)**: Represents the complete navigation state $\mathcal{SE}_2(3)$, i.e., attitude, position, and velocity. It also implements the group ${SE}_2(3)$. +- **[ImuBias](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/ImuBias.h)**: Models constant biases in IMU measurements (accelerometer and gyroscope). + +### Attitude Estimation + +- **[PreintegrationParams](doc/PreintegrationParams.ipynb)**: Parameters for IMU preintegration. +- **[PreintegratedRotation](doc/PreintegratedRotation.ipynb)**: Handles gyroscope measurements to track rotation changes. +- **[AHRSFactor](doc/AHRSFactor.ipynb)**: Attitude and Heading Reference System factor for orientation estimation. +- **[AttitudeFactor](doc/AttitudeFactor.ipynb)**: Factors for attitude estimation from reference directions. + +### IMU Preintegration (See also below) + +- **[PreintegrationBase](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/PreintegrationBase.h)**: Base class for IMU preintegration classes. +- **[ManifoldPreintegration](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/ManifoldPreintegration.h)**: Implements IMU preintegration using manifold-based methods as in the Forster et al paper. +- **[TangentPreintegration](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/TangentPreintegration.h)**: Implements IMU preintegration using tangent space methods, developed at Skydio. +- **[ImuFactor](doc/ImuFactor.ipynb)**: IMU factor. +- **[CombinedImuFactor](doc/CombinedImuFactor.ipynb)**: IMU factor with built-in bias evolution. + +### GNSS Integration + +- **[GPSFactor](doc/GPSFactor.ipynb)**: Factor for incorporating GPS position measurements. +- **[BarometricFactor](doc/BarometricFactor.ipynb)**: Incorporates barometric altitude measurements. + +### Magnetic Field Integration + +- **[MagFactor](doc/MagFactor.ipynb)**: Factor for incorporating magnetic field measurements. +- **[MagPoseFactor](doc/MagPoseFactor.ipynb)**: Factor for incorporating magnetic field measurements with pose constraints. + +### Simulation Tools + +- **[Scenario](doc/Scenario.ipynb)**: Base class for defining motion scenarios. +- **[ConstantTwistScenario](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/Scenario.h)**: Implements constant twist (angular and linear velocity) motion. +- **[AcceleratingScenario](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/Scenario.h)**: Implements constantly accelerating motion. +- **[ScenarioRunner](doc/ScenarioRunner.ipynb)**: Executes scenarios and generates IMU measurements. + +## AHRSFactor and Preintegration + +This section describes the classes primarily involved in Attitude and Heading Reference Systems (AHRS), which rely on gyroscope measurements for orientation preintegration. + +```mermaid +classDiagram + direction LR + + class PreintegratedRotationParams { + +Matrix3 gyroscopeCovariance + +Vector3 omegaCoriolis + +Pose3 body_P_sensor + } + + class PreintegratedRotation { + +double deltaTij_ + +Rot3 deltaRij_ + +Matrix3 delRdelBiasOmega_ + +integrateGyroMeasurement() + +biascorrectedDeltaRij() + } + PreintegratedRotation ..> PreintegratedRotationParams : uses + + class PreintegratedAhrsMeasurements { + +Matrix3 preintMeasCov_ + } + PreintegratedAhrsMeasurements --|> PreintegratedRotation : inherits + + class AHRSFactor { + +evaluateError(...) Vector3 + } + AHRSFactor ..> PreintegratedAhrsMeasurements : uses +``` + +The key components are: + +1. **Parameters (`PreintegratedRotationParams`)**: + * Stores parameters specific to gyroscope integration, including gyro noise covariance, optional Coriolis terms, and the sensor's pose relative to the body frame. + +2. **Rotation Preintegration ([PreintegratedRotation](doc/PreintegratedRotation.ipynb))**: + * Handles the core logic for integrating gyroscope measurements over time to estimate the change in orientation (`deltaRij`). + * Calculates the Jacobian of this integrated rotation with respect to gyroscope bias (`delRdelBiasOmega`). + +3. **AHRS Preintegrated Measurements (`PreintegratedAhrsMeasurements`)**: + * Inherits from `PreintegratedRotation` and adds the calculation and storage of the covariance matrix (`preintMeasCov_`) associated with the preintegrated rotation. + * This class specifically accumulates the information needed by the `AHRSFactor`. + +4. **AHRS Factor ([AHRSFactor](doc/AHRSFactor.ipynb))**: + * A factor that constrains two `Rot3` orientation variables and a `Vector3` bias variable using the information accumulated in a `PreintegratedAhrsMeasurements` object. + * It effectively measures the consistency between the orientation change predicted by the integrated gyro measurements and the orientation change implied by the factor's connected state variables. + +## IMU Factor and Preintegration + +This section describes the classes involved in preintegrating full IMU measurements (accelerometer and gyroscope) for use in factors like `ImuFactor` and `CombinedImuFactor`. + +```mermaid +classDiagram + direction TD + + class PreintegrationBase { + <> + +imuBias::ConstantBias biasHat_ + +double deltaTij_ + +resetIntegration()* + +integrateMeasurement()* + +biasCorrectedDelta()* + +predict() + +computeError() + } + + class ManifoldPreintegration { + +NavState deltaXij_ + +update() + } + ManifoldPreintegration --|> PreintegrationBase : implements + + class TangentPreintegration { + +Vector9 preintegrated_ + +update() + } + TangentPreintegration --|> PreintegrationBase : implements + + class PreintegratedImuMeasurements { + +Matrix9 preintMeasCov_ + } + PreintegratedImuMeasurements --|> ManifoldPreintegration : inherits + PreintegratedImuMeasurements --|> TangentPreintegration : inherits + + class PreintegratedCombinedMeasurements { + +Matrix preintMeasCov_ (15x15) + } + PreintegratedCombinedMeasurements --|> ManifoldPreintegration : inherits + PreintegratedCombinedMeasurements --|> TangentPreintegration : inherits + + class ImuFactor { + Pose3, Vector3, Pose3, Vector3, ConstantBias + +evaluateError(...) Vector9 + } + ImuFactor ..> PreintegratedImuMeasurements : uses + class ImuFactor2 { + NavState, NavState, ConstantBias + +evaluateError(...) Vector9 + } + ImuFactor2 ..> PreintegratedImuMeasurements : uses + + + class CombinedImuFactor { + Pose3, Vector3, Pose3, Vector3, ConstantBias + +evaluateError(...) Vector (15) + } + CombinedImuFactor ..> PreintegratedCombinedMeasurements : uses +``` + +```mermaid +classDiagram + direction LR + + class PreintegratedRotationParams { + +Matrix3 gyroscopeCovariance + +Vector3 omegaCoriolis + +Pose3 body_P_sensor + } + class PreintegrationParams { + +Matrix3 accelerometerCovariance + +Vector3 n_gravity + } + PreintegrationParams --|> PreintegratedRotationParams : inherits + + class PreintegrationCombinedParams { + +Matrix3 biasAccCovariance + +Matrix3 biasOmegaCovariance + } + PreintegrationCombinedParams --|> PreintegrationParams : inherits +``` + +The key components are: + +1. **Parameters (`...Params`)**: + * `PreintegratedRotationParams`: Base parameter class (gyro noise, Coriolis, sensor pose). + * `PreintegrationParams`: Adds accelerometer noise, gravity vector, integration noise. + * `PreintegrationCombinedParams`: Adds parameters for bias random walk covariance. + +2. **Preintegration Interface (`PreintegrationBase`)**: + * An abstract base class defining the common interface for different IMU preintegration methods. It manages the bias estimate used during integration (`biasHat_`) and the time interval (`deltaTij_`). + * Defines pure virtual methods for integration, bias correction, and state access. + +3. **Preintegration Implementations**: + * `ManifoldPreintegration`: Concrete implementation of `PreintegrationBase`. Integrates directly on the `NavState` manifold, storing the result as a `NavState`. Corresponds to Forster et al. RSS 2015. + * `TangentPreintegration`: Concrete implementation of `PreintegrationBase`. Integrates increments in the 9D tangent space of `NavState`, storing the result as a `Vector9`. + +4. **Preintegrated Measurements Containers**: + * `PreintegratedImuMeasurements`: Stores the result of standard IMU preintegration along with its 9x9 covariance (`preintMeasCov_`). + * `PreintegratedCombinedMeasurements`: Similar, but designed for the `CombinedImuFactor`. Stores the larger 15x15 covariance matrix (`preintMeasCov_`) that includes correlations with the bias terms. + +5. **IMU Factors (`...Factor`)**: + * [ImuFactor](doc/ImuFactor.ipynb): A 5-way factor connecting previous pose/velocity, current pose/velocity, and a single (constant during the interval) bias estimate. Does *not* model bias evolution between factors. + * [ImuFactor2](doc/ImuFactor.ipynb): A 3-way factor connecting previous `NavState`, current `NavState`, and a single bias estimate. Functionally similar to `ImuFactor` but uses the combined `NavState` type. + * [CombinedImuFactor](doc/CombinedImuFactor.ipynb): A 6-way factor connecting previous pose/velocity, current pose/velocity, previous bias, and current bias. *Includes* a model for bias random walk evolution between the two bias states. + +### Important notes +- Which implementation is used for `PreintegrationType` depends on the compile flag `GTSAM_TANGENT_PREINTEGRATION`, which is true by default. + - If false, `ManifoldPreintegration` is used. Please use this setting to get the exact implementation from {cite:t}`https://doi.org/10.1109/TRO.2016.2597321`. + - If true, `TangentPreintegration` is used. This does the integration on the tangent space of the NavState manifold. +- Using the combined IMU factor is not recommended. Typically biases evolve slowly, and hence a separate, lower frequency Markov chain on the bias is more appropriate. +- For short-duration experiments it is even recommended to use a single constant bias. Bias estimation is notoriously hard to tune/debug, and also acts as a "sink" for any modeling errors. Hence, starting with a constant bias is a good idea to get the rest of the pipeline working. + diff --git a/gtsam/nonlinear/BatchFixedLagSmoother.h b/gtsam/nonlinear/BatchFixedLagSmoother.h index 8dde520a77..f4d06bd243 100644 --- a/gtsam/nonlinear/BatchFixedLagSmoother.h +++ b/gtsam/nonlinear/BatchFixedLagSmoother.h @@ -33,9 +33,18 @@ class GTSAM_EXPORT BatchFixedLagSmoother : public FixedLagSmoother { /// Typedef for a shared pointer to an Incremental Fixed-Lag Smoother typedef std::shared_ptr shared_ptr; - /** default constructor */ + /** + * Construct with parameters + * + * @param smootherLag The length of the smoother lag. Any variable older than this amount will be marginalized out. + * @param parameters The L-M optimization parameters + * @param enforceConsistency A flag indicating if the optimizer should enforce probabilistic consistency by maintaining the + * linearization point of all variables involved in linearized/marginal factors at the edge of the + * smoothing window. + */ BatchFixedLagSmoother(double smootherLag = 0.0, const LevenbergMarquardtParams& parameters = LevenbergMarquardtParams(), bool enforceConsistency = true) : - FixedLagSmoother(smootherLag), parameters_(parameters), enforceConsistency_(enforceConsistency) { } + FixedLagSmoother(smootherLag), parameters_(parameters), enforceConsistency_(enforceConsistency) { + } /** destructor */ ~BatchFixedLagSmoother() override {} diff --git a/gtsam/nonlinear/BayesTreeMarginalizationHelper.h b/gtsam/nonlinear/BayesTreeMarginalizationHelper.h new file mode 100644 index 0000000000..133de6c467 --- /dev/null +++ b/gtsam/nonlinear/BayesTreeMarginalizationHelper.h @@ -0,0 +1,358 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file BayesTreeMarginalizationHelper.h + * @brief Helper functions for marginalizing variables from a Bayes Tree. + * + * @author Jeffrey (Zhiwei Wang) + * @date Oct 28, 2024 + */ + +// \callgraph +#pragma once + +#include +#include +#include +#include +#include +#include +#include "gtsam/dllexport.h" + +namespace gtsam { + +/** + * This class provides helper functions for marginalizing variables from a Bayes Tree. + */ +template +class GTSAM_EXPORT BayesTreeMarginalizationHelper { + +public: + using Clique = typename BayesTree::Clique; + using sharedClique = typename BayesTree::sharedClique; + + /** + * This function identifies variables that need to be re-eliminated before + * performing marginalization. + * + * Re-elimination is necessary for a clique containing marginalizable + * variables if: + * + * 1. Some non-marginalizable variables appear before marginalizable ones + * in that clique; + * 2. Or it has a child node depending on a marginalizable variable AND the + * subtree rooted at that child contains non-marginalizables. + * + * In addition, for any descendant node depending on a marginalizable + * variable, if the subtree rooted at that descendant contains + * non-marginalizable variables (i.e., it lies on a path from one of the + * aforementioned cliques that require re-elimination to a node containing + * non-marginalizable variables at the leaf side), then it also needs to + * be re-eliminated. + * + * @param[in] bayesTree The Bayes tree + * @param[in] marginalizableKeys Keys to be marginalized + * @return Set of additional keys that need to be re-eliminated + */ + static std::unordered_set + gatherAdditionalKeysToReEliminate( + const BayesTree& bayesTree, + const KeyVector& marginalizableKeys) { + const bool debug = ISDEBUG("BayesTreeMarginalizationHelper"); + + std::unordered_set additionalCliques = + gatherAdditionalCliquesToReEliminate(bayesTree, marginalizableKeys); + + std::unordered_set additionalKeys; + for (const Clique* clique : additionalCliques) { + addCliqueToKeySet(clique, &additionalKeys); + } + + if (debug) { + std::cout << "BayesTreeMarginalizationHelper: Additional keys to re-eliminate: "; + for (const Key& key : additionalKeys) { + std::cout << DefaultKeyFormatter(key) << " "; + } + std::cout << std::endl; + } + + return additionalKeys; + } + + protected: + /** + * This function identifies cliques that need to be re-eliminated before + * performing marginalization. + * See the docstring of @ref gatherAdditionalKeysToReEliminate(). + */ + static std::unordered_set + gatherAdditionalCliquesToReEliminate( + const BayesTree& bayesTree, + const KeyVector& marginalizableKeys) { + std::unordered_set additionalCliques; + std::unordered_set marginalizableKeySet( + marginalizableKeys.begin(), marginalizableKeys.end()); + CachedSearch cachedSearch; + + // Check each clique that contains a marginalizable key + for (const Clique* clique : + getCliquesContainingKeys(bayesTree, marginalizableKeySet)) { + if (additionalCliques.count(clique)) { + // The clique has already been visited. This can happen when an + // ancestor of the current clique also contain some marginalizable + // varaibles and it's processed beore the current. + continue; + } + + if (needsReelimination(clique, marginalizableKeySet, &cachedSearch)) { + // Add the current clique + additionalCliques.insert(clique); + + // Then add the dependent cliques + gatherDependentCliques(clique, marginalizableKeySet, &additionalCliques, + &cachedSearch); + } + } + return additionalCliques; + } + + /** + * Gather the cliques containing any of the given keys. + * + * @param[in] bayesTree The Bayes tree + * @param[in] keysOfInterest Set of keys of interest + * @return Set of cliques that contain any of the given keys + */ + static std::unordered_set getCliquesContainingKeys( + const BayesTree& bayesTree, + const std::unordered_set& keysOfInterest) { + std::unordered_set cliques; + for (const Key& key : keysOfInterest) { + cliques.insert(bayesTree[key].get()); + } + return cliques; + } + + /** + * A struct to cache the results of the below two functions. + */ + struct CachedSearch { + std::unordered_map wholeMarginalizableCliques; + std::unordered_map wholeMarginalizableSubtrees; + }; + + /** + * Check if all variables in the clique are marginalizable. + * + * Note we use a cache map to avoid repeated searches. + */ + static bool isWholeCliqueMarginalizable( + const Clique* clique, + const std::unordered_set& marginalizableKeys, + CachedSearch* cache) { + auto it = cache->wholeMarginalizableCliques.find(clique); + if (it != cache->wholeMarginalizableCliques.end()) { + return it->second; + } else { + bool ret = true; + for (Key key : clique->conditional()->frontals()) { + if (!marginalizableKeys.count(key)) { + ret = false; + break; + } + } + cache->wholeMarginalizableCliques.insert({clique, ret}); + return ret; + } + } + + /** + * Check if all variables in the subtree are marginalizable. + * + * Note we use a cache map to avoid repeated searches. + */ + static bool isWholeSubtreeMarginalizable( + const Clique* subtree, + const std::unordered_set& marginalizableKeys, + CachedSearch* cache) { + auto it = cache->wholeMarginalizableSubtrees.find(subtree); + if (it != cache->wholeMarginalizableSubtrees.end()) { + return it->second; + } else { + bool ret = true; + if (isWholeCliqueMarginalizable(subtree, marginalizableKeys, cache)) { + for (const sharedClique& child : subtree->children) { + if (!isWholeSubtreeMarginalizable(child.get(), marginalizableKeys, cache)) { + ret = false; + break; + } + } + } else { + ret = false; + } + cache->wholeMarginalizableSubtrees.insert({subtree, ret}); + return ret; + } + } + + /** + * Check if a clique contains variables that need reelimination due to + * elimination ordering conflicts. + * + * @param[in] clique The clique to check + * @param[in] marginalizableKeys Set of keys to be marginalized + * @return true if any variables in the clique need re-elimination + */ + static bool needsReelimination( + const Clique* clique, + const std::unordered_set& marginalizableKeys, + CachedSearch* cache) { + bool hasNonMarginalizableAhead = false; + + // Check each frontal variable in order + for (Key key : clique->conditional()->frontals()) { + if (marginalizableKeys.count(key)) { + // If we've seen non-marginalizable variables before this one, + // we need to reeliminate + if (hasNonMarginalizableAhead) { + return true; + } + + // Check if any child depends on this marginalizable key and the + // subtree rooted at that child contains non-marginalizables. + for (const sharedClique& child : clique->children) { + if (hasDependency(child.get(), key) && + !isWholeSubtreeMarginalizable(child.get(), marginalizableKeys, cache)) { + return true; + } + } + } else { + hasNonMarginalizableAhead = true; + } + } + return false; + } + + /** + * Gather all dependent nodes that lie on a path from the root clique + * to a clique containing a non-marginalizable variable at the leaf side. + * + * @param[in] rootClique The root clique + * @param[in] marginalizableKeys Set of keys to be marginalized + */ + static void gatherDependentCliques( + const Clique* rootClique, + const std::unordered_set& marginalizableKeys, + std::unordered_set* additionalCliques, + CachedSearch* cache) { + std::vector dependentChildren; + dependentChildren.reserve(rootClique->children.size()); + for (const sharedClique& child : rootClique->children) { + if (additionalCliques->count(child.get())) { + // This child has already been visited. This can happen if the + // child itself contains a marginalizable variable and it's + // processed before the current rootClique. + continue; + } + if (hasDependency(child.get(), marginalizableKeys)) { + dependentChildren.push_back(child.get()); + } + } + gatherDependentCliquesFromChildren( + dependentChildren, marginalizableKeys, additionalCliques, cache); + } + + /** + * A helper function for the above gatherDependentCliques(). + */ + static void gatherDependentCliquesFromChildren( + const std::vector& dependentChildren, + const std::unordered_set& marginalizableKeys, + std::unordered_set* additionalCliques, + CachedSearch* cache) { + std::deque descendants( + dependentChildren.begin(), dependentChildren.end()); + while (!descendants.empty()) { + const Clique* descendant = descendants.front(); + descendants.pop_front(); + + // If the subtree rooted at this descendant contains non-marginalizables, + // it must lie on a path from the root clique to a clique containing + // non-marginalizables at the leaf side. + if (!isWholeSubtreeMarginalizable(descendant, marginalizableKeys, cache)) { + additionalCliques->insert(descendant); + + // Add children of the current descendant to the set descendants. + for (const sharedClique& child : descendant->children) { + if (additionalCliques->count(child.get())) { + // This child has already been visited. + continue; + } else { + descendants.push_back(child.get()); + } + } + } + } + } + + /** + * Add all frontal variables from a clique to a key set. + * + * @param[in] clique Clique to add keys from + * @param[out] additionalKeys Pointer to the output key set + */ + static void addCliqueToKeySet( + const Clique* clique, + std::unordered_set* additionalKeys) { + for (Key key : clique->conditional()->frontals()) { + additionalKeys->insert(key); + } + } + + /** + * Check if the clique depends on the given key. + * + * @param[in] clique Clique to check + * @param[in] key Key to check for dependencies + * @return true if clique depends on the key + */ + static bool hasDependency( + const Clique* clique, Key key) { + auto& conditional = clique->conditional(); + if (std::find(conditional->beginParents(), + conditional->endParents(), key) + != conditional->endParents()) { + return true; + } else { + return false; + } + } + + /** + * Check if the clique depends on any of the given keys. + */ + static bool hasDependency( + const Clique* clique, const std::unordered_set& keys) { + auto& conditional = clique->conditional(); + for (auto it = conditional->beginParents(); + it != conditional->endParents(); ++it) { + if (keys.count(*it)) { + return true; + } + } + + return false; + } +}; +// BayesTreeMarginalizationHelper + +}/// namespace gtsam diff --git a/gtsam_unstable/nonlinear/IncrementalFixedLagSmoother.cpp b/gtsam/nonlinear/IncrementalFixedLagSmoother.cpp similarity index 98% rename from gtsam_unstable/nonlinear/IncrementalFixedLagSmoother.cpp rename to gtsam/nonlinear/IncrementalFixedLagSmoother.cpp index 0cd9ecbacc..394eb77b10 100644 --- a/gtsam_unstable/nonlinear/IncrementalFixedLagSmoother.cpp +++ b/gtsam/nonlinear/IncrementalFixedLagSmoother.cpp @@ -19,8 +19,8 @@ * @date Oct 14, 2012 */ -#include -#include +#include +#include #include namespace gtsam { diff --git a/gtsam/nonlinear/IncrementalFixedLagSmoother.h b/gtsam/nonlinear/IncrementalFixedLagSmoother.h new file mode 100644 index 0000000000..1e4263d4b5 --- /dev/null +++ b/gtsam/nonlinear/IncrementalFixedLagSmoother.h @@ -0,0 +1,159 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file IncrementalFixedLagSmoother.h + * @brief An iSAM2-based fixed-lag smoother. + * + * @author Michael Kaess, Stephen Williams + * @date Oct 14, 2012 + */ + +// \callgraph +#pragma once + +#include +#include +#include "gtsam/dllexport.h" + +namespace gtsam { + +/** + * This is a base class for the various HMF2 implementations. The HMF2 eliminates the factor graph + * such that the active states are placed in/near the root. This base class implements a function + * to calculate the ordering, and an update function to incorporate new factors into the HMF. + */ +class GTSAM_EXPORT IncrementalFixedLagSmoother: public FixedLagSmoother { + +public: + + /// Typedef for a shared pointer to an Incremental Fixed-Lag Smoother + typedef std::shared_ptr shared_ptr; + + /** default constructor */ + IncrementalFixedLagSmoother(double smootherLag = 0.0, + const ISAM2Params& parameters = DefaultISAM2Params()) : + FixedLagSmoother(smootherLag), isam_(parameters) { + } + + /** destructor */ + ~IncrementalFixedLagSmoother() override { + } + + /** Print the factor for debugging and testing (implementing Testable) */ + void print(const std::string& s = "IncrementalFixedLagSmoother:\n", + const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override; + + /** Check if two IncrementalFixedLagSmoother Objects are equal */ + bool equals(const FixedLagSmoother& rhs, double tol = 1e-9) const override; + + /** + * Add new factors, updating the solution and re-linearizing as needed. + * @param newFactors new factors on old and/or new variables + * @param newTheta new values for new variables only + * @param timestamps an (optional) map from keys to real time stamps + * @param factorsToRemove an (optional) list of factors to remove. + */ + Result update(const NonlinearFactorGraph& newFactors = NonlinearFactorGraph(), + const Values& newTheta = Values(), // + const KeyTimestampMap& timestamps = KeyTimestampMap(), + const FactorIndices& factorsToRemove = FactorIndices()) override; + + /** Compute an estimate from the incomplete linear delta computed during the last update. + * This delta is incomplete because it was not updated below wildfire_threshold. If only + * a single variable is needed, it is faster to call calculateEstimate(const KEY&). + */ + Values calculateEstimate() const override { + return isam_.calculateEstimate(); + } + + /** Compute an estimate for a single variable using its incomplete linear delta computed + * during the last update. This is faster than calling the no-argument version of + * calculateEstimate, which operates on all variables. + * @param key + * @return + */ + template + VALUE calculateEstimate(Key key) const { + return isam_.calculateEstimate(key); + } + + /** return the current set of iSAM2 parameters */ + const ISAM2Params& params() const { + return isam_.params(); + } + + /** Access the current set of factors */ + const NonlinearFactorGraph& getFactors() const { + return isam_.getFactorsUnsafe(); + } + + /** Access the current linearization point */ + const Values& getLinearizationPoint() const { + return isam_.getLinearizationPoint(); + } + + /** Access the current set of deltas to the linearization point */ + const VectorValues& getDelta() const { + return isam_.getDelta(); + } + + /// Calculate marginal covariance on given variable + Matrix marginalCovariance(Key key) const { + return isam_.marginalCovariance(key); + } + + /// Get results of latest isam2 update + const ISAM2Result& getISAM2Result() const{ return isamResult_; } + + /// Get the iSAM2 object which is used for the inference internally + const ISAM2& getISAM2() const { return isam_; } + +protected: + + /** Create default parameters */ + static ISAM2Params DefaultISAM2Params() { + ISAM2Params params; + params.findUnusedFactorSlots = true; + return params; + } + + /** An iSAM2 object used to perform inference. The smoother lag is controlled + * by what factors are removed each iteration */ + ISAM2 isam_; + + /** Store results of latest isam2 update */ + ISAM2Result isamResult_; + + /** Erase any keys associated with timestamps before the provided time */ + void eraseKeysBefore(double timestamp); + + /** Fill in an iSAM2 ConstrainedKeys structure such that the provided keys are eliminated before all others */ + void createOrderingConstraints(const KeyVector& marginalizableKeys, + std::optional >& constrainedKeys) const; + +private: + /** Private methods for printing debug information */ + static void PrintKeySet(const std::set& keys, const std::string& label = + "Keys:"); + static void PrintSymbolicFactor(const GaussianFactor::shared_ptr& factor); + static void PrintSymbolicGraph(const GaussianFactorGraph& graph, + const std::string& label = "Factor Graph:"); + static void PrintSymbolicTree(const gtsam::ISAM2& isam, + const std::string& label = "Bayes Tree:"); + static void PrintSymbolicTreeHelper( + const gtsam::ISAM2Clique::shared_ptr& clique, const std::string indent = + ""); + +}; +// IncrementalFixedLagSmoother + +}/// namespace gtsam diff --git a/gtsam/nonlinear/doc/BatchFixedLagSmoother.ipynb b/gtsam/nonlinear/doc/BatchFixedLagSmoother.ipynb new file mode 100644 index 0000000000..56b4e414af --- /dev/null +++ b/gtsam/nonlinear/doc/BatchFixedLagSmoother.ipynb @@ -0,0 +1,59 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "id": "283174f8", + "metadata": {}, + "source": [ + "# BatchFixedLagSmoother\n", + "\n", + "## Overview\n", + "\n", + "The `IncrementalFixedLagSmoother` is a [FixedLagSmoother](FixedLagSmoother.ipynb) that uses [LevenbergMarquardtOptimizer](LevenbergMarquardtOptimizer.ipynb) for batch optimization.\n", + "\n", + "This fixed lag smoother will **batch-optimize** at every iteration, but warm-started from the last estimate." + ] + }, + { + "cell_type": "markdown", + "id": "92b4f851", + "metadata": {}, + "source": [ + "## API\n", + "\n", + "### Constructor\n", + "\n", + "You construct a `BatchFixedLagSmoother` object with the following parameters:\n", + "\n", + "- **smootherLag**: The length of the smoother lag. Any variable older than this amount will be marginalized out. *(Default: 0.0)*\n", + "- **parameters**: The Levenberg-Marquardt optimization parameters. *(Default: `LevenbergMarquardtParams()`)* \n", + "- **enforceConsistency**: A flag indicating whether the optimizer should enforce probabilistic consistency by maintaining the linearization point of all variables involved in linearized/marginal factors at the edge of the smoothing window. *(Default: `true`)*\n", + "\n", + "### Smoothing and Optimization\n", + "\n", + "- **update**: This method is the core of the `BatchFixedLagSmoother`. It processes new factors and variables, updating the current estimate of the state. The update method also manages the marginalization of variables that fall outside the fixed lag window.\n", + "\n", + "### Computational Considerations\n", + "\n", + "Every call to `update` triggers a batch LM optimization: use the parameters to control the convergence thresholds to bound computation to fit within your application." + ] + }, + { + "cell_type": "markdown", + "id": "4a2bdd3e", + "metadata": {}, + "source": [ + "## Internals\n", + "\n", + "- **marginalize**: This function handles the marginalization of variables that are no longer within the fixed lag window. Marginalization is a crucial step in maintaining the size of the factor graph, ensuring that only relevant variables are kept for optimization.\n" + ] + } + ], + "metadata": { + "language_info": { + "name": "python" + } + }, + "nbformat": 4, + "nbformat_minor": 5 +} diff --git a/gtsam/nonlinear/doc/CustomFactor.ipynb b/gtsam/nonlinear/doc/CustomFactor.ipynb new file mode 100644 index 0000000000..beb2961bba --- /dev/null +++ b/gtsam/nonlinear/doc/CustomFactor.ipynb @@ -0,0 +1,316 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "id": "31f395c5", + "metadata": {}, + "source": [ + "# CustomFactor" + ] + }, + { + "cell_type": "markdown", + "id": "1a3591a2", + "metadata": {}, + "source": [ + "\"Open" + ] + }, + { + "cell_type": "code", + "execution_count": 1, + "id": "5ccb48e4", + "metadata": { + "tags": [ + "remove-cell" + ], + "vscode": { + "languageId": "markdown" + } + }, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "\u001b[31mERROR: Could not find a version that satisfies the requirement gtsam-develop (from versions: none)\u001b[0m\u001b[31m\n", + "\u001b[0m\u001b[31mERROR: No matching distribution found for gtsam-develop\u001b[0m\u001b[31m\n", + "\u001b[0mNote: you may need to restart the kernel to use updated packages.\n" + ] + } + ], + "source": [ + "%pip install --quiet gtsam-develop" + ] + }, + { + "cell_type": "markdown", + "id": "10df70c9", + "metadata": {}, + "source": [ + "\n", + "## Overview\n", + "\n", + "The `CustomFactor` class allows users to define custom error functions and Jacobians, and while it can be used in C++, it is particularly useful for use with the python wrapper.\n", + "\n", + "## Custom Error Function\n", + "\n", + "The `CustomFactor` class allows users to define a custom error function. In C++ it is defined as below:\n", + "\n", + "```cpp\n", + "using JacobianVector = std::vector;\n", + "using CustomErrorFunction = std::function;\n", + "```\n", + "\n", + "The function will be passed a reference to the factor itself so the keys can be accessed, a `Values` reference, and a writeable vector of Jacobians.\n", + "\n", + "## Usage in Python\n", + "\n", + "In order to use a Python-based factor, one needs to have a Python function with the following signature:\n", + "\n", + "```python\n", + "def error_func(this: gtsam.CustomFactor, v: gtsam.Values, H: list[np.ndarray]) -> np.ndarray:\n", + " ...\n", + "```\n", + "\n", + "**Explanation**:\n", + "- `this` is a reference to the `CustomFactor` object. This is required because one can reuse the same `error_func` for multiple factors. `v` is a reference to the current set of values, and `H` is a list of *references* to the list of required Jacobians (see the corresponding C++ documentation). \n", + "- the error returned must be a 1D `numpy` array.\n", + "- If `H` is `None`, it means the current factor evaluation does not need Jacobians. For example, the `error`\n", + "method on a factor does not need Jacobians, so we don't evaluate them to save CPU. If `H` is not `None`,\n", + "each entry of `H` can be assigned a (2D) `numpy` array, as the Jacobian for the corresponding variable.\n", + "- All `numpy` matrices inside should be using `order=\"F\"` to maintain interoperability with C++.\n", + "\n", + "After defining `error_func`, one can create a `CustomFactor` just like any other factor in GTSAM. In summary, to use `CustomFactor`, users must:\n", + "1. Define the custom error function that models the specific measurement or constraint.\n", + "2. Implement the calculation of the Jacobian matrix for the error function.\n", + "3. Define a noise model of the appropriate dimension.\n", + "3. Add the `CustomFactor` to a factor graph, specifying\n", + " - the noise model\n", + " - the keys of the variables it depends on\n", + " - the error function" + ] + }, + { + "cell_type": "markdown", + "id": "c7ec3512", + "metadata": {}, + "source": [ + "**Notes**:\n", + "- There are not a lot of restrictions on the function, but note there is overhead in calling a python function from within a c++ optimization loop. \n", + "- Because `pybind11` needs to lock the Python GIL lock for evaluation of each factor, parallel evaluation of `CustomFactor` is not possible.\n", + "- You can mitigate both of these by having a python function that leverages batching of measurements.\n", + "\n", + "Some more examples of usage in python are given in [test_custom_factor.py](https://github.com/borglab/gtsam/blob/develop/python/gtsam/tests/test_custom_factor.py),[CustomFactorExample.py](https://github.com/borglab/gtsam/blob/develop/python/gtsam/examples/CustomFactorExample.py), and [CameraResectioning.py](https://github.com/borglab/gtsam/blob/develop/python/gtsam/examples/CameraResectioning.py)." + ] + }, + { + "cell_type": "markdown", + "id": "68a66627", + "metadata": {}, + "source": [ + "## Example\n", + "Below is a simple example that mimics a `BetweenFactor`." + ] + }, + { + "cell_type": "code", + "execution_count": 2, + "id": "894bfaf2", + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "CustomFactor on 66, 77\n", + "isotropic dim=3 sigma=0.1\n", + "\n" + ] + } + ], + "source": [ + "import numpy as np\n", + "from gtsam import CustomFactor, noiseModel, Values, Pose2\n", + "\n", + "measurement = Pose2(2, 2, np.pi / 2) # is used to create the error function\n", + "\n", + "def error_func(this: CustomFactor, v: Values, H: list[np.ndarray]=None):\n", + " \"\"\"\n", + " Error function that mimics a BetweenFactor\n", + " :param this: reference to the current CustomFactor being evaluated\n", + " :param v: Values object\n", + " :param H: list of references to the Jacobian arrays\n", + " :return: the non-linear error\n", + " \"\"\"\n", + " key0 = this.keys()[0]\n", + " key1 = this.keys()[1]\n", + " gT1, gT2 = v.atPose2(key0), v.atPose2(key1)\n", + " error = measurement.localCoordinates(gT1.between(gT2))\n", + "\n", + " if H is not None:\n", + " result = gT1.between(gT2)\n", + " H[0] = -result.inverse().AdjointMap()\n", + " H[1] = np.eye(3)\n", + " return error\n", + "\n", + "# we use an isotropic noise model, and keys 66 and 77\n", + "noise_model = noiseModel.Isotropic.Sigma(3, 0.1)\n", + "custom_factor = CustomFactor(noise_model, [66, 77], error_func)\n", + "print(custom_factor)" + ] + }, + { + "cell_type": "markdown", + "id": "b72a8fc7", + "metadata": {}, + "source": [ + "Typically, you would not actually call methods of a custom factor directly: a nonlinear optimizer will call `linearize` in every nonlinear iteration. But if you wanted to, here is how you would do it:" + ] + }, + { + "cell_type": "code", + "execution_count": 3, + "id": "c92caf2c", + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "error = 0.0\n", + "Linearized JacobianFactor:\n", + " A[66] = [\n", + "\t-6.12323e-16, -10, -20;\n", + "\t10, -6.12323e-16, -20;\n", + "\t-0, -0, -10\n", + "]\n", + " A[77] = [\n", + "\t10, 0, 0;\n", + "\t0, 10, 0;\n", + "\t0, 0, 10\n", + "]\n", + " b = [ -0 -0 -0 ]\n", + " No noise model\n", + "\n" + ] + } + ], + "source": [ + "values = Values()\n", + "values.insert(66, Pose2(1, 2, np.pi / 2))\n", + "values.insert(77, Pose2(-1, 4, np.pi))\n", + "\n", + "print(\"error = \", custom_factor.error(values))\n", + "print(\"Linearized JacobianFactor:\\n\", custom_factor.linearize(values))" + ] + }, + { + "cell_type": "markdown", + "id": "d9b61f83", + "metadata": {}, + "source": [ + "## Beware of Jacobians!\n", + "\n", + "It is important to unit-test the Jacobians you provide, because the convention used in GTSAM frequently leads to confusion. In particular, GTSAM updates variables using an exponential map *on the right*. In particular, for a variable $x\\in G$, an n-dimensional Lie group, the Jacobian $H_a$ at $x=a$ is defined as the linear map satisfying\n", + "$$\n", + "\\lim_{\\xi\\rightarrow0}\\frac{\\left|f(a)+H_a\\xi-f\\left(a \\, \\text{Exp}(\\xi)\\right)\\right|}{\\left|\\xi\\right|}=0,\n", + "$$\n", + "where $\\xi$ is a n-vector corresponding to an element in the Lie algebra $\\mathfrak{g}$, and $\\text{Exp}(\\xi)\\doteq\\exp(\\xi^{\\wedge})$, with $\\exp$ the exponential map from $\\mathfrak{g}$ back to $G$. The same holds for n-dimensional manifold $M$, in which case we use a suitable retraction instead of the exponential map. More details and examples can be found in [doc/math.pdf](https://github.com/borglab/gtsam/blob/develop/gtsam/doc/math.pdf).\n", + "\n", + "To test your Jacobians, you can use the handy `gtsam.utils.numerical_derivative` module. We give an example below:" + ] + }, + { + "cell_type": "code", + "execution_count": 4, + "id": "c815269f", + "metadata": {}, + "outputs": [], + "source": [ + "from gtsam.utils.numerical_derivative import numericalDerivative21, numericalDerivative22\n", + "\n", + "# Allocate the Jacobians and call error_func\n", + "H = [np.empty((6, 6), order='F'),np.empty((6, 6), order='F')]\n", + "error_func(custom_factor, values, H)\n", + "\n", + "# We use error_func directly, so we need to create a binary function constructing the values.\n", + "def f (T1, T2):\n", + " v = Values()\n", + " v.insert(66, T1)\n", + " v.insert(77, T2)\n", + " return error_func(custom_factor, v)\n", + "numerical0 = numericalDerivative21(f, values.atPose2(66), values.atPose2(77))\n", + "numerical1 = numericalDerivative22(f, values.atPose2(66), values.atPose2(77))\n", + "\n", + "# Check the numerical derivatives against the analytical ones\n", + "np.testing.assert_allclose(H[0], numerical0, rtol=1e-5, atol=1e-8)\n", + "np.testing.assert_allclose(H[1], numerical1, rtol=1e-5, atol=1e-8)" + ] + }, + { + "cell_type": "markdown", + "id": "fd09b0fc", + "metadata": {}, + "source": [ + "## Implementation Notes\n", + "\n", + "`CustomFactor` is a `NonlinearFactor` that has a `std::function` as its callback.\n", + "This callback can be translated to a Python function call, thanks to `pybind11`'s functional support.\n", + "\n", + "The constructor of `CustomFactor` is\n", + "```cpp\n", + "/**\n", + "* Constructor\n", + "* @param noiseModel shared pointer to noise model\n", + "* @param keys keys of the variables\n", + "* @param errorFunction the error functional\n", + "*/\n", + "CustomFactor(const SharedNoiseModel& noiseModel, const KeyVector& keys, const CustomErrorFunction& errorFunction) :\n", + " Base(noiseModel, keys) {\n", + " this->error_function_ = errorFunction;\n", + "}\n", + "```\n", + "\n", + "At construction time, `pybind11` will pass the handle to the Python callback function as a `std::function` object.\n", + "\n", + "Something that deserves a special mention is this:\n", + "```cpp\n", + "/*\n", + " * NOTE\n", + " * ==========\n", + " * pybind11 will invoke a copy if this is `JacobianVector &`,\n", + " * and modifications in Python will not be reflected.\n", + " *\n", + " * This is safe because this is passing a const pointer, \n", + " * and pybind11 will maintain the `std::vector` memory layout.\n", + " * Thus the pointer will never be invalidated.\n", + " */\n", + "using CustomErrorFunction = std::function;\n", + "```\n", + "which is not documented in `pybind11` docs. One needs to be aware of this if they wanted to implement similar \"mutable\" arguments going across the Python-C++ boundary.\n" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "py312", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.12.6" + } + }, + "nbformat": 4, + "nbformat_minor": 5 +} diff --git a/gtsam/nonlinear/doc/DoglegOptimizer.ipynb b/gtsam/nonlinear/doc/DoglegOptimizer.ipynb new file mode 100644 index 0000000000..bff4d2609d --- /dev/null +++ b/gtsam/nonlinear/doc/DoglegOptimizer.ipynb @@ -0,0 +1,80 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "id": "f851cef5", + "metadata": {}, + "source": [ + "# DoglegOptimizer\n", + "\n", + "## Overview\n", + "\n", + "The `DoglegOptimizer` class in GTSAM is a specialized optimization algorithm designed for solving nonlinear least squares problems. It implements the Dogleg method, which is a hybrid approach combining the steepest descent and Gauss-Newton methods.\n", + "\n", + "The Dogleg method is characterized by its use of two distinct steps:\n", + "\n", + "1. **Cauchy Point**: The steepest descent direction, calculated as:\n", + " $$ p_u = -\\alpha \\nabla f(x) $$\n", + " where $\\alpha$ is a scalar step size.\n", + "\n", + "2. **Gauss-Newton Step**: The solution to the linearized problem, providing a more accurate but computationally expensive step:\n", + " $$ p_{gn} = -(J^T J)^{-1} J^T r $$\n", + " where $J$ is the Jacobian matrix and $r$ is the residual vector.\n", + "\n", + "The Dogleg step, $p_{dl}$, is a combination of these two steps, determined by the trust region radius $\\Delta$.\n", + "\n", + "Key features:\n", + "\n", + "- **Hybrid Approach**: Combines the strengths of both the steepest descent and Gauss-Newton methods.\n", + "- **Trust Region Method**: Utilizes a trust region to determine the step size, balancing between the accuracy of Gauss-Newton and the robustness of steepest descent.\n", + "- **Efficient for Nonlinear Problems**: Designed to handle complex nonlinear least squares problems effectively." + ] + }, + { + "cell_type": "markdown", + "id": "758e347b", + "metadata": {}, + "source": [ + "## Key Methods\n", + "\n", + "Please see the base class [NonlinearOptimizer.ipynb](NonlinearOptimizer.ipynb).\n", + "\n", + "## Parameters\n", + "\n", + "The `DoglegParams` class defines parameters specific to Powell's Dogleg optimization algorithm:\n", + "\n", + "| Parameter | Description |\n", + "|-----------|-------------|\n", + "| `deltaInitial` | Initial trust region radius that controls step size (default: 1.0) |\n", + "| `verbosityDL` | Controls algorithm-specific diagnostic output (options: SILENT, VERBOSE) |\n", + "\n", + "These parameters complement the standard optimization parameters inherited from `NonlinearOptimizerParams`, which include:\n", + "\n", + "- Maximum iterations\n", + "- Relative and absolute error thresholds\n", + "- Error function verbosity\n", + "- Linear solver type\n", + "\n", + "Powell's Dogleg algorithm combines Gauss-Newton and gradient descent approaches within a trust region framework. The `deltaInitial` parameter defines the initial size of this trust region, which adaptively changes during optimization based on how well the linear approximation matches the nonlinear function.\n", + "\n", + "## Usage Considerations\n", + "\n", + "- **Initial Guess**: The performance of the Dogleg optimizer can be sensitive to the initial guess. A good initial estimate can significantly speed up convergence.\n", + "- **Parameter Tuning**: The choice of the initial trust region radius and other parameters can affect the convergence rate and stability of the optimization.\n", + "\n", + "## Files\n", + "\n", + "- [DoglegOptimizer.h](https://github.com/borglab/gtsam/blob/develop/gtsam/nonlinear/DoglegOptimizer.h)\n", + "- [DoglegOptimizer.cpp](https://github.com/borglab/gtsam/blob/develop/gtsam/nonlinear/DoglegOptimizer.cpp)\n", + "- [DoglegParams.h](https://github.com/borglab/gtsam/blob/develop/gtsam/nonlinear/DoglegParams.h)" + ] + } + ], + "metadata": { + "language_info": { + "name": "python" + } + }, + "nbformat": 4, + "nbformat_minor": 5 +} diff --git a/gtsam/nonlinear/doc/ExpressionFactor.ipynb b/gtsam/nonlinear/doc/ExpressionFactor.ipynb new file mode 100644 index 0000000000..1b4f850ab3 --- /dev/null +++ b/gtsam/nonlinear/doc/ExpressionFactor.ipynb @@ -0,0 +1,46 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "id": "59407eaf", + "metadata": {}, + "source": [ + "# ExpressionFactor\n", + "\n", + "## Overview\n", + "\n", + "The `ExpressionFactor` class in GTSAM is a template class designed to work with factor graphs in the context of nonlinear optimization. It represents a factor that can be constructed from a [GTSAM expression](../../../doc/expressions.md), allowing for flexible and efficient computation of error terms in optimization problems.\n", + "\n", + "The `ExpressionFactor` class allows users to define factors based on expressions in C++, that use (reverse) automatic differentiation to compute their Jacobians.\n", + "\n", + "## Main Methods\n", + "\n", + "### Constructor\n", + "\n", + "The `ExpressionFactor` class provides a constructor that allows for the initialization of the factor with a specific expression and measurement:\n", + "\n", + "```cpp\n", + " /**\n", + " * Constructor: creates a factor from a measurement and measurement function\n", + " * @param noiseModel the noise model associated with a measurement\n", + " * @param measurement actual value of the measurement, of type T\n", + " * @param expression predicts the measurement from Values\n", + " * The keys associated with the factor, returned by keys(), are sorted.\n", + " */\n", + " ExpressionFactor(const SharedNoiseModel& noiseModel, //\n", + " const T& measurement, const Expression& expression)\n", + " : NoiseModelFactor(noiseModel), measured_(measurement) {\n", + " initialize(expression);\n", + " }\n", + "```" + ] + } + ], + "metadata": { + "language_info": { + "name": "python" + } + }, + "nbformat": 4, + "nbformat_minor": 5 +} diff --git a/gtsam/nonlinear/doc/ExpressionFactorGraph.ipynb b/gtsam/nonlinear/doc/ExpressionFactorGraph.ipynb new file mode 100644 index 0000000000..1c22e1315b --- /dev/null +++ b/gtsam/nonlinear/doc/ExpressionFactorGraph.ipynb @@ -0,0 +1,35 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "id": "a1c00a8c", + "metadata": {}, + "source": [ + "# ExpressionFactorGraph \n", + "\n", + "## Overview\n", + "\n", + "The `ExpressionFactorGraph` class in GTSAM is a specialized factor graph designed to work with expressions. It extends the capabilities of a standard factor graph by allowing factors created from [GTSAM expressions](../../../doc/expressions.md), that implement automatic differentiation. It creates [ExpressionFactors](ExpressionFactor.ipynb).\n", + "\n", + "### Adding Expression Factors\n", + "\n", + "use **addExpressionFactor**: This method allows the user to add a new factor to the graph based on a symbolic expression. The expression defines the relationship between the variables involved in the factor.\n", + "```c++\n", + " template\n", + " void addExpressionFactor(const Expression& h, const T& z,\n", + " const SharedNoiseModel& R) {\n", + " using F = ExpressionFactor;\n", + " push_back(std::allocate_shared(Eigen::aligned_allocator(), R, z, h));\n", + " }\n", + "```" + ] + } + ], + "metadata": { + "language_info": { + "name": "python" + } + }, + "nbformat": 4, + "nbformat_minor": 5 +} diff --git a/gtsam/nonlinear/doc/ExtendedKalmanFilter.ipynb b/gtsam/nonlinear/doc/ExtendedKalmanFilter.ipynb new file mode 100644 index 0000000000..bf24e7e104 --- /dev/null +++ b/gtsam/nonlinear/doc/ExtendedKalmanFilter.ipynb @@ -0,0 +1,79 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "id": "93869c17", + "metadata": {}, + "source": [ + "# ExtendedKalmanFilter\n", + "\n", + "## Overview\n", + "\n", + "The `ExtendedKalmanFilter` class in GTSAM is an implementation of the [Extended Kalman Filter (EKF)](https://en.wikipedia.org/wiki/Extended_Kalman_filter), which is a powerful tool for estimating the state of a nonlinear dynamic system.\n", + "\n", + "See also [this notebook](../../../python/gtsam/examples/easyPoint2KalmanFilter.ipynb) for the python version of the C++ example below." + ] + }, + { + "cell_type": "markdown", + "id": "161c36eb", + "metadata": {}, + "source": [ + "## Using the ExtendedKalmanFilter Class\n", + "\n", + "The `ExtendedKalmanFilter` class in GTSAM provides a flexible way to implement Kalman filtering using factor graphs. Here's a step-by-step guide based on the example provided in [easyPoint2KalmanFilter.cpp](https://github.com/borglab/gtsam/blob/develop/examples/easyPoint2KalmanFilter.cpp):\n", + "\n", + "### Steps to Use the ExtendedKalmanFilter\n", + "\n", + "1. **Initialize the Filter**:\n", + " - Define the initial state (e.g., position) and its covariance.\n", + " - Create a key for the initial state.\n", + " - Instantiate the `ExtendedKalmanFilter` object with the initial state and covariance.\n", + "\n", + " ```cpp\n", + " Point2 x_initial(0.0, 0.0);\n", + " SharedDiagonal P_initial = noiseModel::Diagonal::Sigmas(Vector2(0.1, 0.1));\n", + " Symbol x0('x', 0);\n", + " ExtendedKalmanFilter ekf(x0, x_initial, P_initial);\n", + " ```\n", + "\n", + "2. Predict the Next State:\n", + "\n", + " - Define the motion model using a BetweenFactor.\n", + " - Predict the next state using the predict method.\n", + " ```cpp\n", + " Symbol x1('x', 1);\n", + " Point2 difference(1, 0);\n", + " SharedDiagonal Q = noiseModel::Diagonal::Sigmas(Vector2(0.1, 0.1), true);\n", + " BetweenFactor factor1(x0, x1, difference, Q);\n", + " Point2 x1_predict = ekf.predict(factor1);\n", + " ```\n", + "\n", + "3. Update the State with Measurements:\n", + " - Define the measurement model using a PriorFactor.\n", + " - Update the state using the update method.\n", + " ```cpp\n", + " Point2 z1(1.0, 0.0);\n", + " SharedDiagonal R = noiseModel::Diagonal::Sigmas(Vector2(0.25, 0.25), true);\n", + " PriorFactor factor2(x1, z1, R);\n", + " Point2 x1_update = ekf.update(factor2);\n", + " ```\n", + "4. Repeat for Subsequent Time Steps:\n", + "\n", + " - Repeat the prediction and update steps for subsequent states and measurements.\n", + "\n", + "## Example Use Case\n", + "This example demonstrates tracking a moving 2D point using a simple linear motion model and position measurements. The ExtendedKalmanFilter class allows for flexible modeling of both the motion and measurement processes using GTSAM's factor graph framework.\n", + "\n", + "For the full implementation, see the [easyPoint2KalmanFilter.cpp](https://github.com/borglab/gtsam/blob/develop/examples/easyPoint2KalmanFilter.cpp) file.\n" + ] + } + ], + "metadata": { + "language_info": { + "name": "python" + } + }, + "nbformat": 4, + "nbformat_minor": 5 +} diff --git a/gtsam/nonlinear/doc/FixedLagSmoother.ipynb b/gtsam/nonlinear/doc/FixedLagSmoother.ipynb new file mode 100644 index 0000000000..50ac1900d8 --- /dev/null +++ b/gtsam/nonlinear/doc/FixedLagSmoother.ipynb @@ -0,0 +1,44 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "id": "cdd2fdc5", + "metadata": {}, + "source": [ + "# FixedLagSmoother\n", + "\n", + "## Overview\n", + "\n", + "The `FixedLagSmoother` class is the base class for [BatchFixedLagSmoother](BatchFixedLagSmoother.ipynb) and [IncrementalFixedLagSmoother](IncrementalFixedLagSmoother.ipynb).\n", + "\n", + "It provides an API for fixed-lag smoothing in nonlinear factor graphs. It maintains a sliding window of the most recent variables and marginalizes out older variables. This is particularly useful in real-time applications where memory and computational efficiency are critical." + ] + }, + { + "cell_type": "markdown", + "id": "8d372784", + "metadata": {}, + "source": [ + "## Mathematical Formulation\n", + "\n", + "In fixed-lag smoothing the objective is to estimate the state $\\mathbf{x}_t$ given all measurements up to time $t$, but only retaining a fixed window of recent states. The optimization problem can be expressed as:\n", + "$$\n", + "\\min_{\\mathbf{x}_{t-L:t}} \\sum_{i=1}^{N} \\| \\mathbf{h}_i(\\mathbf{x}_{t-L:t}) - \\mathbf{z}_i \\|^2\n", + "$$\n", + "where $L$ is the fixed lag, $\\mathbf{h}_i$ are the measurement functions, and $\\mathbf{z}_i$ are the measurements.\n", + "In practice, the functions $\\mathbf{h}_i$ depend only on a subset of the state variables $\\mathbf{X}_i$, and the optimization is performed over a set of $N$ *factors* $\\phi_i$ instead:\n", + "$$\n", + "\\min_{\\mathbf{x}_{t-L:t}} \\sum_{i=1}^{N} \\| \\phi_i(\\mathbf{X}_i; \\mathbf{z}_i) \\|^2\n", + "$$\n", + "The API below allows the user to add new factors at every iteration, which will be automatically pruned after they no longer depend on any variables in the lag." + ] + } + ], + "metadata": { + "language_info": { + "name": "python" + } + }, + "nbformat": 4, + "nbformat_minor": 5 +} diff --git a/gtsam/nonlinear/doc/GaussNewtonOptimizer.ipynb b/gtsam/nonlinear/doc/GaussNewtonOptimizer.ipynb new file mode 100644 index 0000000000..82932189cb --- /dev/null +++ b/gtsam/nonlinear/doc/GaussNewtonOptimizer.ipynb @@ -0,0 +1,63 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "id": "6463d580", + "metadata": {}, + "source": [ + "# GaussNewtonOptimizer\n", + "\n", + "## Overview\n", + "\n", + "The `GaussNewtonOptimizer` class in GTSAM is designed to optimize nonlinear factor graphs using the Gauss-Newton algorithm. This class is particularly suited for problems where the cost function can be approximated well by a quadratic function near the minimum. The Gauss-Newton method is an iterative optimization technique that updates the solution by linearizing the nonlinear system at each iteration.\n", + "\n", + "The Gauss-Newton algorithm is based on the idea of linearizing the nonlinear residuals $r(x)$ around the current estimate $x_k$. The update step is derived from solving the normal equations:\n", + "\n", + "$$ J(x_k)^T J(x_k) \\Delta x = -J(x_k)^T r(x_k) $$\n", + "\n", + "where $J(x_k)$ is the Jacobian of the residuals with respect to the variables. The solution $\\Delta x$ is used to update the estimate:\n", + "\n", + "$$ x_{k+1} = x_k + \\Delta x $$\n", + "\n", + "This process is repeated iteratively until convergence.\n", + "\n", + "Key features:\n", + "\n", + "- **Iterative Optimization**: The optimizer refines the solution iteratively by linearizing the nonlinear system around the current estimate.\n", + "- **Convergence Control**: It provides mechanisms to control the convergence through parameters such as maximum iterations and relative error tolerance.\n", + "- **Integration with GTSAM**: Seamlessly integrates with GTSAM's factor graph framework, allowing it to be used with various types of factors and variables.\n", + "\n", + "## Key Methods\n", + "\n", + "Please see the base class [NonlinearOptimizer.ipynb](NonlinearOptimizer.ipynb).\n", + "\n", + "## Parameters\n", + "\n", + "The Gauss-Newton optimizer uses the standard optimization parameters inherited from `NonlinearOptimizerParams`, which include:\n", + "\n", + "- Maximum iterations\n", + "- Relative and absolute error thresholds\n", + "- Error function verbosity\n", + "- Linear solver type\n", + "\n", + "## Usage Considerations\n", + "\n", + "- **Initial Guess**: The quality of the initial guess can significantly affect the convergence and performance of the Gauss-Newton optimizer.\n", + "- **Non-convexity**: Since the method relies on linear approximations, it may struggle with highly non-convex problems or those with poor initial estimates.\n", + "- **Performance**: The Gauss-Newton method is generally faster than other nonlinear optimization methods like Levenberg-Marquardt for problems that are well-approximated by a quadratic model near the solution.\n", + "\n", + "## Files\n", + "\n", + "- [GaussNewtonOptimizer.h](https://github.com/borglab/gtsam/blob/develop/gtsam/nonlinear/GaussNewtonOptimizer.h)\n", + "- [GaussNewtonOptimizer.cpp](https://github.com/borglab/gtsam/blob/develop/gtsam/nonlinear/GaussNewtonOptimizer.cpp)" + ] + } + ], + "metadata": { + "language_info": { + "name": "python" + } + }, + "nbformat": 4, + "nbformat_minor": 5 +} diff --git a/gtsam/nonlinear/doc/GncOptimizer.ipynb b/gtsam/nonlinear/doc/GncOptimizer.ipynb new file mode 100644 index 0000000000..9fa3344cf8 --- /dev/null +++ b/gtsam/nonlinear/doc/GncOptimizer.ipynb @@ -0,0 +1,79 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "id": "c950beef", + "metadata": {}, + "source": [ + "# GncOptimizer\n", + "\n", + "## Overview\n", + "\n", + "The `GncOptimizer` class in GTSAM is designed to perform robust optimization using Graduated Non-Convexity (GNC). This method is particularly useful in scenarios where the optimization problem is affected by outliers. The GNC approach gradually transitions from a convex approximation of the problem to the original non-convex problem, thereby improving robustness and convergence.\n", + "\n", + "The `GncOptimizer` leverages a robust cost function $\\rho(e)$, where $e$ is the error term. The goal is to minimize the sum of these robust costs over all measurements:\n", + "\n", + "$$\n", + "\\min_x \\sum_i \\rho(e_i(x))\n", + "$$\n", + "\n", + "In the context of GNC, the robust cost function is gradually transformed from a convex approximation to the original non-convex form. This transformation is controlled by a parameter $\\mu$, which is adjusted during the optimization process:\n", + "\n", + "$$\n", + "\\rho_\\mu(e) = \\frac{1}{\\mu} \\rho(\\mu e)\n", + "$$\n", + "\n", + "As $\\mu$ increases, the function $\\rho_\\mu(e)$ transitions from a convex to a non-convex shape, allowing the optimizer to handle outliers effectively.\n", + "\n", + "Key features:\n", + "\n", + "- **Robust Optimization**: The GncOptimizer is specifically tailored to handle optimization problems with outliers, using a robust cost function that can mitigate their effects.\n", + "- **Graduated Non-Convexity**: This technique allows the optimizer to start with a convex problem and gradually transform it into the original non-convex problem, which helps in avoiding local minima.\n", + "- **Customizable Parameters**: Users can adjust various parameters to control the behavior of the optimizer, such as the type of robust loss function and the parameters governing the GNC process.\n", + "\n", + "## Key Methods\n", + "\n", + "Please see the base class [NonlinearOptimizer.ipynb](NonlinearOptimizer.ipynb).\n", + "\n", + "## Parameters\n", + "\n", + "The `GncParams` class defines parameters specific to the GNC optimization algorithm:\n", + "\n", + "| Parameter | Type | Default Value | Description |\n", + "|-----------|------|---------------|-------------|\n", + "| lossType | GncLossType | TLS | Type of robust loss function (GM = Geman McClure or TLS = Truncated least squares) |\n", + "| maxIterations | size_t | 100 | Maximum number of iterations |\n", + "| muStep | double | 1.4 | Multiplicative factor to reduce/increase mu in GNC |\n", + "| relativeCostTol | double | 1e-5 | Threshold for relative cost change to stop iterating |\n", + "| weightsTol | double | 1e-4 | Threshold for weights being close to binary to stop iterating (TLS only) |\n", + "| verbosity | Verbosity enum | SILENT | Verbosity level (options: SILENT, SUMMARY, MU, WEIGHTS, VALUES) |\n", + "| knownInliers | IndexVector | Empty | Slots in factor graph for measurements known to be inliers |\n", + "| knownOutliers | IndexVector | Empty | Slots in factor graph for measurements known to be outliers |\n", + "\n", + "These parameters complement the standard optimization parameters inherited from `NonlinearOptimizerParams`, which include:\n", + "\n", + "- Maximum iterations\n", + "- Relative and absolute error thresholds\n", + "- Error function verbosity\n", + "- Linear solver type\n", + "\n", + "## Usage Considerations\n", + "\n", + "- **Outlier Rejection**: The `GncOptimizer` is particularly effective in scenarios with significant outlier presence, such as SLAM or bundle adjustment problems.\n", + "- **Parameter Tuning**: Proper tuning of the GNC parameters is crucial for achieving optimal performance. Users should experiment with different settings to find the best configuration for their specific problem.\n", + "\n", + "## Files\n", + "\n", + "- [GncOptimizer.h](https://github.com/borglab/gtsam/blob/develop/gtsam/nonlinear/GncOptimizer.h)\n", + "- [GncParams.h](https://github.com/borglab/gtsam/blob/develop/gtsam/nonlinear/GncParams.h)" + ] + } + ], + "metadata": { + "language_info": { + "name": "python" + } + }, + "nbformat": 4, + "nbformat_minor": 5 +} diff --git a/gtsam/nonlinear/doc/ISAM2.ipynb b/gtsam/nonlinear/doc/ISAM2.ipynb new file mode 100644 index 0000000000..d5f89df91b --- /dev/null +++ b/gtsam/nonlinear/doc/ISAM2.ipynb @@ -0,0 +1,56 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "id": "867a20bc", + "metadata": {}, + "source": [ + "# ISAM2\n", + "\n", + "## Overview\n", + "\n", + "The `ISAM2` class in GTSAM is an incremental smoothing and mapping algorithm that efficiently updates the solution to a nonlinear optimization problem as new measurements are added. This class is particularly useful in applications such as SLAM (Simultaneous Localization and Mapping) where real-time performance is crucial. \n", + "\n", + "The algorithm is described in the 2012 IJJR paper by {cite:t}`http://dx.doi.org/10.1177/0278364911430419`. For background, also see the more recent booklet by {cite:t}`https://doi.org/10.1561/2300000043`.\n", + "\n", + "## Key Features\n", + "\n", + "- **Incremental Updates**: `ISAM2` allows for incremental updates to the factor graph, avoiding the need to solve the entire problem from scratch with each new measurement.\n", + "- **Nonlinear Optimization**: Capable of handling nonlinear systems, leveraging iterative optimization techniques to refine estimates.\n", + "- **Efficient Variable Reordering**: Dynamically reorders variables to maintain sparsity and improve computational efficiency." + ] + }, + { + "cell_type": "markdown", + "id": "9ce0ec12", + "metadata": {}, + "source": [ + "## Main Methods\n", + "\n", + "### Initialization and Configuration\n", + "\n", + "- **ISAM2 Constructor**: Initializes the `ISAM2` object with optional parameters for configuring the behavior of the algorithm, such as relinearization thresholds and ordering strategies.\n", + "\n", + "### Updating the Graph\n", + "\n", + "- **update**: Incorporates new factors and variables into the existing factor graph. This method performs the core incremental update, refining the solution based on new measurements.\n", + "\n", + "### Accessing Results\n", + "\n", + "- **calculateEstimate**: Retrieves the current estimate of the variables in the factor graph. This method can be called with specific variable keys to obtain their estimates.\n", + "- **marginalCovariance**: Computes the marginal covariance of a specified variable, providing insight into the uncertainty of the estimate.\n", + "\n", + "### Advanced Features\n", + "\n", + "- **getFactorsUnsafe**: Provides access to the internal factor graph, allowing for advanced manipulations and custom analysis." + ] + } + ], + "metadata": { + "language_info": { + "name": "python" + } + }, + "nbformat": 4, + "nbformat_minor": 5 +} diff --git a/gtsam/nonlinear/doc/IncrementalFixedLagSmoother.ipynb b/gtsam/nonlinear/doc/IncrementalFixedLagSmoother.ipynb new file mode 100644 index 0000000000..287e00d026 --- /dev/null +++ b/gtsam/nonlinear/doc/IncrementalFixedLagSmoother.ipynb @@ -0,0 +1,23 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "id": "cdd2fdc5", + "metadata": {}, + "source": [ + "# IncrementalFixedLagSmoother\n", + "\n", + "## Overview\n", + "\n", + "The `IncrementalFixedLagSmoother` is a [FixedLagSmoother](FixedLagSmoother.ipynb) that uses [iSAM2](iSAM2.ipynb) for incremental inference.\n" + ] + } + ], + "metadata": { + "language_info": { + "name": "python" + } + }, + "nbformat": 4, + "nbformat_minor": 5 +} diff --git a/gtsam/nonlinear/doc/LevenbergMarquardtOptimizer.ipynb b/gtsam/nonlinear/doc/LevenbergMarquardtOptimizer.ipynb new file mode 100644 index 0000000000..434e258425 --- /dev/null +++ b/gtsam/nonlinear/doc/LevenbergMarquardtOptimizer.ipynb @@ -0,0 +1,87 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "id": "29642bb2", + "metadata": {}, + "source": [ + "# LevenbergMarquardtOptimizer\n", + "\n", + "## Overview\n", + "\n", + "The `LevenbergMarquardtOptimizer` class in GTSAM is a specialized optimizer that implements the Levenberg-Marquardt algorithm. This algorithm is a popular choice for solving non-linear least squares problems, which are common in various applications such as computer vision, robotics, and machine learning.\n", + "\n", + "The Levenberg-Marquardt algorithm is an iterative technique that interpolates between the Gauss-Newton algorithm and the method of gradient descent. It is particularly useful for optimizing problems where the solution is expected to be near the initial guess.\n", + "\n", + "The Levenberg-Marquardt algorithm seeks to minimize a cost function $F(x)$ of the form:\n", + "\n", + "$$\n", + "F(x) = \\frac{1}{2} \\sum_{i=1}^{m} r_i(x)^2\n", + "$$\n", + "\n", + "where $r_i(x)$ are the residuals. The update rule for the algorithm is given by:\n", + "\n", + "$$\n", + "x_{k+1} = x_k - (J^T J + \\lambda I)^{-1} J^T r\n", + "$$\n", + "\n", + "Here, $J$ is the Jacobian matrix of the residuals, $\\lambda$ is the damping parameter, and $I$ is the identity matrix.\n", + "\n", + "Key features:\n", + "\n", + "- **Non-linear Optimization**: The class is designed to handle non-linear optimization problems efficiently.\n", + "- **Damping Mechanism**: It incorporates a damping parameter to control the step size, balancing between the Gauss-Newton and gradient descent methods.\n", + "- **Iterative Improvement**: The optimizer iteratively refines the solution, reducing the error at each step.\n", + "\n", + "## Key Methods\n", + "\n", + "Please see the base class [NonlinearOptimizer.ipynb](NonlinearOptimizer.ipynb).\n", + "\n", + "## Parameters\n", + "\n", + "The `LevenbergMarquardtParams` class defines parameters specific to this optimization algorithm:\n", + "\n", + "| Parameter | Type | Default Value | Description |\n", + "|-----------|------|---------------|-------------|\n", + "| lambdaInitial | double | 1e-5 | The initial Levenberg-Marquardt damping term |\n", + "| lambdaFactor | double | 10.0 | The amount by which to multiply or divide lambda when adjusting lambda |\n", + "| lambdaUpperBound | double | 1e5 | The maximum lambda to try before assuming the optimization has failed |\n", + "| lambdaLowerBound | double | 0.0 | The minimum lambda used in LM |\n", + "| verbosityLM | VerbosityLM | SILENT | The verbosity level for Levenberg-Marquardt |\n", + "| minModelFidelity | double | 1e-3 | Lower bound for the modelFidelity to accept the result of an LM iteration |\n", + "| logFile | std::string | \"\" | An optional CSV log file, with [iteration, time, error, lambda] |\n", + "| diagonalDamping | bool | false | If true, use diagonal of Hessian |\n", + "| useFixedLambdaFactor | bool | true | If true applies constant increase (or decrease) to lambda according to lambdaFactor |\n", + "| minDiagonal | double | 1e-6 | When using diagonal damping saturates the minimum diagonal entries |\n", + "| maxDiagonal | double | 1e32 | When using diagonal damping saturates the maximum diagonal entries |\n", + "\n", + "These parameters complement the standard optimization parameters inherited from `NonlinearOptimizerParams`, which include:\n", + "\n", + "- Maximum iterations\n", + "- Relative and absolute error thresholds\n", + "- Error function verbosity\n", + "- Linear solver type\n", + "\n", + "## Usage Notes\n", + "\n", + "- The choice of the initial guess can significantly affect the convergence speed and the quality of the solution.\n", + "- Proper tuning of the damping parameter $\\lambda$ is crucial for balancing the convergence rate and stability.\n", + "- The optimizer is most effective when the residuals are approximately linear near the solution.\n", + "\n", + "## Files\n", + "\n", + "- [LevenbergMarquardtOptimizer.h](https://github.com/borglab/gtsam/blob/develop/gtsam/nonlinear/LevenbergMarquardtOptimizer.h)\n", + "- [LevenbergMarquardtOptimizer.cpp](https://github.com/borglab/gtsam/blob/develop/gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp)\n", + "- [LevenbergMarquardtParams.h](https://github.com/borglab/gtsam/blob/develop/gtsam/nonlinear/LevenbergMarquardtParams.h)\n", + "- [LevenbergMarquardtParams.cpp](https://github.com/borglab/gtsam/blob/develop/gtsam/nonlinear/LevenbergMarquardtParams.cpp)" + ] + } + ], + "metadata": { + "language_info": { + "name": "python" + } + }, + "nbformat": 4, + "nbformat_minor": 5 +} diff --git a/gtsam/nonlinear/doc/LinearContainerFactor.ipynb b/gtsam/nonlinear/doc/LinearContainerFactor.ipynb new file mode 100644 index 0000000000..602c4e401b --- /dev/null +++ b/gtsam/nonlinear/doc/LinearContainerFactor.ipynb @@ -0,0 +1,33 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "id": "f4c73cc1", + "metadata": {}, + "source": [ + "# LinearContainerFactor\n", + "\n", + "## Overview\n", + "\n", + "The `LinearContainerFactor` class in GTSAM is a specialized factor that encapsulates a linear factor within a nonlinear factor graph. This is used extensively when marginalizing out variables.\n", + "\n", + "## Key Features\n", + "\n", + "- **Encapsulation of Linear Factors**: The primary function of the `LinearContainerFactor` is to store a linear factor and its associated values, enabling it to be used within a nonlinear context.\n", + "- **Error Calculation**: It provides mechanisms to compute the error of the factor given a set of values.\n", + "- **Jacobian Computation**: The class can compute the Jacobian matrix, which is essential for optimization processes.\n", + "\n", + "## Key Methods\n", + "\n", + "- **LinearContainerFactor**: This constructor initializes the `LinearContainerFactor` with a linear factor and optionally with values. It serves as the entry point for creating an instance of this class." + ] + } + ], + "metadata": { + "language_info": { + "name": "python" + } + }, + "nbformat": 4, + "nbformat_minor": 5 +} diff --git a/gtsam/nonlinear/doc/NonlinearConjugateGradientOptimizer.ipynb b/gtsam/nonlinear/doc/NonlinearConjugateGradientOptimizer.ipynb new file mode 100644 index 0000000000..848509e7fb --- /dev/null +++ b/gtsam/nonlinear/doc/NonlinearConjugateGradientOptimizer.ipynb @@ -0,0 +1,67 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "id": "48970ca0", + "metadata": {}, + "source": [ + "# NonlinearConjugateGradientOptimizer\n", + "\n", + "## Overview\n", + "\n", + "The `NonlinearConjugateGradientOptimizer` class in GTSAM is an implementation of the nonlinear conjugate gradient method for optimizing nonlinear functions. This optimizer is particularly useful for solving large-scale optimization problems where the Hessian matrix is not easily computed or stored. The conjugate gradient method is an iterative algorithm that seeks to find the minimum of a function by following a series of conjugate directions.\n", + "\n", + "The nonlinear conjugate gradient method seeks to minimize a nonlinear function $f(x)$ by iteratively updating the solution $x_k$ according to:\n", + "\n", + "$$ x_{k+1} = x_k + \\alpha_k p_k $$\n", + "\n", + "where $p_k$ is the search direction and $\\alpha_k$ is the step size determined by a line search. The search direction $p_k$ is computed using the gradient of the function and a conjugate gradient update formula, such as the Fletcher-Reeves or Polak-Ribiere formulas:\n", + "\n", + "- **Fletcher-Reeves**: \n", + " $$ \\beta_k^{FR} = \\frac{\\nabla f(x_{k+1})^T \\nabla f(x_{k+1})}{\\nabla f(x_k)^T \\nabla f(x_k)} $$\n", + " \n", + "- **Polak-Ribiere**: \n", + " $$ \\beta_k^{PR} = \\frac{\\nabla f(x_{k+1})^T (\\nabla f(x_{k+1}) - \\nabla f(x_k))}{\\nabla f(x_k)^T \\nabla f(x_k)} $$\n", + "\n", + "The choice of $\\beta_k$ affects the convergence properties of the algorithm.\n", + "\n", + "Key features:\n", + "\n", + "- **Optimization Method**: Implements the nonlinear conjugate gradient method, which is an extension of the linear conjugate gradient method to nonlinear optimization problems.\n", + "- **Efficiency**: Suitable for large-scale problems due to its iterative nature and reduced memory requirements compared to methods that require the Hessian matrix.\n", + "- **Flexibility**: Can be used with various line search strategies and conjugate gradient update formulas.\n", + "\n", + "## Key Methods\n", + "\n", + "Please see the base class [NonlinearOptimizer.ipynb](NonlinearOptimizer.ipynb).\n", + "\n", + "## Parameters\n", + "\n", + "The nonlinear conjugate gradient optimizer uses the standard optimization parameters inherited from `NonlinearOptimizerParams`, which include:\n", + "\n", + "- Maximum iterations\n", + "- Relative and absolute error thresholds\n", + "- Error function verbosity\n", + "- Linear solver type\n", + "\n", + "## Usage Notes\n", + "\n", + "- The `NonlinearConjugateGradientOptimizer` is most effective when the problem size is large and the computation of the Hessian is impractical.\n", + "- Users should choose an appropriate line search method and conjugate gradient update formula based on the specific characteristics of their optimization problem.\n", + "- Monitoring the error and values during optimization can provide insights into the convergence behavior and help diagnose potential issues.\n", + "\n", + "## Files\n", + "\n", + "- [NonlinearConjugateGradientOptimizer.h](https://github.com/borglab/gtsam/blob/develop/gtsam/nonlinear/NonlinearConjugateGradientOptimizer.h)\n", + "- [NonlinearConjugateGradientOptimizer.cpp](https://github.com/borglab/gtsam/blob/develop/gtsam/nonlinear/NonlinearConjugateGradientOptimizer.cpp)" + ] + } + ], + "metadata": { + "language_info": { + "name": "python" + } + }, + "nbformat": 4, + "nbformat_minor": 5 +} diff --git a/gtsam/nonlinear/doc/NonlinearEquality.ipynb b/gtsam/nonlinear/doc/NonlinearEquality.ipynb new file mode 100644 index 0000000000..98c3656b12 --- /dev/null +++ b/gtsam/nonlinear/doc/NonlinearEquality.ipynb @@ -0,0 +1,124 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# NonlinearEquality\n", + "\n", + "The `NonlinearEquality` family of factors in GTSAM provides constraints to enforce equality between variables or between a variable and a constant value. These factors are useful in optimization problems where strict equality constraints are required. Below is an overview of the API, grouped by functionality." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## NonlinearEquality\n", + "\n", + "The `NonlinearEquality` factor enforces equality between a variable and a feasible value. It supports both exact and inexact evaluation modes.\n", + "\n", + "### Constructors\n", + "- `NonlinearEquality(Key j, const T& feasible, const CompareFunction& compare)` \n", + " Creates a factor that enforces exact equality between the variable at key `j` and the feasible value `feasible`. \n", + " - `j`: Key of the variable to constrain. \n", + " - `feasible`: The feasible value to enforce equality with. \n", + " - `compare`: Optional comparison function (default uses `traits::Equals`).\n", + "\n", + "- `NonlinearEquality(Key j, const T& feasible, double error_gain, const CompareFunction& compare)` \n", + " Creates a factor that allows inexact evaluation with a specified error gain. \n", + " - `error_gain`: Gain applied to the error when the constraint is violated.\n", + "\n", + "### Methods\n", + "- `double error(const Values& c) const` \n", + " Computes the error for the given values. Returns `0.0` if the constraint is satisfied, or a scaled error if `allow_error_` is enabled.\n", + "\n", + "- `Vector evaluateError(const T& xj, OptionalMatrixType H = nullptr) const` \n", + " Evaluates the error vector for the given variable value `xj`. Optionally computes the Jacobian matrix `H`.\n", + "\n", + "- `GaussianFactor::shared_ptr linearize(const Values& x) const` \n", + " Linearizes the factor at the given values `x` to create a Gaussian factor." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## NonlinearEquality1\n", + "\n", + "The `NonlinearEquality1` factor is a unary equality constraint that fixes a variable to a specific value.\n", + "\n", + "### Constructors\n", + "- `NonlinearEquality1(const X& value, Key key, double mu = 1000.0)` \n", + " Creates a factor that fixes the variable at `key` to the value `value`. \n", + " - `value`: The fixed value for the variable. \n", + " - `key`: Key of the variable to constrain. \n", + " - `mu`: Strength of the constraint (default: `1000.0`).\n", + "\n", + "### Methods\n", + "- `Vector evaluateError(const X& x1, OptionalMatrixType H = nullptr) const` \n", + " Evaluates the error vector for the given variable value `x1`. Optionally computes the Jacobian matrix `H`.\n", + "\n", + "- `void print(const std::string& s, const KeyFormatter& keyFormatter) const` \n", + " Prints the factor details, including the fixed value and noise model." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## NonlinearEquality2\n", + "\n", + "The `NonlinearEquality2` factor is a binary equality constraint that enforces equality between two variables.\n", + "\n", + "### Constructors\n", + "- `NonlinearEquality2(Key key1, Key key2, double mu = 1e4)` \n", + " Creates a factor that enforces equality between the variables at `key1` and `key2`. \n", + " - `key1`: Key of the first variable. \n", + " - `key2`: Key of the second variable. \n", + " - `mu`: Strength of the constraint (default: `1e4`).\n", + "\n", + "### Methods\n", + "- `Vector evaluateError(const T& x1, const T& x2, OptionalMatrixType H1 = nullptr, OptionalMatrixType H2 = nullptr) const` \n", + " Evaluates the error vector for the given variable values `x1` and `x2`. Optionally computes the Jacobian matrices `H1` and `H2`.\n", + "\n", + "- `void print(const std::string& s, const KeyFormatter& keyFormatter) const` \n", + " Prints the factor details, including the keys and noise model." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Common Features\n", + "\n", + "### Error Handling Modes\n", + "- Exact Evaluation: Throws an error during linearization if the constraint is violated. \n", + "- Inexact Evaluation: Allows nonzero error and scales it using the `error_gain_` parameter.\n", + "\n", + "### Serialization\n", + "All factors support serialization for saving and loading models.\n", + "\n", + "### Testable Interface\n", + "All factors implement the `Testable` interface, providing methods like:\n", + "- `void print(const std::string& s, const KeyFormatter& keyFormatter) const` \n", + " Prints the factor details.\n", + "- `bool equals(const NonlinearFactor& f, double tol) const` \n", + " Checks if two factors are equal within a specified tolerance." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "These factors provide a flexible way to enforce equality constraints in nonlinear optimization problems, making them useful for applications like SLAM, robotics, and control systems." + ] + } + ], + "metadata": { + "language_info": { + "name": "python" + } + }, + "nbformat": 4, + "nbformat_minor": 2 +} diff --git a/gtsam/nonlinear/doc/NonlinearFactor.ipynb b/gtsam/nonlinear/doc/NonlinearFactor.ipynb new file mode 100644 index 0000000000..a5986d9ccd --- /dev/null +++ b/gtsam/nonlinear/doc/NonlinearFactor.ipynb @@ -0,0 +1,84 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "id": "381ccaaa", + "metadata": {}, + "source": [ + "# NonlinearFactor\n", + "\n", + "## Overview\n", + "\n", + "The `NonlinearFactor` class in GTSAM is a fundamental component used in nonlinear optimization. It represents a factor in a factor graph. The class is designed to work with nonlinear, continuous functions." + ] + }, + { + "cell_type": "markdown", + "id": "94ffa16d", + "metadata": {}, + "source": [ + "## Mathematical Formulation\n", + "\n", + "The `NonlinearFactor` is generally represented by a function $f(x)$, where $x$ is a vector of variables. The error is given by:\n", + "$$\n", + "e(x) = f(x)- z\n", + "$$\n", + "where $z$ is the observed measurement. The optimization process aims to minimize the sum of squared errors:\n", + "$$\n", + "\\min_x \\sum_i \\| e_i(x) \\|^2 \n", + "$$\n", + "\n", + "Linearization involves approximating $f(x)$ around a point $x_0$:\n", + "$$\n", + "f(x) \\approx f(x_0) + A\\delta x\n", + "$$\n", + "where $A$ is the Jacobian matrix of $f$ at $x_0$, and $\\delta x \\doteq x - x_0$. This leads to a linearized error:\n", + "$$\n", + "e(x) \\approx (f(x_0) + A\\delta x) - z = A\\delta x - b\n", + "$$\n", + "where $b\\doteq z - f(x_0)$ is the prediction error." + ] + }, + { + "cell_type": "markdown", + "id": "e3842ba3", + "metadata": {}, + "source": [ + "## Key Functionalities\n", + "\n", + "### Error Calculation\n", + "\n", + "- **evaluateError**: This method computes the error vector for the factor given a set of variable values. The error is typically the difference between the predicted measurement and the actual measurement. The function can also return the Jacobian matrices if needed, which are crucial for optimization algorithms like Gauss-Newton or Levenberg-Marquardt.\n", + "\n", + "### Jacobian and Hessian\n", + "\n", + "- **linearize**: This method linearizes the nonlinear factor around a linearization point. It returns a `GaussianFactor`, which is an approximation of the `NonlinearFactor` using a first-order Taylor expansion. This is a critical step in iterative optimization methods, where the problem is repeatedly linearized and solved.\n", + "\n", + "### Active Flag\n", + "\n", + "- **active**: This function checks whether the factor should be included in the optimization process. A factor might be inactive if it does not contribute to the error, which can occur in cases of conditional constraints or gating functions.\n", + "\n", + "### Dimensionality\n", + "\n", + "- **dim**: Returns the dimensionality of the factor, which corresponds to the size of the error vector. This is important for understanding the contribution of the factor to the overall optimization problem.\n", + "\n", + "### Key Management\n", + "\n", + "- **keys**: Provides access to the keys (or variable indices) involved in the factor. This is essential for understanding which variables the factor is connected to in the factor graph.\n", + "\n", + "## Usage Notes\n", + "\n", + "- The `NonlinearFactor` class is typically used in conjunction with a `NonlinearFactorGraph`, which is a collection of such factors.\n", + "- Users need to implement the `evaluateError` method in derived classes to define the specific measurement model.\n", + "- The class is designed to be flexible and extensible, allowing for custom factors to be created for specific applications." + ] + } + ], + "metadata": { + "language_info": { + "name": "python" + } + }, + "nbformat": 4, + "nbformat_minor": 5 +} diff --git a/gtsam/nonlinear/doc/NonlinearFactorGraph.ipynb b/gtsam/nonlinear/doc/NonlinearFactorGraph.ipynb new file mode 100644 index 0000000000..cb373ce9e2 --- /dev/null +++ b/gtsam/nonlinear/doc/NonlinearFactorGraph.ipynb @@ -0,0 +1,63 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "id": "a58d890a", + "metadata": {}, + "source": [ + "# NonlinearFactorGraph\n", + "\n", + "## Overview\n", + "\n", + "The `NonlinearFactorGraph` class in GTSAM is a key component for representing and solving nonlinear factor graphs. A factor graph is a bipartite graph that represents the factorization of a function, commonly used in probabilistic graphical models. In the context of GTSAM, it is used to represent the structure of optimization problems, e.g., in the domain of simultaneous localization and mapping (SLAM) or structure from motion (SfM).\n", + "\n", + "## Key Functionalities\n", + "\n", + "### Construction and Initialization\n", + "\n", + "- **Constructor**: The class provides a default constructor to initialize an empty nonlinear factor graph.\n", + "\n", + "### Factor Management\n", + "\n", + "- **add**: This method allows adding a new factor to the graph. Factors represent constraints or measurements in the optimization problem.\n", + "- **reserve**: Pre-allocates space for a specified number of factors, optimizing memory usage when the number of factors is known in advance.\n", + "\n", + "### Graph Operations\n", + "\n", + "- **resize**: Adjusts the size of the factor graph, which can be useful when dynamically modifying the graph structure.\n", + "- **remove**: Removes a factor from the graph, identified by its index.\n", + "\n", + "### Querying and Access\n", + "\n", + "- **size**: Returns the number of factors currently in the graph.\n", + "- **empty**: Checks if the graph contains any factors.\n", + "- **at**: Accesses a specific factor by its index.\n", + "- **back**: Retrieves the last factor in the graph.\n", + "- **front**: Retrieves the first factor in the graph." + ] + }, + { + "cell_type": "markdown", + "id": "71b15f4c", + "metadata": {}, + "source": [ + "### Optimization and Linearization\n", + "\n", + "- **linearize**: Converts the nonlinear factor graph into a linear factor graph at a given linearization point. This is a crucial step in iterative optimization algorithms like [Gauss-Newton](./GaussNewtonOptimizer.ipynb) or [Levenberg-Marquardt](./LevenbergMarquardtOptimizer.ipynb).\n", + " \n", + " The linearization process involves computing the Jacobian matrices of the nonlinear functions, resulting in a linear approximation:\n", + " \n", + " $$ f(x) \\approx f(x_0) + A(x - x_0) $$\n", + " \n", + " where $A$ is the Jacobian matrix evaluated at the point $x_0$." + ] + } + ], + "metadata": { + "language_info": { + "name": "python" + } + }, + "nbformat": 4, + "nbformat_minor": 5 +} diff --git a/gtsam/nonlinear/doc/NonlinearISAM.ipynb b/gtsam/nonlinear/doc/NonlinearISAM.ipynb new file mode 100644 index 0000000000..167cb94ff1 --- /dev/null +++ b/gtsam/nonlinear/doc/NonlinearISAM.ipynb @@ -0,0 +1,23 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "id": "2b6fc012", + "metadata": {}, + "source": [ + "# NonlinearISAM\n", + "\n", + "## Overview\n", + "\n", + "The `NonlinearISAM` class wraps the incremental factorization version of iSAM {cite:p}`http://dx.doi.org/10.1109/TRO.2008.2006706`. It is largely superseded by [iSAM2](./ISAM2.ipynb) but it is a simpler class, with less bells and whistles, that might be easier to debug. For background, also see the more recent booklet by {cite:t}`https://doi.org/10.1561/2300000043`.\n" + ] + } + ], + "metadata": { + "language_info": { + "name": "python" + } + }, + "nbformat": 4, + "nbformat_minor": 5 +} diff --git a/gtsam/nonlinear/doc/NonlinearOptimizer.ipynb b/gtsam/nonlinear/doc/NonlinearOptimizer.ipynb new file mode 100644 index 0000000000..135cc42f15 --- /dev/null +++ b/gtsam/nonlinear/doc/NonlinearOptimizer.ipynb @@ -0,0 +1,60 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "id": "2e4812da", + "metadata": {}, + "source": [ + "# NonlinearOptimizer\n", + "\n", + "## Overview\n", + "\n", + "The `NonlinearOptimizer` class in GTSAM is a the base class for (batch) nonlinear optimization solvers. It provides the basic API for optimizing nonlinear factor graphs, commonly used in robotics and computer vision applications.\n", + "\n", + "The primary purpose of the `NonlinearOptimizer` is to iteratively refine an initial estimate of a solution to minimize a nonlinear cost function. Specific optimization algorithms like Gauss-Newton, Levenberg-Marquardt, and Dogleg and implemented in derived class.\n", + "\n", + "## Mathematical Foundation\n", + "\n", + "The optimization process in `NonlinearOptimizer` is based on iterative methods that solve for the minimum of a nonlinear cost function. The general approach involves linearizing the nonlinear problem at the current estimate and solving the resulting linear system to update the estimate. This process is repeated until convergence criteria are met.\n", + "\n", + "The optimization problem can be formally defined as:\n", + "\n", + "$$\n", + "\\min_{x} \\sum_{i} \\| \\phi_i(x) \\|^2\n", + "$$\n", + "\n", + "where $x$ is the vector of variables to be optimized, and $\\phi_i(x)$ are the residuals of the factors in the graph.\n", + "\n", + "## Key Methods\n", + "\n", + "- The `optimize()` method is the core function of the `NonlinearOptimizer` class. It performs the optimization process, iteratively updating the estimate to converge to a local minimum of the cost function.\n", + "- The `error()` method computes the total error of the current estimate. This is typically the sum of squared errors for all factors in the graph. Mathematically, the error can be expressed as:\n", + " $$\n", + " E(x) = \\sum_{i} \\| \\phi_i(x) \\|^2\n", + " $$\n", + " where $\\phi_i(x)$ represents the residual error of the $i$-th factor.\n", + "- The `values()` method returns the current set of variable estimates. These estimates are updated during the optimization process.\n", + "- The `iterations()` method provides the number of iterations performed during the optimization process. This can be useful for analyzing the convergence behavior of the optimizer.\n", + "- The `params()` method returns the parameters used by the optimizer. These parameters can include settings like convergence thresholds, maximum iterations, and other algorithm-specific options.\n", + "\n", + "## Usage\n", + "\n", + "The `NonlinearOptimizer` class is typically not used directly. Instead, one of its derived classes, such as `GaussNewtonOptimizer`, `LevenbergMarquardtOptimizer`, or `DoglegOptimizer`, is used to perform specific types of optimization. These derived classes implement the `optimize()` method according to their respective algorithms.\n", + "\n", + "## Files\n", + "\n", + "- [NonlinearOptimizer.h](https://github.com/borglab/gtsam/blob/develop/gtsam/nonlinear/NonlinearOptimizer.h)\n", + "- [NonlinearOptimizer.cpp](https://github.com/borglab/gtsam/blob/develop/gtsam/nonlinear/NonlinearOptimizer.cpp)\n", + "- [NonlinearOptimizerParams.h](https://github.com/borglab/gtsam/blob/develop/gtsam/nonlinear/NonlinearOptimizerParams.h)\n", + "- [NonlinearOptimizerParams.cpp](https://github.com/borglab/gtsam/blob/develop/gtsam/nonlinear/NonlinearOptimizerParams.cpp)" + ] + } + ], + "metadata": { + "language_info": { + "name": "python" + } + }, + "nbformat": 4, + "nbformat_minor": 5 +} diff --git a/gtsam/nonlinear/doc/PriorFactor.ipynb b/gtsam/nonlinear/doc/PriorFactor.ipynb new file mode 100644 index 0000000000..9974669fca --- /dev/null +++ b/gtsam/nonlinear/doc/PriorFactor.ipynb @@ -0,0 +1,53 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "id": "ec35011c", + "metadata": {}, + "source": [ + "# PriorFactor\n", + "\n", + "## Overview\n", + "\n", + "The `PriorFactor` represents a prior belief about a variable in the form of a Gaussian distribution. This class is crucial for incorporating prior knowledge into the optimization process, which can significantly enhance the accuracy and robustness of the solutions.\n", + "\n", + "## Key Functionalities\n", + "\n", + "### PriorFactor Construction\n", + "\n", + "The `PriorFactor` is constructed by specifying a key, a prior value, and a noise model. The key identifies the variable in the factor graph, the prior value represents the expected value of the variable, and the noise model encapsulates the uncertainty associated with this prior belief.\n", + "\n", + "### Error Calculation\n", + "\n", + "The primary role of the `PriorFactor` is to compute the error between the estimated value of a variable and its prior. This error is typically defined as:\n", + "\n", + "$$\n", + "e(x) = x - \\mu\n", + "$$\n", + "\n", + "where $x$ is the estimated value, and $\\mu$ is the prior mean. The error is then weighted by the noise model to form the contribution of this factor to the overall objective function.\n", + "\n", + "### Adding to a Factor Graph\n", + "\n", + "[NonlinearFactorGraph](./NonlinearFactorGraph.ipynb) has a templated method `addPrior` that provides a convenient way to add priors.\n", + "\n", + "## Usage Considerations\n", + "\n", + "- **Noise Model**: The choice of noise model is critical as it determines how strongly the prior is enforced. A tighter noise model implies a stronger belief in the prior. *Note that very strong priors might make the condition number of the linear systems to be solved very high. In this case consider adding a [NonlinearEqualityFactor]\n", + "- **Integration with Other Factors**: The `PriorFactor` is typically used in conjunction with other factors that model the system dynamics and measurements. It helps anchor the solution, especially in scenarios with limited or noisy measurements.\n", + "- **Applications**: Common applications include SLAM (Simultaneous Localization and Mapping), where priors on initial poses or landmarks can significantly improve map accuracy and convergence speed.\n", + "\n", + "## Conclusion\n", + "\n", + "The `PriorFactor` class is a fundamental component in GTSAM for incorporating prior information into the factor graph framework. By understanding its construction, error computation, and integration into the optimization process, users can effectively leverage prior knowledge to enhance their estimation and optimization tasks." + ] + } + ], + "metadata": { + "language_info": { + "name": "python" + } + }, + "nbformat": 4, + "nbformat_minor": 5 +} diff --git a/gtsam/nonlinear/doc/WhiteNoiseFactor.ipynb b/gtsam/nonlinear/doc/WhiteNoiseFactor.ipynb new file mode 100644 index 0000000000..fdbf91922b --- /dev/null +++ b/gtsam/nonlinear/doc/WhiteNoiseFactor.ipynb @@ -0,0 +1,67 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "id": "5a0c879e", + "metadata": {}, + "source": [ + "# WhiteNoiseFactor\n", + "\n", + "*Below is partly generated with ChatGPT 4o, needs to be verified.*\n", + "\n", + "## Overview\n", + "\n", + "The `WhiteNoiseFactor` in GTSAM is a binary nonlinear factor designed to estimate the parameters of zero-mean Gaussian white noise. It uses a **mean-precision parameterization**, where the mean $ \\mu $ and precision $ \\tau = 1/\\sigma^2 $ are treated as variables to be optimized." + ] + }, + { + "cell_type": "markdown", + "id": "b40b3242", + "metadata": {}, + "source": [ + "## Parameterization\n", + "\n", + "The factor models the negative log-likelihood of a zero-mean Gaussian distribution as follows,\n", + "$$\n", + "f(z, \\mu, \\tau) = \\log(\\sqrt{2\\pi}) - 0.5 \\log(\\tau) + 0.5 \\tau (z - \\mu)^2\n", + "$$\n", + "where:\n", + "- $ z $: Measurement value (observed data).\n", + "- $ \\mu $: Mean of the Gaussian distribution (to be estimated).\n", + "- $ \\tau $: Precision of the Gaussian distribution $ \\tau = 1/\\sigma^2 $, also to be estimated).\n", + "\n", + "This formulation allows the factor to optimize both the mean and precision of the noise model simultaneously." + ] + }, + { + "cell_type": "markdown", + "id": "2f36abdb", + "metadata": {}, + "source": [ + "## Use Case: Estimating IMU Noise Characteristics\n", + "\n", + "The `WhiteNoiseFactor` can be used in system identification tasks, such as estimating the noise characteristics of an IMU. Here's how it would work:\n", + "\n", + "1. **Define the Measurement**:\n", + " - Collect a series of IMU measurements (e.g., accelerometer or gyroscope readings) under known conditions (e.g., stationary or constant velocity).\n", + "\n", + "2. **Set Up the Factor Graph**:\n", + " - Add `WhiteNoiseFactor` instances to the factor graph for each measurement, linking the observed value $ z $ to the mean and precision variables.\n", + "\n", + "3. **Optimize the Graph**:\n", + " - Use GTSAM's nonlinear optimization tools to solve for the mean $ \\mu $ and precision $ \\tau $ that best explain the observed measurements.\n", + "\n", + "4. **Extract Noise Characteristics**:\n", + " - The optimized mean $ \\mu $ represents the bias in the sensor measurements.\n", + " - The optimized precision $ \\tau $ can be inverted to compute the standard deviation $ \\sigma = 1/\\sqrt{\\tau} $, which represents the noise level." + ] + } + ], + "metadata": { + "language_info": { + "name": "python" + } + }, + "nbformat": 4, + "nbformat_minor": 5 +} diff --git a/gtsam/nonlinear/nonlinear.i b/gtsam/nonlinear/nonlinear.i index 5092713b79..c13defbad7 100644 --- a/gtsam/nonlinear/nonlinear.i +++ b/gtsam/nonlinear/nonlinear.i @@ -731,6 +731,20 @@ virtual class BatchFixedLagSmoother : gtsam::FixedLagSmoother { VALUE calculateEstimate(size_t key) const; }; +#include +virtual class IncrementalFixedLagSmoother : gtsam::FixedLagSmoother { + IncrementalFixedLagSmoother(); + IncrementalFixedLagSmoother(double smootherLag); + IncrementalFixedLagSmoother(double smootherLag, const gtsam::ISAM2Params& params); + + void print(string s = "IncrementalFixedLagSmoother:\n") const; + + gtsam::ISAM2Params params() const; + + gtsam::NonlinearFactorGraph getFactors() const; + gtsam::ISAM2 getISAM2() const; +}; + #include template -#include -virtual class IncrementalFixedLagSmoother : gtsam::FixedLagSmoother { - IncrementalFixedLagSmoother(); - IncrementalFixedLagSmoother(double smootherLag); - IncrementalFixedLagSmoother(double smootherLag, const gtsam::ISAM2Params& params); - - void print(string s = "IncrementalFixedLagSmoother:\n") const; - - gtsam::ISAM2Params params() const; - - gtsam::NonlinearFactorGraph getFactors() const; - gtsam::ISAM2 getISAM2() const; -}; #include virtual class ConcurrentFilter { diff --git a/gtsam_unstable/nonlinear/BayesTreeMarginalizationHelper.h b/gtsam_unstable/nonlinear/BayesTreeMarginalizationHelper.h index 1e367e55cd..6e7d699b4a 100644 --- a/gtsam_unstable/nonlinear/BayesTreeMarginalizationHelper.h +++ b/gtsam_unstable/nonlinear/BayesTreeMarginalizationHelper.h @@ -9,350 +9,13 @@ * -------------------------------------------------------------------------- */ -/** - * @file BayesTreeMarginalizationHelper.h - * @brief Helper functions for marginalizing variables from a Bayes Tree. - * - * @author Jeffrey (Zhiwei Wang) - * @date Oct 28, 2024 - */ - -// \callgraph #pragma once -#include -#include -#include -#include -#include -#include -#include "gtsam_unstable/dllexport.h" - -namespace gtsam { - -/** - * This class provides helper functions for marginalizing variables from a Bayes Tree. - */ -template -class GTSAM_UNSTABLE_EXPORT BayesTreeMarginalizationHelper { - -public: - using Clique = typename BayesTree::Clique; - using sharedClique = typename BayesTree::sharedClique; - - /** - * This function identifies variables that need to be re-eliminated before - * performing marginalization. - * - * Re-elimination is necessary for a clique containing marginalizable - * variables if: - * - * 1. Some non-marginalizable variables appear before marginalizable ones - * in that clique; - * 2. Or it has a child node depending on a marginalizable variable AND the - * subtree rooted at that child contains non-marginalizables. - * - * In addition, for any descendant node depending on a marginalizable - * variable, if the subtree rooted at that descendant contains - * non-marginalizable variables (i.e., it lies on a path from one of the - * aforementioned cliques that require re-elimination to a node containing - * non-marginalizable variables at the leaf side), then it also needs to - * be re-eliminated. - * - * @param[in] bayesTree The Bayes tree - * @param[in] marginalizableKeys Keys to be marginalized - * @return Set of additional keys that need to be re-eliminated - */ - static std::unordered_set - gatherAdditionalKeysToReEliminate( - const BayesTree& bayesTree, - const KeyVector& marginalizableKeys) { - const bool debug = ISDEBUG("BayesTreeMarginalizationHelper"); - - std::unordered_set additionalCliques = - gatherAdditionalCliquesToReEliminate(bayesTree, marginalizableKeys); - - std::unordered_set additionalKeys; - for (const Clique* clique : additionalCliques) { - addCliqueToKeySet(clique, &additionalKeys); - } - - if (debug) { - std::cout << "BayesTreeMarginalizationHelper: Additional keys to re-eliminate: "; - for (const Key& key : additionalKeys) { - std::cout << DefaultKeyFormatter(key) << " "; - } - std::cout << std::endl; - } - - return additionalKeys; - } - - protected: - /** - * This function identifies cliques that need to be re-eliminated before - * performing marginalization. - * See the docstring of @ref gatherAdditionalKeysToReEliminate(). - */ - static std::unordered_set - gatherAdditionalCliquesToReEliminate( - const BayesTree& bayesTree, - const KeyVector& marginalizableKeys) { - std::unordered_set additionalCliques; - std::unordered_set marginalizableKeySet( - marginalizableKeys.begin(), marginalizableKeys.end()); - CachedSearch cachedSearch; - - // Check each clique that contains a marginalizable key - for (const Clique* clique : - getCliquesContainingKeys(bayesTree, marginalizableKeySet)) { - if (additionalCliques.count(clique)) { - // The clique has already been visited. This can happen when an - // ancestor of the current clique also contain some marginalizable - // varaibles and it's processed beore the current. - continue; - } - - if (needsReelimination(clique, marginalizableKeySet, &cachedSearch)) { - // Add the current clique - additionalCliques.insert(clique); - - // Then add the dependent cliques - gatherDependentCliques(clique, marginalizableKeySet, &additionalCliques, - &cachedSearch); - } - } - return additionalCliques; - } - - /** - * Gather the cliques containing any of the given keys. - * - * @param[in] bayesTree The Bayes tree - * @param[in] keysOfInterest Set of keys of interest - * @return Set of cliques that contain any of the given keys - */ - static std::unordered_set getCliquesContainingKeys( - const BayesTree& bayesTree, - const std::unordered_set& keysOfInterest) { - std::unordered_set cliques; - for (const Key& key : keysOfInterest) { - cliques.insert(bayesTree[key].get()); - } - return cliques; - } - - /** - * A struct to cache the results of the below two functions. - */ - struct CachedSearch { - std::unordered_map wholeMarginalizableCliques; - std::unordered_map wholeMarginalizableSubtrees; - }; - - /** - * Check if all variables in the clique are marginalizable. - * - * Note we use a cache map to avoid repeated searches. - */ - static bool isWholeCliqueMarginalizable( - const Clique* clique, - const std::unordered_set& marginalizableKeys, - CachedSearch* cache) { - auto it = cache->wholeMarginalizableCliques.find(clique); - if (it != cache->wholeMarginalizableCliques.end()) { - return it->second; - } else { - bool ret = true; - for (Key key : clique->conditional()->frontals()) { - if (!marginalizableKeys.count(key)) { - ret = false; - break; - } - } - cache->wholeMarginalizableCliques.insert({clique, ret}); - return ret; - } - } - - /** - * Check if all variables in the subtree are marginalizable. - * - * Note we use a cache map to avoid repeated searches. - */ - static bool isWholeSubtreeMarginalizable( - const Clique* subtree, - const std::unordered_set& marginalizableKeys, - CachedSearch* cache) { - auto it = cache->wholeMarginalizableSubtrees.find(subtree); - if (it != cache->wholeMarginalizableSubtrees.end()) { - return it->second; - } else { - bool ret = true; - if (isWholeCliqueMarginalizable(subtree, marginalizableKeys, cache)) { - for (const sharedClique& child : subtree->children) { - if (!isWholeSubtreeMarginalizable(child.get(), marginalizableKeys, cache)) { - ret = false; - break; - } - } - } else { - ret = false; - } - cache->wholeMarginalizableSubtrees.insert({subtree, ret}); - return ret; - } - } - - /** - * Check if a clique contains variables that need reelimination due to - * elimination ordering conflicts. - * - * @param[in] clique The clique to check - * @param[in] marginalizableKeys Set of keys to be marginalized - * @return true if any variables in the clique need re-elimination - */ - static bool needsReelimination( - const Clique* clique, - const std::unordered_set& marginalizableKeys, - CachedSearch* cache) { - bool hasNonMarginalizableAhead = false; - - // Check each frontal variable in order - for (Key key : clique->conditional()->frontals()) { - if (marginalizableKeys.count(key)) { - // If we've seen non-marginalizable variables before this one, - // we need to reeliminate - if (hasNonMarginalizableAhead) { - return true; - } - - // Check if any child depends on this marginalizable key and the - // subtree rooted at that child contains non-marginalizables. - for (const sharedClique& child : clique->children) { - if (hasDependency(child.get(), key) && - !isWholeSubtreeMarginalizable(child.get(), marginalizableKeys, cache)) { - return true; - } - } - } else { - hasNonMarginalizableAhead = true; - } - } - return false; - } - - /** - * Gather all dependent nodes that lie on a path from the root clique - * to a clique containing a non-marginalizable variable at the leaf side. - * - * @param[in] rootClique The root clique - * @param[in] marginalizableKeys Set of keys to be marginalized - */ - static void gatherDependentCliques( - const Clique* rootClique, - const std::unordered_set& marginalizableKeys, - std::unordered_set* additionalCliques, - CachedSearch* cache) { - std::vector dependentChildren; - dependentChildren.reserve(rootClique->children.size()); - for (const sharedClique& child : rootClique->children) { - if (additionalCliques->count(child.get())) { - // This child has already been visited. This can happen if the - // child itself contains a marginalizable variable and it's - // processed before the current rootClique. - continue; - } - if (hasDependency(child.get(), marginalizableKeys)) { - dependentChildren.push_back(child.get()); - } - } - gatherDependentCliquesFromChildren( - dependentChildren, marginalizableKeys, additionalCliques, cache); - } - - /** - * A helper function for the above gatherDependentCliques(). - */ - static void gatherDependentCliquesFromChildren( - const std::vector& dependentChildren, - const std::unordered_set& marginalizableKeys, - std::unordered_set* additionalCliques, - CachedSearch* cache) { - std::deque descendants( - dependentChildren.begin(), dependentChildren.end()); - while (!descendants.empty()) { - const Clique* descendant = descendants.front(); - descendants.pop_front(); - - // If the subtree rooted at this descendant contains non-marginalizables, - // it must lie on a path from the root clique to a clique containing - // non-marginalizables at the leaf side. - if (!isWholeSubtreeMarginalizable(descendant, marginalizableKeys, cache)) { - additionalCliques->insert(descendant); - - // Add children of the current descendant to the set descendants. - for (const sharedClique& child : descendant->children) { - if (additionalCliques->count(child.get())) { - // This child has already been visited. - continue; - } else { - descendants.push_back(child.get()); - } - } - } - } - } - - /** - * Add all frontal variables from a clique to a key set. - * - * @param[in] clique Clique to add keys from - * @param[out] additionalKeys Pointer to the output key set - */ - static void addCliqueToKeySet( - const Clique* clique, - std::unordered_set* additionalKeys) { - for (Key key : clique->conditional()->frontals()) { - additionalKeys->insert(key); - } - } - - /** - * Check if the clique depends on the given key. - * - * @param[in] clique Clique to check - * @param[in] key Key to check for dependencies - * @return true if clique depends on the key - */ - static bool hasDependency( - const Clique* clique, Key key) { - auto& conditional = clique->conditional(); - if (std::find(conditional->beginParents(), - conditional->endParents(), key) - != conditional->endParents()) { - return true; - } else { - return false; - } - } - - /** - * Check if the clique depends on any of the given keys. - */ - static bool hasDependency( - const Clique* clique, const std::unordered_set& keys) { - auto& conditional = clique->conditional(); - for (auto it = conditional->beginParents(); - it != conditional->endParents(); ++it) { - if (keys.count(*it)) { - return true; - } - } +#ifdef _MSC_VER +#pragma message("BayesTreeMarginalizationHelper was moved to the gtsam/nonlinear directory") +#else +#warning "BayesTreeMarginalizationHelper was moved to the gtsam/nonlinear directory" +#endif - return false; - } -}; -// BayesTreeMarginalizationHelper -}/// namespace gtsam +#include \ No newline at end of file diff --git a/gtsam_unstable/nonlinear/IncrementalFixedLagSmoother.h b/gtsam_unstable/nonlinear/IncrementalFixedLagSmoother.h index 20747324a4..caf6b7234d 100644 --- a/gtsam_unstable/nonlinear/IncrementalFixedLagSmoother.h +++ b/gtsam_unstable/nonlinear/IncrementalFixedLagSmoother.h @@ -9,151 +9,13 @@ * -------------------------------------------------------------------------- */ -/** - * @file IncrementalFixedLagSmoother.h - * @brief An iSAM2-based fixed-lag smoother. - * - * @author Michael Kaess, Stephen Williams - * @date Oct 14, 2012 - */ - -// \callgraph #pragma once -#include -#include -#include "gtsam_unstable/dllexport.h" - -namespace gtsam { - -/** - * This is a base class for the various HMF2 implementations. The HMF2 eliminates the factor graph - * such that the active states are placed in/near the root. This base class implements a function - * to calculate the ordering, and an update function to incorporate new factors into the HMF. - */ -class GTSAM_UNSTABLE_EXPORT IncrementalFixedLagSmoother: public FixedLagSmoother { - -public: - - /// Typedef for a shared pointer to an Incremental Fixed-Lag Smoother - typedef std::shared_ptr shared_ptr; - - /** default constructor */ - IncrementalFixedLagSmoother(double smootherLag = 0.0, - const ISAM2Params& parameters = DefaultISAM2Params()) : - FixedLagSmoother(smootherLag), isam_(parameters) { - } - - /** destructor */ - ~IncrementalFixedLagSmoother() override { - } - - /** Print the factor for debugging and testing (implementing Testable) */ - void print(const std::string& s = "IncrementalFixedLagSmoother:\n", - const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override; - - /** Check if two IncrementalFixedLagSmoother Objects are equal */ - bool equals(const FixedLagSmoother& rhs, double tol = 1e-9) const override; - - /** - * Add new factors, updating the solution and re-linearizing as needed. - * @param newFactors new factors on old and/or new variables - * @param newTheta new values for new variables only - * @param timestamps an (optional) map from keys to real time stamps - * @param factorsToRemove an (optional) list of factors to remove. - */ - Result update(const NonlinearFactorGraph& newFactors = NonlinearFactorGraph(), - const Values& newTheta = Values(), // - const KeyTimestampMap& timestamps = KeyTimestampMap(), - const FactorIndices& factorsToRemove = FactorIndices()) override; - - /** Compute an estimate from the incomplete linear delta computed during the last update. - * This delta is incomplete because it was not updated below wildfire_threshold. If only - * a single variable is needed, it is faster to call calculateEstimate(const KEY&). - */ - Values calculateEstimate() const override { - return isam_.calculateEstimate(); - } - - /** Compute an estimate for a single variable using its incomplete linear delta computed - * during the last update. This is faster than calling the no-argument version of - * calculateEstimate, which operates on all variables. - * @param key - * @return - */ - template - VALUE calculateEstimate(Key key) const { - return isam_.calculateEstimate(key); - } - - /** return the current set of iSAM2 parameters */ - const ISAM2Params& params() const { - return isam_.params(); - } - - /** Access the current set of factors */ - const NonlinearFactorGraph& getFactors() const { - return isam_.getFactorsUnsafe(); - } - - /** Access the current linearization point */ - const Values& getLinearizationPoint() const { - return isam_.getLinearizationPoint(); - } - - /** Access the current set of deltas to the linearization point */ - const VectorValues& getDelta() const { - return isam_.getDelta(); - } - - /// Calculate marginal covariance on given variable - Matrix marginalCovariance(Key key) const { - return isam_.marginalCovariance(key); - } - - /// Get results of latest isam2 update - const ISAM2Result& getISAM2Result() const{ return isamResult_; } - - /// Get the iSAM2 object which is used for the inference internally - const ISAM2& getISAM2() const { return isam_; } - -protected: - - /** Create default parameters */ - static ISAM2Params DefaultISAM2Params() { - ISAM2Params params; - params.findUnusedFactorSlots = true; - return params; - } - - /** An iSAM2 object used to perform inference. The smoother lag is controlled - * by what factors are removed each iteration */ - ISAM2 isam_; - - /** Store results of latest isam2 update */ - ISAM2Result isamResult_; - - /** Erase any keys associated with timestamps before the provided time */ - void eraseKeysBefore(double timestamp); - - /** Fill in an iSAM2 ConstrainedKeys structure such that the provided keys are eliminated before all others */ - void createOrderingConstraints(const KeyVector& marginalizableKeys, - std::optional >& constrainedKeys) const; - -private: - /** Private methods for printing debug information */ - static void PrintKeySet(const std::set& keys, const std::string& label = - "Keys:"); - static void PrintSymbolicFactor(const GaussianFactor::shared_ptr& factor); - static void PrintSymbolicGraph(const GaussianFactorGraph& graph, - const std::string& label = "Factor Graph:"); - static void PrintSymbolicTree(const gtsam::ISAM2& isam, - const std::string& label = "Bayes Tree:"); - static void PrintSymbolicTreeHelper( - const gtsam::ISAM2Clique::shared_ptr& clique, const std::string indent = - ""); +#ifdef _MSC_VER +#pragma message("IncrementalFixedLagSmoother was moved to the gtsam/nonlinear directory") +#else +#warning "IncrementalFixedLagSmoother was moved to the gtsam/nonlinear directory" +#endif -}; -// IncrementalFixedLagSmoother -}/// namespace gtsam +#include \ No newline at end of file diff --git a/myst.yml b/myst.yml index aa7f4a9d2c..de5278d85e 100644 --- a/myst.yml +++ b/myst.yml @@ -8,11 +8,21 @@ project: toc: - file: README.md - file: INSTALL.md - - file: ./gtsam/user_guide.md + - file: ./doc/user_guide.md children: - file: ./gtsam/geometry/geometry.md children: - pattern: ./gtsam/geometry/doc/* + - file: ./gtsam/nonlinear/nonlinear.md + children: + - pattern: ./gtsam/nonlinear/doc/* + - file: ./gtsam/navigation/navigation.md + children: + - pattern: ./gtsam/navigation/doc/* + - file: ./doc/examples.md + children: + - pattern: ./python/gtsam/examples/*.ipynb + - file: ./doc/expressions.md site: nav: - title: Getting started diff --git a/python/CustomFactors.md b/python/CustomFactors.md index 0a387bb4ff..84b13bdfe0 100644 --- a/python/CustomFactors.md +++ b/python/CustomFactors.md @@ -1,114 +1,4 @@ # GTSAM Python-based factors -One now can build factors purely in Python using the `CustomFactor` factor. +One now can build factors purely in Python using the `CustomFactor` factor. See [this notebook](../gtsam/nonlinear/doc/CustomFactor.ipynb) for usage. -## Usage - -In order to use a Python-based factor, one needs to have a Python function with the following signature: - -```python -import gtsam -import numpy as np -from typing import List - -def error_func(this: gtsam.CustomFactor, v: gtsam.Values, H: List[np.ndarray]) -> np.ndarray: - ... -``` - -`this` is a reference to the `CustomFactor` object. This is required because one can reuse the same -`error_func` for multiple factors. `v` is a reference to the current set of values, and `H` is a list of -**references** to the list of required Jacobians (see the corresponding C++ documentation). Note that -the error returned must be a 1D `numpy` array. - -If `H` is `None`, it means the current factor evaluation does not need Jacobians. For example, the `error` -method on a factor does not need Jacobians, so we don't evaluate them to save CPU. If `H` is not `None`, -each entry of `H` can be assigned a (2D) `numpy` array, as the Jacobian for the corresponding variable. - -All `numpy` matrices inside should be using `order="F"` to maintain interoperability with C++. - -After defining `error_func`, one can create a `CustomFactor` just like any other factor in GTSAM: - -```python -noise_model = gtsam.noiseModel.Unit.Create(3) -# constructor(, , ) -cf = gtsam.CustomFactor(noise_model, [X(0), X(1)], error_func) -``` - -## Example - -The following is a simple `BetweenFactor` implemented in Python. - -```python -import gtsam -import numpy as np -from typing import List - -expected = Pose2(2, 2, np.pi / 2) - -def error_func(this: CustomFactor, v: gtsam.Values, H: List[np.ndarray]) -> np.ndarray: - """ - Error function that mimics a BetweenFactor - :param this: reference to the current CustomFactor being evaluated - :param v: Values object - :param H: list of references to the Jacobian arrays - :return: the non-linear error - """ - key0 = this.keys()[0] - key1 = this.keys()[1] - gT1, gT2 = v.atPose2(key0), v.atPose2(key1) - error = expected.localCoordinates(gT1.between(gT2)) - - if H is not None: - result = gT1.between(gT2) - H[0] = -result.inverse().AdjointMap() - H[1] = np.eye(3) - return error - -noise_model = gtsam.noiseModel.Unit.Create(3) -cf = gtsam.CustomFactor(noise_model, gtsam.KeyVector([0, 1]), error_func) -``` - -In general, the Python-based factor works just like their C++ counterparts. - -## Known Issues - -Because of the `pybind11`-based translation, the performance of `CustomFactor` is not guaranteed. -Also, because `pybind11` needs to lock the Python GIL lock for evaluation of each factor, parallel -evaluation of `CustomFactor` is not possible. - -## Implementation - -`CustomFactor` is a `NonlinearFactor` that has a `std::function` as its callback. -This callback can be translated to a Python function call, thanks to `pybind11`'s functional support. - -The constructor of `CustomFactor` is -```c++ -/** -* Constructor -* @param noiseModel shared pointer to noise model -* @param keys keys of the variables -* @param errorFunction the error functional -*/ -CustomFactor(const SharedNoiseModel& noiseModel, const KeyVector& keys, const CustomErrorFunction& errorFunction) : - Base(noiseModel, keys) { - this->error_function_ = errorFunction; -} -``` - -At construction time, `pybind11` will pass the handle to the Python callback function as a `std::function` object. - -Something worth special mention is this: -```c++ -/* - * NOTE - * ========== - * pybind11 will invoke a copy if this is `JacobianVector &`, and modifications in Python will not be reflected. - * - * This is safe because this is passing a const pointer, and pybind11 will maintain the `std::vector` memory layout. - * Thus the pointer will never be invalidated. - */ -using CustomErrorFunction = std::function; -``` - -which is not documented in `pybind11` docs. One needs to be aware of this if they wanted to implement similar -"mutable" arguments going across the Python-C++ boundary. diff --git a/python/README.md b/python/README.md index 5f7522920f..4d195a8213 100644 --- a/python/README.md +++ b/python/README.md @@ -38,6 +38,14 @@ For instructions on updating the version of the [wrap library](https://github.co See Windows Installation in INSTALL.md in the root directory. +## Generate Docstrings + +The wrap library provides for building the Python wrapper with docstrings included, sourced from the C++ Doxygen comments. To build the Python wrapper with docstrings, follow these instructions: + +1. Build GTSAM with the flag `-DGTSAM_GENERATE_DOC_XML=1`. This will compile the `doc/Doxyfile.in` into a `Doxyfile` with `GENERATE_XML` set to `ON`. +2. From the project root directory, run `doxygen build//doc/Doxyfile`. This will generate the Doxygen XML documentation in `xml/`. +3. Build the Python wrapper with the CMake option `GTWRAP_ADD_DOCSTRINGS` enabled. + ## Unit Tests The Python toolbox also has a small set of unit tests located in the diff --git a/python/gtsam/examples/CameraResectioning.ipynb b/python/gtsam/examples/CameraResectioning.ipynb new file mode 100644 index 0000000000..e037dbfff8 --- /dev/null +++ b/python/gtsam/examples/CameraResectioning.ipynb @@ -0,0 +1,188 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# Camera Resectioning Example\n", + "\n", + "This is a 1:1 transcription of CameraResectioning.cpp, but using custom factors." + ] + }, + { + "cell_type": "markdown", + "metadata": { + "tags": [ + "remove-cell" + ] + }, + "source": [ + "GTSAM Copyright 2010-2022, Georgia Tech Research Corporation,\n", + "Atlanta, Georgia 30332-0415\n", + "All Rights Reserved\n", + "\n", + "Authors: Frank Dellaert, et al. (see THANKS for the full author list)\n", + "\n", + "See LICENSE for the license information" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "\"Open" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": { + "tags": [ + "remove-cell" + ], + "vscode": { + "languageId": "markdown" + } + }, + "outputs": [], + "source": [ + "%pip install --quiet gtsam-develop" + ] + }, + { + "cell_type": "code", + "execution_count": 1, + "metadata": {}, + "outputs": [], + "source": [ + "import numpy as np\n", + "from gtsam import Cal3_S2, CustomFactor, LevenbergMarquardtOptimizer, KeyVector\n", + "from gtsam import NonlinearFactor, NonlinearFactorGraph\n", + "from gtsam import PinholeCameraCal3_S2, Point2, Point3, Pose3, Rot3, Values\n", + "from gtsam.noiseModel import Base as SharedNoiseModel, Diagonal\n", + "from gtsam.symbol_shorthand import X" + ] + }, + { + "cell_type": "code", + "execution_count": 2, + "metadata": {}, + "outputs": [], + "source": [ + "def resectioning_factor(\n", + " model: SharedNoiseModel,\n", + " key: int,\n", + " calib: Cal3_S2,\n", + " p: Point2,\n", + " P: Point3,\n", + ") -> NonlinearFactor:\n", + "\n", + " def error_func(this: CustomFactor, v: Values, H: list[np.ndarray]) -> np.ndarray:\n", + " pose = v.atPose3(this.keys()[0])\n", + " camera = PinholeCameraCal3_S2(pose, calib)\n", + " if H is None:\n", + " return camera.project(P) - p\n", + " Dpose = np.zeros((2, 6), order=\"F\")\n", + " result = camera.project(P, Dpose) - p\n", + " H[0] = Dpose\n", + " return result\n", + "\n", + " return CustomFactor(model, KeyVector([key]), error_func)\n" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Assumptions:\n", + "- Camera: $f = 1$, Image: $100\\times100$, center: $50, 50.0$\n", + "- Pose (ground truth): $(X_w, -Y_w, -Z_w, [0,0,2.0]^T)$\n", + "- Known landmarks: $(10,10,0), (-10,10,0), (-10,-10,0), (10,-10,0)$\n", + "- Perfect measurements: $(55,45), (45,45), (45,55), (55,55)$\n" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Final result:\n", + "\n", + "Values with 1 values:\n", + "Value x1: (gtsam::Pose3)\n", + "R: [\n", + "\t1, 0, 0;\n", + "\t0, -1, 0;\n", + "\t0, 0, -1\n", + "]\n", + "t: 0 0 2\n", + "\n" + ] + } + ], + "source": [ + "# Create camera intrinsic parameters\n", + "calibration = Cal3_S2(1, 1, 0, 50, 50)\n", + "\n", + "# 1. create graph\n", + "graph = NonlinearFactorGraph()\n", + "\n", + "# 2. add factors to the graph\n", + "measurement_noise = Diagonal.Sigmas(np.array([0.5, 0.5]))\n", + "graph.add(\n", + " resectioning_factor(\n", + " measurement_noise, X(1), calibration, Point2(55, 45), Point3(10, 10, 0)\n", + " )\n", + ")\n", + "graph.add(\n", + " resectioning_factor(\n", + " measurement_noise, X(1), calibration, Point2(45, 45), Point3(-10, 10, 0)\n", + " )\n", + ")\n", + "graph.add(\n", + " resectioning_factor(\n", + " measurement_noise, X(1), calibration, Point2(45, 55), Point3(-10, -10, 0)\n", + " )\n", + ")\n", + "graph.add(\n", + " resectioning_factor(\n", + " measurement_noise, X(1), calibration, Point2(55, 55), Point3(10, -10, 0)\n", + " )\n", + ")\n", + "\n", + "# 3. Create an initial estimate for the camera pose\n", + "initial: Values = Values()\n", + "initial.insert(X(1), Pose3(Rot3(1, 0, 0, 0, -1, 0, 0, 0, -1), Point3(0, 0, 1)))\n", + "\n", + "# 4. Optimize the graph using Levenberg-Marquardt\n", + "result: Values = LevenbergMarquardtOptimizer(graph, initial).optimize()\n", + "result.print(\"Final result:\\n\")" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "py312", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.12.6" + } + }, + "nbformat": 4, + "nbformat_minor": 2 +} diff --git a/python/gtsam/examples/CameraResectioning.py b/python/gtsam/examples/CameraResectioning.py deleted file mode 100644 index e962b40bbc..0000000000 --- a/python/gtsam/examples/CameraResectioning.py +++ /dev/null @@ -1,85 +0,0 @@ -# pylint: disable=consider-using-from-import,invalid-name,no-name-in-module,no-member,missing-function-docstring -""" -This is a 1:1 transcription of CameraResectioning.cpp. -""" -import numpy as np -from gtsam import Cal3_S2, CustomFactor, LevenbergMarquardtOptimizer, KeyVector -from gtsam import NonlinearFactor, NonlinearFactorGraph -from gtsam import PinholeCameraCal3_S2, Point2, Point3, Pose3, Rot3, Values -from gtsam.noiseModel import Base as SharedNoiseModel, Diagonal -from gtsam.symbol_shorthand import X - - -def resectioning_factor( - model: SharedNoiseModel, - key: int, - calib: Cal3_S2, - p: Point2, - P: Point3, -) -> NonlinearFactor: - - def error_func(this: CustomFactor, v: Values, H: list[np.ndarray]) -> np.ndarray: - pose = v.atPose3(this.keys()[0]) - camera = PinholeCameraCal3_S2(pose, calib) - if H is None: - return camera.project(P) - p - Dpose = np.zeros((2, 6), order="F") - Dpoint = np.zeros((2, 3), order="F") - Dcal = np.zeros((2, 5), order="F") - result = camera.project(P, Dpose, Dpoint, Dcal) - p - H[0] = Dpose - return result - - return CustomFactor(model, KeyVector([key]), error_func) - - -def main() -> None: - """ - Camera: f = 1, Image: 100x100, center: 50, 50.0 - Pose (ground truth): (Xw, -Yw, -Zw, [0,0,2.0]') - Known landmarks: - 3D Points: (10,10,0) (-10,10,0) (-10,-10,0) (10,-10,0) - Perfect measurements: - 2D Point: (55,45) (45,45) (45,55) (55,55) - """ - - # read camera intrinsic parameters - calib = Cal3_S2(1, 1, 0, 50, 50) - - # 1. create graph - graph = NonlinearFactorGraph() - - # 2. add factors to the graph - measurement_noise = Diagonal.Sigmas(np.array([0.5, 0.5])) - graph.add( - resectioning_factor( - measurement_noise, X(1), calib, Point2(55, 45), Point3(10, 10, 0) - ) - ) - graph.add( - resectioning_factor( - measurement_noise, X(1), calib, Point2(45, 45), Point3(-10, 10, 0) - ) - ) - graph.add( - resectioning_factor( - measurement_noise, X(1), calib, Point2(45, 55), Point3(-10, -10, 0) - ) - ) - graph.add( - resectioning_factor( - measurement_noise, X(1), calib, Point2(55, 55), Point3(10, -10, 0) - ) - ) - - # 3. Create an initial estimate for the camera pose - initial: Values = Values() - initial.insert(X(1), Pose3(Rot3(1, 0, 0, 0, -1, 0, 0, 0, -1), Point3(0, 0, 1))) - - # 4. Optimize the graph using Levenberg-Marquardt - result: Values = LevenbergMarquardtOptimizer(graph, initial).optimize() - result.print("Final result:\n") - - -if __name__ == "__main__": - main() diff --git a/python/gtsam/examples/DiscreteBayesTree.ipynb b/python/gtsam/examples/DiscreteBayesTree.ipynb new file mode 100644 index 0000000000..f980a22c0f --- /dev/null +++ b/python/gtsam/examples/DiscreteBayesTree.ipynb @@ -0,0 +1,1013 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# The Discrete Bayes Tree\n", + "\n", + "An example of building a Bayes net, then eliminating it into a Bayes tree. Mirrors the code in `testDiscreteBayesTree.cpp` ." + ] + }, + { + "cell_type": "markdown", + "metadata": { + "tags": [ + "remove-cell" + ] + }, + "source": [ + "GTSAM Copyright 2010-2022, Georgia Tech Research Corporation,\n", + "Atlanta, Georgia 30332-0415\n", + "All Rights Reserved\n", + "\n", + "Authors: Frank Dellaert, et al. (see THANKS for the full author list)\n", + "\n", + "See LICENSE for the license information" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "\"Open" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": { + "tags": [ + "remove-cell" + ] + }, + "outputs": [], + "source": [ + "# This needs gtbook:\n", + "% pip install --quiet gtbook" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "from gtsam import DiscreteBayesTree, DiscreteBayesNet, DiscreteKeys, DiscreteFactorGraph, Ordering\n", + "from gtsam.symbol_shorthand import S" + ] + }, + { + "cell_type": "code", + "execution_count": 2, + "metadata": {}, + "outputs": [], + "source": [ + "def P(*args):\n", + " \"\"\" Create a DiscreteKeys instances from a variable number of DiscreteKey pairs.\"\"\"\n", + " #TODO: We can make life easier by providing variable argument functions in C++ itself.\n", + " dks = DiscreteKeys()\n", + " for key in args:\n", + " dks.push_back(key)\n", + " return dks" + ] + }, + { + "cell_type": "code", + "execution_count": 3, + "metadata": {}, + "outputs": [], + "source": [ + "import graphviz\n", + "class show(graphviz.Source):\n", + " \"\"\" Display an object with a dot method as a graph.\"\"\"\n", + "\n", + " def __init__(self, obj):\n", + " \"\"\"Construct from object with 'dot' method.\"\"\"\n", + " # This small class takes an object, calls its dot function, and uses the\n", + " # resulting string to initialize a graphviz.Source instance. This in turn\n", + " # has a _repr_mimebundle_ method, which then renders it in the notebook.\n", + " super().__init__(obj.dot())" + ] + }, + { + "cell_type": "code", + "execution_count": 4, + "metadata": {}, + "outputs": [ + { + "data": { + "image/svg+xml": [ + "\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "G\n", + "\n", + "\n", + "\n", + "8\n", + "\n", + "8\n", + "\n", + "\n", + "\n", + "0\n", + "\n", + "0\n", + "\n", + "\n", + "\n", + "8->0\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "1\n", + "\n", + "1\n", + "\n", + "\n", + "\n", + "8->1\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "12\n", + "\n", + "12\n", + "\n", + "\n", + "\n", + "12->8\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "12->0\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "12->1\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "9\n", + "\n", + "9\n", + "\n", + "\n", + "\n", + "12->9\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "2\n", + "\n", + "2\n", + "\n", + "\n", + "\n", + "12->2\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "3\n", + "\n", + "3\n", + "\n", + "\n", + "\n", + "12->3\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "9->2\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "9->3\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "10\n", + "\n", + "10\n", + "\n", + "\n", + "\n", + "4\n", + "\n", + "4\n", + "\n", + "\n", + "\n", + "10->4\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "5\n", + "\n", + "5\n", + "\n", + "\n", + "\n", + "10->5\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "13\n", + "\n", + "13\n", + "\n", + "\n", + "\n", + "13->10\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "13->4\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "13->5\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "11\n", + "\n", + "11\n", + "\n", + "\n", + "\n", + "13->11\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "6\n", + "\n", + "6\n", + "\n", + "\n", + "\n", + "13->6\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "7\n", + "\n", + "7\n", + "\n", + "\n", + "\n", + "13->7\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "11->6\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "11->7\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "14\n", + "\n", + "14\n", + "\n", + "\n", + "\n", + "14->8\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "14->12\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "14->9\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "14->10\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "14->13\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "14->11\n", + "\n", + "\n", + "\n", + "\n", + "\n" + ], + "text/plain": [ + "<__main__.show at 0x109c615b0>" + ] + }, + "execution_count": 4, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "# Define DiscreteKey pairs.\n", + "keys = [(j, 2) for j in range(15)]\n", + "\n", + "# Create thin-tree Bayesnet.\n", + "bayesNet = DiscreteBayesNet()\n", + "\n", + "\n", + "bayesNet.add(keys[0], P(keys[8], keys[12]), \"2/3 1/4 3/2 4/1\")\n", + "bayesNet.add(keys[1], P(keys[8], keys[12]), \"4/1 2/3 3/2 1/4\")\n", + "bayesNet.add(keys[2], P(keys[9], keys[12]), \"1/4 8/2 2/3 4/1\")\n", + "bayesNet.add(keys[3], P(keys[9], keys[12]), \"1/4 2/3 3/2 4/1\")\n", + "\n", + "bayesNet.add(keys[4], P(keys[10], keys[13]), \"2/3 1/4 3/2 4/1\")\n", + "bayesNet.add(keys[5], P(keys[10], keys[13]), \"4/1 2/3 3/2 1/4\")\n", + "bayesNet.add(keys[6], P(keys[11], keys[13]), \"1/4 3/2 2/3 4/1\")\n", + "bayesNet.add(keys[7], P(keys[11], keys[13]), \"1/4 2/3 3/2 4/1\")\n", + "\n", + "bayesNet.add(keys[8], P(keys[12], keys[14]), \"T 1/4 3/2 4/1\")\n", + "bayesNet.add(keys[9], P(keys[12], keys[14]), \"4/1 2/3 F 1/4\")\n", + "bayesNet.add(keys[10], P(keys[13], keys[14]), \"1/4 3/2 2/3 4/1\")\n", + "bayesNet.add(keys[11], P(keys[13], keys[14]), \"1/4 2/3 3/2 4/1\")\n", + "\n", + "bayesNet.add(keys[12], P(keys[14]), \"3/1 3/1\")\n", + "bayesNet.add(keys[13], P(keys[14]), \"1/3 3/1\")\n", + "\n", + "bayesNet.add(keys[14], P(), \"1/3\")\n", + "\n", + "show(bayesNet)" + ] + }, + { + "cell_type": "code", + "execution_count": 5, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "DiscreteValues{0: 1, 1: 1, 2: 0, 3: 1, 4: 1, 5: 1, 6: 0, 7: 1, 8: 0, 9: 0, 10: 0, 11: 0, 12: 1, 13: 1, 14: 0}\n", + "DiscreteValues{0: 0, 1: 1, 2: 0, 3: 0, 4: 1, 5: 0, 6: 0, 7: 0, 8: 1, 9: 1, 10: 0, 11: 1, 12: 0, 13: 0, 14: 1}\n", + "DiscreteValues{0: 1, 1: 0, 2: 1, 3: 1, 4: 0, 5: 0, 6: 1, 7: 0, 8: 1, 9: 0, 10: 1, 11: 1, 12: 0, 13: 1, 14: 0}\n", + "DiscreteValues{0: 1, 1: 1, 2: 0, 3: 0, 4: 1, 5: 1, 6: 1, 7: 1, 8: 0, 9: 1, 10: 0, 11: 0, 12: 1, 13: 0, 14: 1}\n", + "DiscreteValues{0: 0, 1: 0, 2: 1, 3: 0, 4: 1, 5: 1, 6: 1, 7: 0, 8: 1, 9: 1, 10: 0, 11: 1, 12: 0, 13: 0, 14: 1}\n" + ] + } + ], + "source": [ + "# Sample Bayes net (needs conditionals added in elimination order!)\n", + "for i in range(5):\n", + " print(bayesNet.sample())" + ] + }, + { + "cell_type": "code", + "execution_count": 6, + "metadata": {}, + "outputs": [ + { + "data": { + "image/svg+xml": [ + "\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "var0\n", + "\n", + "0\n", + "\n", + "\n", + "\n", + "factor0\n", + "\n", + "\n", + "\n", + "\n", + "var0--factor0\n", + "\n", + "\n", + "\n", + "\n", + "var1\n", + "\n", + "1\n", + "\n", + "\n", + "\n", + "factor1\n", + "\n", + "\n", + "\n", + "\n", + "var1--factor1\n", + "\n", + "\n", + "\n", + "\n", + "var2\n", + "\n", + "2\n", + "\n", + "\n", + "\n", + "factor2\n", + "\n", + "\n", + "\n", + "\n", + "var2--factor2\n", + "\n", + "\n", + "\n", + "\n", + "var3\n", + "\n", + "3\n", + "\n", + "\n", + "\n", + "factor3\n", + "\n", + "\n", + "\n", + "\n", + "var3--factor3\n", + "\n", + "\n", + "\n", + "\n", + "var4\n", + "\n", + "4\n", + "\n", + "\n", + "\n", + "factor4\n", + "\n", + "\n", + "\n", + "\n", + "var4--factor4\n", + "\n", + "\n", + "\n", + "\n", + "var5\n", + "\n", + "5\n", + "\n", + "\n", + "\n", + "factor5\n", + "\n", + "\n", + "\n", + "\n", + "var5--factor5\n", + "\n", + "\n", + "\n", + "\n", + "var6\n", + "\n", + "6\n", + "\n", + "\n", + "\n", + "factor6\n", + "\n", + "\n", + "\n", + "\n", + "var6--factor6\n", + "\n", + "\n", + "\n", + "\n", + "var7\n", + "\n", + "7\n", + "\n", + "\n", + "\n", + "factor7\n", + "\n", + "\n", + "\n", + "\n", + "var7--factor7\n", + "\n", + "\n", + "\n", + "\n", + "var8\n", + "\n", + "8\n", + "\n", + "\n", + "\n", + "var8--factor0\n", + "\n", + "\n", + "\n", + "\n", + "var8--factor1\n", + "\n", + "\n", + "\n", + "\n", + "factor8\n", + "\n", + "\n", + "\n", + "\n", + "var8--factor8\n", + "\n", + "\n", + "\n", + "\n", + "var9\n", + "\n", + "9\n", + "\n", + "\n", + "\n", + "var9--factor2\n", + "\n", + "\n", + "\n", + "\n", + "var9--factor3\n", + "\n", + "\n", + "\n", + "\n", + "factor9\n", + "\n", + "\n", + "\n", + "\n", + "var9--factor9\n", + "\n", + "\n", + "\n", + "\n", + "var10\n", + "\n", + "10\n", + "\n", + "\n", + "\n", + "var10--factor4\n", + "\n", + "\n", + "\n", + "\n", + "var10--factor5\n", + "\n", + "\n", + "\n", + "\n", + "factor10\n", + "\n", + "\n", + "\n", + "\n", + "var10--factor10\n", + "\n", + "\n", + "\n", + "\n", + "var11\n", + "\n", + "11\n", + "\n", + "\n", + "\n", + "var11--factor6\n", + "\n", + "\n", + "\n", + "\n", + "var11--factor7\n", + "\n", + "\n", + "\n", + "\n", + "factor11\n", + "\n", + "\n", + "\n", + "\n", + "var11--factor11\n", + "\n", + "\n", + "\n", + "\n", + "var12\n", + "\n", + "12\n", + "\n", + "\n", + "\n", + "var14\n", + "\n", + "14\n", + "\n", + "\n", + "\n", + "var12--var14\n", + "\n", + "\n", + "\n", + "\n", + "var12--factor0\n", + "\n", + "\n", + "\n", + "\n", + "var12--factor1\n", + "\n", + "\n", + "\n", + "\n", + "var12--factor2\n", + "\n", + "\n", + "\n", + "\n", + "var12--factor3\n", + "\n", + "\n", + "\n", + "\n", + "var12--factor8\n", + "\n", + "\n", + "\n", + "\n", + "var12--factor9\n", + "\n", + "\n", + "\n", + "\n", + "var13\n", + "\n", + "13\n", + "\n", + "\n", + "\n", + "var13--var14\n", + "\n", + "\n", + "\n", + "\n", + "var13--factor4\n", + "\n", + "\n", + "\n", + "\n", + "var13--factor5\n", + "\n", + "\n", + "\n", + "\n", + "var13--factor6\n", + "\n", + "\n", + "\n", + "\n", + "var13--factor7\n", + "\n", + "\n", + "\n", + "\n", + "var13--factor10\n", + "\n", + "\n", + "\n", + "\n", + "var13--factor11\n", + "\n", + "\n", + "\n", + "\n", + "var14--factor8\n", + "\n", + "\n", + "\n", + "\n", + "var14--factor9\n", + "\n", + "\n", + "\n", + "\n", + "var14--factor10\n", + "\n", + "\n", + "\n", + "\n", + "var14--factor11\n", + "\n", + "\n", + "\n", + "\n", + "factor14\n", + "\n", + "\n", + "\n", + "\n", + "var14--factor14\n", + "\n", + "\n", + "\n", + "\n" + ], + "text/plain": [ + "<__main__.show at 0x109c61f10>" + ] + }, + "execution_count": 6, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "# Create a factor graph out of the Bayes net.\n", + "factorGraph = DiscreteFactorGraph(bayesNet)\n", + "show(factorGraph)" + ] + }, + { + "cell_type": "code", + "execution_count": 7, + "metadata": {}, + "outputs": [ + { + "data": { + "image/svg+xml": [ + "\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "G\n", + "\n", + "\n", + "\n", + "0\n", + "\n", + "8,12,14\n", + "\n", + "\n", + "\n", + "1\n", + "\n", + "0 : 8,12\n", + "\n", + "\n", + "\n", + "0->1\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "2\n", + "\n", + "1 : 8,12\n", + "\n", + "\n", + "\n", + "0->2\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "3\n", + "\n", + "9 : 12,14\n", + "\n", + "\n", + "\n", + "0->3\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "6\n", + "\n", + "10,13 : 14\n", + "\n", + "\n", + "\n", + "0->6\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "4\n", + "\n", + "2 : 9,12\n", + "\n", + "\n", + "\n", + "3->4\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "5\n", + "\n", + "3 : 9,12\n", + "\n", + "\n", + "\n", + "3->5\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "7\n", + "\n", + "4 : 10,13\n", + "\n", + "\n", + "\n", + "6->7\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "8\n", + "\n", + "5 : 10,13\n", + "\n", + "\n", + "\n", + "6->8\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "9\n", + "\n", + "11 : 13,14\n", + "\n", + "\n", + "\n", + "6->9\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "10\n", + "\n", + "6 : 11,13\n", + "\n", + "\n", + "\n", + "9->10\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "11\n", + "\n", + "7 : 11,13\n", + "\n", + "\n", + "\n", + "9->11\n", + "\n", + "\n", + "\n", + "\n", + "\n" + ], + "text/plain": [ + "<__main__.show at 0x109c61b50>" + ] + }, + "execution_count": 7, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "# Create a BayesTree out of the factor graph.\n", + "ordering = Ordering()\n", + "for j in range(15): ordering.push_back(j)\n", + "bayesTree = factorGraph.eliminateMultifrontal(ordering)\n", + "show(bayesTree)" + ] + } + ], + "metadata": { + "interpreter": { + "hash": "31f2aee4e71d21fbe5cf8b01ff0e069b9275f58929596ceb00d14d90e3e16cd6" + }, + "kernelspec": { + "display_name": "Python 3.8.9 64-bit", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.9.7" + }, + "orig_nbformat": 4 + }, + "nbformat": 4, + "nbformat_minor": 2 +} diff --git a/python/gtsam/examples/DiscreteSwitching.ipynb b/python/gtsam/examples/DiscreteSwitching.ipynb new file mode 100644 index 0000000000..4af283cbdb --- /dev/null +++ b/python/gtsam/examples/DiscreteSwitching.ipynb @@ -0,0 +1,805 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# A Discrete Switching System\n", + "\n", + "A la multi-hypothesis-smoother (MHS), but all discrete.\n" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "tags": [ + "remove-cell" + ] + }, + "source": [ + "GTSAM Copyright 2010-2022, Georgia Tech Research Corporation,\n", + "Atlanta, Georgia 30332-0415\n", + "All Rights Reserved\n", + "\n", + "Authors: Frank Dellaert, et al. (see THANKS for the full author list)\n", + "\n", + "See LICENSE for the license information" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "\"Open" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": { + "tags": [ + "remove-cell" + ] + }, + "outputs": [], + "source": [ + "# This needs gtbook:\n", + "% pip install --quiet gtbook" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "from gtsam import DiscreteBayesNet, DiscreteKeys, DiscreteFactorGraph, Ordering\n", + "from gtsam.symbol_shorthand import S\n", + "from gtsam.symbol_shorthand import M" + ] + }, + { + "cell_type": "code", + "execution_count": 2, + "metadata": {}, + "outputs": [], + "source": [ + "def P(*args):\n", + " \"\"\" Create a DiscreteKeys instances from a variable number of DiscreteKey pairs.\"\"\"\n", + " # TODO: We can make life easier by providing variable argument functions in C++ itself.\n", + " dks = DiscreteKeys()\n", + " for key in args:\n", + " dks.push_back(key)\n", + " return dks\n" + ] + }, + { + "cell_type": "code", + "execution_count": 3, + "metadata": {}, + "outputs": [], + "source": [ + "import graphviz\n", + "\n", + "\n", + "class show(graphviz.Source):\n", + " \"\"\" Display an object with a dot method as a graph.\"\"\"\n", + "\n", + " def __init__(self, obj):\n", + " \"\"\"Construct from object with 'dot' method.\"\"\"\n", + " # This small class takes an object, calls its dot function, and uses the\n", + " # resulting string to initialize a graphviz.Source instance. This in turn\n", + " # has a _repr_mimebundle_ method, which then renders it in the notebook.\n", + " super().__init__(obj.dot())\n" + ] + }, + { + "cell_type": "code", + "execution_count": 4, + "metadata": {}, + "outputs": [ + { + "data": { + "text/html": [ + "

DiscreteBayesNet of size 4

\n", + "

P(s2|m1,s1):

\n", + "\n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + "
m1s1012
000.90.10
010.10.80.1
0200.10.9
100.10.90
1100.10.9
120.900.1
\n", + "
\n", + "
\n", + "

P(s3|m2,s2):

\n", + "\n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + "
m2s2012
000.90.10
010.10.80.1
0200.10.9
100.10.90
1100.10.9
120.900.1
\n", + "
\n", + "
\n", + "

P(s4|m3,s3):

\n", + "\n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + "
m3s3012
000.90.10
010.10.80.1
0200.10.9
100.10.90
1100.10.9
120.900.1
\n", + "
\n", + "
\n", + "

P(s5|m4,s4):

\n", + "\n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + "
m4s4012
000.90.10
010.10.80.1
0200.10.9
100.10.90
1100.10.9
120.900.1
\n", + "
\n" + ], + "text/markdown": [ + "`DiscreteBayesNet` of size 4\n", + "\n", + " *P(s2|m1,s1):*\n", + "\n", + "|*m1*|*s1*|0|1|2|\n", + "|:-:|:-:|:-:|:-:|:-:|\n", + "|0|0|0.9|0.1|0|\n", + "|0|1|0.1|0.8|0.1|\n", + "|0|2|0|0.1|0.9|\n", + "|1|0|0.1|0.9|0|\n", + "|1|1|0|0.1|0.9|\n", + "|1|2|0.9|0|0.1|\n", + "\n", + " *P(s3|m2,s2):*\n", + "\n", + "|*m2*|*s2*|0|1|2|\n", + "|:-:|:-:|:-:|:-:|:-:|\n", + "|0|0|0.9|0.1|0|\n", + "|0|1|0.1|0.8|0.1|\n", + "|0|2|0|0.1|0.9|\n", + "|1|0|0.1|0.9|0|\n", + "|1|1|0|0.1|0.9|\n", + "|1|2|0.9|0|0.1|\n", + "\n", + " *P(s4|m3,s3):*\n", + "\n", + "|*m3*|*s3*|0|1|2|\n", + "|:-:|:-:|:-:|:-:|:-:|\n", + "|0|0|0.9|0.1|0|\n", + "|0|1|0.1|0.8|0.1|\n", + "|0|2|0|0.1|0.9|\n", + "|1|0|0.1|0.9|0|\n", + "|1|1|0|0.1|0.9|\n", + "|1|2|0.9|0|0.1|\n", + "\n", + " *P(s5|m4,s4):*\n", + "\n", + "|*m4*|*s4*|0|1|2|\n", + "|:-:|:-:|:-:|:-:|:-:|\n", + "|0|0|0.9|0.1|0|\n", + "|0|1|0.1|0.8|0.1|\n", + "|0|2|0|0.1|0.9|\n", + "|1|0|0.1|0.9|0|\n", + "|1|1|0|0.1|0.9|\n", + "|1|2|0.9|0|0.1|\n", + "\n" + ], + "text/plain": [ + "DiscreteBayesNet\n", + " \n", + "size: 4\n", + "conditional 0: P( s2 | m1 s1 ):\n", + " Choice(s2) \n", + " 0 Choice(s1) \n", + " 0 0 Choice(m1) \n", + " 0 0 0 Leaf 0.9\n", + " 0 0 1 Leaf 0.1\n", + " 0 1 Choice(m1) \n", + " 0 1 0 Leaf 0.1\n", + " 0 1 1 Leaf 0\n", + " 0 2 Choice(m1) \n", + " 0 2 0 Leaf 0\n", + " 0 2 1 Leaf 0.9\n", + " 1 Choice(s1) \n", + " 1 0 Choice(m1) \n", + " 1 0 0 Leaf 0.1\n", + " 1 0 1 Leaf 0.9\n", + " 1 1 Choice(m1) \n", + " 1 1 0 Leaf 0.8\n", + " 1 1 1 Leaf 0.1\n", + " 1 2 Choice(m1) \n", + " 1 2 0 Leaf 0.1\n", + " 1 2 1 Leaf 0\n", + " 2 Choice(s1) \n", + " 2 0 Choice(m1) \n", + " 2 0 0 Leaf 0\n", + " 2 0 1 Leaf 0\n", + " 2 1 Choice(m1) \n", + " 2 1 0 Leaf 0.1\n", + " 2 1 1 Leaf 0.9\n", + " 2 2 Choice(m1) \n", + " 2 2 0 Leaf 0.9\n", + " 2 2 1 Leaf 0.1\n", + "\n", + "conditional 1: P( s3 | m2 s2 ):\n", + " Choice(s3) \n", + " 0 Choice(s2) \n", + " 0 0 Choice(m2) \n", + " 0 0 0 Leaf 0.9\n", + " 0 0 1 Leaf 0.1\n", + " 0 1 Choice(m2) \n", + " 0 1 0 Leaf 0.1\n", + " 0 1 1 Leaf 0\n", + " 0 2 Choice(m2) \n", + " 0 2 0 Leaf 0\n", + " 0 2 1 Leaf 0.9\n", + " 1 Choice(s2) \n", + " 1 0 Choice(m2) \n", + " 1 0 0 Leaf 0.1\n", + " 1 0 1 Leaf 0.9\n", + " 1 1 Choice(m2) \n", + " 1 1 0 Leaf 0.8\n", + " 1 1 1 Leaf 0.1\n", + " 1 2 Choice(m2) \n", + " 1 2 0 Leaf 0.1\n", + " 1 2 1 Leaf 0\n", + " 2 Choice(s2) \n", + " 2 0 Choice(m2) \n", + " 2 0 0 Leaf 0\n", + " 2 0 1 Leaf 0\n", + " 2 1 Choice(m2) \n", + " 2 1 0 Leaf 0.1\n", + " 2 1 1 Leaf 0.9\n", + " 2 2 Choice(m2) \n", + " 2 2 0 Leaf 0.9\n", + " 2 2 1 Leaf 0.1\n", + "\n", + "conditional 2: P( s4 | m3 s3 ):\n", + " Choice(s4) \n", + " 0 Choice(s3) \n", + " 0 0 Choice(m3) \n", + " 0 0 0 Leaf 0.9\n", + " 0 0 1 Leaf 0.1\n", + " 0 1 Choice(m3) \n", + " 0 1 0 Leaf 0.1\n", + " 0 1 1 Leaf 0\n", + " 0 2 Choice(m3) \n", + " 0 2 0 Leaf 0\n", + " 0 2 1 Leaf 0.9\n", + " 1 Choice(s3) \n", + " 1 0 Choice(m3) \n", + " 1 0 0 Leaf 0.1\n", + " 1 0 1 Leaf 0.9\n", + " 1 1 Choice(m3) \n", + " 1 1 0 Leaf 0.8\n", + " 1 1 1 Leaf 0.1\n", + " 1 2 Choice(m3) \n", + " 1 2 0 Leaf 0.1\n", + " 1 2 1 Leaf 0\n", + " 2 Choice(s3) \n", + " 2 0 Choice(m3) \n", + " 2 0 0 Leaf 0\n", + " 2 0 1 Leaf 0\n", + " 2 1 Choice(m3) \n", + " 2 1 0 Leaf 0.1\n", + " 2 1 1 Leaf 0.9\n", + " 2 2 Choice(m3) \n", + " 2 2 0 Leaf 0.9\n", + " 2 2 1 Leaf 0.1\n", + "\n", + "conditional 3: P( s5 | m4 s4 ):\n", + " Choice(s5) \n", + " 0 Choice(s4) \n", + " 0 0 Choice(m4) \n", + " 0 0 0 Leaf 0.9\n", + " 0 0 1 Leaf 0.1\n", + " 0 1 Choice(m4) \n", + " 0 1 0 Leaf 0.1\n", + " 0 1 1 Leaf 0\n", + " 0 2 Choice(m4) \n", + " 0 2 0 Leaf 0\n", + " 0 2 1 Leaf 0.9\n", + " 1 Choice(s4) \n", + " 1 0 Choice(m4) \n", + " 1 0 0 Leaf 0.1\n", + " 1 0 1 Leaf 0.9\n", + " 1 1 Choice(m4) \n", + " 1 1 0 Leaf 0.8\n", + " 1 1 1 Leaf 0.1\n", + " 1 2 Choice(m4) \n", + " 1 2 0 Leaf 0.1\n", + " 1 2 1 Leaf 0\n", + " 2 Choice(s4) \n", + " 2 0 Choice(m4) \n", + " 2 0 0 Leaf 0\n", + " 2 0 1 Leaf 0\n", + " 2 1 Choice(m4) \n", + " 2 1 0 Leaf 0.1\n", + " 2 1 1 Leaf 0.9\n", + " 2 2 Choice(m4) \n", + " 2 2 0 Leaf 0.9\n", + " 2 2 1 Leaf 0.1\n" + ] + }, + "execution_count": 4, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "nrStates = 3\n", + "K = 5\n", + "\n", + "bayesNet = DiscreteBayesNet()\n", + "for k in range(1, K):\n", + " key = S(k), nrStates\n", + " key_plus = S(k+1), nrStates\n", + " mode = M(k), 2\n", + " bayesNet.add(key_plus, P(mode, key), \"9/1/0 1/8/1 0/1/9 1/9/0 0/1/9 9/0/1\")\n", + "\n", + "bayesNet" + ] + }, + { + "cell_type": "code", + "execution_count": 5, + "metadata": {}, + "outputs": [ + { + "data": { + "image/svg+xml": [ + "\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "var7854277750134145025\n", + "\n", + "m1\n", + "\n", + "\n", + "\n", + "var8286623314361712642\n", + "\n", + "s2\n", + "\n", + "\n", + "\n", + "var7854277750134145025->var8286623314361712642\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "var7854277750134145026\n", + "\n", + "m2\n", + "\n", + "\n", + "\n", + "var8286623314361712643\n", + "\n", + "s3\n", + "\n", + "\n", + "\n", + "var7854277750134145026->var8286623314361712643\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "var7854277750134145027\n", + "\n", + "m3\n", + "\n", + "\n", + "\n", + "var8286623314361712644\n", + "\n", + "s4\n", + "\n", + "\n", + "\n", + "var7854277750134145027->var8286623314361712644\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "var7854277750134145028\n", + "\n", + "m4\n", + "\n", + "\n", + "\n", + "var8286623314361712645\n", + "\n", + "s5\n", + "\n", + "\n", + "\n", + "var7854277750134145028->var8286623314361712645\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "var8286623314361712641\n", + "\n", + "s1\n", + "\n", + "\n", + "\n", + "var8286623314361712641->var8286623314361712642\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "var8286623314361712642->var8286623314361712643\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "var8286623314361712643->var8286623314361712644\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "var8286623314361712644->var8286623314361712645\n", + "\n", + "\n", + "\n", + "\n", + "\n" + ], + "text/plain": [ + "<__main__.show at 0x11216aea0>" + ] + }, + "execution_count": 5, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "show(bayesNet)" + ] + }, + { + "cell_type": "code", + "execution_count": 6, + "metadata": {}, + "outputs": [ + { + "data": { + "image/svg+xml": [ + "\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "var7854277750134145025\n", + "\n", + "m1\n", + "\n", + "\n", + "\n", + "factor0\n", + "\n", + "\n", + "\n", + "\n", + "var7854277750134145025--factor0\n", + "\n", + "\n", + "\n", + "\n", + "var7854277750134145026\n", + "\n", + "m2\n", + "\n", + "\n", + "\n", + "factor1\n", + "\n", + "\n", + "\n", + "\n", + "var7854277750134145026--factor1\n", + "\n", + "\n", + "\n", + "\n", + "var7854277750134145027\n", + "\n", + "m3\n", + "\n", + "\n", + "\n", + "factor2\n", + "\n", + "\n", + "\n", + "\n", + "var7854277750134145027--factor2\n", + "\n", + "\n", + "\n", + "\n", + "var7854277750134145028\n", + "\n", + "m4\n", + "\n", + "\n", + "\n", + "factor3\n", + "\n", + "\n", + "\n", + "\n", + "var7854277750134145028--factor3\n", + "\n", + "\n", + "\n", + "\n", + "var8286623314361712641\n", + "\n", + "s1\n", + "\n", + "\n", + "\n", + "var8286623314361712641--factor0\n", + "\n", + "\n", + "\n", + "\n", + "var8286623314361712642\n", + "\n", + "s2\n", + "\n", + "\n", + "\n", + "var8286623314361712642--factor0\n", + "\n", + "\n", + "\n", + "\n", + "var8286623314361712642--factor1\n", + "\n", + "\n", + "\n", + "\n", + "var8286623314361712643\n", + "\n", + "s3\n", + "\n", + "\n", + "\n", + "var8286623314361712643--factor1\n", + "\n", + "\n", + "\n", + "\n", + "var8286623314361712643--factor2\n", + "\n", + "\n", + "\n", + "\n", + "var8286623314361712644\n", + "\n", + "s4\n", + "\n", + "\n", + "\n", + "var8286623314361712644--factor2\n", + "\n", + "\n", + "\n", + "\n", + "var8286623314361712644--factor3\n", + "\n", + "\n", + "\n", + "\n", + "var8286623314361712645\n", + "\n", + "s5\n", + "\n", + "\n", + "\n", + "var8286623314361712645--factor3\n", + "\n", + "\n", + "\n", + "\n" + ], + "text/plain": [ + "<__main__.show at 0x1121a44d0>" + ] + }, + "execution_count": 6, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "# Create a factor graph out of the Bayes net.\n", + "factorGraph = DiscreteFactorGraph(bayesNet)\n", + "show(factorGraph)" + ] + }, + { + "cell_type": "code", + "execution_count": 9, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Position 0: s1, s2, s3, s4, s5, m1, m2, m3, m4\n", + "\n" + ] + } + ], + "source": [ + "# Create a BayesTree out of the factor graph.\n", + "ordering = Ordering()\n", + "# First eliminate \"continuous\" states in time order\n", + "for k in range(1, K+1):\n", + " ordering.push_back(S(k))\n", + "for k in range(1, K):\n", + " ordering.push_back(M(k))\n", + "print(ordering)\n", + "bayesTree = factorGraph.eliminateMultifrontal(ordering)" + ] + }, + { + "cell_type": "code", + "execution_count": 8, + "metadata": {}, + "outputs": [ + { + "data": { + "image/svg+xml": [ + "\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "G\n", + "\n", + "\n", + "\n", + "0\n", + "\n", + "s4, s5, m1, m2, m3, m4\n", + "\n", + "\n", + "\n", + "1\n", + "\n", + "s3 : m1, m2, m3, s4\n", + "\n", + "\n", + "\n", + "0->1\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "2\n", + "\n", + "s2 : m1, m2, s3\n", + "\n", + "\n", + "\n", + "1->2\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "3\n", + "\n", + "s1 : m1, s2\n", + "\n", + "\n", + "\n", + "2->3\n", + "\n", + "\n", + "\n", + "\n", + "\n" + ], + "text/plain": [ + "<__main__.show at 0x11775c3e0>" + ] + }, + "execution_count": 8, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "show(bayesTree)" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "py312", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.12.6" + }, + "orig_nbformat": 4 + }, + "nbformat": 4, + "nbformat_minor": 2 +} diff --git a/python/gtsam/examples/EqF.ipynb b/python/gtsam/examples/EqF.ipynb index 33d7f74da9..9eec85d554 100644 --- a/python/gtsam/examples/EqF.ipynb +++ b/python/gtsam/examples/EqF.ipynb @@ -6,18 +6,44 @@ "source": [ "# Equivariant Filter Bias\n", "\n", - "Implementing the example in [Fornasier et al, 2022, Overcoming Bias: Equivariant Filter Design for Biased Attitude Estimation with Online Calibration](https://arxiv.org/pdf/2209.12038).\n", + "Implementing the example in the \"Overcoming Bias\" paper by {cite:t}`https://doi.org/10.1109/LRA.2022.3210867` ([arxiv version](https://arxiv.org/pdf/2209.12038)).\n", + "This notebook was created by converting [Alessandro Fornasier's equivariant filter code](https://github.com/aau-cns/ABC-EqF) to use GTSAM's built-in data structures.\n", "\n", - "This notebook uses Alessandro Fornasier's equivariant filter code (https://github.com/aau-cns/ABC-EqF) converted to use GTSAM's libraries.\n", - "Authors: Jennifer Oum & Darshan Rajasekaran\n", + "Authors: Jennifer Oum & Darshan Rajasekaran" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "\"Open" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "tags": [ + "remove-cell" + ] + }, + "source": [ + "GTSAM Copyright 2010-2022, Georgia Tech Research Corporation,\n", + "Atlanta, Georgia 30332-0415\n", + "All Rights Reserved\n", "\n", - "We start by installing gtsam (GTSAM's python wrapper) and gtbook." + "Authors: Frank Dellaert, et al. (see THANKS for the full author list)\n", + "\n", + "See LICENSE for the license information" ] }, { "cell_type": "code", - "execution_count": 68, - "metadata": {}, + "execution_count": null, + "metadata": { + "tags": [ + "remove-cell" + ] + }, "outputs": [ { "name": "stdout", @@ -28,12 +54,13 @@ } ], "source": [ + "# We start by installing gtsam (GTSAM's python wrapper) and gtbook.\n", "%pip install --quiet gtsam gtbook" ] }, { "cell_type": "code", - "execution_count": 69, + "execution_count": null, "metadata": {}, "outputs": [], "source": [ @@ -47,7 +74,7 @@ "import gtsam\n", "from gtsam import findExampleDataFile, Rot3\n", "\n", - "from EqF import *\n" + "from EqF import *" ] }, { diff --git a/python/gtsam/examples/RangeISAMExample_plaza2.ipynb b/python/gtsam/examples/RangeISAMExample_plaza2.ipynb index f11636606c..d8b5ff4ebe 100644 --- a/python/gtsam/examples/RangeISAMExample_plaza2.ipynb +++ b/python/gtsam/examples/RangeISAMExample_plaza2.ipynb @@ -3,6 +3,21 @@ { "cell_type": "markdown", "metadata": {}, + "source": [ + "# Range SLAM with iSAM\n", + "\n", + "A 2D Range SLAM example, with iSAM and smart range factors\n", + "\n", + "Author: Frank Dellaert" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "tags": [ + "remove-cell" + ] + }, "source": [ "GTSAM Copyright 2010-2022, Georgia Tech Research Corporation,\n", "Atlanta, Georgia 30332-0415\n", @@ -10,11 +25,30 @@ "\n", "Authors: Frank Dellaert, et al. (see THANKS for the full author list)\n", "\n", - "See LICENSE for the license information\n", - "\n", - "A 2D Range SLAM example, with iSAM and smart range factors\n", - "\n", - "Author: Frank Dellaert" + "See LICENSE for the license information" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "\"Open" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": { + "tags": [ + "remove-cell" + ], + "vscode": { + "languageId": "markdown" + } + }, + "outputs": [], + "source": [ + "%pip install --quiet gtsam-develop" ] }, { diff --git a/python/gtsam/notebooks/easyPoint2KalmanFilter.ipynb b/python/gtsam/examples/easyPoint2KalmanFilter.ipynb similarity index 72% rename from python/gtsam/notebooks/easyPoint2KalmanFilter.ipynb rename to python/gtsam/examples/easyPoint2KalmanFilter.ipynb index 1bdd12b8e2..5417fca3be 100644 --- a/python/gtsam/notebooks/easyPoint2KalmanFilter.ipynb +++ b/python/gtsam/examples/easyPoint2KalmanFilter.ipynb @@ -1,24 +1,76 @@ { "cells": [ { - "cell_type": "code", - "execution_count": 1, + "cell_type": "markdown", "metadata": {}, - "outputs": [], "source": [ - "\"\"\"\n", + "# Extended Kalman Filter\n", + "\n", "Extended Kalman filter on a moving 2D point, but done using factor graphs.\n", "This example uses the ExtendedKalmanFilter class to perform filtering\n", "on a linear system, demonstrating the same operations as in elaboratePoint2KalmanFilter.\n", - "\"\"\"\n", "\n", + "Author: Matt Kielo" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "tags": [ + "remove-cell" + ] + }, + "source": [ + "GTSAM Copyright 2010-2022, Georgia Tech Research Corporation,\n", + "Atlanta, Georgia 30332-0415\n", + "All Rights Reserved\n", + "\n", + "Authors: Frank Dellaert, et al. (see THANKS for the full author list)\n", + "\n", + "See LICENSE for the license information" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "\"Open" + ] + }, + { + "cell_type": "code", + "execution_count": 1, + "metadata": { + "tags": [ + "remove-cell" + ] + }, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Note: you may need to restart the kernel to use updated packages.\n" + ] + } + ], + "source": [ + "%pip install --quiet gtsam gtbook" + ] + }, + { + "cell_type": "code", + "execution_count": 2, + "metadata": {}, + "outputs": [], + "source": [ "import gtsam\n", "import numpy as np" ] }, { "cell_type": "code", - "execution_count": 2, + "execution_count": 3, "metadata": {}, "outputs": [], "source": [ @@ -49,7 +101,7 @@ }, { "cell_type": "code", - "execution_count": 3, + "execution_count": 4, "metadata": {}, "outputs": [ { @@ -64,8 +116,8 @@ "X3 Update: [3. 0.]\n", "\n", "Easy Final Covariance (after update):\n", - " [[0.0193 0. ]\n", - " [0. 0.0193]]\n" + " [[0.01930567 0. ]\n", + " [0. 0.01930567]]\n" ] } ], @@ -100,7 +152,7 @@ ], "metadata": { "kernelspec": { - "display_name": "Python 3", + "display_name": "py312", "language": "python", "name": "python3" }, @@ -114,7 +166,7 @@ "name": "python", "nbconvert_exporter": "python", "pygments_lexer": "ipython3", - "version": "3.10.12" + "version": "3.12.6" } }, "nbformat": 4, diff --git a/python/gtsam/notebooks/elaboratePoint2KalmanFilter.ipynb b/python/gtsam/examples/elaboratePoint2KalmanFilter.ipynb similarity index 84% rename from python/gtsam/notebooks/elaboratePoint2KalmanFilter.ipynb rename to python/gtsam/examples/elaboratePoint2KalmanFilter.ipynb index 34c467c356..afd195c20f 100644 --- a/python/gtsam/notebooks/elaboratePoint2KalmanFilter.ipynb +++ b/python/gtsam/examples/elaboratePoint2KalmanFilter.ipynb @@ -1,34 +1,69 @@ { "cells": [ { - "cell_type": "code", - "execution_count": 1, + "cell_type": "markdown", "metadata": {}, - "outputs": [], "source": [ - "\"\"\"\n", + "\n", + "# Elaborate EKF Example\n", + "\n", "Simple linear Kalman filter on a moving 2D point using factor graphs in GTSAM.\n", "This example manually creates all of the needed data structures to show how\n", "the Kalman filter works under the hood using factor graphs, but uses a loop\n", "to handle the repetitive prediction and update steps.\n", "\n", - "Based on the C++ example by Frank Dellaert and Stephen Williams\n", - "\"\"\"\n", + "Author: Matt Kielo. Based on the C++ example by Frank Dellaert and Stephen Williams" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "tags": [ + "remove-cell" + ] + }, + "source": [ + "GTSAM Copyright 2010-2022, Georgia Tech Research Corporation,\n", + "Atlanta, Georgia 30332-0415\n", + "All Rights Reserved\n", + "\n", + "Authors: Frank Dellaert, et al. (see THANKS for the full author list)\n", "\n", + "See LICENSE for the license information" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "\"Open" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ "import gtsam\n", "import numpy as np\n", "from gtsam import Point2, noiseModel\n", "from gtsam.symbol_shorthand import X" ] }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "The code below basically implements the SRIF (Square-root Information filter version of the EKF) with Cholesky factorization." + ] + }, { "cell_type": "code", - "execution_count": 2, + "execution_count": null, "metadata": {}, "outputs": [], "source": [ - "# [code below basically does SRIF with Cholesky]\n", - "\n", "# Setup containers for linearization points\n", "linearization_points = gtsam.Values()\n", "\n", diff --git a/python/gtsam/notebooks/DiscreteBayesTree.ipynb b/python/gtsam/notebooks/DiscreteBayesTree.ipynb deleted file mode 100644 index 066c31d6a8..0000000000 --- a/python/gtsam/notebooks/DiscreteBayesTree.ipynb +++ /dev/null @@ -1,200 +0,0 @@ -{ - "cells": [ - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "# The Discrete Bayes Tree\n", - "\n", - "An example of building a Bayes net, then eliminating it into a Bayes tree. Mirrors the code in `testDiscreteBayesTree.cpp` .\n" - ] - }, - { - "cell_type": "code", - "execution_count": 1, - "metadata": {}, - "outputs": [], - "source": [ - "from gtsam import DiscreteBayesTree, DiscreteBayesNet, DiscreteKeys, DiscreteFactorGraph, Ordering\n", - "from gtsam.symbol_shorthand import S\n" - ] - }, - { - "cell_type": "code", - "execution_count": 2, - "metadata": {}, - "outputs": [], - "source": [ - "def P(*args):\n", - " \"\"\" Create a DiscreteKeys instances from a variable number of DiscreteKey pairs.\"\"\"\n", - " #TODO: We can make life easier by providing variable argument functions in C++ itself.\n", - " dks = DiscreteKeys()\n", - " for key in args:\n", - " dks.push_back(key)\n", - " return dks" - ] - }, - { - "cell_type": "code", - "execution_count": 3, - "metadata": {}, - "outputs": [], - "source": [ - "import graphviz\n", - "class show(graphviz.Source):\n", - " \"\"\" Display an object with a dot method as a graph.\"\"\"\n", - "\n", - " def __init__(self, obj):\n", - " \"\"\"Construct from object with 'dot' method.\"\"\"\n", - " # This small class takes an object, calls its dot function, and uses the\n", - " # resulting string to initialize a graphviz.Source instance. This in turn\n", - " # has a _repr_mimebundle_ method, which then renders it in the notebook.\n", - " super().__init__(obj.dot())" - ] - }, - { - "cell_type": "code", - "execution_count": 4, - "metadata": {}, - "outputs": [ - { - "data": { - "image/svg+xml": "\n\n\n\n\n\nG\n\n\n\n8\n\n8\n\n\n\n0\n\n0\n\n\n\n8->0\n\n\n\n\n\n1\n\n1\n\n\n\n8->1\n\n\n\n\n\n12\n\n12\n\n\n\n12->8\n\n\n\n\n\n12->0\n\n\n\n\n\n12->1\n\n\n\n\n\n9\n\n9\n\n\n\n12->9\n\n\n\n\n\n2\n\n2\n\n\n\n12->2\n\n\n\n\n\n3\n\n3\n\n\n\n12->3\n\n\n\n\n\n9->2\n\n\n\n\n\n9->3\n\n\n\n\n\n10\n\n10\n\n\n\n4\n\n4\n\n\n\n10->4\n\n\n\n\n\n5\n\n5\n\n\n\n10->5\n\n\n\n\n\n13\n\n13\n\n\n\n13->10\n\n\n\n\n\n13->4\n\n\n\n\n\n13->5\n\n\n\n\n\n11\n\n11\n\n\n\n13->11\n\n\n\n\n\n6\n\n6\n\n\n\n13->6\n\n\n\n\n\n7\n\n7\n\n\n\n13->7\n\n\n\n\n\n11->6\n\n\n\n\n\n11->7\n\n\n\n\n\n14\n\n14\n\n\n\n14->8\n\n\n\n\n\n14->12\n\n\n\n\n\n14->9\n\n\n\n\n\n14->10\n\n\n\n\n\n14->13\n\n\n\n\n\n14->11\n\n\n\n\n\n", - "text/plain": [ - "<__main__.show at 0x109c615b0>" - ] - }, - "execution_count": 4, - "metadata": {}, - "output_type": "execute_result" - } - ], - "source": [ - "# Define DiscreteKey pairs.\n", - "keys = [(j, 2) for j in range(15)]\n", - "\n", - "# Create thin-tree Bayesnet.\n", - "bayesNet = DiscreteBayesNet()\n", - "\n", - "\n", - "bayesNet.add(keys[0], P(keys[8], keys[12]), \"2/3 1/4 3/2 4/1\")\n", - "bayesNet.add(keys[1], P(keys[8], keys[12]), \"4/1 2/3 3/2 1/4\")\n", - "bayesNet.add(keys[2], P(keys[9], keys[12]), \"1/4 8/2 2/3 4/1\")\n", - "bayesNet.add(keys[3], P(keys[9], keys[12]), \"1/4 2/3 3/2 4/1\")\n", - "\n", - "bayesNet.add(keys[4], P(keys[10], keys[13]), \"2/3 1/4 3/2 4/1\")\n", - "bayesNet.add(keys[5], P(keys[10], keys[13]), \"4/1 2/3 3/2 1/4\")\n", - "bayesNet.add(keys[6], P(keys[11], keys[13]), \"1/4 3/2 2/3 4/1\")\n", - "bayesNet.add(keys[7], P(keys[11], keys[13]), \"1/4 2/3 3/2 4/1\")\n", - "\n", - "bayesNet.add(keys[8], P(keys[12], keys[14]), \"T 1/4 3/2 4/1\")\n", - "bayesNet.add(keys[9], P(keys[12], keys[14]), \"4/1 2/3 F 1/4\")\n", - "bayesNet.add(keys[10], P(keys[13], keys[14]), \"1/4 3/2 2/3 4/1\")\n", - "bayesNet.add(keys[11], P(keys[13], keys[14]), \"1/4 2/3 3/2 4/1\")\n", - "\n", - "bayesNet.add(keys[12], P(keys[14]), \"3/1 3/1\")\n", - "bayesNet.add(keys[13], P(keys[14]), \"1/3 3/1\")\n", - "\n", - "bayesNet.add(keys[14], P(), \"1/3\")\n", - "\n", - "show(bayesNet)" - ] - }, - { - "cell_type": "code", - "execution_count": 5, - "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "DiscreteValues{0: 1, 1: 1, 2: 0, 3: 1, 4: 1, 5: 1, 6: 0, 7: 1, 8: 0, 9: 0, 10: 0, 11: 0, 12: 1, 13: 1, 14: 0}\n", - "DiscreteValues{0: 0, 1: 1, 2: 0, 3: 0, 4: 1, 5: 0, 6: 0, 7: 0, 8: 1, 9: 1, 10: 0, 11: 1, 12: 0, 13: 0, 14: 1}\n", - "DiscreteValues{0: 1, 1: 0, 2: 1, 3: 1, 4: 0, 5: 0, 6: 1, 7: 0, 8: 1, 9: 0, 10: 1, 11: 1, 12: 0, 13: 1, 14: 0}\n", - "DiscreteValues{0: 1, 1: 1, 2: 0, 3: 0, 4: 1, 5: 1, 6: 1, 7: 1, 8: 0, 9: 1, 10: 0, 11: 0, 12: 1, 13: 0, 14: 1}\n", - "DiscreteValues{0: 0, 1: 0, 2: 1, 3: 0, 4: 1, 5: 1, 6: 1, 7: 0, 8: 1, 9: 1, 10: 0, 11: 1, 12: 0, 13: 0, 14: 1}\n" - ] - } - ], - "source": [ - "# Sample Bayes net (needs conditionals added in elimination order!)\n", - "for i in range(5):\n", - " print(bayesNet.sample())" - ] - }, - { - "cell_type": "code", - "execution_count": 6, - "metadata": {}, - "outputs": [ - { - "data": { - "image/svg+xml": "\n\n\n\n\n\n\n\n\nvar0\n\n0\n\n\n\nfactor0\n\n\n\n\nvar0--factor0\n\n\n\n\nvar1\n\n1\n\n\n\nfactor1\n\n\n\n\nvar1--factor1\n\n\n\n\nvar2\n\n2\n\n\n\nfactor2\n\n\n\n\nvar2--factor2\n\n\n\n\nvar3\n\n3\n\n\n\nfactor3\n\n\n\n\nvar3--factor3\n\n\n\n\nvar4\n\n4\n\n\n\nfactor4\n\n\n\n\nvar4--factor4\n\n\n\n\nvar5\n\n5\n\n\n\nfactor5\n\n\n\n\nvar5--factor5\n\n\n\n\nvar6\n\n6\n\n\n\nfactor6\n\n\n\n\nvar6--factor6\n\n\n\n\nvar7\n\n7\n\n\n\nfactor7\n\n\n\n\nvar7--factor7\n\n\n\n\nvar8\n\n8\n\n\n\nvar8--factor0\n\n\n\n\nvar8--factor1\n\n\n\n\nfactor8\n\n\n\n\nvar8--factor8\n\n\n\n\nvar9\n\n9\n\n\n\nvar9--factor2\n\n\n\n\nvar9--factor3\n\n\n\n\nfactor9\n\n\n\n\nvar9--factor9\n\n\n\n\nvar10\n\n10\n\n\n\nvar10--factor4\n\n\n\n\nvar10--factor5\n\n\n\n\nfactor10\n\n\n\n\nvar10--factor10\n\n\n\n\nvar11\n\n11\n\n\n\nvar11--factor6\n\n\n\n\nvar11--factor7\n\n\n\n\nfactor11\n\n\n\n\nvar11--factor11\n\n\n\n\nvar12\n\n12\n\n\n\nvar14\n\n14\n\n\n\nvar12--var14\n\n\n\n\nvar12--factor0\n\n\n\n\nvar12--factor1\n\n\n\n\nvar12--factor2\n\n\n\n\nvar12--factor3\n\n\n\n\nvar12--factor8\n\n\n\n\nvar12--factor9\n\n\n\n\nvar13\n\n13\n\n\n\nvar13--var14\n\n\n\n\nvar13--factor4\n\n\n\n\nvar13--factor5\n\n\n\n\nvar13--factor6\n\n\n\n\nvar13--factor7\n\n\n\n\nvar13--factor10\n\n\n\n\nvar13--factor11\n\n\n\n\nvar14--factor8\n\n\n\n\nvar14--factor9\n\n\n\n\nvar14--factor10\n\n\n\n\nvar14--factor11\n\n\n\n\nfactor14\n\n\n\n\nvar14--factor14\n\n\n\n\n", - "text/plain": [ - "<__main__.show at 0x109c61f10>" - ] - }, - "execution_count": 6, - "metadata": {}, - "output_type": "execute_result" - } - ], - "source": [ - "# Create a factor graph out of the Bayes net.\n", - "factorGraph = DiscreteFactorGraph(bayesNet)\n", - "show(factorGraph)" - ] - }, - { - "cell_type": "code", - "execution_count": 7, - "metadata": {}, - "outputs": [ - { - "data": { - "image/svg+xml": "\n\n\n\n\n\nG\n\n\n\n0\n\n8,12,14\n\n\n\n1\n\n0 : 8,12\n\n\n\n0->1\n\n\n\n\n\n2\n\n1 : 8,12\n\n\n\n0->2\n\n\n\n\n\n3\n\n9 : 12,14\n\n\n\n0->3\n\n\n\n\n\n6\n\n10,13 : 14\n\n\n\n0->6\n\n\n\n\n\n4\n\n2 : 9,12\n\n\n\n3->4\n\n\n\n\n\n5\n\n3 : 9,12\n\n\n\n3->5\n\n\n\n\n\n7\n\n4 : 10,13\n\n\n\n6->7\n\n\n\n\n\n8\n\n5 : 10,13\n\n\n\n6->8\n\n\n\n\n\n9\n\n11 : 13,14\n\n\n\n6->9\n\n\n\n\n\n10\n\n6 : 11,13\n\n\n\n9->10\n\n\n\n\n\n11\n\n7 : 11,13\n\n\n\n9->11\n\n\n\n\n\n", - "text/plain": [ - "<__main__.show at 0x109c61b50>" - ] - }, - "execution_count": 7, - "metadata": {}, - "output_type": "execute_result" - } - ], - "source": [ - "# Create a BayesTree out of the factor graph.\n", - "ordering = Ordering()\n", - "for j in range(15): ordering.push_back(j)\n", - "bayesTree = factorGraph.eliminateMultifrontal(ordering)\n", - "show(bayesTree)" - ] - } - ], - "metadata": { - "interpreter": { - "hash": "31f2aee4e71d21fbe5cf8b01ff0e069b9275f58929596ceb00d14d90e3e16cd6" - }, - "kernelspec": { - "display_name": "Python 3.8.9 64-bit", - "language": "python", - "name": "python3" - }, - "language_info": { - "codemirror_mode": { - "name": "ipython", - "version": 3 - }, - "file_extension": ".py", - "mimetype": "text/x-python", - "name": "python", - "nbconvert_exporter": "python", - "pygments_lexer": "ipython3", - "version": "3.9.7" - }, - "orig_nbformat": 4 - }, - "nbformat": 4, - "nbformat_minor": 2 -} diff --git a/python/gtsam/notebooks/DiscreteSwitching.ipynb b/python/gtsam/notebooks/DiscreteSwitching.ipynb deleted file mode 100644 index 6872e78c80..0000000000 --- a/python/gtsam/notebooks/DiscreteSwitching.ipynb +++ /dev/null @@ -1,155 +0,0 @@ -{ - "cells": [ - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "# A Discrete Switching System\n", - "\n", - "A la MHS, but all discrete.\n" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "from gtsam import DiscreteBayesNet, DiscreteKeys, DiscreteFactorGraph, Ordering\n", - "from gtsam.symbol_shorthand import S\n", - "from gtsam.symbol_shorthand import M\n" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "def P(*args):\n", - " \"\"\" Create a DiscreteKeys instances from a variable number of DiscreteKey pairs.\"\"\"\n", - " # TODO: We can make life easier by providing variable argument functions in C++ itself.\n", - " dks = DiscreteKeys()\n", - " for key in args:\n", - " dks.push_back(key)\n", - " return dks\n" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "import graphviz\n", - "\n", - "\n", - "class show(graphviz.Source):\n", - " \"\"\" Display an object with a dot method as a graph.\"\"\"\n", - "\n", - " def __init__(self, obj):\n", - " \"\"\"Construct from object with 'dot' method.\"\"\"\n", - " # This small class takes an object, calls its dot function, and uses the\n", - " # resulting string to initialize a graphviz.Source instance. This in turn\n", - " # has a _repr_mimebundle_ method, which then renders it in the notebook.\n", - " super().__init__(obj.dot())\n" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "nrStates = 3\n", - "K = 5\n", - "\n", - "bayesNet = DiscreteBayesNet()\n", - "for k in range(1, K):\n", - " key = S(k), nrStates\n", - " key_plus = S(k+1), nrStates\n", - " mode = M(k), 2\n", - " bayesNet.add(key_plus, P(mode, key), \"9/1/0 1/8/1 0/1/9 1/9/0 0/1/9 9/0/1\")\n", - "\n", - "bayesNet" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "show(bayesNet)" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "# Create a factor graph out of the Bayes net.\n", - "factorGraph = DiscreteFactorGraph(bayesNet)\n", - "show(factorGraph)" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "# Create a BayesTree out of the factor graph.\n", - "ordering = Ordering()\n", - "# First eliminate \"continuous\" states in time order\n", - "for k in range(1, K+1):\n", - " ordering.push_back(S(k))\n", - "for k in range(1, K):\n", - " ordering.push_back(M(k))\n", - "print(ordering)\n", - "bayesTree = factorGraph.eliminateMultifrontal(ordering)\n", - "bayesTree" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "show(bayesTree)" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [] - } - ], - "metadata": { - "interpreter": { - "hash": "31f2aee4e71d21fbe5cf8b01ff0e069b9275f58929596ceb00d14d90e3e16cd6" - }, - "kernelspec": { - "display_name": "Python 3.8.9 64-bit", - "language": "python", - "name": "python3" - }, - "language_info": { - "codemirror_mode": { - "name": "ipython", - "version": 3 - }, - "file_extension": ".py", - "mimetype": "text/x-python", - "name": "python", - "nbconvert_exporter": "python", - "pygments_lexer": "ipython3", - "version": "3.9.7" - }, - "orig_nbformat": 4 - }, - "nbformat": 4, - "nbformat_minor": 2 -}