Namespaces | Classes | Typedefs | Functions | Variables
gtsam::internal Namespace Reference

Namespaces

 linearAlgorithms
 

Classes

struct  apply_compose
 
struct  apply_compose< double >
 
class  AutoTicToc
 
class  BinaryExpression
 Binary Expression. More...
 
class  BinarySumNode
 Binary Sum Expression. More...
 
struct  CallRecord
 
struct  CallRecordImplementor
 
class  ConstantExpression
 Constant Expression. More...
 
struct  ConvertToDynamicIf
 
struct  ConvertToDynamicIf< false >
 
struct  DoglegState
 
struct  DynamicTraits
 
class  ExecutionTrace
 
class  ExpressionNode
 
struct  FastDefaultAllocator
 Default allocator for list, map, and set types. More...
 
struct  FastDefaultVectorAllocator
 Default allocator for vector types (we never use boost pool for vectors) More...
 
struct  FixedSizeMatrix
 
struct  GetDimensionImpl
 Extra manifold traits for fixed-dimension types. More...
 
struct  GetDimensionImpl< Class, Eigen::Dynamic >
 Extra manifold traits for variable-dimension types. More...
 
struct  handle
 
struct  handle< Eigen::Matrix< double, M, N > >
 
struct  handle_matrix
 
struct  handle_matrix< Eigen::Matrix< double, M, N >, false >
 
struct  handle_matrix< Eigen::Matrix< double, M, N >, true >
 
struct  HasManifoldPrereqs
 Requirements on type to pass it to Manifold template below. More...
 
struct  HasVectorSpacePrereqs
 Requirements on type to pass it to Manifold template below. More...
 
struct  Jacobian
 meta-function to generate fixed-size JacobianTA type More...
 
class  JacobianMap
 
class  LeafExpression
 Leaf Expression, if no chart is given, assume default chart and value_type is just the plain value. More...
 
struct  LevenbergMarquardtState
 
struct  LieGroup
 Both LieGroupTraits and Testable. More...
 
struct  LieGroupTraits
 
struct  LogDeterminantData
 Struct to help with traversing the Bayes Tree for log-determinant computation. Records the data which is passed to the child nodes in pre-order visit. More...
 
struct  Manifold
 Both ManifoldTraits and Testable. More...
 
struct  ManifoldTraits
 
struct  NonlinearOptimizerState
 
class  ScalarMultiplyNode
 Expression for scalar multiplication. More...
 
struct  ScalarTraits
 
class  TernaryExpression
 Ternary Expression. More...
 
class  TimingOutline
 
class  UnaryExpression
 Unary Function Expression. More...
 
struct  UseBlockIf
 
struct  UseBlockIf< false, Derived >
 Handle Leaf Case for Dynamic Matrix type (slower) More...
 
struct  VectorSpace
 VectorSpace provides both Testable and VectorSpaceTraits. More...
 
struct  VectorSpaceImpl
 VectorSpaceTraits Implementation for Fixed sizes. More...
 
struct  VectorSpaceImpl< Class, Eigen::Dynamic >
 VectorSpaceTraits implementation for dynamic types. More...
 
struct  VectorSpaceTraits
 

Typedefs

typedef std::aligned_storage< 1, TraceAlignment >::type ExecutionTraceStorage
 

Functions

static Similarity3 align (const Point3Pairs &d_abPointPairs, const Rot3 &aRb, const Point3Pair &centroids)
 This method estimates the similarity transform from differences point pairs,. More...
 
static Similarity2 Align (const Point2Pairs &d_abPointPairs, const Rot2 &aRb, const Point2Pair &centroids)
 This method estimates the similarity transform from differences point pairs, given a known or estimated rotation and point centroids. More...
 
static Similarity3 alignGivenR (const Point3Pairs &abPointPairs, const Rot3 &aRb)
 This method estimates the similarity transform from point pairs, given a known or estimated rotation. More...
 
static Similarity2 AlignGivenR (const Point2Pairs &abPointPairs, const Rot2 &aRb)
 This method estimates the similarity transform from point pairs, given a known or estimated rotation. Refer to: http://www5.informatik.uni-erlangen.de/Forschung/Publikationen/2005/Zinsser05-PSR.pdf Chapter 3. More...
 
