GenericValue.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 
12 /*
13  * @file GenericValue.h
14  * @brief Wraps any type T so it can play as a Value
15  * @date October, 2014
16  * @author Michael Bosse, Abel Gawel, Renaud Dube
17  * based on DerivedValue.h by Duy Nguyen Ta
18  */
19 
20 #pragma once
21 
22 #include <gtsam/base/Manifold.h>
23 #include <gtsam/base/types.h>
24 #include <gtsam/base/Value.h>
25 
26 #include <cmath>
27 #include <iostream>
28 #include <typeinfo> // operator typeid
29 
30 #ifdef _WIN32
31 #define GENERICVALUE_VISIBILITY
32 #else
33 // This will trigger a LNKxxxx on MSVC, so disable for MSVC build
34 // Please refer to https://github.com/borglab/gtsam/blob/develop/Using-GTSAM-EXPORT.md
35 #define GENERICVALUE_VISIBILITY GTSAM_EXPORT
36 #endif
37 
38 namespace gtsam {
39 
43 template<class T>
44 class GenericValue: public Value {
45 
46 public:
47 
48  typedef T type;
49 
50 protected:
51 
53 
54 public:
55  // Only needed for serialization.
57 
59  GenericValue(const T& value) : Value(),
60  value_(value) {}
61 
62  GenericValue(const GenericValue& other) = default;
63 
65  const T& value() const {
66  return value_;
67  }
68 
70  T& value() {
71  return value_;
72  }
73 
75  ~GenericValue() override {
76  }
77 
79  bool equals_(const Value& p, double tol = 1e-9) const override {
80  // Cast the base class Value pointer to a templated generic class pointer
81  const GenericValue& genericValue2 = static_cast<const GenericValue&>(p);
82  // Return the result of using the equals traits for the derived class
83  return traits<T>::Equals(this->value_, genericValue2.value_, tol);
84  }
85 
87  bool equals(const GenericValue &other, double tol = 1e-9) const {
88  return traits<T>::Equals(this->value(), other.value(), tol);
89  }
90 
92  void print(const std::string& str) const override {
93  std::cout << "(" << demangle(typeid(T).name()) << ")\n";
95  }
96 
100  Value* clone_() const override {
101  GenericValue* ptr = new GenericValue(*this); // calls copy constructor to fill in
102  return ptr;
103  }
104 
108  void deallocate_() const override {
109  delete this;
110  }
111 
115  std::shared_ptr<Value> clone() const override {
116  return std::allocate_shared<GenericValue>(Eigen::aligned_allocator<GenericValue>(), *this);
117  }
118 
120  Value* retract_(const Vector& delta) const override {
121  // Call retract on the derived class using the retract trait function
122  const T retractResult = traits<T>::Retract(GenericValue<T>::value(), delta);
123 
124  Value* resultAsValue = new GenericValue(retractResult);
125 
126  // Return the pointer to the Value base class
127  return resultAsValue;
128  }
129 
131  Vector localCoordinates_(const Value& value2) const override {
132  // Cast the base class Value pointer to a templated generic class pointer
133  const GenericValue<T>& genericValue2 =
134  static_cast<const GenericValue<T>&>(value2);
135 
136  // Return the result of calling localCoordinates trait on the derived class
137  return traits<T>::Local(GenericValue<T>::value(), genericValue2.value());
138  }
139 
143  }
144 
146  Vector localCoordinates(const GenericValue& value2) const {
147  return localCoordinates_(value2);
148  }
149 
151  size_t dim() const override {
153  }
154 
156  Value& operator=(const Value& rhs) override {
157  // Cast the base class Value pointer to a derived class pointer
158  const GenericValue& derivedRhs = static_cast<const GenericValue&>(rhs);
159 
160  // Do the assignment and return the result
161  *this = GenericValue(derivedRhs); // calls copy constructor
162  return *this;
163  }
164 
165  protected:
166 
170  Value::operator=(static_cast<Value const&>(rhs));
171  value_ = rhs.value_;
172  return *this;
173  }
174 
175  private:
176 
177 #if GTSAM_ENABLE_BOOST_SERIALIZATION
178 
179  friend class boost::serialization::access;
180  template<class ARCHIVE>
181  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
182  ar & boost::serialization::make_nvp("GenericValue",
183  boost::serialization::base_object<Value>(*this));
184  ar & boost::serialization::make_nvp("value", value_);
185  }
186 #endif
187 
188  // Alignment, see https://eigen.tuxfamily.org/dox/group__TopicStructHavingEigenMembers.html
189  constexpr static const bool NeedsToAlign = (sizeof(T) % 16) == 0;
190 public:
192 };
193 
195 #define GTSAM_VALUE_EXPORT(Type) BOOST_CLASS_EXPORT(gtsam::GenericValue<Type>)
196 
197 // traits
198 template <typename ValueType>
199 struct traits<GenericValue<ValueType> >
200  : public Testable<GenericValue<ValueType> > {};
201 
202 // define Value::cast here since now GenericValue has been declared
203 template<typename ValueType>
204 const ValueType& Value::cast() const {
205  return dynamic_cast<const GenericValue<ValueType>&>(*this).value();
206 }
207 
210 template<class T>
212  return GenericValue<T>(v);
213 }
214 
215 
216 } /* namespace gtsam */
gtsam::GenericValue::retract
GenericValue retract(const Vector &delta) const
Non-virtual version of retract.
Definition: GenericValue.h:141
gtsam::GenericValue::GenericValue
GenericValue()
Definition: GenericValue.h:56
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
types.h
Typedefs for easier changing of types.
gtsam::GenericValue::clone
std::shared_ptr< Value > clone() const override
Definition: GenericValue.h:115
gtsam::GenericValue::value_
T value_
The wrapped value.
Definition: GenericValue.h:52
T
Eigen::Triplet< double > T
Definition: Tutorial_sparse_example.cpp:6
gtsam::genericValue
GenericValue< T > genericValue(const T &v)
Definition: GenericValue.h:211
gtsam::GenericValue::print
void print(const std::string &str) const override
Virtual print function, uses traits.
Definition: GenericValue.h:92
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:39
name
static char name[]
Definition: rgamma.c:72
gtsam::GenericValue::equals_
bool equals_(const Value &p, double tol=1e-9) const override
equals implementing generic Value interface
Definition: GenericValue.h:79
gtsam::GenericValue
Definition: GenericValue.h:44
gtsam::GenericValue::localCoordinates_
Vector localCoordinates_(const Value &value2) const override
Generic Value interface version of localCoordinates.
Definition: GenericValue.h:131
gtsam::GenericValue::GenericValue
GenericValue(const T &value)
Construct from value.
Definition: GenericValue.h:59
Eigen::aligned_allocator
STL compatible allocator to use with types requiring a non standrad alignment.
Definition: Memory.h:878
gtsam.examples.PlanarManipulatorExample.delta
def delta(g0, g1)
Definition: PlanarManipulatorExample.py:45
gtsam::GenericValue::operator=
Value & operator=(const Value &rhs) override
Assignment operator.
Definition: GenericValue.h:156
gtsam::GenericValue::value
const T & value() const
Return a constant value.
Definition: GenericValue.h:65
gtsam::GenericValue::operator=
GenericValue< T > & operator=(const GenericValue< T > &rhs)
Definition: GenericValue.h:169
gtsam::Value
Definition: Value.h:39
gtsam::GenericValue::value
T & value()
Return the value.
Definition: GenericValue.h:70
Manifold.h
Base class and basic functions for Manifold types.
gtsam::GenericValue::retract_
Value * retract_(const Vector &delta) const override
Generic Value interface version of retract.
Definition: GenericValue.h:120
Eigen::Triplet< double >
str
Definition: pytypes.h:1558
gtsam
traits
Definition: SFMdata.h:40
gtsam::Testable
Definition: Testable.h:152
gtsam::traits
Definition: Group.h:36
gtsam::demangle
std::string demangle(const char *name)
Pretty print Value type name.
Definition: types.cpp:37
p
float * p
Definition: Tutorial_Map_using.cpp:9
gtsam::GenericValue::type
T type
Definition: GenericValue.h:48
gtsam::Print
void Print(const CONTAINER &keys, const string &s, const KeyFormatter &keyFormatter)
Definition: Key.cpp:65
v
Array< int, Dynamic, 1 > v
Definition: Array_initializer_list_vector_cxx11.cpp:1
gtsam::tol
const G double tol
Definition: Group.h:79
gtsam::GenericValue::equals
bool equals(const GenericValue &other, double tol=1e-9) const
non virtual equals function, uses traits
Definition: GenericValue.h:87
gtsam::GenericValue::clone_
Value * clone_() const override
Definition: GenericValue.h:100
GTSAM_MAKE_ALIGNED_OPERATOR_NEW_IF
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign)
Definition: types.h:288
gtsam::GenericValue::NeedsToAlign
constexpr static const bool NeedsToAlign
Definition: GenericValue.h:189
gtsam::GenericValue::dim
size_t dim() const override
Return run-time dimensionality.
Definition: GenericValue.h:151
gtsam::GenericValue::~GenericValue
~GenericValue() override
Destructor.
Definition: GenericValue.h:75
pybind_wrapper_test_script.other
other
Definition: pybind_wrapper_test_script.py:42
gtsam::Value::operator=
virtual Value & operator=(const Value &)
Definition: Value.h:84
Value.h
The base class for any variable that can be optimized or used in a factor.
gtsam::GenericValue::deallocate_
void deallocate_() const override
Definition: GenericValue.h:108
gtsam::Value::cast
const ValueType & cast() const
Definition: GenericValue.h:204
gtsam::GenericValue::localCoordinates
Vector localCoordinates(const GenericValue &value2) const
Non-virtual version of localCoordinates.
Definition: GenericValue.h:146


gtsam
Author(s):
autogenerated on Tue Jan 7 2025 04:02:18