OptionalJacobian.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 #include <gtsam/config.h> // Configuration from CMake
22 #include <Eigen/Dense>
23 
24 #ifndef OPTIONALJACOBIAN_NOBOOST
25 #include <boost/optional.hpp>
26 #endif
27 
28 namespace gtsam {
29 
38 template<int Rows, int Cols>
40 
41 public:
42 
46 
47 private:
48 
50 
51  // Trick from http://eigen.tuxfamily.org/dox/group__TutorialMapClass.html
52  // uses "placement new" to make map_ usurp the memory of the fixed size matrix
53  void usurp(double* data) {
54  new (&map_) Eigen::Map<Jacobian>(data);
55  }
56 
57  // Private and very dangerous constructor straight from memory
58  OptionalJacobian(double* data) : map_(nullptr) {
59  if (data) usurp(data);
60  }
61 
62  template<int M, int N>
63  friend class OptionalJacobian;
64 
65 public:
66 
69  map_(nullptr) {
70  }
71 
73  OptionalJacobian(Jacobian& fixed) :
74  map_(nullptr) {
75  usurp(fixed.data());
76  }
77 
79  OptionalJacobian(Jacobian* fixedPtr) :
80  map_(nullptr) {
81  if (fixedPtr)
82  usurp(fixedPtr->data());
83  }
84 
86  OptionalJacobian(Eigen::MatrixXd& dynamic) :
87  map_(nullptr) {
88  dynamic.resize(Rows, Cols); // no malloc if correct size
89  usurp(dynamic.data());
90  }
91 
92 #ifndef OPTIONALJACOBIAN_NOBOOST
93 
95  OptionalJacobian(boost::none_t /*none*/) :
96  map_(nullptr) {
97  }
98 
100  OptionalJacobian(const boost::optional<Eigen::MatrixXd&> optional) :
101  map_(nullptr) {
102  if (optional) {
103  optional->resize(Rows, Cols);
104  usurp(optional->data());
105  }
106  }
107 
108 #endif
109 
112  // template <typename Derived, bool InnerPanel>
113  // OptionalJacobian(Eigen::Block<Derived,Rows,Cols,InnerPanel> block) : map_(nullptr) { ?? }
114 
116  operator bool() const {
117  return map_.data() != nullptr;
118  }
119 
122  return map_;
123  }
124 
127  return &map_;
128  }
129 
132  // template <int M, int N>
133  // OptionalJacobian<M, N> block(int startRow, int startCol) {
134  // if (*this)
135  // OptionalJacobian<M, N>(map_.block<M, N>(startRow, startCol));
136  // else
137  // return OptionalJacobian<M, N>();
138  // }
139 
143  template <int N>
145  if (*this)
146  return OptionalJacobian<Rows, N>(&map_(0,startCol));
147  else
148  return OptionalJacobian<Rows, N>();
149  }
150 
155 };
156 
157 // The pure dynamic specialization of this is needed to support
158 // variable-sized types. Note that this is designed to work like the
159 // boost optional scheme from GTSAM 3.
160 template<>
162 
163 public:
164 
166  typedef Eigen::MatrixXd Jacobian;
167 
168 private:
169 
170  Jacobian* pointer_;
171 
172 public:
173 
176  pointer_(nullptr) {
177  }
178 
180  OptionalJacobian(Jacobian* pointer) : pointer_(pointer) {}
181 
183  OptionalJacobian(Jacobian& dynamic) : pointer_(&dynamic) {}
184 
185 #ifndef OPTIONALJACOBIAN_NOBOOST
186 
188  OptionalJacobian(boost::none_t /*none*/) :
189  pointer_(nullptr) {
190  }
191 
193  OptionalJacobian(const boost::optional<Eigen::MatrixXd&> optional) :
194  pointer_(nullptr) {
195  if (optional) pointer_ = &(*optional);
196  }
197 
198 #endif
199 
201  operator bool() const {
202  return pointer_!=nullptr;
203  }
204 
206  Jacobian& operator*() {
207  return *pointer_;
208  }
209 
211  Jacobian* operator->(){ return pointer_; }
212 };
213 
214 // forward declare
215 template <typename T> struct traits;
216 
222 template <class T, class A>
223 struct MakeJacobian {
225 };
226 
233 template<class T, class A>
237 };
238 
239 } // namespace gtsam
240 
void usurp(double *data)
View on constructor argument, if given.
OptionalJacobian< traits< T >::dimension, traits< A >::dimension > type
OptionalJacobian(double *data)
A matrix or vector expression mapping an existing array of data.
Definition: Map.h:94
: meta-function to generate Jacobian
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar * data() const
Namespace containing all symbols from the Eigen library.
Definition: jet.h:637
OptionalJacobian(boost::none_t)
Constructor with boost::none just makes empty.
OptionalJacobian< Rows, N > cols(int startCol)
OptionalJacobian(const boost::optional< Eigen::MatrixXd & > optional)
Constructor compatible with old-style derivatives.
Eigen::Matrix< double, traits< T >::dimension, traits< A >::dimension > type
int data[]
OptionalJacobian()
Default constructor acts like boost::none.
static const int Cols
traits
Definition: chartTesting.h:28
OptionalJacobian(Jacobian &dynamic)
Construct from refrence to dynamic matrix.
OptionalJacobian(Jacobian &fixed)
Constructor that will usurp data of a fixed-size matrix.
: meta-function to generate JacobianTA optional reference Used mainly by Expressions ...
OptionalJacobian(Jacobian *pointer)
Construct from pointer to dynamic matrix.
const int Dynamic
Definition: Constants.h:21
Eigen::Map< Jacobian > * operator->()
operator->()
OptionalJacobian()
View on constructor argument, if given.
The matrix class, also used for vectors and row-vectors.
OptionalJacobian(Eigen::MatrixXd &dynamic)
Constructor that will resize a dynamic matrix (unless already correct)
OptionalJacobian(Jacobian *fixedPtr)
Constructor that will usurp data of a fixed-size matrix, pointer version.
Eigen::Matrix< double, Rows, Cols > Jacobian
Jacobian & operator*()
De-reference, like boost optional.
OptionalJacobian(boost::none_t)
Constructor with boost::none just makes empty.
Eigen::Map< Jacobian > & operator*()
De-reference, like boost optional.
OptionalJacobian(const boost::optional< Eigen::MatrixXd & > optional)
Constructor compatible with old-style derivatives.
Eigen::Map< Jacobian > map_


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:43:06