Rot3 attitude (const NavState &X, OptionalJacobian< 3, 9 > H)
 
static Matrix2 CalculateH (const Point2Pairs &d_abPointPairs)
 Form outer product H. More...
 
static Matrix3 calculateH (const Point3Pairs &d_abPointPairs)
 Form outer product H. More...
 
NonlinearFactorGraph calculateMarginalFactors (const NonlinearFactorGraph &graph, const Values &theta, const KeySet &remainingKeys, const GaussianFactorGraph::Eliminate &eliminateFunction)
 
static double CalculateScale (const Point2Pairs &d_abPointPairs, const Rot2 &aRb)
 Form inner products x and y and calculate scale. More...
 
static double calculateScale (const Point3Pairs &d_abPointPairs, const Rot3 &aRb)
 Form inner products x and y and calculate scale. More...
 
constexpr int DimensionSO (int N)
 Calculate dimensionality of SO<N> manifold, or return Dynamic if so. More...
 
template<class FACTOR >
std::pair< std::shared_ptr< SymbolicConditional >, std::shared_ptr< SymbolicFactor > > EliminateSymbolic (const FactorGraph< FACTOR > &factors, const Ordering &keys)
 
GTSAM_EXPORT std::weak_ptr< TimingOutlinegCurrentTimer (gTimingRoot)
 
size_t getTicTocID (const char *descriptionC)
 
GTSAM_EXPORT std::shared_ptr< TimingOutlinegTimingRoot (new TimingOutline("Total", getTicTocID("Total")))
 
template<typename Derived >
void handleLeafCase (const Eigen::MatrixBase< Derived > &dTdA, JacobianMap &jacobians, Key key)
 Handle Leaf Case: reverse AD ends here, by writing a matrix into Jacobians. More...
 
template<class BAYESTREE >
double logDeterminant (const typename BAYESTREE::sharedClique &clique)
 
LogDeterminantDatalogDeterminant (const GaussianBayesTreeClique::shared_ptr &clique, LogDeterminantData &parentSum)
 
constexpr int NSquaredSO (int N)
 
template<class BAYESTREE >
void optimizeInPlace (const typename BAYESTREE::sharedClique &clique, VectorValues &result)
 
static void optimizeInPlace (const ISAM2::sharedClique &clique, VectorValues *result)
 
Point3 position (const NavState &X, OptionalJacobian< 3, 9 > H)
 
template<class T , class A >
static void PrintJacobianAndTrace (const std::string &indent, const typename Jacobian< T, A >::type &dTdA, const ExecutionTrace< A > trace)
 
template<class CAMERA , class POINT >
Point2 project4 (const CAMERA &camera, const POINT &p, OptionalJacobian< 2, CAMERA::dimension > Dcam, OptionalJacobian< 2, FixedDimension< POINT >::value > Dpoint)
 
template<class CALIBRATION , class POINT >
Point2 project6 (const Pose3 &x, const Point3 &p, const Cal3_S2 &K, OptionalJacobian< 2, 6 > Dpose, OptionalJacobian< 2, 3 > Dpoint, OptionalJacobian< 2, 5 > Dcal)
 
Rot3 rotation (const Pose3 &pose, OptionalJacobian< 3, 6 > H)
 
bool structureCompareOp (const VectorValues::value_type &a, const VectorValues::value_type &b)
 
static Point3Pairs subtractCentroids (const Point3Pairs &abPointPairs, const Point3Pair &centroids)
 Subtract centroids from point pairs. More...
 
static Point2Pairs SubtractCentroids (const Point2Pairs &abPointPairs, const Point2Pair &centroids)
 Subtract centroids from point pairs. More...
 
template<typename T >
bool testExpressionJacobians (const std::string &name_, const gtsam::Expression< T > &expression, const gtsam::Values &values, double nd_step, double tolerance)
 
bool testFactorJacobians (const std::string &name_, const NoiseModelFactor &factor, const gtsam::Values &values, double delta, double tolerance)
 
void tic (size_t id, const char *labelC)
 
void toc (size_t id, const char *labelC)
 
