inference/Symbol.h
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, 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 
19 #pragma once
20 
21 #include <gtsam/inference/Key.h>
22 #include <gtsam/base/Testable.h>
23 #include <boost/serialization/nvp.hpp>
24 #include <boost/function.hpp>
25 #include <cstdint>
26 
27 namespace gtsam {
28 
34 class GTSAM_EXPORT Symbol {
35 protected:
36  unsigned char c_;
38 
39 public:
40 
42  Symbol() :
43  c_(0), j_(0) {
44  }
45 
47  Symbol(const Symbol& key) :
48  c_(key.c_), j_(key.j_) {
49  }
50 
52  Symbol(unsigned char c, std::uint64_t j) :
53  c_(c), j_(j) {
54  }
55 
57  Symbol(Key key);
58 
60  Key key() const;
61 
63  operator Key() const { return key(); }
64 
66  void print(const std::string& s = "") const;
67 
69  bool equals(const Symbol& expected, double tol = 0.0) const;
70 
72  unsigned char chr() const {
73  return c_;
74  }
75 
77  std::uint64_t index() const {
78  return j_;
79  }
80 
82  operator std::string() const;
83 
85  std::string string() const { return std::string(*this); };
86 
88  bool operator<(const Symbol& comp) const {
89  return c_ < comp.c_ || (comp.c_ == c_ && j_ < comp.j_);
90  }
91 
93  bool operator==(const Symbol& comp) const {
94  return comp.c_ == c_ && comp.j_ == j_;
95  }
96 
98  bool operator==(Key comp) const {
99  return comp == (Key)(*this);
100  }
101 
103  bool operator!=(const Symbol& comp) const {
104  return comp.c_ != c_ || comp.j_ != j_;
105  }
106 
108  bool operator!=(Key comp) const {
109  return comp != (Key)(*this);
110  }
111 
117  static boost::function<bool(Key)> ChrTest(unsigned char c);
118 
120  GTSAM_EXPORT friend std::ostream &operator<<(std::ostream &, const Symbol &);
121 
122 private:
123 
125  friend class boost::serialization::access;
126  template<class ARCHIVE>
127  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
128  ar & BOOST_SERIALIZATION_NVP(c_);
129  ar & BOOST_SERIALIZATION_NVP(j_);
130  }
131 };
132 
134 inline Key symbol(unsigned char c, std::uint64_t j) { return (Key)Symbol(c,j); }
135 
137 inline unsigned char symbolChr(Key key) { return Symbol(key).chr(); }
138 
140 inline std::uint64_t symbolIndex(Key key) { return Symbol(key).index(); }
141 
142 namespace symbol_shorthand {
143 inline Key A(std::uint64_t j) { return Symbol('a', j); }
144 inline Key B(std::uint64_t j) { return Symbol('b', j); }
145 inline Key C(std::uint64_t j) { return Symbol('c', j); }
146 inline Key D(std::uint64_t j) { return Symbol('d', j); }
147 inline Key E(std::uint64_t j) { return Symbol('e', j); }
148 inline Key F(std::uint64_t j) { return Symbol('f', j); }
149 inline Key G(std::uint64_t j) { return Symbol('g', j); }
150 inline Key H(std::uint64_t j) { return Symbol('h', j); }
151 inline Key I(std::uint64_t j) { return Symbol('i', j); }
152 inline Key J(std::uint64_t j) { return Symbol('j', j); }
153 inline Key K(std::uint64_t j) { return Symbol('k', j); }
154 inline Key L(std::uint64_t j) { return Symbol('l', j); }
155 inline Key M(std::uint64_t j) { return Symbol('m', j); }
156 inline Key N(std::uint64_t j) { return Symbol('n', j); }
157 inline Key O(std::uint64_t j) { return Symbol('o', j); }
158 inline Key P(std::uint64_t j) { return Symbol('p', j); }
159 inline Key Q(std::uint64_t j) { return Symbol('q', j); }
160 inline Key R(std::uint64_t j) { return Symbol('r', j); }
161 inline Key S(std::uint64_t j) { return Symbol('s', j); }
162 inline Key T(std::uint64_t j) { return Symbol('t', j); }
163 inline Key U(std::uint64_t j) { return Symbol('u', j); }
164 inline Key V(std::uint64_t j) { return Symbol('v', j); }
165 inline Key W(std::uint64_t j) { return Symbol('w', j); }
166 inline Key X(std::uint64_t j) { return Symbol('x', j); }
167 inline Key Y(std::uint64_t j) { return Symbol('y', j); }
168 inline Key Z(std::uint64_t j) { return Symbol('z', j); }
169 }
170 
174  const unsigned char c_;
175 public:
176  constexpr SymbolGenerator(const unsigned char c) : c_(c) {}
177  Symbol operator()(const std::uint64_t j) const { return Symbol(c_, j); }
178  constexpr unsigned char chr() const { return c_; }
179 };
180 
182 template<> struct traits<Symbol> : public Testable<Symbol> {};
183 
184 } // \ namespace gtsam
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
Key M(std::uint64_t j)
Symbol operator()(const std::uint64_t j) const
Key N(std::uint64_t j)
std::ostream & operator<<(std::ostream &os, const Dih6 &m)
Definition: testGroup.cpp:109
Key E(std::uint64_t j)
constexpr unsigned char chr() const
Key F(std::uint64_t j)
Concept check for values that can be used in unit tests.
bool operator<(const Symbol &comp) const
JacobiRotation< float > G
Matrix expected
Definition: testMatrix.cpp:974
unsigned char chr() const
Key P(std::uint64_t j)
Key K(std::uint64_t j)
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
unsigned char c_
Rot2 R(Rot2::fromAngle(0.1))
bool operator==(const Symbol &comp) const
Symbol(unsigned char c, std::uint64_t j)
Key I(std::uint64_t j)
Key W(std::uint64_t j)
void serialize(ARCHIVE &ar, const unsigned int)
Key H(std::uint64_t j)
Key X(std::uint64_t j)
Key Z(std::uint64_t j)
Key D(std::uint64_t j)
Key C(std::uint64_t j)
std::uint64_t j_
bool operator!=(const Symbol &comp) const
Key Q(std::uint64_t j)
Key O(std::uint64_t j)
Key S(std::uint64_t j)
unsigned __int64 uint64_t
Definition: ms_stdint.h:95
constexpr SymbolGenerator(const unsigned char c)
RealScalar s
bool operator==(Key comp) const
Key symbol(unsigned char c, std::uint64_t j)
JacobiRotation< float > J
traits
Definition: chartTesting.h:28
Key T(std::uint64_t j)
Key Y(std::uint64_t j)
Key L(std::uint64_t j)
Key V(std::uint64_t j)
std::string string() const
Return string representation of the key.
Symbol(const Symbol &key)
bool operator!=(Key comp) const
const G double tol
Definition: Group.h:83
const unsigned char c_
unsigned char symbolChr(Key key)
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
std::ptrdiff_t j
std::uint64_t symbolIndex(Key key)
std::uint64_t index() const


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:45:07