44 bool defaultToUnit =
true);
52 enum { Dim = Rot::VectorN2::RowsAtCompileTime };
53 using MatrixNN =
typename Rot::MatrixNN;
54 Eigen::Matrix<double, Dim, 1> vecM_;
59 using NoiseModelFactor1<Rot>::evaluateError;
61 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
67 vecM_ << Eigen::Map<const Matrix>(M.data(), Dim, 1);
72 return R.vec(H) - vecM_;
82 enum { Dim = Rot::VectorN2::RowsAtCompileTime };
87 using NoiseModelFactor2<Rot, Rot>::evaluateError;
97 Vector
error = R2.vec(H2) - R1.vec(H1);
112 Eigen::Matrix<double, Rot::dimension, Rot::dimension>
114 enum { Dim = Rot::VectorN2::RowsAtCompileTime };
119 using NoiseModelFactor2<Rot, Rot>::evaluateError;
121 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
132 R2hat_H_R1_(R12.inverse().AdjointMap()) {}
141 const KeyFormatter &keyFormatter = DefaultKeyFormatter)
const override {
142 std::cout << s <<
"FrobeniusBetweenFactor<" <<
demangle(
typeid(Rot).name())
143 <<
">(" << keyFormatter(this->key1()) <<
"," 144 << keyFormatter(this->key2()) <<
")\n";
146 this->noiseModel_->print(
" noise model: ");
151 double tol = 1e-9)
const override {
164 const Rot R2hat = R1.compose(R12_);
165 Eigen::Matrix<double, Dim, Rot::dimension> vec_H_R2hat;
166 Vector
error = R2.vec(H2) - R2hat.vec(H1 ? &vec_H_R2hat :
nullptr);
167 if (H1) *H1 = -vec_H_R2hat * R2hat_H_R1_;
Definition: NonlinearFactor.h:431
double error(const Values &c) const override
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
Vector evaluateError(const Rot &R1, const Rot &R2, OptionalMatrixType H1, OptionalMatrixType H2) const override
Error is just Frobenius norm between rotation matrices.
Definition: FrobeniusFactor.h:95
EIGEN_MAKE_ALIGNED_OPERATOR_NEW FrobeniusPrior(Key j, const MatrixNN &M, const SharedNoiseModel &model=nullptr)
Constructor.
Definition: FrobeniusFactor.h:64
Definition: NonlinearFactor.h:68
Definition: FrobeniusFactor.h:110
Matrix * OptionalMatrixType
Definition: NonlinearFactor.h:55
bool equals(const NonlinearFactor &expected, double tol=1e-9) const override
assert equality up to a tolerance
Definition: FrobeniusFactor.h:150
std::string GTSAM_EXPORT demangle(const char *name)
Function to demangle type name of variable, e.g. demangle(typeid(x).name())
Vector evaluateError(const Rot &R, OptionalMatrixType H) const override
Error is just Frobenius norm between Rot element and vectorized matrix M.
Definition: FrobeniusFactor.h:71
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Definition: Key.h:35
GTSAM_EXPORT SharedNoiseModel ConvertNoiseModel(const SharedNoiseModel &model, size_t n, bool defaultToUnit=true)
Definition: FrobeniusFactor.h:81
Definition: chartTesting.h:28
Non-linear factor base classes.
FrobeniusFactor(Key j1, Key j2, const SharedNoiseModel &model=nullptr)
Constructor.
Definition: FrobeniusFactor.h:90
Vector evaluateError(const Rot &R1, const Rot &R2, OptionalMatrixType H1, OptionalMatrixType H2) const override
Error is Frobenius norm between R1*R12 and R2.
Definition: FrobeniusFactor.h:162
FrobeniusBetweenFactor(Key j1, Key j2, const Rot &R12, const SharedNoiseModel &model=nullptr)
Construct from two keys and measured rotation.
Definition: FrobeniusFactor.h:127
void print(const std::string &s, const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
print with optional string
Definition: FrobeniusFactor.h:140
N*N matrix representation of SO(N). N can be Eigen::Dynamic.
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:102
Definition: FrobeniusFactor.h:51
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:741
3D rotation represented as a rotation matrix or quaternion