Point3 translation (const Pose3 &pose, OptionalJacobian< 3, 6 > H)
 
template<typename T >
TupAlign (T &value, unsigned requiredAlignment=TraceAlignment)
 
template<typename T >
T upAligned (T value, unsigned requiredAlignment=TraceAlignment)
 
void updateRgProd (const ISAM2::sharedClique &clique, const KeySet &replacedKeys, const VectorValues &grad, VectorValues *RgProd, size_t *varsUpdated)
 
Velocity3 velocity (const NavState &X, OptionalJacobian< 3, 9 > H)
 

Variables

const int CallRecordMaxVirtualStaticRows = 5
 
GTSAM_EXTERN_EXPORT std::weak_ptr< TimingOutlinegCurrentTimer
 
GTSAM_EXTERN_EXPORT std::shared_ptr< TimingOutlinegTimingRoot
 
static const std::shared_ptr< TimingOutlinenullTimingOutline
 
static const unsigned TraceAlignment = 32
 

Typedef Documentation

◆ ExecutionTraceStorage

typedef std::aligned_storage<1, TraceAlignment>::type gtsam::internal::ExecutionTraceStorage

Definition at line 48 of file ExecutionTrace.h.

Function Documentation

◆ align()

static Similarity3 gtsam::internal::align ( const Point3Pairs d_abPointPairs,
const Rot3 aRb,
const Point3Pair centroids 
)
static

This method estimates the similarity transform from differences point pairs,.

Definition at line 69 of file Similarity3.cpp.

◆ Align()

static Similarity2 gtsam::internal::Align ( const Point2Pairs d_abPointPairs,
const Rot2 aRb,
const Point2Pair centroids 
)
static

This method estimates the similarity transform from differences point pairs, given a known or estimated rotation and point centroids.

Parameters
d_abPointPairs
aRb
centroids
Returns
Similarity2

Definition at line 74 of file Similarity2.cpp.

◆ alignGivenR()

static Similarity3 gtsam::internal::alignGivenR ( const Point3Pairs abPointPairs,
const Rot3 aRb 
)
static

This method estimates the similarity transform from point pairs, given a known or estimated rotation.

Definition at line 80 of file Similarity3.cpp.

◆ AlignGivenR()

static Similarity2 gtsam::internal::AlignGivenR ( const Point2Pairs abPointPairs,
const Rot2 aRb 
)
static

This method estimates the similarity transform from point pairs, given a known or estimated rotation. Refer to: http://www5.informatik.uni-erlangen.de/Forschung/Publikationen/2005/Zinsser05-PSR.pdf Chapter 3.

Parameters
abPointPairs
aRb
Returns
Similarity2

Definition at line 94 of file Similarity2.cpp.

◆ attitude()

Rot3 gtsam::internal::attitude ( const NavState X,
OptionalJacobian< 3, 9 >  H 
)

Definition at line 22 of file navigation/expressions.h.

◆ CalculateH()

static Matrix2 gtsam::internal::CalculateH ( const Point2Pairs d_abPointPairs)
static

Form outer product H.

Definition at line 57 of file Similarity2.cpp.

◆ calculateH()

static Matrix3 gtsam::internal::calculateH ( const Point3Pairs d_abPointPairs)
static

Form outer product H.

Definition at line 59 of file Similarity3.cpp.

◆ calculateMarginalFactors()

NonlinearFactorGraph gtsam::internal::calculateMarginalFactors ( const NonlinearFactorGraph graph,
const Values theta,
const KeySet remainingKeys,
const GaussianFactorGraph::Eliminate eliminateFunction 
)

Calculate the marginal on the specified keys, returning a set of LinearContainerFactors. Unlike other GTSAM functions with similar purposes, this version can operate on disconnected graphs.

Definition at line 54 of file ConcurrentFilteringAndSmoothing.cpp.

◆ CalculateScale()

static double gtsam::internal::CalculateScale ( const Point2Pairs d_abPointPairs,
const Rot2 aRb 
)
static

Form inner products x and y and calculate scale.

Definition at line 43 of file Similarity2.cpp.

◆ calculateScale()

static double gtsam::internal::calculateScale ( const Point3Pairs d_abPointPairs,
const Rot3 aRb 
)
static

