Giter Club home page Giter Club logo

manif's Introduction

manif

A small header-only library for Lie theory

GHA appveyor Documentation codecov GitHub JOSS

Package Summary

manif is a Lie theory library for state-estimation targeted at robotics applications. It is developed as a header-only C++11 library with Python 3 wrappers.

At the moment, it provides the groups:

  • ℝ(n): Euclidean space with addition.
  • SO(2): rotations in the plane.
  • SE(2): rigid motion (rotation and translation) in the plane.
  • SO(3): rotations in 3D space.
  • SE(3): rigid motion (rotation and translation) in 3D space.
  • SE_2(3): extended pose (rotation, translation and velocity) in 3D space, introduced (to the best of knowledge) in this paper. NOTE: The implementation here differs slightly from the developments in the paper.
  • SGal(3): The Special Galilean group (rotation, translation, velocity and time) in 3D space, described in these papers [1] & [2].
  • Bundle<>: allows manipulating a manifold bundle as a single Lie group. Referred to as a composite manifold in Section IV of the reference paper.

Other Lie groups can and will be added, contributions are welcome.

manif is based on the mathematical presentation of the Lie theory available in this paper. We recommend every user of manif to read the paper (17 pages) before starting to use the library. The paper provides a thorough introduction to Lie theory, in a simplified way so as to make the entrance to Lie theory easy for the average roboticist who is interested in designing rigorous and elegant state estimation algorithms.

You may also find the following video online, 'Lie theory for the roboticist', a lecture given at IRI-UPC. In a rush? Check out our Lie group cheat sheet.

It provides analytic computation of Jacobians for all the operations listed below.

Details

Quick Start

Get quickly started with manif following our 'quick start' guides for both C++ and Python.

Features

Available Operations

