Classes | Namespaces | Typedefs | Functions | Variables
testExpressionFactor.cpp File Reference

unit tests for Block Automatic Differentiation More...

#include <gtsam/slam/expressions.h>
#include <gtsam/slam/GeneralSFMFactor.h>
#include <gtsam/slam/ProjectionFactor.h>
#include <gtsam/nonlinear/PriorFactor.h>
#include <gtsam/nonlinear/expressionTesting.h>
#include <gtsam/nonlinear/ExpressionFactor.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/base/Testable.h>
#include <CppUnitLite/TestHarness.h>
#include <boost/assign/list_of.hpp>
Include dependency graph for testExpressionFactor.cpp:

Go to the source code of this file.

Classes

struct  Combine
 
struct  leaf::MyValues
 
class  TestNaryFactor
 

Namespaces

 leaf
 
 test_operator
 

Typedefs

typedef Eigen::Matrix< double, 9, 9 > Matrix9
 
typedef Eigen::Matrix< double, 9, 3 > Matrix93
 

Functions

static double combine3 (const double &x, const double &y, const double &z, OptionalJacobian< 1, 1 > H1, OptionalJacobian< 1, 1 > H2, OptionalJacobian< 1, 1 > H3)
 
Rot3 composeThree (const Rot3 &R1, const Rot3 &R2, const Rot3 &R3, OptionalJacobian< 3, 3 > H1, OptionalJacobian< 3, 3 > H2, OptionalJacobian< 3, 3 > H3)
 
Vector3 test_operator::f (const Point2 &a, const Vector3 &b, OptionalJacobian< 3, 2 > H1, OptionalJacobian< 3, 3 > H2)
 
Vector9 id9 (const Vector9 &v, OptionalJacobian< 9, 9 > H)
 
int main ()
 
Point2 measured (-17, 30)
 
static Point2 myUncal (const Cal3_S2 &K, const Point2 &p, OptionalJacobian< 2, 5 > Dcal, OptionalJacobian< 2, 2 > Dp)
 
 TEST (ExpressionFactor, Leaf)
 
 TEST (ExpressionFactor, Model)
 
 TEST (ExpressionFactor, Constrained)
 
 TEST (ExpressionFactor, Unary)
 
 TEST (ExpressionFactor, Wide)
 
 TEST (ExpressionFactor, Binary)
 
 TEST (ExpressionFactor, Shallow)
 
 TEST (ExpressionFactor, tree)
 
 TEST (ExpressionFactor, Compose1)
 
 TEST (ExpressionFactor, compose2)
 
 TEST (ExpressionFactor, compose3)
 
 TEST (ExpressionFactor, composeTernary)
 
 TEST (ExpressionFactor, tree_finite_differences)
 
 TEST (ExpressionFactor, push_back)
 
 TEST (Expression, testMultipleCompositions)
 
 TEST (Expression, testMultipleCompositions2)
 
 TEST (ExpressionFactor, MultiplyWithInverse)
 
 TEST (ExpressionFactor, MultiplyWithInverseFunction)
 
 TEST (ExpressionFactor, variadicTemplate)
 
Vector9 wide (const Point3 &p, OptionalJacobian< 9, 3 > H)
 

Variables

SharedNoiseModel model = noiseModel::Unit::Create(2)
 
Point2_ leaf::p (2)
 
Point2(* Project )(const Point3 &, OptionalJacobian< 2, 3 >) = &PinholeBase::Project
 
leaf::MyValues leaf::values
 

Detailed Description

unit tests for Block Automatic Differentiation

Date
September 18, 2014
Author
Frank Dellaert
Paul Furgale

Definition in file testExpressionFactor.cpp.

Typedef Documentation

typedef Eigen::Matrix<double,9,9> Matrix9

Definition at line 146 of file testExpressionFactor.cpp.

typedef Eigen::Matrix<double,9,3> Matrix93

Definition at line 139 of file testExpressionFactor.cpp.

Function Documentation

