LabeledSymbol.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 
20 #pragma once
21 
22 #include <functional>
23 #include <gtsam/inference/Symbol.h>
24 
25 namespace gtsam {
26 
35 class GTSAM_EXPORT LabeledSymbol {
36 protected:
37  unsigned char c_, label_;
39 
40 public:
42  LabeledSymbol();
43 
46 
48  LabeledSymbol(unsigned char c, unsigned char label, std::uint64_t j);
49 
52 
54  operator gtsam::Key() const;
55 
56  // Testable Requirements
57  void print(const std::string& s = "") const;
58 
59  bool equals(const LabeledSymbol& expected, double tol = 0.0) const {
60  return (*this) == expected;
61  }
62 
64  gtsam::Key key() const { return (gtsam::Key) *this; }
65 
67  inline unsigned char label() const { return label_; }
68 
70  inline unsigned char chr() const { return c_; }
71 
73  inline size_t index() const { return j_; }
74 
76  operator std::string() const;
77 
79  bool operator<(const LabeledSymbol& comp) const;
80  bool operator==(const LabeledSymbol& comp) const;
81  bool operator==(gtsam::Key comp) const;
82  bool operator!=(const LabeledSymbol& comp) const;
83  bool operator!=(gtsam::Key comp) const;
84 
91  // Checks only the type
92  static std::function<bool(gtsam::Key)> TypeTest(unsigned char c);
93 
94  // Checks only the robot ID (label_)
95  static std::function<bool(gtsam::Key)> LabelTest(unsigned char label);
96 
97  // Checks both type and the robot ID
98  static std::function<bool(gtsam::Key)> TypeLabelTest(unsigned char c, unsigned char label);
99 
100  // Converts to upper/lower versions of labels
101  LabeledSymbol upper() const { return LabeledSymbol(c_, toupper(label_), j_); }
102  LabeledSymbol lower() const { return LabeledSymbol(c_, tolower(label_), j_); }
103 
104  // Create a new symbol with a different character.
105  LabeledSymbol newChr(unsigned char c) const { return LabeledSymbol(c, label_, j_); }
106 
107  // Create a new symbol with a different label.
108  LabeledSymbol newLabel(unsigned char label) const { return LabeledSymbol(c_, label, j_); }
109 
111  friend GTSAM_EXPORT std::ostream &operator<<(std::ostream &, const LabeledSymbol &);
112 
113 private:
114 
115 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
116 
117  friend class boost::serialization::access;
118  template<class ARCHIVE>
119  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
120  ar & BOOST_SERIALIZATION_NVP(c_);
121  ar & BOOST_SERIALIZATION_NVP(label_);
122  ar & BOOST_SERIALIZATION_NVP(j_);
123  }
124 #endif
125 }; // \class LabeledSymbol
126 
128 inline Key mrsymbol(unsigned char c, unsigned char label, size_t j) {
129  return (Key)LabeledSymbol(c,label,j);
130 }
131 
133 inline unsigned char mrsymbolChr(Key key) { return LabeledSymbol(key).chr(); }
134 
136 inline unsigned char mrsymbolLabel(Key key) { return LabeledSymbol(key).label(); }
137 
139 inline size_t mrsymbolIndex(Key key) { return LabeledSymbol(key).index(); }
140 
142 template<> struct traits<LabeledSymbol> : public Testable<LabeledSymbol> {};
143 
144 } // \namespace gtsam
145 
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
const gtsam::Symbol key('X', 0)
unsigned char chr() const
Definition: LabeledSymbol.h:70
unsigned char label_
Definition: LabeledSymbol.h:37
std::ostream & operator<<(std::ostream &os, const Dih6 &m)
Definition: testGroup.cpp:109
bool operator!=(const Matrix &A, const Matrix &B)
Definition: base/Matrix.h:106
bool operator<(const benchmark_t &b1, const benchmark_t &b2)
std::string serialize(const T &input)
serializes to a string
Matrix expected
Definition: testMatrix.cpp:971
LabeledSymbol newLabel(unsigned char label) const
std::uint64_t j_
Definition: LabeledSymbol.h:38
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
size_t index() const
Definition: LabeledSymbol.h:73
unsigned char mrsymbolLabel(Key key)
bool operator==(const Matrix &A, const Matrix &B)
Definition: base/Matrix.h:99
gtsam::Key key() const
Definition: LabeledSymbol.h:64
unsigned __int64 uint64_t
Definition: ms_stdint.h:95
unsigned char label() const
Definition: LabeledSymbol.h:67
RealScalar s
Key mrsymbol(unsigned char c, unsigned char label, size_t j)
LabeledSymbol upper() const
traits
Definition: chartTesting.h:28
const G double tol
Definition: Group.h:86
unsigned char mrsymbolChr(Key key)
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:102
size_t mrsymbolIndex(Key key)
std::ptrdiff_t j
LabeledSymbol newChr(unsigned char c) const
LabeledSymbol lower() const
bool equals(const LabeledSymbol &expected, double tol=0.0) const
Definition: LabeledSymbol.h:59


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