ExecutionTrace.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 #include <gtsam/config.h> // Configuration from CMake
22 #include <gtsam/inference/Key.h>
23 #include <gtsam/base/Manifold.h>
24 
25 #include <boost/type_traits/aligned_storage.hpp>
26 
27 #include <Eigen/Core>
28 #include <iostream>
29 
30 namespace gtsam {
31 namespace internal {
32 
33 template<int T> struct CallRecord;
34 
38 static const unsigned TraceAlignment = 32;
40 
41 template<bool UseBlock, typename Derived>
42 struct UseBlockIf {
43  static void addToJacobian(const Eigen::MatrixBase<Derived>& dTdA,
44  JacobianMap& jacobians, Key key) {
45  // block makes HUGE difference
46  jacobians(key).block<Derived::RowsAtCompileTime, Derived::ColsAtCompileTime>(
47  0, 0) += dTdA;
48  }
49 };
50 
52 template<typename Derived>
53 struct UseBlockIf<false, Derived> {
54  static void addToJacobian(const Eigen::MatrixBase<Derived>& dTdA,
55  JacobianMap& jacobians, Key key) {
56  jacobians(key) += dTdA;
57  }
58 };
59 
61 template<typename Derived>
63  JacobianMap& jacobians, Key key) {
64  UseBlockIf<
65  Derived::RowsAtCompileTime != Eigen::Dynamic
66  && Derived::ColsAtCompileTime != Eigen::Dynamic, Derived>::addToJacobian(
67  dTdA, jacobians, key);
68 }
69 
91 template<class T>
92 class ExecutionTrace {
93  static const int Dim = traits<T>::dimension;
95  enum {
96  Constant, Leaf, Function
97  } kind;
98  union {
101  } content;
102 
103  public:
104 
107  kind(Constant) {
108  }
109 
111  void setLeaf(Key key) {
112  kind = Leaf;
113  content.key = key;
114  }
115 
117  void setFunction(CallRecord<Dim>* record) {
118  kind = Function;
119  content.ptr = record;
120  }
121 
123  void print(const std::string& indent = "") const {
124  if (kind == Constant)
125  std::cout << indent << "Constant" << std::endl;
126  else if (kind == Leaf)
127  std::cout << indent << "Leaf, key = " << content.key << std::endl;
128  else if (kind == Function) {
129  content.ptr->print(indent + " ");
130  }
131  }
132 
134  template<class Record>
135  boost::optional<Record*> record() {
136  if (kind != Function)
137  return boost::none;
138  else {
139  Record* p = dynamic_cast<Record*>(content.ptr);
140  return p ? boost::optional<Record*>(p) : boost::none;
141  }
142  }
143 
148  void startReverseAD1(JacobianMap& jacobians) const {
149  if (kind == Leaf) {
150  // This branch will only be called on trivial Leaf expressions, i.e. Priors
151  static const JacobianTT I = JacobianTT::Identity();
152  handleLeafCase(I, jacobians, content.key);
153  } else if (kind == Function)
154  // This is the more typical entry point, starting the AD pipeline
155  // Inside startReverseAD2 the correctly dimensioned pipeline is chosen.
156  content.ptr->startReverseAD2(jacobians);
157  }
158 
160  // This is a crucial method in selecting the pipeline dimension: since it is templated method
161  // it will call the templated Record method reverseAD2. Hence, at this point in the pipeline
162  // there are as many reverseAD1 and reverseAD2 versions as there are different Jacobian sizes.
163  template<typename DerivedMatrix>
165  JacobianMap& jacobians) const {
166  if (kind == Leaf)
167  handleLeafCase(dTdA, jacobians, content.key);
168  else if (kind == Function)
169  content.ptr->reverseAD2(dTdA, jacobians);
170  }
171 
173  if (kind == Function) {
174  content.ptr->~CallRecord<Dim>();
175  }
176  }
177 
180 };
181 
182 } // namespace internal
183 } // namespace gtsam
void print(const std::string &indent="") const
Print.
void reverseAD1(const Eigen::MatrixBase< DerivedMatrix > &dTdA, JacobianMap &jacobians) const
Either add to Jacobians (Leaf) or propagate (Function)
ExecutionTrace< T > type
Define type so we can apply it as a meta-function.
ExecutionTrace()
Pointer always starts out as a Constant.
JacobianMap for returning derivatives from expressions.
void handleLeafCase(const Eigen::MatrixBase< Derived > &dTdA, JacobianMap &jacobians, Key key)
Handle Leaf Case: reverse AD ends here, by writing a matrix into Jacobians.
boost::aligned_storage< 1, TraceAlignment >::type ExecutionTraceStorage
boost::optional< Record * > record()
Return record pointer, quite unsafe, used only for testing.
static void addToJacobian(const Eigen::MatrixBase< Derived > &dTdA, JacobianMap &jacobians, Key key)
Base class and basic functions for Manifold types.
static const Matrix I
Definition: lago.cpp:35
traits
Definition: chartTesting.h:28
void setFunction(CallRecord< Dim > *record)
Take ownership of pointer to a Function Record.
void startReverseAD1(JacobianMap &jacobians) const
Eigen::Matrix< double, Dim, Dim > JacobianTT
float * p
static const unsigned TraceAlignment
const int Dynamic
Definition: Constants.h:21
The matrix class, also used for vectors and row-vectors.
void setLeaf(Key key)
Change pointer to a Leaf Record.
Base class for all dense matrices, vectors, and expressions.
Definition: MatrixBase.h:48
static void addToJacobian(const Eigen::MatrixBase< Derived > &dTdA, JacobianMap &jacobians, Key key)
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61


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