LabeledSymbol.cpp
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 
18 #include <iostream>
19 
20 #include <boost/format.hpp>
21 #include <boost/bind.hpp>
22 
23 #include <boost/lexical_cast.hpp>
24 
26 
27 namespace gtsam {
28 
29 using namespace std;
30 
31 /* ************************************************************************* */
33 : c_(0), label_(0), j_(0) {}
34 
35 /* ************************************************************************* */
37 : c_(key.c_), label_(key.label_), j_(key.j_) {}
38 
39 /* ************************************************************************* */
40 LabeledSymbol::LabeledSymbol(unsigned char c, unsigned char label, std::uint64_t j)
41 : c_(c), label_(label), j_(j) {}
42 
43 /* ************************************************************************* */
45  const size_t keyBits = sizeof(gtsam::Key) * 8;
46  const size_t chrBits = sizeof(unsigned char) * 8;
47  const size_t lblBits = sizeof(unsigned char) * 8;
48  const size_t indexBits = keyBits - chrBits - lblBits;
49  const gtsam::Key chrMask = gtsam::Key(std::numeric_limits<unsigned char>::max()) << (indexBits + lblBits);
51  const gtsam::Key indexMask = ~(chrMask | lblMask);
52  c_ = (unsigned char)((key & chrMask) >> (indexBits + lblBits));
53  label_ = (unsigned char)((key & lblMask) >> indexBits);
54  j_ = key & indexMask;
55 }
56 
57 /* ************************************************************************* */
58 LabeledSymbol::operator gtsam::Key() const {
59  const size_t keyBits = sizeof(gtsam::Key) * 8;
60  const size_t chrBits = sizeof(unsigned char) * 8;
61  const size_t lblBits = sizeof(unsigned char) * 8;
62  const size_t indexBits = keyBits - chrBits - lblBits;
63  const gtsam::Key chrMask = gtsam::Key(std::numeric_limits<unsigned char>::max()) << (indexBits + lblBits);
65  const gtsam::Key indexMask = ~(chrMask | lblMask);
66  if(j_ > indexMask)
67  throw std::invalid_argument("Symbol index is too large");
68  gtsam::Key key = (gtsam::Key(c_) << (indexBits + lblBits)) | (gtsam::Key(label_) << indexBits) | j_;
69  return key;
70 }
71 
72 /* ************************************************************************* */
73 void LabeledSymbol::print(const std::string& s) const {
74  std::cout << s << ": " << (std::string) (*this) << std::endl;
75 }
76 
77 /* ************************************************************************* */
78 LabeledSymbol::operator std::string() const {
79  return str(boost::format("%c%c%d") % c_ % label_ % j_);
80 }
81 
82 /* ************************************************************************* */
83 bool LabeledSymbol::operator<(const LabeledSymbol& comp) const {
84  return c_ < comp.c_
85  || (comp.c_ == c_ && label_ < comp.label_)
86  || (comp.c_ == c_ && comp.label_ == label_ && j_ < comp.j_);
87 }
88 
89 /* ************************************************************************* */
90 bool LabeledSymbol::operator==(const LabeledSymbol& comp) const {
91  return comp.c_ == c_ && comp.label_ == label_ && comp.j_ == j_;
92 }
93 
94 /* ************************************************************************* */
95 bool LabeledSymbol::operator!=(const LabeledSymbol& comp) const {
96  return comp.c_ != c_ || comp.label_ != label_ || comp.j_ != j_;
97 }
98 
99 /* ************************************************************************* */
101  return comp == (gtsam::Key)(*this);
102 }
103 
104 /* ************************************************************************* */
106  return comp != (gtsam::Key)(*this);
107 }
108 
109 /* ************************************************************************* */
111 
112 boost::function<bool(gtsam::Key)> LabeledSymbol::TypeTest(unsigned char c) {
113  return boost::bind(&LabeledSymbol::chr, boost::bind(make, _1)) == c;
114 }
115 
116 boost::function<bool(gtsam::Key)> LabeledSymbol::LabelTest(unsigned char label) {
117  return boost::bind(&LabeledSymbol::label, boost::bind(make, _1)) == label;
118 }
119 
120 boost::function<bool(gtsam::Key)> LabeledSymbol::TypeLabelTest(unsigned char c, unsigned char label) {
121  return boost::bind(&LabeledSymbol::chr, boost::bind(make, _1)) == c &&
122  boost::bind(&LabeledSymbol::label, boost::bind(make, _1)) == label;
123 }
124 
125 /* ************************************************************************* */
126 GTSAM_EXPORT std::ostream &operator<<(std::ostream &os, const LabeledSymbol &symbol) {
127  os << StreamedKey(symbol);
128  return os;
129 }
130 
131 /* ************************************************************************* */
132 
133 } // \namespace gtsam
134 
bool operator!=(const LabeledSymbol &comp) const
#define max(a, b)
Definition: datatypes.h:20
unsigned char label_
Definition: LabeledSymbol.h:37
unsigned char label() const
Definition: LabeledSymbol.h:67
static LabeledSymbol make(gtsam::Key key)
static const Key chrMask
Definition: Symbol.cpp:33
static const Key indexMask
Definition: Symbol.cpp:34
std::uint64_t j_
Definition: LabeledSymbol.h:38
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
Definition: Half.h:150
static boost::function< bool(gtsam::Key)> TypeTest(unsigned char c)
static const size_t indexBits
Definition: Symbol.cpp:32
gtsam::Key key() const
Definition: LabeledSymbol.h:64
unsigned char chr() const
Definition: LabeledSymbol.h:70
unsigned __int64 uint64_t
Definition: ms_stdint.h:95
To use the key_formatter on Keys, they must be wrapped in a StreamedKey.
Definition: Key.h:58
unsigned char c_
Definition: LabeledSymbol.h:37
RealScalar s
Key symbol(unsigned char c, std::uint64_t j)
static const size_t chrBits
Definition: Symbol.cpp:31
static boost::function< bool(gtsam::Key)> TypeLabelTest(unsigned char c, unsigned char label)
traits
Definition: chartTesting.h:28
static const size_t keyBits
Definition: Symbol.cpp:30
ofstream os("timeSchurFactors.csv")
void print(const std::string &s="") const
bool operator==(const LabeledSymbol &comp) const
friend GTSAM_EXPORT std::ostream & operator<<(std::ostream &, const LabeledSymbol &)
Output stream operator that can be used with key_formatter (see Key.h).
bool operator<(const LabeledSymbol &comp) const
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
std::ptrdiff_t j
static boost::function< bool(gtsam::Key)> LabelTest(unsigned char label)


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:42:26