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 NoiseModelFactor2<Point3, Point3> {
43  private:
46 
47  public:
50 
51  TranslationFactor(Key a, Key b, const Unit3& w_aZb,
53  : Base(noiseModel, a, b), measured_w_aZb_(w_aZb.point3()) {}
54 
67  const Point3& Ta, const Point3& Tb,
68  boost::optional<Matrix&> H1 = boost::none,
69  boost::optional<Matrix&> H2 = boost::none) const override {
70  const Point3 dir = Tb - Ta;
71  Matrix33 H_predicted_dir;
72  const Point3 predicted = normalize(dir, H1 || H2 ? &H_predicted_dir : nullptr);
73  if (H1) *H1 = -H_predicted_dir;
74  if (H2) *H2 = H_predicted_dir;
75  return predicted - measured_w_aZb_;
76  }
77 
78  private:
80  template <class ARCHIVE>
81  void serialize(ARCHIVE& ar, const unsigned int /*version*/) {
82  ar& boost::serialization::make_nvp(
83  "Base", boost::serialization::base_object<Base>(*this));
84  }
85 }; // \ TranslationFactor
86 } // namespace gtsam
TranslationFactor(Key a, Key b, const Unit3 &w_aZb, const SharedNoiseModel &noiseModel)
TranslationFactor()
default constructor
const SharedNoiseModel & noiseModel() const
access to the noise model
Unit3 dir(nM)
Array33i a
static void normalize(Signature::Row &row)
Definition: Signature.cpp:158
Represents a 3D point on a unit sphere.
Definition: Unit3.h:42
Eigen::VectorXd Vector
Definition: Vector.h:38
void serialize(ARCHIVE &ar, const unsigned int)
Vector evaluateError(const Point3 &Ta, const Point3 &Tb, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none) const override
Caclulate error: (norm(Tb - Ta) - measurement) where Tb and Ta are Point3 translations and measuremen...
static const Point3 point3(0.08, 0.08, 0.0)
const G & b
Definition: Group.h:83
friend class boost::serialization::access
traits
Definition: chartTesting.h:28
NoiseModelFactor2< Point3, Point3 > Base
Non-linear factor base classes.
3D Point
Vector3 Point3
Definition: Point3.h:35
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:51:06