gtsam 4.2.0
gtsam
Loading...
Searching...
No Matches
PoseRotationPrior.h
Go to the documentation of this file.
1
10#pragma once
11
14
15
16namespace gtsam {
17
18template<class POSE>
20public:
21
22 typedef PoseRotationPrior<POSE> This;
24 typedef POSE Pose;
25 typedef typename POSE::Translation Translation;
26 typedef typename POSE::Rotation Rotation;
27
28 GTSAM_CONCEPT_POSE_TYPE(Pose)
29 GTSAM_CONCEPT_GROUP_TYPE(Pose)
30 GTSAM_CONCEPT_LIE_TYPE(Rotation)
31
32 // Get dimensions of pose and rotation type at compile time
33 static const int xDim = FixedDimension<POSE>::value;
35
36protected:
37
38 Rotation measured_;
39
40public:
41
44
46 PoseRotationPrior(Key key, const Rotation& rot_z, const SharedNoiseModel& model)
47 : Base(model, key), measured_(rot_z) {}
48
50 PoseRotationPrior(Key key, const POSE& pose_z, const SharedNoiseModel& model)
51 : Base(model, key), measured_(pose_z.rotation()) {}
52
53 ~PoseRotationPrior() override {}
54
56 gtsam::NonlinearFactor::shared_ptr clone() const override {
57 return boost::static_pointer_cast<gtsam::NonlinearFactor>(
58 gtsam::NonlinearFactor::shared_ptr(new This(*this))); }
59
60 // access
61 const Rotation& measured() const { return measured_; }
62
63 // testable
64
66 bool equals(const NonlinearFactor& expected, double tol=1e-9) const override {
67 const This *e = dynamic_cast<const This*> (&expected);
68 return e != nullptr && Base::equals(*e, tol) && measured_.equals(e->measured_, tol);
69 }
70
72 void print(const std::string& s="", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override {
73 Base::print(s + "PoseRotationPrior", keyFormatter);
74 measured_.print("Measured Rotation");
75 }
76
78 Vector evaluateError(const Pose& pose, boost::optional<Matrix&> H = boost::none) const override {
79 const Rotation& newR = pose.rotation();
80 if (H) {
81 *H = Matrix::Zero(rDim, xDim);
82 std::pair<size_t, size_t> rotInterval = POSE::rotationInterval();
83 (*H).middleCols(rotInterval.first, rDim).setIdentity(rDim, rDim);
84 }
85
86 return measured_.localCoordinates(newR);
87 }
88
89private:
90
93 template<class ARCHIVE>
94 void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
95 // NoiseModelFactor1 instead of NoiseModelFactorN for backward compatibility
96 ar & boost::serialization::make_nvp("NoiseModelFactor1",
97 boost::serialization::base_object<Base>(*this));
98 ar & BOOST_SERIALIZATION_NVP(measured_);
99 }
100};
101
102} // \namespace gtsam
103
104
105
106
Non-linear factor base classes.
Global functions in a separate testing namespace.
Definition chartTesting.h:28
noiseModel::Base::shared_ptr SharedNoiseModel
Aliases.
Definition NoiseModel.h:724
std::uint64_t Key
Integer nonlinear key type.
Definition types.h:100
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
Give fixed size dimension of a type, fails at compile time if dynamic.
Definition Manifold.h:164
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
A convenient base class for creating your own NoiseModelFactor with n variables.
Definition NonlinearFactor.h:400
Key key() const
Returns a key.
Definition NonlinearFactor.h:518
Definition PoseRotationPrior.h:19
PoseRotationPrior(Key key, const Rotation &rot_z, const SharedNoiseModel &model)
standard constructor
Definition PoseRotationPrior.h:46
PoseRotationPrior(Key key, const POSE &pose_z, const SharedNoiseModel &model)
Constructor that pulls the translation from an incoming POSE.
Definition PoseRotationPrior.h:50
gtsam::NonlinearFactor::shared_ptr clone() const override
Definition PoseRotationPrior.h:56
bool equals(const NonlinearFactor &expected, double tol=1e-9) const override
equals specialized to this factor
Definition PoseRotationPrior.h:66
PoseRotationPrior()
default constructor - only use for serialization
Definition PoseRotationPrior.h:43
Vector evaluateError(const Pose &pose, boost::optional< Matrix & > H=boost::none) const override
h(x)-z
Definition PoseRotationPrior.h:78
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
print contents
Definition PoseRotationPrior.h:72
friend class boost::serialization::access
Serialization function.
Definition PoseRotationPrior.h:92
Concept-checking macros for geometric objects Each macro instantiates a concept check structure,...