ExpressionNode.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 
24 #include <gtsam/nonlinear/Values.h>
25 
26 #include <typeinfo> // operator typeid
27 #include <ostream>
28 #include <map>
29 
30 class ExpressionFactorBinaryTest;
31 // Forward declare for testing
32 
33 namespace gtsam {
34 namespace internal {
35 
36 template<typename T>
37 T & upAlign(T & value, unsigned requiredAlignment = TraceAlignment) {
38  // right now only word sized types are supported.
39  // Easy to extend if needed,
40  // by somehow inferring the unsigned integer of same size
41  static_assert(sizeof(T) == sizeof(size_t));
42  size_t & uiValue = reinterpret_cast<size_t &>(value);
43  size_t misAlignment = uiValue % requiredAlignment;
44  if (misAlignment) {
45  uiValue += requiredAlignment - misAlignment;
46  }
47  return value;
48 }
49 template<typename T>
50 T upAligned(T value, unsigned requiredAlignment = TraceAlignment) {
51  return upAlign(value, requiredAlignment);
52 }
53 
54 //-----------------------------------------------------------------------------
55 
63 template<class T>
64 class ExpressionNode {
65 
66 protected:
67 
68  size_t traceSize_;
69 
71  ExpressionNode(size_t traceSize = 0) :
73  }
74 
75 public:
76 
78  virtual ~ExpressionNode() {
79  }
80 
82  virtual void print(const std::string& indent = "") const = 0;
83 
85  GTSAM_EXPORT
86  friend std::ostream& operator<<(std::ostream& os, const ExpressionNode& node) {
87  os << "Expression of type " << demangle(typeid(T).name());
88  if (node.traceSize_ > 0) os << ", trace size = " << node.traceSize_;
89  os << "\n";
90  return os;
91  }
92 
94  virtual std::set<Key> keys() const {
95  std::set<Key> keys;
96  return keys;
97  }
98 
100  virtual void dims(std::map<Key, int>& map) const {
101  }
102 
103  // Return size needed for memory buffer in traceExecution
104  size_t traceSize() const {
105  return traceSize_;
106  }
107 
109  virtual T value(const Values& values) const = 0;
110 
112  virtual T traceExecution(const Values& values, ExecutionTrace<T>& trace,
113  char* traceStorage) const = 0;
114 };
115 
116 //-----------------------------------------------------------------------------
118 template<class T>
120 
123 
126  constant_(value) {
127  }
128 
129  friend class Expression<T> ;
130 
131 public:
132 
134  ~ConstantExpression() override {
135  }
136 
138  void print(const std::string& indent = "") const override {
139  std::cout << indent << "Constant" << std::endl;
140  }
141 
143  T value(const Values& values) const override {
144  return constant_;
145  }
146 
149  char* traceStorage) const override {
150  return constant_;
151  }
152 
154 };
155 
156 //-----------------------------------------------------------------------------
158 template<typename T>
159 class LeafExpression: public ExpressionNode<T> {
160  typedef T value_type;
161 
164 
167  key_(key) {
168  }
169 
170  friend class Expression<T>;
171 
172 public:
173 
175  ~LeafExpression() override {
176  }
177 
179  void print(const std::string& indent = "") const override {
180  std::cout << indent << "Leaf, key = " << DefaultKeyFormatter(key_) << std::endl;
181  }
182 
184  std::set<Key> keys() const override {
185  std::set<Key> keys;
186  keys.insert(key_);
187  return keys;
188  }
189 
191  void dims(std::map<Key, int>& map) const override {
192  map[key_] = traits<T>::dimension;
193  }
194 
196  T value(const Values& values) const override {
197  return values.at<T>(key_);
198  }
199 
202  char* traceStorage) const override {
203  trace.setLeaf(key_);
204  return values.at<T>(key_);
205  }
206 
207 };
208 
209 //-----------------------------------------------------------------------------
211 template<class T, class A>
212 struct Jacobian {
214 };
215 
216 // Helper function for printing Jacobians with compact Eigen format, and trace
217 template <class T, class A>
218 static void PrintJacobianAndTrace(const std::string& indent,
219  const typename Jacobian<T, A>::type& dTdA,
220  const ExecutionTrace<A> trace) {
221  static const Eigen::IOFormat kMatlabFormat(0, 1, " ", "; ", "", "", "[", "]");
222  std::cout << indent << "D(" << demangle(typeid(T).name()) << ")/D(" << demangle(typeid(A).name())
223  << ") = " << dTdA.format(kMatlabFormat) << std::endl;
224  trace.print(indent);
225 }
226 
227 //-----------------------------------------------------------------------------
229 template<class T, class A1>
230 class UnaryExpression: public ExpressionNode<T> {
231 
233  std::shared_ptr<ExpressionNode<A1> > expression1_;
235 
238  expression1_(e1.root()), function_(f) {
239  this->traceSize_ = upAligned(sizeof(Record)) + e1.traceSize();
240  }
241 
242  friend class Expression<T>;
243 
244 public:
245 
247  ~UnaryExpression() override {
248  }
249 
251  void print(const std::string& indent = "") const override {
252  std::cout << indent << "UnaryExpression" << std::endl;
253  expression1_->print(indent + " ");
254  }
255 
257  T value(const Values& values) const override {
258  return function_(expression1_->value(values), {});
259  }
260 
262  std::set<Key> keys() const override {
263  return expression1_->keys();
264  }
265 
267  void dims(std::map<Key, int>& map) const override {
268  expression1_->dims(map);
269  }
270 
271  // Inner Record Class
272  struct Record: public CallRecordImplementor<Record, traits<T>::dimension> {
273 
277 
279  Record(const Values& values, const ExpressionNode<A1>& expression1, char* ptr)
280  : value1(expression1.traceExecution(values, trace1, ptr + upAligned(sizeof(Record)))) {}
281 
283  void print(const std::string& indent) const {
284  std::cout << indent << "UnaryExpression::Record {" << std::endl;
285  PrintJacobianAndTrace<T,A1>(indent, dTdA1, trace1);
286  std::cout << indent << "}" << std::endl;
287  }
288 
290  void startReverseAD4(JacobianMap& jacobians) const {
291  // This is the crucial point where the size of the AD pipeline is selected.
292  // One pipeline is started for each argument, but the number of rows in each
293  // pipeline is the same, namely the dimension of the output argument T.
294  // For example, if the entire expression is rooted by a binary function
295  // yielding a 2D result, then the matrix dTdA will have 2 rows.
296  // ExecutionTrace::reverseAD1 just passes this on to CallRecord::reverseAD2
297  // which calls the correctly sized CallRecord::reverseAD3, which in turn
298  // calls reverseAD4 below.
299  trace1.reverseAD1(dTdA1, jacobians);
300  }
301 
303  template<typename MatrixType>
304  void reverseAD4(const MatrixType & dFdT, JacobianMap& jacobians) const {
305  trace1.reverseAD1(dFdT * dTdA1, jacobians);
306  }
307  };
308 
311  char* ptr) const override {
312  assert(reinterpret_cast<size_t>(ptr) % TraceAlignment == 0);
313 
314  // Create a Record in the memory pointed to by ptr
315  // Calling the constructor will record the traces for all arguments
316  // Write an Expression<A> execution trace in record->trace
317  // Iff Constant or Leaf, this will not write to traceStorage, only to trace.
318  // Iff the expression is functional, write all Records in traceStorage buffer
319  // Return value of type T is recorded in record->value
320  // NOTE(frank, abe): The destructor on this record is never called due to this placement new
321  // Records must only contain statically sized objects!
322  Record* record = new (ptr) Record(values, *expression1_, ptr);
323 
324  // Our trace parameter is set to point to the Record
325  trace.setFunction(record);
326 
327  // Finally, the function call fills in the Jacobian dTdA1
328  return function_(record->value1, record->dTdA1);
329  }
330 };
331 
332 //-----------------------------------------------------------------------------
334 template<class T, class A1, class A2>
336 
338  std::shared_ptr<ExpressionNode<A1> > expression1_;
339  std::shared_ptr<ExpressionNode<A2> > expression2_;
341 
344  const Expression<A2>& e2) :
345  expression1_(e1.root()), expression2_(e2.root()), function_(f) {
346  this->traceSize_ = //
347  upAligned(sizeof(Record)) + e1.traceSize() + e2.traceSize();
348  }
349 
350  friend class Expression<T>;
351  friend class ::ExpressionFactorBinaryTest;
352 
353 public:
354 
356  ~BinaryExpression() override {
357  }
358 
360  void print(const std::string& indent = "") const override {
361  std::cout << indent << "BinaryExpression" << std::endl;
362  expression1_->print(indent + " ");
363  expression2_->print(indent + " ");
364  }
365 
367  T value(const Values& values) const override {
368  using std::nullopt;
369  return function_(expression1_->value(values), expression2_->value(values),
370  {}, {});
371  }
372 
374  std::set<Key> keys() const override {
375  std::set<Key> keys = expression1_->keys();
376  std::set<Key> myKeys = expression2_->keys();
377  keys.insert(myKeys.begin(), myKeys.end());
378  return keys;
379  }
380 
382  void dims(std::map<Key, int>& map) const override {
383  expression1_->dims(map);
384  expression2_->dims(map);
385  }
386 
387  // Inner Record Class
388  struct Record: public CallRecordImplementor<Record, traits<T>::dimension> {
389 
392 
395 
396  // TODO(frank): These aren't needed kill them!
399 
401  Record(const Values& values, const ExpressionNode<A1>& expression1,
402  const ExpressionNode<A2>& expression2, char* ptr)
403  : value1(expression1.traceExecution(values, trace1, ptr += upAligned(sizeof(Record)))),
404  value2(expression2.traceExecution(values, trace2, ptr += expression1.traceSize())) {}
405 
407  void print(const std::string& indent) const {
408  std::cout << indent << "BinaryExpression::Record {" << std::endl;
409  PrintJacobianAndTrace<T,A1>(indent, dTdA1, trace1);
410  PrintJacobianAndTrace<T,A2>(indent, dTdA2, trace2);
411  std::cout << indent << "}" << std::endl;
412  }
413 
415  void startReverseAD4(JacobianMap& jacobians) const {
416  trace1.reverseAD1(dTdA1, jacobians);
417  trace2.reverseAD1(dTdA2, jacobians);
418  }
419 
421  template<typename MatrixType>
422  void reverseAD4(const MatrixType & dFdT, JacobianMap& jacobians) const {
423  trace1.reverseAD1(dFdT * dTdA1, jacobians);
424  trace2.reverseAD1(dFdT * dTdA2, jacobians);
425  }
426  };
427 
430  char* ptr) const override {
431  assert(reinterpret_cast<size_t>(ptr) % TraceAlignment == 0);
432  Record* record = new (ptr) Record(values, *expression1_, *expression2_, ptr);
433  trace.setFunction(record);
434  return function_(record->value1, record->value2, record->dTdA1, record->dTdA2);
435  }
436 };
437 
438 //-----------------------------------------------------------------------------
440 template<class T, class A1, class A2, class A3>
442 
444  std::shared_ptr<ExpressionNode<A1> > expression1_;
445  std::shared_ptr<ExpressionNode<A2> > expression2_;
446  std::shared_ptr<ExpressionNode<A3> > expression3_;
448 
451  const Expression<A2>& e2, const Expression<A3>& e3) :
452  expression1_(e1.root()), expression2_(e2.root()), expression3_(e3.root()), //
453  function_(f) {
454  this->traceSize_ = upAligned(sizeof(Record)) + //
455  e1.traceSize() + e2.traceSize() + e3.traceSize();
456  }
457 
458  friend class Expression<T>;
459 
460 public:
461 
463  ~TernaryExpression() override {
464  }
465 
467  void print(const std::string& indent = "") const override {
468  std::cout << indent << "TernaryExpression" << std::endl;
469  expression1_->print(indent + " ");
470  expression2_->print(indent + " ");
471  expression3_->print(indent + " ");
472  }
473 
475  T value(const Values& values) const override {
476  using std::nullopt;
477  return function_(expression1_->value(values), expression2_->value(values),
478  expression3_->value(values), {}, {}, {});
479  }
480 
482  std::set<Key> keys() const override {
483  std::set<Key> keys = expression1_->keys();
484  std::set<Key> myKeys = expression2_->keys();
485  keys.insert(myKeys.begin(), myKeys.end());
486  myKeys = expression3_->keys();
487  keys.insert(myKeys.begin(), myKeys.end());
488  return keys;
489  }
490 
492  void dims(std::map<Key, int>& map) const override {
493  expression1_->dims(map);
494  expression2_->dims(map);
495  expression3_->dims(map);
496  }
497 
498  // Inner Record Class
499  struct Record: public CallRecordImplementor<Record, traits<T>::dimension> {
500 
502 
506 
510 
514 
516  Record(const Values& values, const ExpressionNode<A1>& expression1,
517  const ExpressionNode<A2>& expression2,
518  const ExpressionNode<A3>& expression3, char* ptr)
519  : value1(expression1.traceExecution(values, trace1, ptr += upAligned(sizeof(Record)))),
520  value2(expression2.traceExecution(values, trace2, ptr += expression1.traceSize())),
521  value3(expression3.traceExecution(values, trace3, ptr += expression2.traceSize())) {}
522 
524  void print(const std::string& indent) const {
525  std::cout << indent << "TernaryExpression::Record {" << std::endl;
526  PrintJacobianAndTrace<T,A1>(indent, dTdA1, trace1);
527  PrintJacobianAndTrace<T,A2>(indent, dTdA2, trace2);
528  PrintJacobianAndTrace<T,A3>(indent, dTdA3, trace3);
529  std::cout << indent << "}" << std::endl;
530  }
531 
533  void startReverseAD4(JacobianMap& jacobians) const {
534  trace1.reverseAD1(dTdA1, jacobians);
535  trace2.reverseAD1(dTdA2, jacobians);
536  trace3.reverseAD1(dTdA3, jacobians);
537  }
538 
540  template<typename MatrixType>
541  void reverseAD4(const MatrixType & dFdT, JacobianMap& jacobians) const {
542  trace1.reverseAD1(dFdT * dTdA1, jacobians);
543  trace2.reverseAD1(dFdT * dTdA2, jacobians);
544  trace3.reverseAD1(dFdT * dTdA3, jacobians);
545  }
546  };
547 
550  char* ptr) const override {
551  assert(reinterpret_cast<size_t>(ptr) % TraceAlignment == 0);
552  Record* record = new (ptr) Record(values, *expression1_, *expression2_, *expression3_, ptr);
553  trace.setFunction(record);
554  return function_(record->value1, record->value2, record->value3,
555  record->dTdA1, record->dTdA2, record->dTdA3);
556  }
557 };
558 
559 //-----------------------------------------------------------------------------
561 template <class T>
563  // Check that T is a vector space
565 
566  double scalar_;
567  std::shared_ptr<ExpressionNode<T> > expression_;
568 
569  public:
571  ScalarMultiplyNode(double s, const Expression<T>& e) : scalar_(s), expression_(e.root()) {
572  this->traceSize_ = upAligned(sizeof(Record)) + e.traceSize();
573  }
574 
576  ~ScalarMultiplyNode() override {}
577 
579  void print(const std::string& indent = "") const override {
580  std::cout << indent << "ScalarMultiplyNode" << std::endl;
581  expression_->print(indent + " ");
582  }
583 
585  T value(const Values& values) const override {
586  return scalar_ * expression_->value(values);
587  }
588 
590  std::set<Key> keys() const override {
591  return expression_->keys();
592  }
593 
595  void dims(std::map<Key, int>& map) const override {
596  expression_->dims(map);
597  }
598 
599  // Inner Record Class
600  struct Record : public CallRecordImplementor<Record, traits<T>::dimension> {
601  static const int Dim = traits<T>::dimension;
603 
604  double scalar_dTdA;
606 
608  void print(const std::string& indent) const {
609  std::cout << indent << "ScalarMultiplyNode::Record {" << std::endl;
610  std::cout << indent << "D(" << demangle(typeid(T).name()) << ")/D(" << demangle(typeid(T).name())
611  << ") = " << scalar_dTdA << std::endl;
612  trace.print();
613  std::cout << indent << "}" << std::endl;
614  }
615 
617  void startReverseAD4(JacobianMap& jacobians) const {
618  trace.reverseAD1(scalar_dTdA * JacobianTT::Identity(), jacobians);
619  }
620 
622  template <typename MatrixType>
623  void reverseAD4(const MatrixType& dFdT, JacobianMap& jacobians) const {
624  trace.reverseAD1(dFdT * scalar_dTdA, jacobians);
625  }
626  };
627 
630  char* ptr) const override {
631  assert(reinterpret_cast<size_t>(ptr) % TraceAlignment == 0);
632  Record* record = new (ptr) Record();
633  ptr += upAligned(sizeof(Record));
634  T value = expression_->traceExecution(values, record->trace, ptr);
635  ptr += expression_->traceSize();
636  trace.setFunction(record);
637  record->scalar_dTdA = scalar_;
638  return scalar_ * value;
639  }
640 };
641 
642 
643 //-----------------------------------------------------------------------------
645 template <class T>
646 class BinarySumNode : public ExpressionNode<T> {
648  std::shared_ptr<ExpressionNode<T> > expression1_;
649  std::shared_ptr<ExpressionNode<T> > expression2_;
650 
651  public:
652  explicit BinarySumNode() {
653  this->traceSize_ = upAligned(sizeof(Record));
654  }
655 
658  : expression1_(e1.root()), expression2_(e2.root()) {
659  this->traceSize_ = //
660  upAligned(sizeof(Record)) + e1.traceSize() + e2.traceSize();
661  }
662 
664  ~BinarySumNode() override {}
665 
667  void print(const std::string& indent = "") const override {
668  std::cout << indent << "BinarySumNode" << std::endl;
669  expression1_->print(indent + " ");
670  expression2_->print(indent + " ");
671  }
672 
674  T value(const Values& values) const override {
675  return expression1_->value(values) + expression2_->value(values);
676  }
677 
679  std::set<Key> keys() const override {
680  std::set<Key> keys = expression1_->keys();
681  std::set<Key> myKeys = expression2_->keys();
682  keys.insert(myKeys.begin(), myKeys.end());
683  return keys;
684  }
685 
687  void dims(std::map<Key, int>& map) const override {
688  expression1_->dims(map);
689  expression2_->dims(map);
690  }
691 
692  // Inner Record Class
693  struct Record : public CallRecordImplementor<Record, traits<T>::dimension> {
696 
698  void print(const std::string& indent) const {
699  std::cout << indent << "BinarySumNode::Record {" << std::endl;
700  trace1.print(indent);
701  trace2.print(indent);
702  std::cout << indent << "}" << std::endl;
703  }
704 
706  void startReverseAD4(JacobianMap& jacobians) const {
707  // NOTE(frank): equivalent to trace.reverseAD1(dTdA, jacobians) with dTdA=Identity
708  trace1.startReverseAD1(jacobians);
709  trace2.startReverseAD1(jacobians);
710  }
711 
713  template <typename MatrixType>
714  void reverseAD4(const MatrixType& dFdT, JacobianMap& jacobians) const {
715  // NOTE(frank): equivalent to trace.reverseAD1(dFdT * dTdA, jacobians) with dTdA=Identity
716  trace1.reverseAD1(dFdT, jacobians);
717  trace2.reverseAD1(dFdT, jacobians);
718  }
719  };
720 
723  char* ptr) const override {
724  assert(reinterpret_cast<size_t>(ptr) % TraceAlignment == 0);
725  Record *record = new (ptr) Record();
726  trace.setFunction(record);
727 
728  auto ptr1 = ptr + upAligned(sizeof(Record));
729  auto ptr2 = ptr1 + expression1_->traceSize();
730  return expression1_->traceExecution(values, record->trace1, ptr1) +
731  expression2_->traceExecution(values, record->trace2, ptr2);
732  }
733 };
734 
735 } // namespace internal
736 } // namespace gtsam
gtsam::internal::UnaryExpression::Record::trace1
ExecutionTrace< A1 > trace1
Definition: ExpressionNode.h:275
gtsam::internal::BinarySumNode::Record::trace1
ExecutionTrace< T > trace1
Definition: ExpressionNode.h:694
gtsam::internal::UnaryExpression::UnaryExpression
UnaryExpression(Function f, const Expression< A1 > &e1)
Constructor with a unary function f, and input argument e1.
Definition: ExpressionNode.h:237
gtsam::internal::ExpressionNode::traceSize
size_t traceSize() const
Definition: ExpressionNode.h:104
gtsam::internal::LeafExpression::keys
std::set< Key > keys() const override
Return keys that play in this expression.
Definition: ExpressionNode.h:184
gtsam::internal::BinarySumNode::Record
Definition: ExpressionNode.h:693
gtsam::internal::ConstantExpression
Constant Expression.
Definition: ExpressionNode.h:119
gtsam::internal::ExecutionTrace
Definition: Expression.h:39
gtsam::internal::ExecutionTrace::setLeaf
void setLeaf(Key key)
Change pointer to a Leaf Record.
Definition: ExecutionTrace.h:120
gtsam::internal::BinarySumNode::Record::startReverseAD4
void startReverseAD4(JacobianMap &jacobians) const
If the BinarySumExpression is the root, we just start as many pipelines as there are terms.
Definition: ExpressionNode.h:706
Eigen::IOFormat
Stores a set of parameters controlling the way matrices are printed.
Definition: IO.h:51
gtsam::internal::BinaryExpression::Record::dTdA1
Jacobian< T, A1 >::type dTdA1
Definition: ExpressionNode.h:390
gtsam::internal::TernaryExpression::Record::reverseAD4
void reverseAD4(const MatrixType &dFdT, JacobianMap &jacobians) const
Given df/dT, multiply in dT/dA and continue reverse AD process.
Definition: ExpressionNode.h:541
A3
static const double A3[]
Definition: expn.h:8
gtsam::internal::ExpressionNode::dims
virtual void dims(std::map< Key, int > &map) const
Return dimensions for each argument, as a map.
Definition: ExpressionNode.h:100
gtsam.examples.DogLegOptimizerExample.type
type
Definition: DogLegOptimizerExample.py:111
gtsam::internal::ExpressionNode::~ExpressionNode
virtual ~ExpressionNode()
Destructor.
Definition: ExpressionNode.h:78
gtsam::internal::Jacobian::type
Eigen::Matrix< double, traits< T >::dimension, traits< A >::dimension > type
Definition: ExpressionNode.h:213
s
RealScalar s
Definition: level1_cplx_impl.h:126
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
gtsam::internal::BinaryExpression::Record::trace1
ExecutionTrace< A1 > trace1
Definition: ExpressionNode.h:393
gtsam::internal::ScalarMultiplyNode::expression_
std::shared_ptr< ExpressionNode< T > > expression_
Definition: ExpressionNode.h:567
gtsam::internal::ExpressionNode::traceExecution
virtual T traceExecution(const Values &values, ExecutionTrace< T > &trace, char *traceStorage) const =0
Construct an execution trace for reverse AD.
MatrixType
MatrixXf MatrixType
Definition: benchmark-blocking-sizes.cpp:52
gtsam::internal::TernaryExpression::Record::value3
A3 value3
Definition: ExpressionNode.h:513
gtsam::internal::UnaryExpression::print
void print(const std::string &indent="") const override
Print.
Definition: ExpressionNode.h:251
gtsam::internal::TraceAlignment
static const unsigned TraceAlignment
Definition: ExecutionTrace.h:45
gtsam::internal::ExpressionNode::operator<<
GTSAM_EXPORT friend std::ostream & operator<<(std::ostream &os, const ExpressionNode &node)
Streaming.
Definition: ExpressionNode.h:86
gtsam::internal::BinaryExpression::Record::dTdA2
Jacobian< T, A2 >::type dTdA2
Definition: ExpressionNode.h:391
gtsam::internal::UnaryExpression::dims
void dims(std::map< Key, int > &map) const override
Return dimensions for each argument.
Definition: ExpressionNode.h:267
gtsam::internal::BinaryExpression::keys
std::set< Key > keys() const override
Return keys that play in this expression.
Definition: ExpressionNode.h:374
gtsam::internal::BinarySumNode::dims
void dims(std::map< Key, int > &map) const override
Return dimensions for each argument.
Definition: ExpressionNode.h:687
gtsam::internal::UnaryExpression
Unary Function Expression.
Definition: ExpressionNode.h:230
gtsam::internal::BinarySumNode::expression1_
std::shared_ptr< ExpressionNode< T > > expression1_
Definition: ExpressionNode.h:648
gtsam::internal::TernaryExpression::print
void print(const std::string &indent="") const override
Print.
Definition: ExpressionNode.h:467
gtsam::internal::LeafExpression::print
void print(const std::string &indent="") const override
Print.
Definition: ExpressionNode.h:179
gtsam::internal::upAligned
T upAligned(T value, unsigned requiredAlignment=TraceAlignment)
Definition: ExpressionNode.h:50
gtsam::internal::ScalarMultiplyNode::keys
std::set< Key > keys() const override
Return keys that play in this expression.
Definition: ExpressionNode.h:590
gtsam::internal::BinaryExpression::expression2_
std::shared_ptr< ExpressionNode< A2 > > expression2_
Definition: ExpressionNode.h:339
gtsam::internal::ExpressionNode
Definition: Expression.h:40
gtsam::internal::ConstantExpression::value
T value(const Values &values) const override
Return value.
Definition: ExpressionNode.h:143
gtsam::internal::LeafExpression::value_type
T value_type
Definition: ExpressionNode.h:160
gtsam::internal::ExecutionTrace::reverseAD1
void reverseAD1(const Eigen::MatrixBase< DerivedMatrix > &dTdA, JacobianMap &jacobians) const
Either add to Jacobians (Leaf) or propagate (Function)
Definition: ExecutionTrace.h:174
gtsam::internal::LeafExpression::dims
void dims(std::map< Key, int > &map) const override
Return dimensions for each argument.
Definition: ExpressionNode.h:191
gtsam::internal::TernaryExpression::keys
std::set< Key > keys() const override
Return keys that play in this expression.
Definition: ExpressionNode.h:482
gtsam::internal::UnaryExpression::traceExecution
T traceExecution(const Values &values, ExecutionTrace< T > &trace, char *ptr) const override
Construct an execution trace for reverse AD.
Definition: ExpressionNode.h:310
gtsam::internal::ScalarMultiplyNode::Record::startReverseAD4
void startReverseAD4(JacobianMap &jacobians) const
Start the reverse AD process.
Definition: ExpressionNode.h:617
gtsam::internal::BinarySumNode::~BinarySumNode
~BinarySumNode() override
Destructor.
Definition: ExpressionNode.h:664
gtsam::internal::TernaryExpression::Record::trace1
ExecutionTrace< A1 > trace1
Definition: ExpressionNode.h:507
gtsam::internal::ScalarMultiplyNode::Record
Definition: ExpressionNode.h:600
os
ofstream os("timeSchurFactors.csv")
gtsam::internal::LeafExpression::key_
Key key_
The key into values.
Definition: ExpressionNode.h:163
gtsam::internal::BinaryExpression::BinaryExpression
BinaryExpression(Function f, const Expression< A1 > &e1, const Expression< A2 > &e2)
Constructor with a binary function f, and two input arguments.
Definition: ExpressionNode.h:343
gtsam::IsVectorSpace
Vector Space concept.
Definition: VectorSpace.h:470
gtsam::internal::UnaryExpression::~UnaryExpression
~UnaryExpression() override
Destructor.
Definition: ExpressionNode.h:247
gtsam::internal::ScalarMultiplyNode::value
T value(const Values &values) const override
Return value.
Definition: ExpressionNode.h:585
gtsam::internal::TernaryExpression::Record::trace2
ExecutionTrace< A2 > trace2
Definition: ExpressionNode.h:508
ExecutionTrace.h
Execution trace for expressions.
gtsam::internal::BinaryExpression::function_
Function function_
Definition: ExpressionNode.h:340
gtsam::DefaultKeyFormatter
KeyFormatter DefaultKeyFormatter
Assign default key formatter.
Definition: Key.cpp:30
name
static char name[]
Definition: rgamma.c:72
gtsam::internal::BinaryExpression::traceExecution
T traceExecution(const Values &values, ExecutionTrace< T > &trace, char *ptr) const override
Construct an execution trace for reverse AD, see UnaryExpression for explanation.
Definition: ExpressionNode.h:429
gtsam::Expression
Definition: Expression.h:47
gtsam::internal::TernaryExpression::~TernaryExpression
~TernaryExpression() override
Destructor.
Definition: ExpressionNode.h:463
gtsam::internal::UnaryExpression::keys
std::set< Key > keys() const override
Return keys that play in this expression.
Definition: ExpressionNode.h:262
gtsam::internal::ConstantExpression::print
void print(const std::string &indent="") const override
Print.
Definition: ExpressionNode.h:138
gtsam::Values::at
const ValueType at(Key j) const
Definition: Values-inl.h:261
gtsam::internal::TernaryExpression::Record::dTdA1
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Jacobian< T, A1 >::type dTdA1
Definition: ExpressionNode.h:503
gtsam::internal::BinarySumNode::BinarySumNode
BinarySumNode()
Definition: ExpressionNode.h:652
gtsam::internal::TernaryExpression::expression2_
std::shared_ptr< ExpressionNode< A2 > > expression2_
Definition: ExpressionNode.h:445
A
Definition: test_numpy_dtypes.cpp:298
gtsam::internal::TernaryExpression::dims
void dims(std::map< Key, int > &map) const override
Return dimensions for each argument.
Definition: ExpressionNode.h:492
gtsam::internal::TernaryExpression::Record::Record
Record(const Values &values, const ExpressionNode< A1 > &expression1, const ExpressionNode< A2 > &expression2, const ExpressionNode< A3 > &expression3, char *ptr)
Construct record by calling 3 argument expressions.
Definition: ExpressionNode.h:516
gtsam::internal::LeafExpression::LeafExpression
LeafExpression(Key key)
Constructor with a single key.
Definition: ExpressionNode.h:166
gtsam::internal::BinaryExpression::Record::startReverseAD4
void startReverseAD4(JacobianMap &jacobians) const
Start the reverse AD process, see comments in UnaryExpression.
Definition: ExpressionNode.h:415
gtsam::internal::BinarySumNode::Record::reverseAD4
void reverseAD4(const MatrixType &dFdT, JacobianMap &jacobians) const
If we are not the root, we simply pass on the adjoint matrix dFdT to all terms.
Definition: ExpressionNode.h:714
gtsam::internal::UnaryExpression::Record::Record
Record(const Values &values, const ExpressionNode< A1 > &expression1, char *ptr)
Construct record by calling argument expression.
Definition: ExpressionNode.h:279
gtsam::internal::PrintJacobianAndTrace
static void PrintJacobianAndTrace(const std::string &indent, const typename Jacobian< T, A >::type &dTdA, const ExecutionTrace< A > trace)
Definition: ExpressionNode.h:218
gtsam::internal::ScalarMultiplyNode
Expression for scalar multiplication.
Definition: ExpressionNode.h:562
gtsam::internal::TernaryExpression::TernaryExpression
TernaryExpression(Function f, const Expression< A1 > &e1, const Expression< A2 > &e2, const Expression< A3 > &e3)
Constructor with a ternary function f, and two input arguments.
Definition: ExpressionNode.h:450
gtsam::internal::ConstantExpression::~ConstantExpression
~ConstantExpression() override
Destructor.
Definition: ExpressionNode.h:134
gtsam::internal::CallRecordImplementor
Definition: CallRecord.h:140
gtsam::internal::JacobianMap
Definition: JacobianMap.h:32
A2
static const double A2[]
Definition: expn.h:7
gtsam::internal::TernaryExpression
Ternary Expression.
Definition: ExpressionNode.h:441
gtsam::internal::BinarySumNode::value
T value(const Values &values) const override
Return value.
Definition: ExpressionNode.h:674
gtsam::internal::BinarySumNode
Binary Sum Expression.
Definition: ExpressionNode.h:646
gtsam::internal::TernaryExpression::Record
Definition: ExpressionNode.h:499
gtsam::internal::TernaryExpression::Record::dTdA3
Jacobian< T, A3 >::type dTdA3
Definition: ExpressionNode.h:505
gtsam::internal::TernaryExpression::Record::dTdA2
Jacobian< T, A2 >::type dTdA2
Definition: ExpressionNode.h:504
gtsam::internal::ScalarMultiplyNode::Record::scalar_dTdA
double scalar_dTdA
Definition: ExpressionNode.h:604
Eigen::Triplet< double >
gtsam::internal::UnaryExpression::Record
Definition: ExpressionNode.h:272
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
#define EIGEN_MAKE_ALIGNED_OPERATOR_NEW
Definition: Memory.h:841
gtsam::internal::ExecutionTrace::print
void print(const std::string &indent="") const
Print.
Definition: ExecutionTrace.h:132
gtsam::internal::ScalarMultiplyNode::scalar_
double scalar_
Definition: ExpressionNode.h:566
gtsam::internal::BinaryExpression::expression1_
std::shared_ptr< ExpressionNode< A1 > > expression1_
Definition: ExpressionNode.h:338
gtsam::internal::TernaryExpression::Record::value1
A1 value1
Definition: ExpressionNode.h:511
gtsam::internal::BinaryExpression::Record::print
void print(const std::string &indent) const
Print to std::cout.
Definition: ExpressionNode.h:407
gtsam::internal::UnaryExpression::Record::startReverseAD4
void startReverseAD4(JacobianMap &jacobians) const
Start the reverse AD process.
Definition: ExpressionNode.h:290
key
const gtsam::Symbol key('X', 0)
gtsam::internal::BinaryExpression::Record::trace2
ExecutionTrace< A2 > trace2
Definition: ExpressionNode.h:394
gtsam::internal::BinarySumNode::print
void print(const std::string &indent="") const override
Print.
Definition: ExpressionNode.h:667
gtsam::internal::ExpressionNode::print
virtual void print(const std::string &indent="") const =0
Print.
tree::f
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Definition: testExpression.cpp:218
gtsam::internal::BinaryExpression::Record
Definition: ExpressionNode.h:388
gtsam::internal::ScalarMultiplyNode::Record::reverseAD4
void reverseAD4(const MatrixType &dFdT, JacobianMap &jacobians) const
Given df/dT, multiply in dT/dA and continue reverse AD process.
Definition: ExpressionNode.h:623
gtsam::internal::BinaryExpression::Record::reverseAD4
void reverseAD4(const MatrixType &dFdT, JacobianMap &jacobians) const
Given df/dT, multiply in dT/dA and continue reverse AD process.
Definition: ExpressionNode.h:422
gtsam::internal::ConstantExpression::traceExecution
T traceExecution(const Values &values, ExecutionTrace< T > &trace, char *traceStorage) const override
Construct an execution trace for reverse AD.
Definition: ExpressionNode.h:148
gtsam
traits
Definition: chartTesting.h:28
gtsam::internal::LeafExpression::value
T value(const Values &values) const override
Return value.
Definition: ExpressionNode.h:196
gtsam::internal::ExpressionNode::value
virtual T value(const Values &values) const =0
Return value.
gtsam::internal::BinarySumNode::BinarySumNode
BinarySumNode(const Expression< T > &e1, const Expression< T > &e2)
Constructor with a binary function f, and two input arguments.
Definition: ExpressionNode.h:657
gtsam::traits
Definition: Group.h:36
gtsam::internal::TernaryExpression::Record::startReverseAD4
void startReverseAD4(JacobianMap &jacobians) const
Start the reverse AD process, see comments in Base.
Definition: ExpressionNode.h:533
gtsam::internal::TernaryExpression::Record::trace3
ExecutionTrace< A3 > trace3
Definition: ExpressionNode.h:509
gtsam::internal::ScalarMultiplyNode::Record::trace
ExecutionTrace< T > trace
Definition: ExpressionNode.h:605
gtsam::internal::UnaryExpression::function_
Function function_
Definition: ExpressionNode.h:234
leaf::values
leaf::MyValues values
gtsam::Values
Definition: Values.h:65
gtsam::internal::TernaryExpression::Record::value2
A2 value2
Definition: ExpressionNode.h:512
gtsam::demangle
std::string demangle(const char *name)
Pretty print Value type name.
Definition: types.cpp:37
gtsam::Expression::traceSize
size_t traceSize() const
Return size needed for memory buffer in traceExecution.
Definition: Expression-inl.h:160
gtsam::internal::TernaryExpression::value
T value(const Values &values) const override
Return value.
Definition: ExpressionNode.h:475
gtsam::internal::BinaryExpression
Binary Expression.
Definition: ExpressionNode.h:335
gtsam::internal::ExpressionNode::keys
virtual std::set< Key > keys() const
Return keys that play in this expression as a set.
Definition: ExpressionNode.h:94
gtsam::internal::TernaryExpression::Record::print
void print(const std::string &indent) const
Print to std::cout.
Definition: ExpressionNode.h:524
A1
static const double A1[]
Definition: expn.h:6
gtsam::internal::ExecutionTrace::setFunction
void setFunction(CallRecord< Dim > *record)
Take ownership of pointer to a Function Record.
Definition: ExecutionTrace.h:126
gtsam::internal::UnaryExpression::Function
Expression< T >::template UnaryFunction< A1 >::type Function
Definition: ExpressionNode.h:232
gtsam::internal::BinarySumNode::expression2_
std::shared_ptr< ExpressionNode< T > > expression2_
Definition: ExpressionNode.h:649
gtsam::internal::LeafExpression
Leaf Expression, if no chart is given, assume default chart and value_type is just the plain value.
Definition: ExpressionNode.h:159
gtsam::internal::ScalarMultiplyNode::traceExecution
T traceExecution(const Values &values, ExecutionTrace< T > &trace, char *ptr) const override
Construct an execution trace for reverse AD.
Definition: ExpressionNode.h:629
gtsam::internal::TernaryExpression::expression1_
std::shared_ptr< ExpressionNode< A1 > > expression1_
Definition: ExpressionNode.h:444
gtsam::internal::BinaryExpression::Record::value2
A2 value2
Definition: ExpressionNode.h:398
gtsam::internal::LeafExpression::~LeafExpression
~LeafExpression() override
Destructor.
Definition: ExpressionNode.h:175
gtsam::internal::ScalarMultiplyNode::~ScalarMultiplyNode
~ScalarMultiplyNode() override
Destructor.
Definition: ExpressionNode.h:576
gtsam::internal::UnaryExpression::Record::value1
A1 value1
Definition: ExpressionNode.h:276
gtsam::internal::BinaryExpression::print
void print(const std::string &indent="") const override
Print.
Definition: ExpressionNode.h:360
gtsam::internal::ConstantExpression::ConstantExpression
ConstantExpression(const T &value)
Constructor with a value, yielding a constant.
Definition: ExpressionNode.h:125
Eigen::Matrix
The matrix class, also used for vectors and row-vectors.
Definition: 3rdparty/Eigen/Eigen/src/Core/Matrix.h:178
gtsam::internal::ScalarMultiplyNode::Record::Dim
static const int Dim
Definition: ExpressionNode.h:601
gtsam::internal::upAlign
T & upAlign(T &value, unsigned requiredAlignment=TraceAlignment)
Definition: ExpressionNode.h:37
gtsam::internal::ScalarMultiplyNode::Record::JacobianTT
Eigen::Matrix< double, Dim, Dim > JacobianTT
Definition: ExpressionNode.h:602
internal
Definition: BandTriangularSolver.h:13
gtsam::internal::BinaryExpression::Function
Expression< T >::template BinaryFunction< A1, A2 >::type Function
Definition: ExpressionNode.h:337
gtsam::internal::BinarySumNode::NodeT
ExpressionNode< T > NodeT
Definition: ExpressionNode.h:647
gtsam::internal::Jacobian
meta-function to generate fixed-size JacobianTA type
Definition: ExpressionNode.h:212
gtsam::internal::UnaryExpression::Record::dTdA1
Jacobian< T, A1 >::type dTdA1
Definition: ExpressionNode.h:274
gtsam::internal::LeafExpression::traceExecution
T traceExecution(const Values &values, ExecutionTrace< T > &trace, char *traceStorage) const override
Construct an execution trace for reverse AD.
Definition: ExpressionNode.h:201
gtsam::internal::BinaryExpression::value
T value(const Values &values) const override
Return value.
Definition: ExpressionNode.h:367
gtsam::internal::ScalarMultiplyNode::Record::print
void print(const std::string &indent) const
Print to std::cout.
Definition: ExpressionNode.h:608
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
gtsam::internal::BinaryExpression::dims
void dims(std::map< Key, int > &map) const override
Return dimensions for each argument.
Definition: ExpressionNode.h:382
gtsam::internal::ExpressionNode::traceSize_
size_t traceSize_
Definition: ExpressionNode.h:68
gtsam::internal::TernaryExpression::Function
Expression< T >::template TernaryFunction< A1, A2, A3 >::type Function
Definition: ExpressionNode.h:443
gtsam::internal::ScalarMultiplyNode::ScalarMultiplyNode
ScalarMultiplyNode(double s, const Expression< T > &e)
Constructor with a unary function f, and input argument e1.
Definition: ExpressionNode.h:571
gtsam::internal::BinaryExpression::Record::Record
Record(const Values &values, const ExpressionNode< A1 > &expression1, const ExpressionNode< A2 > &expression2, char *ptr)
Construct record by calling argument expressions.
Definition: ExpressionNode.h:401
gtsam::internal::TernaryExpression::traceExecution
T traceExecution(const Values &values, ExecutionTrace< T > &trace, char *ptr) const override
Construct an execution trace for reverse AD, see UnaryExpression for explanation.
Definition: ExpressionNode.h:549
gtsam::internal::BinarySumNode::keys
std::set< Key > keys() const override
Return keys that play in this expression.
Definition: ExpressionNode.h:679
GTSAM_MAKE_ALIGNED_OPERATOR_NEW
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW
Definition: types.h:279
test_callbacks.value
value
Definition: test_callbacks.py:158
gtsam::internal::UnaryExpression::Record::reverseAD4
void reverseAD4(const MatrixType &dFdT, JacobianMap &jacobians) const
Given df/dT, multiply in dT/dA and continue reverse AD process.
Definition: ExpressionNode.h:304
gtsam::internal::BinarySumNode::Record::trace2
ExecutionTrace< T > trace2
Definition: ExpressionNode.h:695
gtsam::internal::BinaryExpression::~BinaryExpression
~BinaryExpression() override
Destructor.
Definition: ExpressionNode.h:356
gtsam::internal::ConstantExpression::constant_
T constant_
The constant value.
Definition: ExpressionNode.h:122
gtsam::internal::BinarySumNode::Record::print
void print(const std::string &indent) const
Print to std::cout.
Definition: ExpressionNode.h:698
gtsam::internal::UnaryExpression::value
T value(const Values &values) const override
Return value.
Definition: ExpressionNode.h:257
gtsam::internal::ScalarMultiplyNode::GTSAM_CONCEPT_ASSERT
GTSAM_CONCEPT_ASSERT(IsVectorSpace< T >)
gtsam::internal::ExpressionNode::ExpressionNode
ExpressionNode(size_t traceSize=0)
Constructor, traceSize is size of the execution trace of expression rooted here.
Definition: ExpressionNode.h:71
gtsam::internal::BinarySumNode::traceExecution
T traceExecution(const Values &values, ExecutionTrace< T > &trace, char *ptr) const override
Construct an execution trace for reverse AD.
Definition: ExpressionNode.h:722
gtsam::internal::UnaryExpression::Record::print
void print(const std::string &indent) const
Print to std::cout.
Definition: ExpressionNode.h:283
Values.h
A non-templated config holding any types of Manifold-group elements.
gtsam::internal::ScalarMultiplyNode::dims
void dims(std::map< Key, int > &map) const override
Return dimensions for each argument.
Definition: ExpressionNode.h:595
gtsam::internal::UnaryExpression::expression1_
std::shared_ptr< ExpressionNode< A1 > > expression1_
Definition: ExpressionNode.h:233
gtsam::internal::BinaryExpression::Record::value1
A1 value1
Definition: ExpressionNode.h:397
gtsam::internal::ScalarMultiplyNode::print
void print(const std::string &indent="") const override
Print.
Definition: ExpressionNode.h:579
gtsam::internal::TernaryExpression::function_
Function function_
Definition: ExpressionNode.h:447
gtsam::internal::TernaryExpression::expression3_
std::shared_ptr< ExpressionNode< A3 > > expression3_
Definition: ExpressionNode.h:446
CallRecord.h
Internals for Expression.h, not for general consumption.


gtsam
Author(s):
autogenerated on Thu Jun 13 2024 03:02:20