Expression.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 
23 #include <gtsam/inference/Symbol.h>
25 #include <gtsam/base/VectorSpace.h>
26 
27 #include <boost/bind.hpp>
28 #include <boost/make_shared.hpp>
29 #include <map>
30 
31 // Forward declare tests
32 class ExpressionFactorShallowTest;
33 
34 namespace gtsam {
35 
36 // Forward declares
37 class Values;
38 template<typename T> class ExpressionFactor;
39 
40 namespace internal {
41 template<typename T> class ExecutionTrace;
42 template<typename T> class ExpressionNode;
43 }
44 
48 template<typename T>
49 class Expression {
50 
51 public:
52 
55 
56 protected:
57 
58  // Paul's trick shared pointer, polymorphic root of entire expression tree
59  boost::shared_ptr<internal::ExpressionNode<T> > root_;
60 
62  Expression(const boost::shared_ptr<internal::ExpressionNode<T> >& root) : root_(root) {}
63 
64 public:
65 
66  // Expressions wrap trees of functions that can evaluate their own derivatives.
67  // The meta-functions below are useful to specify the type of those functions.
68  // Example, a function taking a camera and a 3D point and yielding a 2D point:
69  // Expression<Point2>::BinaryFunction<PinholeCamera<Cal3_S2>,Point3>::type
70  template<class A1>
71  struct UnaryFunction {
72  typedef boost::function<
73  T(const A1&, typename MakeOptionalJacobian<T, A1>::type)> type;
74  };
75 
76  template<class A1, class A2>
77  struct BinaryFunction {
78  typedef boost::function<
79  T(const A1&, const A2&, typename MakeOptionalJacobian<T, A1>::type,
81  };
82 
83  template<class A1, class A2, class A3>
84  struct TernaryFunction {
85  typedef boost::function<
86  T(const A1&, const A2&, const A3&,
90  };
91 
93  Expression(const T& value);
94 
96  Expression(const Key& key);
97 
99  Expression(const Symbol& symbol);
100 
102  Expression(unsigned char c, std::uint64_t j);
103 
105  template<typename A>
106  Expression(typename UnaryFunction<A>::type function,
107  const Expression<A>& expression);
108 
110  template<typename A1, typename A2>
111  Expression(typename BinaryFunction<A1, A2>::type function,
112  const Expression<A1>& expression1, const Expression<A2>& expression2);
113 
115  template<typename A1, typename A2, typename A3>
117  const Expression<A1>& expression1, const Expression<A2>& expression2,
118  const Expression<A3>& expression3);
119 
121  template<typename A>
122  Expression(const Expression<A>& expression,
123  T (A::*method)(typename MakeOptionalJacobian<T, A>::type) const);
124 
126  template<typename A1, typename A2>
127  Expression(const Expression<A1>& expression1,
128  T (A1::*method)(const A2&, typename MakeOptionalJacobian<T, A1>::type,
129  typename MakeOptionalJacobian<T, A2>::type) const,
130  const Expression<A2>& expression2);
131 
133  template<typename A1, typename A2, typename A3>
134  Expression(const Expression<A1>& expression1,
135  T (A1::*method)(const A2&, const A3&,
138  typename MakeOptionalJacobian<T, A3>::type) const,
139  const Expression<A2>& expression2, const Expression<A3>& expression3);
140 
142  virtual ~Expression() {
143  }
144 
146  std::set<Key> keys() const;
147 
149  void dims(std::map<Key, int>& map) const;
150 
152  void print(const std::string& s) const;
153 
159  T value(const Values& values, boost::optional<std::vector<Matrix>&> H =
160  boost::none) const;
161 
167  virtual boost::shared_ptr<Expression> clone() const {
168  return boost::make_shared<Expression>(*this);
169  }
170 
172  const boost::shared_ptr<internal::ExpressionNode<T> >& root() const;
173 
175  size_t traceSize() const;
176 
179 
180 protected:
181 
184 
186  typedef std::pair<KeyVector, FastVector<int> > KeysAndDims;
187  KeysAndDims keysAndDims() const;
188 
190  T valueAndDerivatives(const Values& values, const KeyVector& keys,
191  const FastVector<int>& dims, std::vector<Matrix>& H) const;
192 
194  T traceExecution(const Values& values, internal::ExecutionTrace<T>& trace,
195  void* traceStorage) const;
196 
198  T valueAndJacobianMap(const Values& values,
199  internal::JacobianMap& jacobians) const;
200 
201  // be very selective on who can access these private methods:
202  friend class ExpressionFactor<T> ;
204 
205  // and add tests
206  friend class ::ExpressionFactorShallowTest;
207 };
208 
213 template <typename T>
215  // Check that T is a vector space
217 
218  public:
219  explicit ScalarMultiplyExpression(double s, const Expression<T>& e);
220 };
221 
226 template <typename T>
227 class BinarySumExpression : public Expression<T> {
228  // Check that T is a vector space
230 
231  public:
232  explicit BinarySumExpression(const Expression<T>& e1, const Expression<T>& e2);
233 };
234 
235 
241 template <typename T, typename A>
243  const boost::function<T(A)>& f, const Expression<A>& expression,
245  // Use lambda to endow f with a linear Jacobian
247  [=](const A& value, typename MakeOptionalJacobian<T, A>::type H) {
248  if (H)
249  *H << dTdA;
250  return f(value);
251  };
252  return Expression<T>(g, expression);
253 }
254 
261 template <typename T>
264 }
265 
272 template <typename T>
274  return BinarySumExpression<T>(e1, e2);
275 }
276 
278 template <typename T>
280  // TODO(frank, abe): Implement an actual negate operator instead of multiplying by -1
281  return e1 + (-1.0) * e2;
282 }
283 
289 template<typename T>
290 Expression<T> operator*(const Expression<T>& e1, const Expression<T>& e2);
291 
297 template<typename T>
298 std::vector<Expression<T> > createUnknowns(size_t n, char c, size_t start = 0);
299 
300 } // namespace gtsam
301 
303 
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
std::pair< KeyVector, FastVector< int > > KeysAndDims
Keys and dimensions in same order.
Definition: Expression.h:186
boost::function< T(const A1 &, typename MakeOptionalJacobian< T, A1 >::type)> type
Definition: Expression.h:73
virtual boost::shared_ptr< Expression > clone() const
Definition: Expression.h:167
BOOST_CONCEPT_ASSERT((boost::RandomAccessRangeConcept< ListOfOneContainer< int > >))
int n
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
leaf::MyValues values
JacobianMap for returning derivatives from expressions.
std::vector< Expression< T > > createUnknowns(size_t n, char c, size_t start)
Construct an array of leaves.
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set set xzeroaxis lt lw set x2zeroaxis lt lw set yzeroaxis lt lw set y2zeroaxis lt lw set tics in set ticslevel set tics set mxtics default set mytics default set mx2tics default set my2tics default set xtics border mirror norotate autofreq set ytics border mirror norotate autofreq set ztics border nomirror norotate autofreq set nox2tics set noy2tics set timestamp bottom norotate set rrange[*:*] noreverse nowriteback set trange[*:*] noreverse nowriteback set urange[*:*] noreverse nowriteback set vrange[*:*] noreverse nowriteback set xlabel matrix size set x2label set timefmt d m y n H
const mpreal root(const mpreal &x, unsigned long int k, mp_rnd_t r=mpreal::get_default_rnd())
Definition: mpreal.h:2194
Vector Space concept.
Definition: VectorSpace.h:470
Point2 operator*(double s, const Point2 &p)
multiply with scalar
Definition: Point2.h:45
Expression< T > type
Define type so we can apply it as a meta-function.
Definition: Expression.h:54
void g(const string &key, int i)
Definition: testBTree.cpp:43
virtual ~Expression()
Destructor.
Definition: Expression.h:142
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:86
boost::shared_ptr< internal::ExpressionNode< T > > root_
Definition: Expression.h:59
unsigned __int64 uint64_t
Definition: ms_stdint.h:95
Eigen::Triplet< double > T
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
Expression(const boost::shared_ptr< internal::ExpressionNode< T > > &root)
Construct with a custom root.
Definition: Expression.h:62
BinarySumExpression< T > operator-(const Expression< T > &e1, const Expression< T > &e2)
Construct an expression that subtracts one expression from another.
Definition: Expression.h:279
Key symbol(unsigned char c, std::uint64_t j)
EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half & operator+=(half &a, const half &b)
Definition: Half.h:285
traits
Definition: chartTesting.h:28
Internals for Expression.h, not for general consumption.
std::vector< float > Values
boost::function< T(const A1 &, const A2 &, const A3 &, typename MakeOptionalJacobian< T, A1 >::type, typename MakeOptionalJacobian< T, A2 >::type, typename MakeOptionalJacobian< T, A3 >::type)> type
Definition: Expression.h:89
BinarySumExpression< T > operator+(const Expression< T > &e1, const Expression< T > &e2)
Definition: Expression.h:273
Expression()
Default constructor, for serialization.
Definition: Expression.h:183
boost::function< T(const A1 &, const A2 &, typename MakeOptionalJacobian< T, A1 >::type, typename MakeOptionalJacobian< T, A2 >::type)> type
Definition: Expression.h:80
std::vector< T, typename internal::FastDefaultVectorAllocator< T >::type > FastVector
Definition: FastVector.h:34
Special class for optional Jacobian arguments.
const KeyVector keys
The matrix class, also used for vectors and row-vectors.
Expression< T > linearExpression(const boost::function< T(A)> &f, const Expression< A > &expression, const Eigen::Matrix< double, traits< T >::dimension, traits< A >::dimension > &dTdA)
Definition: Expression.h:242
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
std::ptrdiff_t j


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