static double combine3 ( const double &  x,
const double &  y,
const double &  z,
OptionalJacobian< 1, 1 >  H1,
OptionalJacobian< 1, 1 >  H2,
OptionalJacobian< 1, 1 >  H3 
)
static

Definition at line 534 of file testExpressionFactor.cpp.

Rot3 composeThree ( const Rot3 R1,
const Rot3 R2,
const Rot3 R3,
OptionalJacobian< 3, 3 >  H1,
OptionalJacobian< 3, 3 >  H2,
OptionalJacobian< 3, 3 >  H3 
)

Definition at line 407 of file testExpressionFactor.cpp.

Vector9 id9 ( const Vector9 &  v,
OptionalJacobian< 9, 9 >  H 
)

Definition at line 147 of file testExpressionFactor.cpp.

int main ( void  )

Definition at line 731 of file testExpressionFactor.cpp.

Point2 measured ( 17,
30   
)
static Point2 myUncal ( const Cal3_S2 K,
const Point2 p,
OptionalJacobian< 2, 5 >  Dcal,
OptionalJacobian< 2, 2 >  Dp 
)
static

Definition at line 170 of file testExpressionFactor.cpp.

TEST ( ExpressionFactor  ,
Leaf   
)

Definition at line 59 of file testExpressionFactor.cpp.

TEST ( ExpressionFactor  ,
Model   
)

Definition at line 75 of file testExpressionFactor.cpp.

TEST ( ExpressionFactor  ,
Constrained   
)

Definition at line 96 of file testExpressionFactor.cpp.

TEST ( ExpressionFactor  ,
Unary   
)

Definition at line 114 of file testExpressionFactor.cpp.

TEST ( ExpressionFactor  ,
Wide   
)

Definition at line 151 of file testExpressionFactor.cpp.

TEST ( ExpressionFactor  ,
Binary   
)

Definition at line 176 of file testExpressionFactor.cpp.

TEST ( ExpressionFactor  ,
Shallow   
)

Definition at line 213 of file testExpressionFactor.cpp.

TEST ( ExpressionFactor  ,
tree   
)

Definition at line 272 of file testExpressionFactor.cpp.

TEST ( ExpressionFactor  ,
Compose1   
)

Definition at line 319 of file testExpressionFactor.cpp.

TEST ( ExpressionFactor  ,
compose2   
)

Definition at line 349 of file testExpressionFactor.cpp.

TEST ( ExpressionFactor  ,
compose3   
)

Definition at line 378 of file testExpressionFactor.cpp.

TEST ( ExpressionFactor  ,
composeTernary   
)

Definition at line 419 of file testExpressionFactor.cpp.

TEST ( ExpressionFactor  ,
tree_finite_differences   
)

Definition at line 450 of file testExpressionFactor.cpp.

TEST ( ExpressionFactor  ,
push_back   
)

Definition at line 473 of file testExpressionFactor.cpp.

TEST ( Expression  ,
testMultipleCompositions   
)

Definition at line 491 of file testExpressionFactor.cpp.

TEST ( Expression  ,
testMultipleCompositions2   
)

Definition at line 543 of file testExpressionFactor.cpp.

Definition at line 575 of file testExpressionFactor.cpp.

Definition at line 608 of file testExpressionFactor.cpp.

TEST ( ExpressionFactor  ,
variadicTemplate   
)

Definition at line 706 of file testExpressionFactor.cpp.

Vector9 wide ( const Point3 p,
OptionalJacobian< 9, 3 >  H 
)

Definition at line 140 of file testExpressionFactor.cpp.

Variable Documentation

SharedNoiseModel model = noiseModel::Unit::Create(2)

Definition at line 39 of file testExpressionFactor.cpp.

Point2(* Project) (const Point3 &, OptionalJacobian< 2, 3 >) = &PinholeBase::Project

Definition at line 43 of file testExpressionFactor.cpp.



gtsam
Author(s):
autogenerated on Sat May 8 2021 02:51:41