TranslationFactor.h
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010-2020, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
12 #pragma once
13 
21 #include <gtsam/geometry/Point3.h>
22 #include <gtsam/geometry/Unit3.h>
25 
26 namespace gtsam {
27 
42 class TranslationFactor : public NoiseModelFactorN<Point3, Point3> {
43  private:
46 
47  public:
48 
49  // Provide access to the Matrix& version of evaluateError:
50  using NoiseModelFactor2<Point3, Point3>::evaluateError;
51 
54 
55  TranslationFactor(Key a, Key b, const Unit3& w_aZb,
57  : Base(noiseModel, a, b), measured_w_aZb_(w_aZb.point3()) {}
58 
71  const Point3& Ta, const Point3& Tb,
73  OptionalMatrixType H2) const override {
74  const Point3 dir = Tb - Ta;
75  Matrix33 H_predicted_dir;
76  const Point3 predicted = normalize(dir, H1 || H2 ? &H_predicted_dir : nullptr);
77  if (H1) *H1 = -H_predicted_dir;
78  if (H2) *H2 = H_predicted_dir;
79  return predicted - measured_w_aZb_;
80  }
81 
82  private:
83 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
84  friend class boost::serialization::access;
85  template <class ARCHIVE>
86  void serialize(ARCHIVE& ar, const unsigned int /*version*/) {
87  ar& boost::serialization::make_nvp(
88  "Base", boost::serialization::base_object<Base>(*this));
89  }
90 #endif
91 }; // \ TranslationFactor
92 } // namespace gtsam
std::string serialize(const T &input)
serializes to a string
TranslationFactor(Key a, Key b, const Unit3 &w_aZb, const SharedNoiseModel &noiseModel)
TranslationFactor()
default constructor
static void normalize(Signature::Row &row)
Definition: Signature.cpp:88
Represents a 3D point on a unit sphere.
Definition: Unit3.h:42
const SharedNoiseModel & noiseModel() const
access to the noise model
Matrix * OptionalMatrixType
Eigen::VectorXd Vector
Definition: Vector.h:38
NoiseModelFactorN< Point3, Point3 > Base
const G & b
Definition: Group.h:86
Point3_ point3(const Unit3_ &v)
traits
Definition: chartTesting.h:28
Non-linear factor base classes.
3D Point
Vector3 Point3
Definition: Point3.h:38
Vector evaluateError(const Point3 &Ta, const Point3 &Tb, OptionalMatrixType H1, OptionalMatrixType H2) const override
Caclulate error: (norm(Tb - Ta) - measurement) where Tb and Ta are Point3 translations and measuremen...
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:102
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:741


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:40:22