RelativeElevationFactor.h
Go to the documentation of this file.
1 
10 #pragma once
11 
12 #include <gtsam_unstable/dllexport.h>
13 #include <gtsam/geometry/Pose3.h>
15 
16 namespace gtsam {
17 
28 class GTSAM_UNSTABLE_EXPORT RelativeElevationFactor: public NoiseModelFactor2<Pose3, Point3> {
29 private:
30 
31  double measured_;
35 
36 public:
37 
38  RelativeElevationFactor() : measured_(0.0) {} /* Default constructor */
39 
41  const SharedNoiseModel& model);
42 
44 
47  return boost::static_pointer_cast<gtsam::NonlinearFactor>(
49 
51  Vector evaluateError(const Pose3& pose, const Point3& point,
52  boost::optional<Matrix&> H1 = boost::none, boost::optional<Matrix&> H2 = boost::none) const override;
53 
55  inline double measured() const { return measured_; }
56 
58  bool equals(const NonlinearFactor& expected, double tol=1e-9) const override;
59 
61  void print(const std::string& s="", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override;
62 
63 private:
64 
66  friend class boost::serialization::access;
67  template<class ARCHIVE>
68  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
69  ar & boost::serialization::make_nvp("NoiseModelFactor2",
70  boost::serialization::base_object<Base>(*this));
71  ar & BOOST_SERIALIZATION_NVP(measured_);
72  }
73 }; // RelativeElevationFactor
74 
75 
76 } // \namespace gtsam
77 
78 
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
const gtsam::Key poseKey
noiseModel::Diagonal::shared_ptr model
Matrix expected
Definition: testMatrix.cpp:974
static const KeyFormatter DefaultKeyFormatter
Definition: Key.h:43
const gtsam::Key pointKey
void serialize(ARCHIVE &ar, const unsigned int)
Point3 point(10, 0,-5)
Eigen::VectorXd Vector
Definition: Vector.h:38
static const Pose3 pose(Rot3(Vector3(1,-1,-1).asDiagonal()), Point3(0, 0, 0.5))
boost::shared_ptr< This > shared_ptr
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
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
#define This
traits
Definition: chartTesting.h:28
Non-linear factor base classes.
NoiseModelFactor2< Pose3, Point3 > Base
gtsam::NonlinearFactor::shared_ptr clone() const override
const G double tol
Definition: Group.h:83
Vector3 Point3
Definition: Point3.h:35
Point3 measured
3D Pose
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:734


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:43:51