BinaryMeasurement.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 
26 #include <gtsam/base/Testable.h>
27 #include <gtsam/inference/Factor.h>
28 #include <gtsam/inference/Key.h>
30 
31 #include <iostream>
32 #include <vector>
33 
34 namespace gtsam {
35 
36 template <class T> class BinaryMeasurement : public Factor {
37  // Check that T type is testable
39 
40 public:
41  // shorthand for a smart pointer to a measurement
42  using shared_ptr = typename std::shared_ptr<BinaryMeasurement>;
43 
44 private:
47 
48  public:
50  const SharedNoiseModel &model = nullptr)
51  : Factor(std::vector<Key>({key1, key2})),
53  noiseModel_(model) {}
54 
57 
58  Key key1() const { return keys_[0]; }
59  Key key2() const { return keys_[1]; }
60  const T &measured() const { return measured_; }
61  const SharedNoiseModel &noiseModel() const { return noiseModel_; }
62 
66 
67  void print(const std::string &s, const KeyFormatter &keyFormatter =
68  DefaultKeyFormatter) const override {
69  std::cout << s << "BinaryMeasurement(" << keyFormatter(this->key1()) << ","
70  << keyFormatter(this->key2()) << ")\n";
71  traits<T>::Print(measured_, " measured: ");
72  this->noiseModel_->print(" noise model: ");
73  }
74 
75  bool equals(const BinaryMeasurement &expected, double tol = 1e-9) const {
76  const BinaryMeasurement<T> *e =
77  dynamic_cast<const BinaryMeasurement<T> *>(&expected);
78  return e != nullptr && Factor::equals(*e) &&
79  traits<T>::Equals(this->measured_, e->measured_, tol) &&
80  noiseModel_->equals(*expected.noiseModel());
81  }
83 };
84 } // namespace gtsam
const SharedNoiseModel & noiseModel() const
Concept check for values that can be used in unit tests.
noiseModel::Diagonal::shared_ptr model
Matrix expected
Definition: testMatrix.cpp:971
KeyVector keys_
The keys involved in this factor.
Definition: Factor.h:87
Definition: BFloat16.h:88
static const KeyFormatter DefaultKeyFormatter
Definition: Key.h:43
void print(const std::string &s, const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
print
GTSAM_CONCEPT_ASSERT(IsTestable< T >)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
std::shared_ptr< Factor > shared_ptr
A shared_ptr to this class.
Definition: Factor.h:75
BinaryMeasurement(Key key1, Key key2, const T &measured, const SharedNoiseModel &model=nullptr)
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
traits
Definition: chartTesting.h:28
T measured_
The measurement.
const T & measured() const
SharedNoiseModel noiseModel_
Noise model.
const G double tol
Definition: Group.h:86
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:102
void Print(const CONTAINER &keys, const string &s, const KeyFormatter &keyFormatter)
Definition: Key.cpp:62
bool equals(const BinaryMeasurement &expected, double tol=1e-9) const
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:741
The base class for all factors.
bool equals(const This &other, double tol=1e-9) const
check equality
Definition: Factor.cpp:42


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:33:58