Value.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/config.h> // Configuration from CMake
22 
23 #include <gtsam/base/Vector.h>
24 #if GTSAM_ENABLE_BOOST_SERIALIZATION
25 #include <boost/serialization/nvp.hpp>
26 #include <boost/serialization/assume_abstract.hpp>
27 #endif
28 #include <memory>
29 
30 namespace gtsam {
31 
39  class GTSAM_EXPORT Value {
40  public:
41  // todo - not sure if valid
42  Value() = default;
43  Value(const Value& other) = default;
44 
46  virtual Value* clone_() const = 0;
47 
49  virtual void deallocate_() const = 0;
50 
52  virtual std::shared_ptr<Value> clone() const = 0;
53 
55  virtual bool equals_(const Value& other, double tol = 1e-9) const = 0;
56 
58  virtual void print(const std::string& str = "") const = 0;
59 
65  virtual size_t dim() const = 0;
66 
73  virtual Value* retract_(const Vector& delta) const = 0;
74 
81  virtual Vector localCoordinates_(const Value& value) const = 0;
82 
84  virtual Value& operator=(const Value& /*rhs*/) {
85  //needs a empty definition so recursion in implicit derived assignment operators work
86  return *this;
87  }
88 
90  template<typename ValueType>
91  const ValueType& cast() const;
92 
94  virtual ~Value() {}
95 
96  private:
127 #if GTSAM_ENABLE_BOOST_SERIALIZATION
128  friend class boost::serialization::access;
129  template<class ARCHIVE>
130  void serialize(ARCHIVE & /*ar*/, const unsigned int /*version*/) {
131  }
132 #endif
133 
134  };
135 
136 } /* namespace gtsam */
137 
138 #if GTSAM_ENABLE_BOOST_SERIALIZATION
139 BOOST_SERIALIZATION_ASSUME_ABSTRACT(gtsam::Value)
140 #endif
Vector.h
typedef and functions to augment Eigen's VectorXd
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:39
gtsam::print
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:156
gtsam.examples.PlanarManipulatorExample.delta
def delta(g0, g1)
Definition: PlanarManipulatorExample.py:45
gtsam::Value
Definition: Value.h:39
str
Definition: pytypes.h:1558
gtsam
traits
Definition: SFMdata.h:40
gtsam::tol
const G double tol
Definition: Group.h:79
gtsam::Value::~Value
virtual ~Value()
Definition: Value.h:94
test_callbacks.value
value
Definition: test_callbacks.py:160
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
Eigen::internal::cast
EIGEN_DEVICE_FUNC NewType cast(const OldType &x)
Definition: Eigen/src/Core/MathFunctions.h:460


gtsam
Author(s):
autogenerated on Tue Jan 7 2025 04:09:29