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 | IncrementalRotation |
Function object for incremental rotation. 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 Similarity2 | Align (const Point2Pairs &d_abPointPairs, const Rot2 &aRb, const Point2Pair ¢roids) |
This method estimates the similarity transform from differences point pairs, given a known or estimated rotation and point centroids. More... | |
static Similarity3 | align (const Point3Pairs &d_abPointPairs, const Rot3 &aRb, const Point3Pair ¢roids) |
This method estimates the similarity transform from differences point pairs,. 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... | |
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... | |
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... | |
double | chi_squared_quantile (const double dofs, const double alpha) |
Compute the quantile function of the Chi-Squared distribution. 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< TimingOutline > | gCurrentTimer (gTimingRoot) |
size_t | getTicTocID (const char *descriptionC) |
GTSAM_EXPORT std::shared_ptr< TimingOutline > | gTimingRoot (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... | |
LogDeterminantData & | logDeterminant (const GaussianBayesTreeClique::shared_ptr &clique, LogDeterminantData &parentSum) |
template<class BAYESTREE > | |
double | logDeterminant (const typename BAYESTREE::sharedClique &clique) |
constexpr int | NSquaredSO (int N) |
static void | optimizeInPlace (const ISAM2::sharedClique &clique, VectorValues *result) |
template<class BAYESTREE > | |
void | optimizeInPlace (const typename BAYESTREE::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 POINT &p, const CALIBRATION &K, OptionalJacobian< 2, 6 > Dpose, OptionalJacobian< 2, 3 > Dpoint, OptionalJacobian< 2, CALIBRATION::dimension > Dcal) |
Rot3 | rotation (const Pose3 &pose, OptionalJacobian< 3, 6 > H) |
bool | structureCompareOp (const VectorValues::value_type &a, const VectorValues::value_type &b) |
static Point2Pairs | SubtractCentroids (const Point2Pairs &abPointPairs, const Point2Pair ¢roids) |
Subtract centroids from point pairs. More... | |
static Point3Pairs | subtractCentroids (const Point3Pairs &abPointPairs, const Point3Pair ¢roids) |
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 > | |
T & | upAlign (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< TimingOutline > | gCurrentTimer |
GTSAM_EXTERN_EXPORT std::shared_ptr< TimingOutline > | gTimingRoot |
const static std::shared_ptr< TimingOutline > | nullTimingOutline |
static const unsigned | TraceAlignment = 32 |
typedef std::aligned_storage<1, TraceAlignment>::type gtsam::internal::ExecutionTraceStorage |
Definition at line 48 of file ExecutionTrace.h.
|
static |
This method estimates the similarity transform from differences point pairs, given a known or estimated rotation and point centroids.
d_abPointPairs | |
aRb | |
centroids |
Definition at line 74 of file Similarity2.cpp.
|
static |
This method estimates the similarity transform from differences point pairs,.
Definition at line 69 of file Similarity3.cpp.
|
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.
abPointPairs | |
aRb |
Definition at line 94 of file Similarity2.cpp.
|
static |
This method estimates the similarity transform from point pairs, given a known or estimated rotation.
Definition at line 80 of file Similarity3.cpp.
Rot3 gtsam::internal::attitude | ( | const NavState & | X, |
OptionalJacobian< 3, 9 > | H | ||
) |
Definition at line 22 of file navigation/expressions.h.
|
static |
Form outer product H.
Definition at line 57 of file Similarity2.cpp.
|
static |
Form outer product H.
Definition at line 59 of file Similarity3.cpp.
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.
|
static |
Form inner products x and y and calculate scale.
Definition at line 43 of file Similarity2.cpp.
|
static |
Form inner products x and y and calculate scale.
Definition at line 45 of file Similarity3.cpp.
|
inline |
Compute the quantile function of the Chi-Squared distribution.
The quantile function of the Chi-squared distribution is the quantile of the specific (inverse) incomplete Gamma distribution.
dofs | Degrees of freedom |
alpha | Quantile value |
Definition at line 39 of file ChiSquaredInverse.h.
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.
GTSAM_EXPORT std::weak_ptr<TimingOutline> gtsam::internal::gCurrentTimer | ( | gTimingRoot | ) |
GTSAM_EXPORT size_t gtsam::internal::getTicTocID | ( | const char * | descriptionC | ) |
Definition at line 241 of file timing.cpp.
GTSAM_EXPORT std::shared_ptr<TimingOutline> gtsam::internal::gTimingRoot | ( | new | TimingOutline"Total", getTicTocID("Total") | ) |
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.
LogDeterminantData& gtsam::internal::logDeterminant | ( | const GaussianBayesTreeClique::shared_ptr & | clique, |
LogDeterminantData & | parentSum | ||
) |
Definition at line 49 of file GaussianBayesTree.cpp.
double gtsam::internal::logDeterminant | ( | const typename BAYESTREE::sharedClique & | clique | ) |
Definition at line 42 of file GaussianBayesTree-inl.h.
|
inlinestatic |
Definition at line 35 of file ISAM2-impl.cpp.
void gtsam::internal::optimizeInPlace | ( | const typename BAYESTREE::sharedClique & | clique, |
VectorValues & | result | ||
) |
Definition at line 31 of file GaussianBayesTree-inl.h.
Point3 gtsam::internal::position | ( | const NavState & | X, |
OptionalJacobian< 3, 9 > | H | ||
) |
Definition at line 25 of file navigation/expressions.h.
|
static |
Definition at line 218 of file ExpressionNode.h.
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.
|
inline |
Definition at line 158 of file slam/expressions.h.
|
inline |
Definition at line 80 of file slam/expressions.h.
bool gtsam::internal::structureCompareOp | ( | const VectorValues::value_type & | a, |
const VectorValues::value_type & | b | ||
) |
Definition at line 221 of file VectorValues.cpp.
|
static |
Subtract centroids from point pairs.
Definition at line 31 of file Similarity2.cpp.
|
static |
Subtract centroids from point pairs.
Definition at line 31 of file Similarity3.cpp.
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.
|
inline |
Definition at line 77 of file factorTesting.h.
GTSAM_EXPORT void gtsam::internal::tic | ( | size_t | id, |
const char * | labelC | ||
) |
Definition at line 264 of file timing.cpp.
GTSAM_EXPORT void gtsam::internal::toc | ( | size_t | id, |
const char * | labelC | ||
) |
Definition at line 276 of file timing.cpp.
|
inline |
Definition at line 84 of file slam/expressions.h.
T& gtsam::internal::upAlign | ( | T & | value, |
unsigned | requiredAlignment = TraceAlignment |
||
) |
Definition at line 37 of file ExpressionNode.h.
T gtsam::internal::upAligned | ( | T | value, |
unsigned | requiredAlignment = TraceAlignment |
||
) |
Definition at line 50 of file ExpressionNode.h.
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.
Velocity3 gtsam::internal::velocity | ( | const NavState & | X, |
OptionalJacobian< 3, 9 > | H | ||
) |
Definition at line 28 of file navigation/expressions.h.
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.
GTSAM_EXTERN_EXPORT std::weak_ptr<TimingOutline> gtsam::internal::gCurrentTimer |
GTSAM_EXTERN_EXPORT std::shared_ptr<TimingOutline> gtsam::internal::gTimingRoot |
|
static |
Definition at line 36 of file timing.cpp.
|
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.