45 GTSAM_CONCEPT_LIE_TYPE(VALUE)
70 prior_((Vector(1) << prior).finished()),
72 assert(model->dim() == 1);
82 assert(model->dim() == (
size_t)prior.size());
86 gtsam::NonlinearFactor::shared_ptr
clone()
const override {
87 return boost::static_pointer_cast<gtsam::NonlinearFactor>(
88 gtsam::NonlinearFactor::shared_ptr(
new This(*
this))); }
93 void print(
const std::string& s,
const KeyFormatter& keyFormatter = DefaultKeyFormatter)
const override {
100 const This *e =
dynamic_cast<const This*
> (&expected);
109 Vector
evaluateError(
const T& p, boost::optional<Matrix&> H = boost::none)
const override {
110 Eigen::Matrix<double, T::dimension, T::dimension> H_local;
114 #ifdef GTSAM_ROT3_EXPMAP
115 const Vector full_tangent = T::LocalCoordinates(p, H ? &H_local :
nullptr);
117 const Vector full_tangent = T::Logmap(p, H ? &H_local :
nullptr);
121 (*H) = Matrix::Zero(
indices_.size(), T::dimension);
122 for (
size_t i = 0; i <
indices_.size(); ++i) {
123 (*H).row(i) = H_local.row(
indices_.at(i));
127 Vector partial_tangent = Vector::Zero(
indices_.size());
128 for (
size_t i = 0; i <
indices_.size(); ++i) {
129 partial_tangent(i) = full_tangent(
indices_.at(i));
132 return partial_tangent -
prior_;
136 const Vector& prior()
const {
return prior_; }
137 const std::vector<size_t>& indices()
const {
return indices_; }
141 friend class boost::serialization::access;
142 template<
class ARCHIVE>
143 void serialize(ARCHIVE & ar,
const unsigned int ) {
145 ar & boost::serialization::make_nvp(
"NoiseModelFactor1",
146 boost::serialization::base_object<Base>(*
this));
147 ar & BOOST_SERIALIZATION_NVP(
prior_);
148 ar & BOOST_SERIALIZATION_NVP(
indices_);
Base class and basic functions for Lie types.
Non-linear factor base classes.
Global functions in a separate testing namespace.
Definition chartTesting.h:28
void print(const Matrix &A, const string &s, ostream &stream)
print without optional string, must specify cout yourself
Definition Matrix.cpp:156
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
noiseModel::Base::shared_ptr SharedNoiseModel
Aliases.
Definition NoiseModel.h:724
std::uint64_t Key
Integer nonlinear key type.
Definition types.h:100
bool equal_with_abs_tol(const Eigen::DenseBase< MATRIX > &A, const Eigen::DenseBase< MATRIX > &B, double tol=1e-9)
equals with a tolerance
Definition Matrix.h:81
virtual void print(const std::string &s="Factor", const KeyFormatter &formatter=DefaultKeyFormatter) const
print
Definition Factor.cpp:29
bool equals(const This &other, double tol=1e-9) const
check equality
Definition Factor.cpp:42
Nonlinear factor base class.
Definition NonlinearFactor.h:42
NoiseModelFactorN()
Definition NonlinearFactor.h:469
Key key() const
Returns a key.
Definition NonlinearFactor.h:518
A class for a soft partial prior on any Lie type, with a mask over Expmap parameters.
Definition PartialPriorFactor.h:38
PartialPriorFactor(Key key, const SharedNoiseModel &model)
constructor with just minimum requirements for a factor - allows more computation in the constructor.
Definition PartialPriorFactor.h:60
gtsam::NonlinearFactor::shared_ptr clone() const override
Definition PartialPriorFactor.h:86
PartialPriorFactor()
default constructor - only use for serialization
Definition PartialPriorFactor.h:54
PartialPriorFactor(Key key, const std::vector< size_t > &indices, const Vector &prior, const SharedNoiseModel &model)
Indices Constructor: Specify the relevant measured indices in the tangent vector.
Definition PartialPriorFactor.h:76
Vector prior_
Definition PartialPriorFactor.h:50
Vector evaluateError(const T &p, boost::optional< Matrix & > H=boost::none) const override
implement functions needed to derive from Factor
Definition PartialPriorFactor.h:109
bool equals(const NonlinearFactor &expected, double tol=1e-9) const override
equals
Definition PartialPriorFactor.h:99
void print(const std::string &s, const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
implement functions needed for Testable
Definition PartialPriorFactor.h:93
PartialPriorFactor(Key key, size_t idx, double prior, const SharedNoiseModel &model)
Single Element Constructor: Prior on a single parameter at index 'idx' in the tangent vector.
Definition PartialPriorFactor.h:68
std::vector< size_t > indices_
Definition PartialPriorFactor.h:51