LocalOrientedPlane3Factor.h
Go to the documentation of this file.
1 /*
2  * @file LocalOrientedPlane3Factor.h
3  * @brief LocalOrientedPlane3 Factor class
4  * @author David Wisth
5  * @date February 12, 2021
6  */
7 
8 #pragma once
9 
12 #include <string>
13 
14 namespace gtsam {
15 
35 class LocalOrientedPlane3Factor: public NoiseModelFactor3<Pose3, Pose3,
36  OrientedPlane3> {
37 protected:
40 public:
43 
45 
58  Key poseKey, Key anchorPoseKey, Key landmarkKey)
59  : Base(noiseModel, poseKey, anchorPoseKey, landmarkKey), measured_p_(z) {}
60 
63  Key poseKey, Key anchorPoseKey, Key landmarkKey)
64  : Base(noiseModel, poseKey, anchorPoseKey, landmarkKey), measured_p_(z) {}
65 
67  void print(const std::string& s = "LocalOrientedPlane3Factor",
68  const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override;
69 
70  /***
71  * Vector of errors
72  * @brief Error = measured_plane_.error(a_plane.transform(inv(wTwa) * wTwi))
73  *
74  * This is the error of the measured and predicted plane in the current
75  * sensor frame, i. The plane is represented in the anchor pose, a.
76  *
77  * @param wTwi The pose of the sensor in world coordinates
78  * @param wTwa The pose of the anchor frame in world coordinates
79  * @param a_plane The estimated plane in anchor frame.
80  *
81  * Note: The optimized plane is represented in anchor frame, a, not the
82  * world frame.
83  */
84  Vector evaluateError(const Pose3& wTwi, const Pose3& wTwa,
85  const OrientedPlane3& a_plane,
86  boost::optional<Matrix&> H1 = boost::none,
87  boost::optional<Matrix&> H2 = boost::none,
88  boost::optional<Matrix&> H3 = boost::none) const override;
89 };
90 
91 } // namespace gtsam
92 
const gtsam::Key poseKey
static const KeyFormatter DefaultKeyFormatter
Definition: Key.h:43
Vector evaluateError(const Pose3 &wTwi, const Pose3 &wTwa, const OrientedPlane3 &a_plane, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none, boost::optional< Matrix & > H3=boost::none) const override
const SharedNoiseModel & noiseModel() const
access to the noise model
Represents an infinite plane in 3D, which is composed of a planar normal and its perpendicular distan...
Eigen::VectorXd Vector
Definition: Vector.h:38
void print(const std::string &s="LocalOrientedPlane3Factor", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
print
LocalOrientedPlane3Factor(const Vector4 &z, const SharedGaussian &noiseModel, Key poseKey, Key anchorPoseKey, Key landmarkKey)
LocalOrientedPlane3Factor(const OrientedPlane3 &z, const SharedGaussian &noiseModel, Key poseKey, Key anchorPoseKey, Key landmarkKey)
NoiseModelFactor3< Pose3, Pose3, OrientedPlane3 > Base
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
RealScalar s
traits
Definition: chartTesting.h:28
Non-linear factor base classes.
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
noiseModel::Gaussian::shared_ptr SharedGaussian
Definition: NoiseModel.h:735


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:42:34