45 GTSAM_CONCEPT_LIE_TYPE(VALUE)
73 prior_((Vector(1) << prior).finished()),
75 assert(model->dim() == 1);
84 assert((
size_t)prior_.size() == indices_.size());
85 assert(model->dim() == (size_t)prior.size());
89 gtsam::NonlinearFactor::shared_ptr
clone()
const override {
91 gtsam::NonlinearFactor::shared_ptr(
new This(*
this))); }
96 void print(
const std::string& s,
const KeyFormatter& keyFormatter = DefaultKeyFormatter)
const override {
103 const This *e =
dynamic_cast<const This*
> (&expected);
106 this->indices_ == e->indices_;
113 Eigen::Matrix<double, T::dimension, T::dimension> H_local;
117 #ifdef GTSAM_ROT3_EXPMAP 118 const Vector full_tangent = T::LocalCoordinates(p, H ? &H_local :
nullptr);
120 const Vector full_tangent = T::Logmap(p, H ? &H_local :
nullptr);
124 (*H) = Matrix::Zero(indices_.size(), T::dimension);
125 for (
size_t i = 0; i < indices_.size(); ++i) {
126 (*H).row(i) = H_local.row(indices_.at(i));
130 Vector partial_tangent = Vector::Zero(indices_.size());
131 for (
size_t i = 0; i < indices_.size(); ++i) {
132 partial_tangent(i) = full_tangent(indices_.at(i));
135 return partial_tangent -
prior_;
139 const Vector& prior()
const {
return prior_; }
140 const std::vector<size_t>& indices()
const {
return indices_; }
143 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 145 friend class boost::serialization::access;
146 template<
class ARCHIVE>
147 void serialize(ARCHIVE & ar,
const unsigned int ) {
149 ar & boost::serialization::make_nvp(
"NoiseModelFactor1",
150 boost::serialization::base_object<Base>(*
this));
151 ar & BOOST_SERIALIZATION_NVP(prior_);
152 ar & BOOST_SERIALIZATION_NVP(indices_);
Definition: NonlinearFactor.h:431
PartialPriorFactor(Key key, size_t idx, double prior, const SharedNoiseModel &model)
Definition: PartialPriorFactor.h:71
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
std::string serialize(const T &input)
serializes to a string
Definition: serialization.h:113
virtual Vector evaluateError(const ValueTypes &... x, OptionalMatrixTypeT< ValueTypes >... H) const=0
PartialPriorFactor(Key key, const std::vector< size_t > &indices, const Vector &prior, const SharedNoiseModel &model)
Definition: PartialPriorFactor.h:79
Key key() const
Definition: NonlinearFactor.h:582
Definition: NonlinearFactor.h:68
PartialPriorFactor()
Definition: PartialPriorFactor.h:54
std::vector< size_t > indices_
Indices of the measured tangent space parameters.
Definition: PartialPriorFactor.h:51
Matrix * OptionalMatrixType
Definition: NonlinearFactor.h:55
gtsam::NonlinearFactor::shared_ptr clone() const override
Definition: PartialPriorFactor.h:89
GTSAM_EXPORT void print(const Matrix &A, const std::string &s, std::ostream &stream)
PartialPriorFactor(Key key, const SharedNoiseModel &model)
Definition: PartialPriorFactor.h:60
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
Base class and basic functions for Lie types.
bool equal_with_abs_tol(const Eigen::DenseBase< MATRIX > &A, const Eigen::DenseBase< MATRIX > &B, double tol=1e-9)
Definition: Matrix.h:80
Definition: chartTesting.h:28
void print(const std::string &s, const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Definition: PartialPriorFactor.h:96
Vector prior_
Measurement on tangent space parameters, in compressed form.
Definition: PartialPriorFactor.h:50
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Non-linear factor base classes.
bool equals(const NonlinearFactor &expected, double tol=1e-9) const override
Definition: PartialPriorFactor.h:102
Definition: PartialPriorFactor.h:38
Vector evaluateError(const T &p, OptionalMatrixType H) const override
Definition: PartialPriorFactor.h:112
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:102
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:741