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/base/Testable.h>
22 #include <gtsam/inference/Key.h>
23 
24 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
25 #include <boost/serialization/nvp.hpp>
26 #endif
27 #include <cstdint>
28 #include <functional>
29 
30 namespace gtsam {
31 
37 class GTSAM_EXPORT Symbol {
38 protected:
39  unsigned char c_;
41 
42 public:
43 
45  Symbol() :
46  c_(0), j_(0) {
47  }
48 
50  Symbol(const Symbol& key) :
51  c_(key.c_), j_(key.j_) {
52  }
53 
55  Symbol(unsigned char c, std::uint64_t j) :
56  c_(c), j_(j) {
57  }
58 
60  Symbol(Key key);
61 
63  Key key() const;
64 
66  operator Key() const { return key(); }
67 
69  void print(const std::string& s = "") const;
70 
72  bool equals(const Symbol& expected, double tol = 0.0) const;
73 
75  unsigned char chr() const {
76  return c_;
77  }
78 
80  std::uint64_t index() const {
81  return j_;
82  }
83 
85  operator std::string() const;
86 
88  std::string string() const { return std::string(*this); }
89 
91  bool operator<(const Symbol& comp) const {
92  return c_ < comp.c_ || (comp.c_ == c_ && j_ < comp.j_);
93  }
94 
96  bool operator==(const Symbol& comp) const {
97  return comp.c_ == c_ && comp.j_ == j_;
98  }
99 
101  bool operator==(Key comp) const {
102  return comp == (Key)(*this);
103  }
104 
106  bool operator!=(const Symbol& comp) const {
107  return comp.c_ != c_ || comp.j_ != j_;
108  }
109 
111  bool operator!=(Key comp) const {
112  return comp != (Key)(*this);
113  }
114 
120  static std::function<bool(Key)> ChrTest(unsigned char c);
121 
123  GTSAM_EXPORT friend std::ostream &operator<<(std::ostream &, const Symbol &);
124 
125 private:
126 
127 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
128 
129  friend class boost::serialization::access;
130  template<class ARCHIVE>
131  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
132  ar & BOOST_SERIALIZATION_NVP(c_);
133  ar & BOOST_SERIALIZATION_NVP(j_);
134  }
135 #endif
136 };
137 
139 inline Key symbol(unsigned char c, std::uint64_t j) { return (Key)Symbol(c,j); }
140 
142 inline unsigned char symbolChr(Key key) { return Symbol(key).chr(); }
143 
145 inline std::uint64_t symbolIndex(Key key) { return Symbol(key).index(); }
146 
147 namespace symbol_shorthand {
148 inline Key A(std::uint64_t j) { return Symbol('a', j); }
149 inline Key B(std::uint64_t j) { return Symbol('b', j); }
150 inline Key C(std::uint64_t j) { return Symbol('c', j); }
151 inline Key D(std::uint64_t j) { return Symbol('d', j); }
152 inline Key E(std::uint64_t j) { return Symbol('e', j); }
153 inline Key F(std::uint64_t j) { return Symbol('f', j); }
154 inline Key G(std::uint64_t j) { return Symbol('g', j); }
155 inline Key H(std::uint64_t j) { return Symbol('h', j); }
156 inline Key I(std::uint64_t j) { return Symbol('i', j); }
157 inline Key J(std::uint64_t j) { return Symbol('j', j); }
158 inline Key K(std::uint64_t j) { return Symbol('k', j); }
159 inline Key L(std::uint64_t j) { return Symbol('l', j); }
160 inline Key M(std::uint64_t j) { return Symbol('m', j); }
161 inline Key N(std::uint64_t j) { return Symbol('n', j); }
162 inline Key O(std::uint64_t j) { return Symbol('o', j); }
163 inline Key P(std::uint64_t j) { return Symbol('p', j); }
164 inline Key Q(std::uint64_t j) { return Symbol('q', j); }
165 inline Key R(std::uint64_t j) { return Symbol('r', j); }
166 inline Key S(std::uint64_t j) { return Symbol('s', j); }
167 inline Key T(std::uint64_t j) { return Symbol('t', j); }
168 inline Key U(std::uint64_t j) { return Symbol('u', j); }
169 inline Key V(std::uint64_t j) { return Symbol('v', j); }
170 inline Key W(std::uint64_t j) { return Symbol('w', j); }
171 inline Key X(std::uint64_t j) { return Symbol('x', j); }
172 inline Key Y(std::uint64_t j) { return Symbol('y', j); }
173 inline Key Z(std::uint64_t j) { return Symbol('z', j); }
174 }
175 
179  const unsigned char c_;
180 public:
181  constexpr SymbolGenerator(const unsigned char c) : c_(c) {}
182  Symbol operator()(const std::uint64_t j) const { return Symbol(c_, j); }
183  constexpr unsigned char chr() const { return c_; }
184 };
185 
187 template<> struct traits<Symbol> : public Testable<Symbol> {};
188 
189 } // \ namespace gtsam
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
const gtsam::Symbol key('X', 0)
Key M(std::uint64_t j)
#define I
Definition: main.h:112
Key N(std::uint64_t j)
std::ostream & operator<<(std::ostream &os, const Dih6 &m)
Definition: testGroup.cpp:109
Key F(std::uint64_t j)
Concept check for values that can be used in unit tests.
std::string serialize(const T &input)
serializes to a string
JacobiRotation< float > G
Symbol operator()(const std::uint64_t j) const
Matrix expected
Definition: testMatrix.cpp:971
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))
Symbol(unsigned char c, std::uint64_t j)
Key W(std::uint64_t j)
Key H(std::uint64_t j)
Key X(std::uint64_t j)
DiscreteKey S(1, 2)
bool operator==(Key comp) const
Key Z(std::uint64_t j)
Key D(std::uint64_t j)
Key C(std::uint64_t j)
bool operator==(const Symbol &comp) const
std::uint64_t j_
bool operator<(const Symbol &comp) const
Key Q(std::uint64_t j)
Key O(std::uint64_t j)
std::string string() const
Return string representation of the key.
unsigned __int64 uint64_t
Definition: ms_stdint.h:95
constexpr SymbolGenerator(const unsigned char c)
RealScalar s
Key symbol(unsigned char c, std::uint64_t j)
JacobiRotation< float > J
constexpr unsigned char chr() const
std::uint64_t index() const
traits
Definition: chartTesting.h:28
bool operator!=(Key comp) const
unsigned char chr() const
Key T(std::uint64_t j)
DiscreteKey E(5, 2)
Key Y(std::uint64_t j)
Key L(std::uint64_t j)
Key V(std::uint64_t j)
Symbol(const Symbol &key)
const G double tol
Definition: Group.h:86
const unsigned char c_
unsigned char symbolChr(Key key)
bool operator!=(const Symbol &comp) const
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:102
std::ptrdiff_t j
std::uint64_t symbolIndex(Key key)


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:36:34