25 #include <boost/assign/list_of.hpp> 61 boost::optional<double>
gamma = boost::none)
64 throw std::invalid_argument(
"ShonanGaugeFactor must have p>=d.");
80 size_t i = 0,
j = 0,
n = p - 1 -
d;
82 A.block(i,
j,
n,
n) = invSigma * Matrix::Identity(
n,
n);
89 boost::make_shared<JacobianFactor>(
key, A, Vector::Zero(rows_));
99 size_t dim()
const override {
return rows_; }
103 return whitenedJacobian_;
double error(const Values &c) const override
Calculate the error of the factor: always zero.
EIGEN_DEVICE_FUNC const SqrtReturnType sqrt() const
static size_t Dimension(size_t n)
const mpreal gamma(const mpreal &x, mp_rnd_t r=mpreal::get_default_rnd())
EIGEN_DEVICE_FUNC const Scalar & q
~ShonanGaugeFactor() override
Destructor.
Non-linear factor base classes.
boost::shared_ptr< GaussianFactor > linearize(const Values &c) const override
linearize to a GaussianFactor
boost::shared_ptr< JacobianFactor > whitenedJacobian_
Constant Jacobian.
N*N matrix representation of SO(N). N can be Eigen::Dynamic.
std::uint64_t Key
Integer nonlinear key type.
ShonanGaugeFactor(Key key, size_t p, size_t d=3, boost::optional< double > gamma=boost::none)
size_t dim() const override
get the dimension of the factor (number of rows on linearization)