Form inner products x and y and calculate scale.

Definition at line 45 of file Similarity3.cpp.

◆ DimensionSO()

constexpr int gtsam::internal::DimensionSO ( int  N)

Calculate dimensionality of SO<N> manifold, or return Dynamic if so.

Definition at line 41 of file SOn.h.

◆ EliminateSymbolic()

template<class FACTOR >
std::pair<std::shared_ptr<SymbolicConditional>, std::shared_ptr<SymbolicFactor> > gtsam::internal::EliminateSymbolic ( const FactorGraph< FACTOR > &  factors,
const Ordering keys 
)

Implementation of dense elimination function for symbolic factors. This is a templated version for internally doing symbolic elimination on any factor.

Definition at line 38 of file SymbolicFactor-inst.h.

◆ gCurrentTimer()

GTSAM_EXPORT std::weak_ptr<TimingOutline> gtsam::internal::gCurrentTimer ( gTimingRoot  )

◆ getTicTocID()

GTSAM_EXPORT size_t gtsam::internal::getTicTocID ( const char *  descriptionC)

Definition at line 240 of file timing.cpp.

◆ gTimingRoot()

GTSAM_EXPORT std::shared_ptr<TimingOutline> gtsam::internal::gTimingRoot ( new   TimingOutline"Total", getTicTocID("Total"))

◆ handleLeafCase()

template<typename Derived >
void gtsam::internal::handleLeafCase ( const Eigen::MatrixBase< Derived > &  dTdA,
JacobianMap jacobians,
Key  key 
)

Handle Leaf Case: reverse AD ends here, by writing a matrix into Jacobians.

Definition at line 71 of file ExecutionTrace.h.

◆ logDeterminant() [1/2]

template<class BAYESTREE >
double gtsam::internal::logDeterminant ( const typename BAYESTREE::sharedClique &  clique)

Definition at line 42 of file GaussianBayesTree-inl.h.

◆ logDeterminant() [2/2]

LogDeterminantData& gtsam::internal::logDeterminant ( const GaussianBayesTreeClique::shared_ptr clique,
LogDeterminantData parentSum 
)

Definition at line 49 of file GaussianBayesTree.cpp.

◆ NSquaredSO()

constexpr int gtsam::internal::NSquaredSO ( int  N)

Definition at line 46 of file SOn.h.

◆ optimizeInPlace() [1/2]

template<class BAYESTREE >
void gtsam::internal::optimizeInPlace ( const typename BAYESTREE::sharedClique &  clique,
VectorValues result 
)

Definition at line 31 of file GaussianBayesTree-inl.h.

◆ optimizeInPlace() [2/2]

static void gtsam::internal::optimizeInPlace ( const ISAM2::sharedClique clique,
VectorValues result 
)
inlinestatic

Definition at line 35 of file ISAM2-impl.cpp.

◆ position()

Point3 gtsam::internal::position ( const NavState X,
OptionalJacobian< 3, 9 >  H 
)

Definition at line 25 of file navigation/expressions.h.

◆ PrintJacobianAndTrace()

template<class T , class A >
static void gtsam::internal::PrintJacobianAndTrace ( const std::string &  indent,
const typename Jacobian< T, A >::type dTdA,
const ExecutionTrace< A trace 
)
static

Definition at line 218 of file ExpressionNode.h.

◆ project4()

template<class CAMERA , class POINT >
Point2 gtsam::internal::project4 ( const CAMERA &  camera,
const POINT &  p,
OptionalJacobian< 2, CAMERA::dimension >  Dcam,
OptionalJacobian< 2, FixedDimension< POINT >::value >  Dpoint 
)

Definition at line 144 of file slam/expressions.h.

◆ project6()

template<class CALIBRATION , class POINT >
Point2 gtsam::internal::project6 ( const Pose3 x,
const Point3 p,
const Cal3_S2 K,
OptionalJacobian< 2, 6 >  Dpose,
OptionalJacobian< 2, 3 >  Dpoint,
OptionalJacobian< 2, 5 >  Dcal 
)
inline

Definition at line 158 of file slam/expressions.h.

◆ rotation()