Operation Code
Base Operation
Inverse \mathbf\Phi^{-1} X.inverse()
Composition \mathbf\mathcal{X}\circ\mathbf\mathcal{Y} X * Y
X.compose(Y)
Hat \varphi^\wedge w.hat()
Act on vector \mathbf\mathcal{X}\circ\mathbf v X.act(v)
Retract to group element \exp(\mathbf\varphi^\wedge w.exp()
Lift to tangent space \log(\mathbf\mathcal{X})^\vee X.log()
Manifold Adjoint \operatorname{Adj}(\mathbf\mathcal{X}) X.adj()
Tangent adjoint \operatorname{adj}(\mathbf\varphi^\wedge w.smallAdj()
Composed Operation
Manifold right plus \mathbf\mathcal{X}\circ\exp(\mathbf\varphi^\wedge) X + w
X.plus(w)
X.rplus(w)
Manifold left plus \exp(\mathbf\varphi^\wedge)\circ\mathbf\mathcal{X} w + X
w.plus(X)
w.lplus(X)
Manifold right minus \log(\mathbf\mathcal{Y}^{-1}\circ\mathbf\mathcal{X})^\vee X - Y
X.minus(Y)
X.rminus(Y)
Manifold left minus \log(\mathbf\mathcal{X}\circ\mathbf\mathcal{Y}^{-1})^\vee X.lminus(Y)
Between \mathbf\mathcal{X}^{-1}\circ\mathbf\mathcal{Y} X.between(Y)
Inner Product \langle\varphi,\tau\rangle w.inner(t)
Norm \left\lVert\varphi\right\rVert w.weightedNorm()
w.squaredWeightedNorm()

Above, \mathbf\mathcal{X},\mathbf\mathcal{Y} represent group elements, \mathbf\varphi^\wedge,\tau^\wedge represent elements in the Lie algebra of the Lie group, \mathbf\varphi,\tau or w,t represent the same elements of the tangent space but expressed in Cartesian coordinates in \mathbb{R}^n, and \mathbf{v} or v represents any element of \mathbb{R}^n.

Jacobians

All operations come with their respective analytical Jacobian matrices. Throughout manif, Jacobians are differentiated with respect to a local perturbation on the tangent space. These Jacobians map tangent spaces, as described in this paper.

Currently, manif implements the right Jacobian, whose definition reads:

\frac{\delta f(\mathbf\mathcal{X})}{\delta\mathbf\mathcal{X}}

The Jacobians of any of the aforementionned operations can then be evaluated:

in C++,

  SE3d X = SE3d::Random();
  SE3Tangentd w = SE3Tangentd::Random();

  SE3d::Jacobian J_o_x, J_o_w;

  auto X_plus_w = X.plus(w, J_o_x, J_o_w);

in Python,

  X = SE3.Random()
  w = SE3Tangentd.Random()

  J_o_x = np.zeros((SE3.DoF, SE3.DoF))
  J_o_w = np.zeros((SE3.DoF, SE3.DoF))

  X_plus_w = X.plus(w, J_o_x, J_o_w)

Note

While Jacobians in manif are differentiated with respect to a local perturbation on the tangent space, many non-linear solvers (e.g. Ceres) expect functions to be differentiated with respect to the underlying representation vector of the group element (e.g. with respect to quaternion vector for SO3).

For this reason, manif is compliant with the auto-differentiation libraries ceres::Jet, autodiff::Dual & autodiff::Real.

Documentation

The documentation is available online at the accompanying website. Both the C++ and the Python APIs are documented.

Do you want to build it locally? Find out how on the dedicated page.

Note: throughout the code documentation we refer to 'the paper' which you can find on the dedicated page.

Tutorials and application demos

We provide some self-contained and self-explained C++ examples to help you get started.

You prefer Python? The same examples are also available in Python.

Publications

Check out our related publications and how to cite them.

They use manif

Find out who's already using manif.

Contributing

Want to contribute? Great! Check out our contribution guidelines.

manif's People

Contributors

artivis avatar danielskatz avatar diegoferigo avatar giulioromualdi avatar joansola avatar pettni avatar prashanthr05 avatar qqfly avatar traversaro avatar willat343 avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

manif's Issues

Aliasing in manif.

Dear all,
I am wondering whether manif should adopt the (anti) aliasing helper functions native to Eigen.
In particular, I believe that Eigens .eval() and .noalias() could be relevant and attractive for manif. For instance, in my applications, this helps to greatly reduce the number of temporary expressions and therefore increases speed!

Support gcc-8/9 in CI

Recent PRs (e.g. #137, #138) started to fail CI. This is due to the newly introduced arm64 job which uses gcc-9.

  • support gcc-8
  • support gcc-9
  • add gcc-8 in CI
  • add gcc-9 in CI

Improve Randomization

Manif uses random tangent space element and expMap to generate a random Lie group element:
setRandom coeffs_nonconst() = Tangent::Random().exp().coeffs()

This is not a good idea. Because uniform distribution of tangent space may not lead to uniform distribution of Lie group.

I used the following code to test the Random() function in SO(3) by generating 10000 random elements:

// generate_so3_random_elements.cpp
#include "manif/SO3.h"

#include <vector>
#include <iostream>
#include <fstream>
#include <Eigen/Dense>

using namespace manif;
using namespace std;

int main(int /*argc*/, char ** /*argv*/)
{
    ofstream file;
    file.open("SO3Randomization.txt");
    for (int i = 0; i < 10000; ++i)
    {
        SO3d X = SO3d::Random();
        file << X.coeffs().transpose() << endl;
    }
    file.close();

    return 0;
}

and plotted the axis distribution (on a unit sphere) and angle distribution (with a histogram) in Matlab:

%% plot_so3_distribution.m
clear; clc; close all;
qua = importdata('SO3Randomization.txt');
axang_arr = quat2axang(qua);
figure(1)
plot3(axang_arr(:,1), axang_arr(:,2), axang_arr(:,3), '.');
figure(2)
hist(axang_arr(:,4),100); 

1
2

The Random() function cannot generate uniformly distributed SO3 elements.

Feature: support for composite groups

In several developments it is handy to consider composite manifolds, such as T3xSO3 instead of SE3, or the IMU implementation using T3xT3xSO3.

In the paper, a notation is introduced so as to be able to define, for composite manifolds, the full family of operators: composition, inverse, exp, log, plus and minus, mainly. It is also possible to produce the Jacobians as a block-concatenation of the jacobians of each individual group.

It'd be very interesting if we could create a (probably variadic templated) way of producing composites of any number of groups, and then have the API ready to manipulate them as a single group.

This is probably not trivial to do.

Add SE_2(3) extended pose Lie group manifold to manif

First of all, thank you for this great repository!

I would like to make a feature request for adding an additional Lie group $SE_2(3)$ (extended pose or double direct spatial isometry as introduced in The invariant extended Kalman filter as a stable observer, appendix A2 .
This can be useful in some applications using inertial measurement units. Please see, Associating Uncertainty to Extended Poses for on Lie Group IMU Preintegration with Rotating Earth, where the orientation, position and linear velocity (with the frame located in the origin of the body and the orientation same as the inertial frame) can be packed into a single Lie group.

Similarly. a possible extension could be towards a generic $SE_{N+2}(3)$ Lie group which can be useful for SLAM based applications. Please see Contact-Aided Invariant Extended Kalman Filtering for Legged Robot State Estimation.

@artivis Do you think it would be meaningful to have these Lie groups added to the repository?

I've made an initial implementation for $SE_2(3)$ in my fork with https://github.com/prashanthr05/manif/commit/7169899e337ef0917377c83fd8e4d965704685fd and https://github.com/prashanthr05/manif/commit/c96f1f4465d10b30150e3f7fa3010f7a86dd2b41

However, there is a missing implementation for the action of this Lie group on a vector, act() method. It was not clear to me about how this operation might work.

Let me know what you think about this. If you agree, I can maybe open a PR. Thank you!

Non-const getter for coeffs()

Dear all,
I am working on an optimal control library which supports both native Eigen-types and manif-types, as well as optimal control on manifolds.
I am trying to make things as generic as possible, i.e. write my code such that Eigen-types and manif-types are interchangeable where possible.
One of the unfortunate obstacles in the way is that manif does not have a non-const getter for coeffs().
Do you see any major obstacles for adding such a feature?
Any thoughts and discussion on this would be highly appreciated.
Best!

Introduce Eigen-style transpose() for Tangent-types

Dear all,
what do you think of introducing an Eigen-style transpose() call for manif tangent types?
The context of the question is the same as in #137.
So far, I helped myself with introducing the following public method to my personal clone of manifs tangent_base.h:

auto transpose() const {return coeffs().transpose();} 

Note that it in fact returns the transpose of the underlying data type, i.e. the transpose of an Eigen-matrix.
I would like to hear your opinion regarding such a feature, and like to suggest that this could also be helpful for other users?
Best!

manif creates a package.xml file in devel-folder after build

Dear all,

I am using manif in a catkin (ROS) workspace and encounter the following issue:
When building using catkin build, manif creates a package.xml file in <path_to_ws>/devel/share/manif

Creating a package.xml in the devel folders leads ROS to "believe" that there is a ROS package in devel with the same package name as the orginal package in the src folder. This triggers errors in some ROS tools, in particular rosdep install. Normally ROS packages do not have a package.xml in their devel folder after build, which leads me to believe that this is a manif problem.

Is that package.xml in the devel folder used, or maybe just legacy?

meet trouble by using manif with ceres solver

Hi:

Great work. I'm working on optimization problem by using manif so I can solve the problem with Lie group.

But when I worked on autodiff in ceres solver by solving SE3 problem, I can't find the answer about write my own cost function while use your local parameterization functor, because I don't know the correct residual size according to your local parameterization functor.

Can you give me a hint or a sample ? It would be helpful.

Cheers.

Tangent times scalar product

We like to have the following API extension:

SO3Tangent::operator * (SO3Tangent, scalar)

as in

SO3Tangentd w;
SO3Tangentd wdt = w * dt;

also for other groups

Question about Jacobian in example se2_sam/se3_sam.cpp

Hi, thanks for your work!
In your example se2_sam.cpp(or se3_sam.cpp), for the prior measurement, the residual is:
r=poses[0].log(), so I think the jacobian is:
let t = Log(poses[0]),
$ J = \partial Log(poses[0]) / \partial poses[0] = J_r^{-1}(t) $
so this line:
J.block<DoF, DoF>(row, col) = MatrixT::Identity();
should be:
J.block<DoF, DoF>(row, col) = poses[0].log().rjacinv();.
How do you think?

Unable to compile the library on VisualStudio2019

Hi all, I'm trying to build manif on VisualStudio2019. When I configure the cmake project I get the following error:

Selecting Windows SDK version 10.0.18362.0 to target Windows 10.0.17134.
The CXX compiler identification is MSVC 19.26.28806.0
Check for working CXX compiler: C:/Program Files (x86)/Microsoft Visual Studio/2019/Enterprise/VC/Tools/MSVC/14.26.28801/bin/Hostx64/x64/cl.exe
Check for working CXX compiler: C:/Program Files (x86)/Microsoft Visual Studio/2019/Enterprise/VC/Tools/MSVC/14.26.28801/bin/Hostx64/x64/cl.exe -- works
Detecting CXX compiler ABI info
Detecting CXX compiler ABI info - done
Detecting CXX compile features
Detecting CXX compile features - done
Performing Test COMPILER_SUPPORTS_CXX11
Performing Test COMPILER_SUPPORTS_CXX11 - Failed
CMake Error at CMakeLists.txt:15 (message):
  The compiler C:/Program Files (x86)/Microsoft Visual
  Studio/2019/Enterprise/VC/Tools/MSVC/14.26.28801/bin/Hostx64/x64/cl.exe has
  no C++11 support.  Please use a different C++ compiler.


Configuring incomplete, errors occurred!
See also "C:/Users/gromualdi/robot-code/manif/build/CMakeFiles/CMakeOutput.log".
See also "C:/Users/gromualdi/robot-code/manif/build/CMakeFiles/CMakeError.log".

Associated issue: GiulioRomualdi/lie-group-controllers#1 (comment)

Sample cmakefile for personal projects seems to be missing an argument

If I'm reading this right,

https://cmake.org/cmake/help/v3.0/command/target_include_directories.html

this line in the readme

target_include_directories(${PROJECT_NAME} SYSTEM  ${manif_INCLUDE_DIRS})

should probably be something like

target_include_directories(${PROJECT_NAME} SYSTEM PUBLIC ${manif_INCLUDE_DIRS})

Without the PUBLIC directive I get

CMake Error at CMakeLists.txt:7 (target_include_directories):
  target_include_directories called with invalid arguments

Typo in Exp / Log maps in Appendix D

Hi guys,
Thanks for sharing this work!

I just wanted to let you know that there is a typo about V(θ) in Appendix D. The V(θ) (Eq.174) does not match the left Jacobian of SO(3) (Eq. 145), it misses the powers' values on the denominators.

Cheers,
Maxime

Jacobians using Eigen::MatrixXs

I have trouble using Eigen::MatrixXs as the Jacobians. They are of the correct size, but I guess manif expects these matrices to be of static size?

my example code:

void ProcessorOdom2D::deltaPlusDelta(const Eigen::VectorXs& _delta1, const Eigen::VectorXs& _delta2, const Scalar _Dt2,
                                     Eigen::VectorXs& _delta1_plus_delta2, Eigen::MatrixXs& _jacobian1,
                                     Eigen::MatrixXs& _jacobian2)
{
    assert(_delta1.size() == delta_size_ && "Wrong _delta1 vector size");
    assert(_delta2.size() == delta_size_ && "Wrong _delta2 vector size");
    assert(_delta1_plus_delta2.size() == delta_size_ && "Wrong _delta1_plus_delta2 vector size");
    assert(_jacobian1.rows() == delta_cov_size_ && "Wrong _jacobian1 size");
    assert(_jacobian1.cols() == delta_cov_size_ && "Wrong _jacobian1 size");
    assert(_jacobian2.rows() == delta_cov_size_ && "Wrong _jacobian2 size");
    assert(_jacobian2.cols() == delta_cov_size_ && "Wrong _jacobian2 size");

    // This is just a frame composition in 2D
    SE2s delta1(_delta1(0), _delta1(1), _delta1(2));
    SE2s delta2(_delta2(0), _delta2(1), _delta2(2));
    // SE2s delta1_plus_delta2 = delta1.compose(delta2, _jacobian1, _jacobian2); // THIS FAILS
    SE2s::Jacobian J_D_D1, J_D_D2;
    SE2s delta1_plus_delta2 = delta1.compose(delta2, J_D_D1, J_D_D2); // THIS WORKS ...
    _jacobian1 = J_D_D1; // ... BUT THEN I NEED A COPY HERE
    _jacobian2 = J_D_D2;

    _delta1_plus_delta2 << delta1_plus_delta2.x(), delta1_plus_delta2.y(), delta1_plus_delta2.angle();
}

The error msg when failing is:

/Users/jsola/dev/wolf_lib/core/src/processor/processor_odom_2D.cpp:82:38: error: no matching member function for call to 'compose'
    SE2s delta1_plus_delta2 = delta1.compose(delta2, _jacobian1, _jacobian2); // THIS FAILS
                              ~~~~~~~^~~~~~~

Trivial euclidean manifold E(n) ? (feature request)

Dear all,

I'm an application which takes an "manif" manifold as a template parameter. This works nicely, since the basic interface, accessors and methods are naturally the same for all manifolds.

However, it fails as soon as I want to operate in Euclidean space. What is missing, is essentially a manif-implementation of the must fundamental n-dimensional Euclidean manifold E(n), in which case anything within manif should fall back to the natural Eigen-types and methods.

Is there any plan to add such a feature?

Best, and thanks in advance!

What does the "origin" mean?

image

I can grasp the basic idea of this passage. But the term "origin" confused me. It is the "origin" of the manifold, or that of the tangent vector space? And what is the "origin" of a manifold?

image

There's also an "origin" exists in the latter passage, which I assumed to mean "the time instant t = 0". Am I right?

What does 'Dim' mean?

In struct traits<SO2<_Scalar>> in SO2.h

...
using Vector  = Eigen::Matrix<Scalar, DoF, 1>;

Should the 'DoF' be 'Dim'?
The DoF of SO2 is 1, but the dimension of the Vector SO2 act on is 2.

Typo in Table 1 of the paper

Hi guys,
Just to let you know, I think there is a typo in Table 1 in the paper. In the Exp(T) matrix of SE(3), there should be a 1 instead of a 0 in the bottom right side.
Anyway, thanks for this great work!
Cheers

Include operator()(int idx) for manif tangent-types?

Dear all,
I would like to ask whether you would consider it meaningful to introduce the following operator for manif tangent-types, in order to allow direct access to single elements of the coefficient vector of the tangent objects.
I would suggest something along the lines of this
A trivial way to implement the const-version would be to include the following into tangent_base.h

Scalar operator()(int idx) const {return coeffs()(idx);}

Library renaming

  • lieli reads lili - LIE LIbrary
  • lilly - LIe aLgebra LibrarY
  • lialle - LIe ALgebra Lirary for state Estimation
  • cerise - miCro liE algebRa lIbrary for State Estimation
  • merit - Micro liE algebRa lIbrary for state esTimation

How to derive this two formula?

image

image

The paper states that eq. 68 is derived from the eq. 41a. But I don't know the concrete derivation. Can someone share some hints with me?

As for the eq.69, I know it's derived directly from the eq.68, but why should the $$J_r(\tau)$$ being inversed?

JOSS paper - suggestions

I am reviewing openjournals/joss-reviews#1371 - couple of suggestions regarding the paper:

  • "The library is mathematically grounded in (Solà, Deray, & Atchuthan, 2018)" - perhaps better to write "Mathematical foundations of the library are given in" (or "Mathematical background ..." etc).

  • please fix references to Books and wave_geometry - they are not rendered correctly.

Elaborate a bit on 'a note on jacobians'

Thanks for this work.

Could you add a bit more explanation to 'a note on jacobians' section in the readme?
For example, how should one use manif with ceres correctly.

.isApprox() with default tolerance for Tangent-types?

Just out of curiousity: is there a reason why the method .isApprox() in the Tangent Base class does not have a default value for the tolerance?

If not, would it be an option to add a reasonable default tolerance?

Normalization issue for SO3 with multiple rplus operations

Thanks for this work.

We are considering using manif in our EKF implementation that constantly updates the rotation estimate (SO3) with angular velocity updates stored in Lie algebra. It is working on our own simple LieAlgebra library but it crashes after several iterations when using manif. Minimal code that reproduces the error:

 // Identity
manif::SO3d R = manif::SO3d(0, 0, 0, 1.0);

// Some angular velocity
manif::SO3Tangentd Om = Eigen::Vector3d(0.001, 0.0, 0.0);

// New orientation
for (int i = 0 ; i < 1000; i++) {
   std::cout << i << std::endl;
   R = R.plus(Om);
}

I guess it is related to pull request #72 and I understand your arguments but as for now I think it is necessary to perform R.normalize() after every change to make sure it is still a proper quaternion. Maybe it should be added to the examples concerning EKF/optimization?

Fix `act` throughout the library

the act operation my be wrong throughout the library, this need to be double checked.
Moreover it need to be generalized somehow so that an element can act on e.g. point/vector/etc...

`manif_INCLUDE_DIRS` has duplicate path

The cmake code:

FIND_PACKAGE(manif REQUIRED)
IF(manif_FOUND)
    MESSAGE(STATUS "manif Library FOUND!")
    MESSAGE(STATUS "manif_INCLUDE_DIRS=" ${manif_INCLUDE_DIRS})
ELSEIF(manif_FOUND)
    MESSAGE(STATUS "manif Library NOT FOUND!")
ENDIF(manif_FOUND)

produces

-- manif Library FOUND!
-- manif_INCLUDE_DIRS=/usr/local/include/usr/local/include

where /usr/local/include is appended twice! Then, the line

TARGET_INCLUDE_DIRECTORIES(${PROJECT_NAME} SYSTEM ${manif_INCLUDE_DIRS})

produces not surprisingly

CMake Error at CMakeLists.txt:529 (TARGET_INCLUDE_DIRECTORIES):
  TARGET_INCLUDE_DIRECTORIES called with invalid arguments

Group action on different objects

At the moment, the act function treats its input argument as a point and act on it accordingly (e.g. SE2 rotates and translates). It would be great if act could act appropriately on different objects, likely vectors and points at first.

Options

This calls for a rethinking/redesign of the function with the following options:

  1. distinguish objects with a runtime flag (likely an enum)
  2. distinguish objects with a compile-time flag (e.g. struct assumePoint )
  3. specialize the function for different objects types.

Pro/cons:

1.

Pro:

  • Does not break current user code (flag defaults to point)

Cons:

  • act implementation is going to be a big switch
  • forces to input both Jacobians (possibly nil) to define the flag (see impl below)
  • requires to edit the enum for every new object

2.

Pro:

  • does not break user code (flag defaults to point)
  • easy to add a new object

Cons:

  • more complicated implementation (can't do partial specialization, requires an intermediate template class to do the specialization).

3.

Pro:

  • alleviate confusion as it relies on actual type
  • easy to add a new object
  • looks good :D

Cons:

  • breaks user code
  • requires to define objects classes (e.g. class Point)

Pseudo-code for each options:

  1. act( obj, Ja, Jb, flag )
  2. act< flag >( obj, Ja, Jb )
  3. act( Vector, Ja, Jb )
    act( Point, Ja, Jb )

Implement left-Jacobians

This is a low priority issue.

I am wondering: manif could have the option of providing the left-Jacobians instead of the right-Jacobians. This would give extra power to interface it with other tools that might be using left- logic. This means all implementations that regard uncertainties in the global reference.

As a reminder:

  • Local perturbations --> right plus and minus --> right Jacobians
  • Global perturbations --> left plus and minus --> left Jacobians

For example, Delaert and Drummond typically use left operations. Also Ceres uses left-plus in the local parametrizations they ship with the library.

So Manif could easily adapt to these cases.

The option should be global I guess, something like:

  • In the CMAKE step ---> ugly in my opinion
  • As a runtime function manif::options::setRightJacobians() or whatsoever
  • As a flag in the function calls, e.g. X.inverse(J, manif::LEFT_JAC) --> ugly in my opinion

Basic API

This is a first attempt. Derived classes must implement all methods:

template <Size vector_size; Size manifold_size>
class manifold {
typedef Matrix<Scalar, vector_size, 1> VectorType;
typedef Matrix<Scalar, manifold_size, 1> ManifoldType;
typedef Matrix<Scalar, vector_size, vector_size> JacobianType;

// First, a bunch of static methods:

// lift and retract
static VectorType lift(ManifoldType);
static ManifoldType retract(VectorType);

// inverse and compose
static ManifoldType inverse(ManifoldType);
static ManifoldType compose(ManifoldType m1, ManifoldType m2);
static ManifoldType between(ManifoldType m1, ManifoldType m2);

// right plus and minus
static ManifoldType rplus(ManifoldType, VectorType);
static VectorType rminus(Manifoldtype, ManifoldType);

// left plus and minus
static ManifoldType lplus(VectorType, ManifoldType);
static VectorType lminus(Manifoldtype, ManifoldType);

// left and right Jacobians
static JacobianType Jr(VectorType);
static JacobianType Jr_inv(VectorType);
static JacobianType Jl(VectorType);
static JacobianType Jl_inv(VectorType);

// Basic Jacobians
static JacobianType inverse_jac(ManifoldType);
static JacobianType compose_jac_m1(ManifoldType m1, ManifoldType m2);
static JacobianType compose_jac_m2(ManifoldType m1, ManifoldType m2);
// Other Jacobians might be added

// Action of the manifold on vectors
static VectorType operator * (ManifoldType, VectorType)
// other operations might be added

// then actions applied on objects
ManifoldType inverse();
ManifoldType rplus(VectorType);
ManifoldType lplus(VectorType);
VectorType rminus(ManifoldType);
// etc, replicate most of the statics, but using the manifold object as the first input param

Build instructions somewhat unclear about which make steps to run

The library is header-only. This means that there is nothing to build at installation time.

The documentation suggests running make after cmake, but unless we are building the tests and examples, this is pointless.

Morever, the build instructions do not indicate a make install step. This is necessary so that manif will be found according to the instructions in the "Use Manif in your project" section of the Readme.

Tangent and Vector issues

As tangent elements are vectors after all, they should be assignable. This include also vector expressions. The following shoudl work.

Here, t is a tangent element, u,v are vectors, and K is a matrix. Sizes are of course compatible.

// constructors and assignment
t(v);
v(t);
t = v;
v = t;
// unary expressions
t = -v;
v = -t;
// binary expressions
t = u+v;
t = K*v;
t = t + v;
t = K*t;
v = t + v;
v = K*t;
v = K*t+u;

In particular, I had to write this for it to work:

t = (K*v).eval();

which means that t=v works, but that t=<vector expression> does not work.

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.