#include <GaussianFactorGraph.h>
Public Types | |
typedef FactorGraph< GaussianFactor > | Base |
Typedef to base factor graph type. More... | |
typedef EliminateableFactorGraph< This > | BaseEliminateable |
Typedef to base elimination class. More... | |
typedef KeySet | Keys |
typedef boost::shared_ptr< This > | shared_ptr |
shared_ptr to this class More... | |
typedef GaussianFactorGraph | This |
Typedef to this class. More... | |
Public Types inherited from gtsam::FactorGraph< GaussianFactor > | |
typedef FastVector< sharedFactor >::const_iterator | const_iterator |
typedef GaussianFactor | FactorType |
factor type More... | |
typedef FastVector< sharedFactor >::iterator | iterator |
typedef boost::shared_ptr< GaussianFactor > | sharedFactor |
Shared pointer to a factor. More... | |
typedef sharedFactor | value_type |
Public Types inherited from gtsam::EliminateableFactorGraph< GaussianFactorGraph > | |
typedef EliminationTraitsType::BayesNetType | BayesNetType |
Bayes net type produced by sequential elimination. More... | |
typedef EliminationTraitsType::BayesTreeType | BayesTreeType |
Bayes tree type produced by multifrontal elimination. More... | |
typedef EliminationTraitsType::ConditionalType | ConditionalType |
Conditional type stored in the Bayes net produced by elimination. More... | |
typedef boost::function< EliminationResult(const FactorGraphType &, const Ordering &)> | Eliminate |
The function type that does a single dense elimination step on a subgraph. More... | |
typedef std::pair< boost::shared_ptr< ConditionalType >, boost::shared_ptr< _FactorType > > | EliminationResult |
typedef EliminationTraits< FactorGraphType > | EliminationTraitsType |
Typedef to the specific EliminationTraits for this graph. More... | |
typedef EliminationTraitsType::EliminationTreeType | EliminationTreeType |
Elimination tree type that can do sequential elimination of this graph. More... | |
typedef EliminationTraitsType::JunctionTreeType | JunctionTreeType |
Junction tree type that can do multifrontal elimination of this graph. More... | |
typedef boost::optional< Ordering::OrderingType > | OptionalOrderingType |
Typedef for an optional ordering type. More... | |
typedef boost::optional< const VariableIndex & > | OptionalVariableIndex |
Typedef for an optional variable index as an argument to elimination functions. More... | |
Public Member Functions | |
void | add (const GaussianFactor &factor) |
void | add (const sharedFactor &factor) |
void | add (const Vector &b) |
void | add (Key key1, const Matrix &A1, const Vector &b, const SharedDiagonal &model=SharedDiagonal()) |
void | add (Key key1, const Matrix &A1, Key key2, const Matrix &A2, const Vector &b, const SharedDiagonal &model=SharedDiagonal()) |
void | add (Key key1, const Matrix &A1, Key key2, const Matrix &A2, Key key3, const Matrix &A3, const Vector &b, const SharedDiagonal &model=SharedDiagonal()) |
template<class TERMS > | |
void | add (const TERMS &terms, const Vector &b, const SharedDiagonal &model=SharedDiagonal()) |
virtual GaussianFactorGraph | clone () const |
virtual GaussianFactorGraph::shared_ptr | cloneToPtr () const |
double | error (const VectorValues &x) const |
GaussianFactorGraph () | |
template<typename ITERATOR > | |
GaussianFactorGraph (ITERATOR firstFactor, ITERATOR lastFactor) | |
template<class CONTAINER > | |
GaussianFactorGraph (const CONTAINER &factors) | |
template<class DERIVEDFACTOR > | |
GaussianFactorGraph (const FactorGraph< DERIVEDFACTOR > &graph) | |
std::map< Key, size_t > | getKeyDimMap () const |
Keys | keys () const |
GaussianFactorGraph | negate () const |
VectorValues | optimize (boost::none_t, const Eliminate &function=EliminationTraitsType::DefaultEliminate) const |
double | probPrime (const VectorValues &c) const |
virtual | ~GaussianFactorGraph () |
Testable | |
bool | equals (const This &fg, double tol=1e-9) const |
Linear Algebra | |
std::vector< std::tuple< int, int, double > > | sparseJacobian (const Ordering &ordering, size_t &nrows, size_t &ncols) const |
std::vector< std::tuple< int, int, double > > | sparseJacobian () const |
Matrix | sparseJacobian_ () const |
Matrix | augmentedJacobian (const Ordering &ordering) const |
Matrix | augmentedJacobian () const |
std::pair< Matrix, Vector > | jacobian (const Ordering &ordering) const |
std::pair< Matrix, Vector > | jacobian () const |
Matrix | augmentedHessian (const Ordering &ordering) const |
Matrix | augmentedHessian () const |
std::pair< Matrix, Vector > | hessian (const Ordering &ordering) const |
std::pair< Matrix, Vector > | hessian () const |
virtual VectorValues | hessianDiagonal () const |
virtual std::map< Key, Matrix > | hessianBlockDiagonal () const |
VectorValues | optimize (const Eliminate &function=EliminationTraitsType::DefaultEliminate) const |
VectorValues | optimize (const Ordering &, const Eliminate &function=EliminationTraitsType::DefaultEliminate) const |
VectorValues | optimizeDensely () const |
VectorValues | gradient (const VectorValues &x0) const |
virtual VectorValues | gradientAtZero () const |
VectorValues | optimizeGradientSearch () const |
VectorValues | transposeMultiply (const Errors &e) const |
void | transposeMultiplyAdd (double alpha, const Errors &e, VectorValues &x) const |
Errors | gaussianErrors (const VectorValues &x) const |
Errors | operator* (const VectorValues &x) const |
void | multiplyHessianAdd (double alpha, const VectorValues &x, VectorValues &y) const |
void | multiplyInPlace (const VectorValues &x, Errors &e) const |
void | multiplyInPlace (const VectorValues &x, const Errors::iterator &e) const |
Public Member Functions inherited from gtsam::FactorGraph< GaussianFactor > | |
virtual | ~FactorGraph ()=default |
Default destructor. More... | |
void | reserve (size_t size) |
IsDerived< DERIVEDFACTOR > | push_back (boost::shared_ptr< DERIVEDFACTOR > factor) |
Add a factor directly using a shared_ptr. More... | |
IsDerived< DERIVEDFACTOR > | push_back (const DERIVEDFACTOR &factor) |
IsDerived< DERIVEDFACTOR > | emplace_shared (Args &&...args) |
Emplace a shared pointer to factor of given type. More... | |
IsDerived< DERIVEDFACTOR > | add (boost::shared_ptr< DERIVEDFACTOR > factor) |
add is a synonym for push_back. More... | |
std::enable_if< std::is_base_of< FactorType, DERIVEDFACTOR >::value, boost::assign::list_inserter< RefCallPushBack< This > > >::type | operator+= (boost::shared_ptr< DERIVEDFACTOR > factor) |
+= works well with boost::assign list inserter. More... | |
HasDerivedElementType< ITERATOR > | push_back (ITERATOR firstFactor, ITERATOR lastFactor) |
HasDerivedValueType< ITERATOR > | push_back (ITERATOR firstFactor, ITERATOR lastFactor) |
Push back many factors with an iterator (factors are copied) More... | |
HasDerivedElementType< CONTAINER > | push_back (const CONTAINER &container) |
HasDerivedValueType< CONTAINER > | push_back (const CONTAINER &container) |
Push back non-pointer objects in a container (factors are copied). More... | |
void | add (const FACTOR_OR_CONTAINER &factorOrContainer) |
boost::assign::list_inserter< CRefCallPushBack< This > > | operator+= (const FACTOR_OR_CONTAINER &factorOrContainer) |
std::enable_if< std::is_base_of< This, typename CLIQUE::FactorGraphType >::value >::type | push_back (const BayesTree< CLIQUE > &bayesTree) |
FactorIndices | add_factors (const CONTAINER &factors, bool useEmptySlots=false) |
virtual void | print (const std::string &s="FactorGraph", const KeyFormatter &formatter=DefaultKeyFormatter) const |
print out graph More... | |
bool | equals (const This &fg, double tol=1e-9) const |
size_t | size () const |
bool | empty () const |
const sharedFactor | at (size_t i) const |
sharedFactor & | at (size_t i) |
const sharedFactor | operator[] (size_t i) const |
sharedFactor & | operator[] (size_t i) |
const_iterator | begin () const |
const_iterator | end () const |
sharedFactor | front () const |
sharedFactor | back () const |
iterator | begin () |
iterator | end () |
void | resize (size_t size) |
void | remove (size_t i) |
void | replace (size_t index, sharedFactor factor) |
iterator | erase (iterator item) |
iterator | erase (iterator first, iterator last) |
size_t | nrFactors () const |
KeySet | keys () const |
KeyVector | keyVector () const |
bool | exists (size_t idx) const |
Public Member Functions inherited from gtsam::EliminateableFactorGraph< GaussianFactorGraph > | |
boost::shared_ptr< BayesTreeType > | eliminateMultifrontal (OptionalOrderingType orderingType=boost::none, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const |
boost::shared_ptr< BayesTreeType > | eliminateMultifrontal (const Ordering &ordering, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const |
boost::shared_ptr< BayesTreeType > | eliminateMultifrontal (const Ordering &ordering, const Eliminate &function, OptionalVariableIndex variableIndex, OptionalOrderingType orderingType) const |
boost::shared_ptr< BayesTreeType > | eliminateMultifrontal (const Eliminate &function, OptionalVariableIndex variableIndex=boost::none, OptionalOrderingType orderingType=boost::none) const |
std::pair< boost::shared_ptr< BayesTreeType >, boost::shared_ptr< FactorGraphType > > | eliminatePartialMultifrontal (const Ordering &ordering, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const |
std::pair< boost::shared_ptr< BayesTreeType >, boost::shared_ptr< FactorGraphType > > | eliminatePartialMultifrontal (const KeyVector &variables, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const |
std::pair< boost::shared_ptr< BayesNetType >, boost::shared_ptr< FactorGraphType > > | eliminatePartialSequential (const Ordering &ordering, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const |
std::pair< boost::shared_ptr< BayesNetType >, boost::shared_ptr< FactorGraphType > > | eliminatePartialSequential (const KeyVector &variables, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const |
boost::shared_ptr< BayesNetType > | eliminateSequential (OptionalOrderingType orderingType=boost::none, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const |
boost::shared_ptr< BayesNetType > | eliminateSequential (const Ordering &ordering, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const |
boost::shared_ptr< BayesNetType > | eliminateSequential (const Ordering &ordering, const Eliminate &function, OptionalVariableIndex variableIndex, OptionalOrderingType orderingType) const |
boost::shared_ptr< BayesNetType > | eliminateSequential (const Eliminate &function, OptionalVariableIndex variableIndex=boost::none, OptionalOrderingType orderingType=boost::none) const |
boost::shared_ptr< FactorGraphType > | marginal (const KeyVector &variables, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const |
boost::shared_ptr< BayesNetType > | marginalMultifrontalBayesNet (boost::variant< const Ordering &, const KeyVector & > variables, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const |
boost::shared_ptr< BayesNetType > | marginalMultifrontalBayesNet (boost::variant< const Ordering &, const KeyVector & > variables, const Ordering &marginalizedVariableOrdering, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const |
boost::shared_ptr< BayesNetType > | marginalMultifrontalBayesNet (boost::variant< const Ordering &, const KeyVector & > variables, boost::none_t, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const |
boost::shared_ptr< BayesTreeType > | marginalMultifrontalBayesTree (boost::variant< const Ordering &, const KeyVector & > variables, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const |
boost::shared_ptr< BayesTreeType > | marginalMultifrontalBayesTree (boost::variant< const Ordering &, const KeyVector & > variables, const Ordering &marginalizedVariableOrdering, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const |
boost::shared_ptr< BayesTreeType > | marginalMultifrontalBayesTree (boost::variant< const Ordering &, const KeyVector & > variables, boost::none_t, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const |
Private Member Functions | |
template<class ARCHIVE > | |
void | serialize (ARCHIVE &ar, const unsigned int) |
Friends | |
class | boost::serialization::access |
Additional Inherited Members | |
Protected Member Functions inherited from gtsam::FactorGraph< GaussianFactor > | |
FactorGraph () | |
FactorGraph (ITERATOR firstFactor, ITERATOR lastFactor) | |
FactorGraph (const CONTAINER &factors) | |
Protected Attributes inherited from gtsam::FactorGraph< GaussianFactor > | |
FastVector< sharedFactor > | factors_ |
A Linear Factor Graph is a factor graph where all factors are Gaussian, i.e. Factor == GaussianFactor VectorValues = A values structure of vectors Most of the time, linear factor graphs arise by linearizing a non-linear factor graph.
Definition at line 65 of file GaussianFactorGraph.h.
Typedef to base factor graph type.
Definition at line 72 of file GaussianFactorGraph.h.
Typedef to base elimination class.
Definition at line 73 of file GaussianFactorGraph.h.
Return the set of variables involved in the factors (computes a set union).
Definition at line 138 of file GaussianFactorGraph.h.
typedef boost::shared_ptr<This> gtsam::GaussianFactorGraph::shared_ptr |
shared_ptr to this class
Definition at line 74 of file GaussianFactorGraph.h.
Typedef to this class.
Definition at line 71 of file GaussianFactorGraph.h.
|
inline |
Default constructor
Definition at line 77 of file GaussianFactorGraph.h.
|
inline |
Construct from iterator over factors
Definition at line 81 of file GaussianFactorGraph.h.
|
inlineexplicit |
Construct from container of factors (shared_ptr or plain objects)
Definition at line 85 of file GaussianFactorGraph.h.
|
inline |
Implicit copy/downcast constructor to override explicit template container constructor
Definition at line 89 of file GaussianFactorGraph.h.
|
inlinevirtual |
Virtual destructor
Definition at line 92 of file GaussianFactorGraph.h.
|
inline |
Add a factor by value - makes a copy
Definition at line 102 of file GaussianFactorGraph.h.
|
inline |
Add a factor by pointer - stores pointer without copying the factor
Definition at line 105 of file GaussianFactorGraph.h.
|
inline |
Add a null factor
Definition at line 108 of file GaussianFactorGraph.h.
|
inline |
Add a unary factor
Definition at line 112 of file GaussianFactorGraph.h.
|
inline |
Add a binary factor
Definition at line 117 of file GaussianFactorGraph.h.
|
inline |
Add a ternary factor
Definition at line 123 of file GaussianFactorGraph.h.
|
inline |
Add an n-ary factor
Definition at line 131 of file GaussianFactorGraph.h.
Return a dense Hessian matrix, augmented with the information vector . The augmented Hessian is
and the negative log-likelihood is .
Definition at line 232 of file GaussianFactorGraph.cpp.
Matrix gtsam::GaussianFactorGraph::augmentedHessian | ( | ) | const |
Return a dense Hessian matrix, augmented with the information vector . The augmented Hessian is
and the negative log-likelihood is .
Definition at line 241 of file GaussianFactorGraph.cpp.
Return a dense Jacobian matrix, augmented with b with the noise models baked into A and b. The negative log-likelihood is . See also GaussianFactorGraph::jacobian and GaussianFactorGraph::sparseJacobian.
Definition at line 202 of file GaussianFactorGraph.cpp.
Matrix gtsam::GaussianFactorGraph::augmentedJacobian | ( | ) | const |
Return a dense Jacobian matrix, augmented with b with the noise models baked into A and b. The negative log-likelihood is . See also GaussianFactorGraph::jacobian and GaussianFactorGraph::sparseJacobian.
Definition at line 210 of file GaussianFactorGraph.cpp.
|
virtual |
Clone() performs a deep-copy of the graph, including all of the factors. Cloning preserves null factors so indices for the original graph are still valid for the cloned graph.
Definition at line 79 of file GaussianFactorGraph.cpp.
|
virtual |
CloneToPtr() performs a simple assignment to a new graph and returns it. There is no preservation of null factors!
Definition at line 72 of file GaussianFactorGraph.cpp.
bool gtsam::GaussianFactorGraph::equals | ( | const This & | fg, |
double | tol = 1e-9 |
||
) | const |
Definition at line 43 of file GaussianFactorGraph.cpp.
|
inline |
unnormalized error
Definition at line 145 of file GaussianFactorGraph.h.
Errors gtsam::GaussianFactorGraph::gaussianErrors | ( | const VectorValues & | x | ) | const |
return A*x-b
Definition at line 496 of file GaussianFactorGraph.cpp.
Definition at line 58 of file GaussianFactorGraph.cpp.
VectorValues gtsam::GaussianFactorGraph::gradient | ( | const VectorValues & | x0 | ) | const |
Compute the gradient of the energy function, , centered around . The gradient is .
fg | The Jacobian factor graph $(A,b)$ |
x0 | The center about which to compute the gradient |
Definition at line 341 of file GaussianFactorGraph.cpp.
|
virtual |
Compute the gradient of the energy function, , centered around zero. The gradient is .
fg | The Jacobian factor graph $(A,b)$ |
[output] | g A VectorValues to store the gradient, which must be preallocated, see allocateVectorValues |
Definition at line 353 of file GaussianFactorGraph.cpp.
Return the dense Hessian and information vector , with the noise models baked in. The negative log-likelihood is {1}{2} x^T x + ^T x + c. See also GaussianFactorGraph::augmentedHessian.
Definition at line 249 of file GaussianFactorGraph.cpp.
Return the dense Hessian and information vector , with the noise models baked in. The negative log-likelihood is {1}{2} x^T x + ^T x + c. See also GaussianFactorGraph::augmentedHessian.
Definition at line 257 of file GaussianFactorGraph.cpp.
Return the block diagonal of the Hessian for this factor
Definition at line 275 of file GaussianFactorGraph.cpp.
|
virtual |
Return only the diagonal of the Hessian A'*A, as a VectorValues
Definition at line 264 of file GaussianFactorGraph.cpp.
Return the dense Jacobian and right-hand-side , with the noise models baked into A and b. The negative log-likelihood is . See also GaussianFactorGraph::augmentedJacobian and GaussianFactorGraph::sparseJacobian.
Definition at line 217 of file GaussianFactorGraph.cpp.
Return the dense Jacobian and right-hand-side , with the noise models baked into A and b. The negative log-likelihood is . See also GaussianFactorGraph::augmentedJacobian and GaussianFactorGraph::sparseJacobian.
Definition at line 225 of file GaussianFactorGraph.cpp.
GaussianFactorGraph::Keys gtsam::GaussianFactorGraph::keys | ( | ) | const |
Definition at line 49 of file GaussianFactorGraph.cpp.
void gtsam::GaussianFactorGraph::multiplyHessianAdd | ( | double | alpha, |
const VectorValues & | x, | ||
VectorValues & | y | ||
) | const |
y += alpha*A'A*x
Definition at line 404 of file GaussianFactorGraph.cpp.
void gtsam::GaussianFactorGraph::multiplyInPlace | ( | const VectorValues & | x, |
Errors & | e | ||
) | const |
In-place version e <- A*x that overwrites e.
Definition at line 411 of file GaussianFactorGraph.cpp.
void gtsam::GaussianFactorGraph::multiplyInPlace | ( | const VectorValues & | x, |
const Errors::iterator & | e | ||
) | const |
In-place version e <- A*x that takes an iterator.
Definition at line 416 of file GaussianFactorGraph.cpp.
GaussianFactorGraph gtsam::GaussianFactorGraph::negate | ( | ) | const |
Returns the negation of all factors in this graph - corresponds to antifactors. Will convert all factors to HessianFactors due to negation of information. Cloning preserves null factors so indices for the original graph are still valid for the cloned graph.
Definition at line 91 of file GaussianFactorGraph.cpp.
Errors gtsam::GaussianFactorGraph::operator* | ( | const VectorValues & | x | ) | const |
return A*x
Definition at line 394 of file GaussianFactorGraph.cpp.
VectorValues gtsam::GaussianFactorGraph::optimize | ( | const Eliminate & | function = EliminationTraitsType::DefaultEliminate | ) | const |
Solve the factor graph by performing multifrontal variable elimination in COLAMD order using the dense elimination function specified in function
(default EliminatePreferCholesky), followed by back-substitution in the Bayes tree resulting from elimination. Is equivalent to calling graph.eliminateMultifrontal()->optimize().
Definition at line 294 of file GaussianFactorGraph.cpp.
VectorValues gtsam::GaussianFactorGraph::optimize | ( | const Ordering & | ordering, |
const Eliminate & | function = EliminationTraitsType::DefaultEliminate |
||
) | const |
Solve the factor graph by performing multifrontal variable elimination in COLAMD order using the dense elimination function specified in function
(default EliminatePreferCholesky), followed by back-substitution in the Bayes tree resulting from elimination. Is equivalent to calling graph.eliminateMultifrontal()->optimize().
Definition at line 300 of file GaussianFactorGraph.cpp.
VectorValues gtsam::GaussianFactorGraph::optimize | ( | boost::none_t | , |
const Eliminate & | function = EliminationTraitsType::DefaultEliminate |
||
) | const |
VectorValues gtsam::GaussianFactorGraph::optimizeDensely | ( | ) | const |
Optimize using Eigen's dense Cholesky factorization
Definition at line 307 of file GaussianFactorGraph.cpp.
VectorValues gtsam::GaussianFactorGraph::optimizeGradientSearch | ( | ) | const |
Optimize along the gradient direction, with a closed-form computation to perform the line search. The gradient is computed about .
This function returns that minimizes a reparametrized problem. The error function of a GaussianBayesNet is
with gradient and Hessian
This function performs the line search in the direction of the gradient evaluated at with step size that minimizes :
Optimizing by setting the derivative to zero yields . For efficiency, this function evaluates the denominator without computing the Hessian , returning
Definition at line 365 of file GaussianFactorGraph.cpp.
|
inline |
Unnormalized probability. O(n)
Definition at line 155 of file GaussianFactorGraph.h.
|
inlineprivate |
Definition at line 384 of file GaussianFactorGraph.h.
SparseTriplets gtsam::GaussianFactorGraph::sparseJacobian | ( | const Ordering & | ordering, |
size_t & | nrows, | ||
size_t & | ncols | ||
) | const |
Returns a sparse augmented Jacbian matrix as a vector of i, j, and s, where i(k) and j(k) are the base 0 row and column indices, and s(k) is the entry as a double. The standard deviations are baked into A and b
ordering | the column ordering | |
[out] | nrows | The number of rows in the augmented Jacobian |
[out] | ncols | The number of columns in the augmented Jacobian |
Definition at line 104 of file GaussianFactorGraph.cpp.
SparseTriplets gtsam::GaussianFactorGraph::sparseJacobian | ( | ) | const |
Returns a sparse augmented Jacobian matrix with default ordering
Definition at line 178 of file GaussianFactorGraph.cpp.
Matrix gtsam::GaussianFactorGraph::sparseJacobian_ | ( | ) | const |
Matrix version of sparseJacobian: generates a 3*m matrix with [i,j,s] entries such that S(i(k),j(k)) = s(k), which can be given to MATLAB's sparse. Note: i, j are 1-indexed. The standard deviations are baked into A and b
Definition at line 184 of file GaussianFactorGraph.cpp.
VectorValues gtsam::GaussianFactorGraph::transposeMultiply | ( | const Errors & | e | ) | const |
x = A'*e
Definition at line 477 of file GaussianFactorGraph.cpp.
void gtsam::GaussianFactorGraph::transposeMultiplyAdd | ( | double | alpha, |
const Errors & | e, | ||
VectorValues & | x | ||
) | const |
x += alpha*A'*e
Definition at line 439 of file GaussianFactorGraph.cpp.
|
friend |
Serialization function
Definition at line 382 of file GaussianFactorGraph.h.