Rot3 gtsam::internal::rotation ( const Pose3 pose,
OptionalJacobian< 3, 6 >  H 
)
inline

Definition at line 80 of file slam/expressions.h.

◆ structureCompareOp()

bool gtsam::internal::structureCompareOp ( const VectorValues::value_type a,
const VectorValues::value_type b 
)

Definition at line 211 of file VectorValues.cpp.

◆ subtractCentroids()

static Point3Pairs gtsam::internal::subtractCentroids ( const Point3Pairs abPointPairs,
const Point3Pair centroids 
)
static

Subtract centroids from point pairs.

Definition at line 31 of file Similarity3.cpp.

◆ SubtractCentroids()

static Point2Pairs gtsam::internal::SubtractCentroids ( const Point2Pairs abPointPairs,
const Point2Pair centroids 
)
static

Subtract centroids from point pairs.

Definition at line 31 of file Similarity2.cpp.

◆ testExpressionJacobians()

template<typename T >
bool gtsam::internal::testExpressionJacobians ( const std::string &  name_,
const gtsam::Expression< T > &  expression,
const gtsam::Values values,
double  nd_step,
double  tolerance 
)

Definition at line 31 of file expressionTesting.h.

◆ testFactorJacobians()

bool gtsam::internal::testFactorJacobians ( const std::string &  name_,
const NoiseModelFactor factor,
const gtsam::Values values,
double  delta,
double  tolerance 
)
inline

Definition at line 77 of file factorTesting.h.

◆ tic()

GTSAM_EXPORT void gtsam::internal::tic ( size_t  id,
const char *  labelC 
)

Definition at line 263 of file timing.cpp.

◆ toc()

GTSAM_EXPORT void gtsam::internal::toc ( size_t  id,
const char *  labelC 
)

Definition at line 275 of file timing.cpp.

◆ translation()

Point3 gtsam::internal::translation ( const Pose3 pose,
OptionalJacobian< 3, 6 >  H 
)
inline

Definition at line 84 of file slam/expressions.h.

◆ upAlign()

template<typename T >
T& gtsam::internal::upAlign ( T value,
unsigned  requiredAlignment = TraceAlignment 
)

Definition at line 37 of file ExpressionNode.h.

◆ upAligned()

template<typename T >
T gtsam::internal::upAligned ( T  value,
unsigned  requiredAlignment = TraceAlignment 
)

Definition at line 50 of file ExpressionNode.h.

◆ updateRgProd()

void gtsam::internal::updateRgProd ( const ISAM2::sharedClique clique,
const KeySet replacedKeys,
const VectorValues grad,
VectorValues RgProd,
size_t varsUpdated 
)

Definition at line 79 of file ISAM2-impl.cpp.

◆ velocity()

Velocity3 gtsam::internal::velocity ( const NavState X,
OptionalJacobian< 3, 9 >  H 
)

Definition at line 28 of file navigation/expressions.h.

Variable Documentation

◆ CallRecordMaxVirtualStaticRows

const int gtsam::internal::CallRecordMaxVirtualStaticRows = 5

CallRecordMaxVirtualStaticRows tells which separate virtual reverseAD with specific static rows (1..CallRecordMaxVirtualStaticRows) methods are part of the CallRecord interface. It is used to keep the testCallRecord unit test in sync.

Definition at line 133 of file CallRecord.h.

◆ gCurrentTimer

GTSAM_EXTERN_EXPORT std::weak_ptr<TimingOutline> gtsam::internal::gCurrentTimer

Definition at line 235 of file timing.h.

◆ gTimingRoot

GTSAM_EXTERN_EXPORT std::shared_ptr<TimingOutline> gtsam::internal::gTimingRoot

Definition at line 234 of file timing.h.

◆ nullTimingOutline

const std::shared_ptr<TimingOutline> gtsam::internal::nullTimingOutline
static

Definition at line 35 of file timing.cpp.

◆ TraceAlignment

const unsigned gtsam::internal::TraceAlignment = 32
static

Storage type for the execution trace. It enforces the proper alignment in a portable way. Provide a traceSize() sized array of this type to traceExecution as traceStorage.

Definition at line 45 of file ExecutionTrace.h.



gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:47:15