Wrapped combine constructors for JacobianFactor and HessianFactor
parent
426b4d79cf
commit
a7e7da49a5
2
gtsam.h
2
gtsam.h
|
@ -1173,6 +1173,7 @@ virtual class JacobianFactor : gtsam::GaussianFactor {
|
|||
const gtsam::noiseModel::Diagonal* model);
|
||||
JacobianFactor(size_t i1, Matrix A1, size_t i2, Matrix A2, size_t i3, Matrix A3,
|
||||
Vector b, const gtsam::noiseModel::Diagonal* model);
|
||||
JacobianFactor(const gtsam::GaussianFactorGraph& graph);
|
||||
|
||||
//Testable
|
||||
void print(string s) const;
|
||||
|
@ -1217,6 +1218,7 @@ virtual class HessianFactor : gtsam::GaussianFactor {
|
|||
HessianFactor(size_t j1, size_t j2, size_t j3, Matrix G11, Matrix G12, Matrix G13,
|
||||
Vector g1, Matrix G22, Matrix G23, Vector g2, Matrix G33, Vector g3,
|
||||
double f);
|
||||
HessianFactor(const gtsam::GaussianFactorGraph& factors);
|
||||
|
||||
//Testable
|
||||
size_t size() const;
|
||||
|
|
Loading…
Reference in New Issue