Expression-inl.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 
24 #include <map>
25 #include <memory>
26 #include <set>
27 #include <string>
28 #include <vector>
29 #include <cassert>
30 
31 
32 namespace gtsam {
33 
34 template<typename T>
36  root_(new internal::ConstantExpression<T>(value)) {
37 }
38 
39 template<typename T>
41  root_(new internal::LeafExpression<T>(key)) {
42 }
43 
44 template<typename T>
46  root_(new internal::LeafExpression<T>(symbol)) {
47 }
48 
49 template<typename T>
51  root_(new internal::LeafExpression<T>(Symbol(c, j))) {
52 }
53 
55 template<typename T>
56 template<typename A>
58  const Expression<A>& expression) :
59  root_(new internal::UnaryExpression<T, A>(function, expression)) {
60 }
61 
63 template<typename T>
64 template<typename A1, typename A2>
66  const Expression<A1>& expression1, const Expression<A2>& expression2) :
67  root_(
68  new internal::BinaryExpression<T, A1, A2>(function, expression1,
69  expression2)) {
70 }
71 
73 template<typename T>
74 template<typename A1, typename A2, typename A3>
76  const Expression<A1>& expression1, const Expression<A2>& expression2,
77  const Expression<A3>& expression3) :
78  root_(
79  new internal::TernaryExpression<T, A1, A2, A3>(function, expression1,
80  expression2, expression3)) {
81 }
82 
84 template<typename T>
85 template<typename A>
87  T (A::*method)(typename MakeOptionalJacobian<T, A>::type) const) :
88  root_(
89  new internal::UnaryExpression<T, A>(std::bind(method,
90  std::placeholders::_1, std::placeholders::_2),
91  expression)) {
92 }
93 
95 template<typename T>
96 template<typename A1, typename A2>
98  T (A1::*method)(const A2&, typename MakeOptionalJacobian<T, A1>::type,
99  typename MakeOptionalJacobian<T, A2>::type) const,
100  const Expression<A2>& expression2) :
101  root_(
102  new internal::BinaryExpression<T, A1, A2>(
103  std::bind(method, std::placeholders::_1,
104  std::placeholders::_2, std::placeholders::_3,
105  std::placeholders::_4),
106  expression1, expression2)) {
107 }
108 
110 template<typename T>
111 template<typename A1, typename A2, typename A3>
113  T (A1::*method)(const A2&, const A3&,
116  typename MakeOptionalJacobian<T, A3>::type) const,
117  const Expression<A2>& expression2, const Expression<A3>& expression3) :
118  root_(
119  new internal::TernaryExpression<T, A1, A2, A3>(
120  std::bind(method, std::placeholders::_1,
121  std::placeholders::_2, std::placeholders::_3,
122  std::placeholders::_4, std::placeholders::_5,
123  std::placeholders::_6),
124  expression1, expression2, expression3)) {
125 }
126 
127 template<typename T>
128 std::set<Key> Expression<T>::keys() const {
129  return root_->keys();
130 }
131 
132 template<typename T>
133 void Expression<T>::dims(std::map<Key, int>& map) const {
134  root_->dims(map);
135 }
136 
137 template<typename T>
138 void Expression<T>::print(const std::string& s) const {
139  root_->print(s);
140 }
141 
142 template<typename T>
144  std::vector<Matrix>* H) const {
145  if (H) {
146  // Call private version that returns derivatives in H
147  const auto [keys, dims] = keysAndDims();
148  return valueAndDerivatives(values, keys, dims, *H);
149  } else {
150  // no derivatives needed, just return value
151  return root_->value(values);
152  }
153 }
154 
155 template<typename T>
156 const std::shared_ptr<internal::ExpressionNode<T> >& Expression<T>::root() const {
157  return root_;
158 }
159 
160 template<typename T>
161 size_t Expression<T>::traceSize() const {
162  return root_->traceSize();
163 }
164 
165 // Private methods:
166 
167 template<typename T>
169  const KeyVector& keys, const FastVector<int>& dims,
170  std::vector<Matrix>& H) const {
171 
172  // H should be pre-allocated
173  assert(H.size()==keys.size());
174 
175  // Pre-allocate and zero VerticalBlockMatrix
176  static const int Dim = traits<T>::dimension;
177  VerticalBlockMatrix Ab(dims, Dim);
178  Ab.matrix().setZero();
179  internal::JacobianMap jacobianMap(keys, Ab);
180 
181  // Call unsafe version
182  T result = valueAndJacobianMap(values, jacobianMap);
183 
184  // Copy blocks into the vector of jacobians passed in
185  for (DenseIndex i = 0; i < static_cast<DenseIndex>(keys.size()); i++)
186  H[i] = Ab(i);
187 
188  return result;
189 }
190 
191 template<typename T>
193  internal::ExecutionTrace<T>& trace, char* traceStorage) const {
194  return root_->traceExecution(values, trace, traceStorage);
195 }
196 
197 // Allocate a single block of aligned memory using a unique_ptr.
198 inline std::unique_ptr<internal::ExecutionTraceStorage[]> allocAligned(size_t size) {
199  const size_t alignedSize = (size + internal::TraceAlignment - 1) / internal::TraceAlignment;
200  return std::unique_ptr<internal::ExecutionTraceStorage[]>(
201  new internal::ExecutionTraceStorage[alignedSize]);
202 }
203 
204 template<typename T>
206  internal::JacobianMap& jacobians) const {
207  try {
208  // We allocate a single block of aligned memory using a unique_ptr.
209  const size_t size = traceSize();
210  auto traceStorage = allocAligned(size);
211 
212  // The traceExecution call then fills this memory
213  // with an execution trace, made up entirely of "Record" structs, see
214  // the FunctionalNode class in expression-inl.h
216  T value(this->traceExecution(values, trace, reinterpret_cast<char *>(traceStorage.get())));
217 
218  // We then calculate the Jacobians using reverse automatic differentiation (AD).
219  trace.startReverseAD1(jacobians);
220  return value;
221  } catch (const std::bad_alloc &e) {
222  std::cerr << "valueAndJacobianMap exception: " << e.what() << '\n';
223  throw e;
224  }
225  // Here traceStorage will be de-allocated properly.
226 }
227 
228 template<typename T>
230  std::map<Key, int> map;
231  dims(map);
232  size_t n = map.size();
234  // Copy map into pair of vectors
235  auto key_it = pair.first.begin();
236  auto dim_it = pair.second.begin();
237  for (const auto& [key, value] : map) {
238  *key_it++ = key;
239  *dim_it++ = value;
240  }
241  return pair;
242 }
243 
244 namespace internal {
245 // http://stackoverflow.com/questions/16260445/boost-bind-to-operator
246 template<class T>
248  typedef T result_type;
249  static const int Dim = traits<T>::dimension;
250  T operator()(const T& x, const T& y, OptionalJacobian<Dim, Dim> H1 =
251  {}, OptionalJacobian<Dim, Dim> H2 = {}) const {
252  return x.compose(y, H1, H2);
253  }
254 };
255 
256 template <>
257 struct apply_compose<double> {
258  double operator()(const double& x, const double& y,
259  OptionalJacobian<1, 1> H1 = {},
260  OptionalJacobian<1, 1> H2 = {}) const {
261  if (H1) H1->setConstant(y);
262  if (H2) H2->setConstant(x);
263  return x * y;
264  }
265 };
266 
267 } // namespace internal
268 
269 // Global methods:
270 
272 template<typename T>
274  const Expression<T>& expression2) {
275  return Expression<T>(
276  std::bind(internal::apply_compose<T>(), std::placeholders::_1,
277  std::placeholders::_2, std::placeholders::_3,
278  std::placeholders::_4),
279  expression1, expression2);
280 }
281 
283 template<typename T>
284 std::vector<Expression<T> > createUnknowns(size_t n, char c, size_t start) {
285  std::vector<Expression<T> > unknowns;
286  unknowns.reserve(n);
287  for (size_t i = start; i < start + n; i++)
288  unknowns.push_back(Expression<T>(c, i));
289  return unknowns;
290 }
291 
292 template <typename T>
294  : Expression<T>(std::make_shared<internal::ScalarMultiplyNode<T>>(s, e)) {}
295 
296 
297 template <typename T>
299  : Expression<T>(std::make_shared<internal::BinarySumNode<T>>(e1, e2)) {}
300 
301 template <typename T>
303  root_ = std::make_shared<internal::BinarySumNode<T>>(*this, e);
304  return *this;
305 }
306 
307 } // namespace gtsam
gtsam::internal::apply_compose::result_type
T result_type
Definition: Expression-inl.h:248
H
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
Definition: gnuplot_common_settings.hh:74
Eigen::internal::print
EIGEN_STRONG_INLINE Packet4f print(const Packet4f &a)
Definition: NEON/PacketMath.h:3115
gtsam::internal::ExecutionTrace
Definition: Expression.h:39
gtsam::internal::apply_compose
Definition: Expression-inl.h:247
A3
static const double A3[]
Definition: expn.h:8
gtsam.examples.DogLegOptimizerExample.type
type
Definition: DogLegOptimizerExample.py:111
s
RealScalar s
Definition: level1_cplx_impl.h:126
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
keys
const KeyVector keys
Definition: testRegularImplicitSchurFactor.cpp:40
gtsam::BinarySumExpression::BinarySumExpression
BinarySumExpression(const Expression< T > &e1, const Expression< T > &e2)
Definition: Expression-inl.h:298
c
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
gtsam::FastVector
std::vector< T, typename internal::FastDefaultVectorAllocator< T >::type > FastVector
Definition: FastVector.h:34
gtsam::internal::TraceAlignment
static const unsigned TraceAlignment
Definition: ExecutionTrace.h:45
x
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 x
Definition: gnuplot_common_settings.hh:12
different_sigmas::values
HybridValues values
Definition: testHybridBayesNet.cpp:245
gtsam::KeyVector
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:92
result
Values result
Definition: OdometryOptimize.cpp:8
size
Scalar Scalar int size
Definition: benchVecAdd.cpp:17
gtsam::Expression
Definition: Expression.h:47
n
int n
Definition: BiCGSTAB_simple.cpp:1
A
Definition: test_numpy_dtypes.cpp:298
gtsam::internal::ExecutionTrace::startReverseAD1
void startReverseAD1(JacobianMap &jacobians) const
Definition: ExecutionTrace.h:157
gtsam::VerticalBlockMatrix
Definition: VerticalBlockMatrix.h:44
gtsam::Expression::KeysAndDims
std::pair< KeyVector, FastVector< int > > KeysAndDims
Keys and dimensions in same order.
Definition: Expression.h:191
gtsam::ScalarMultiplyExpression
Definition: Expression.h:219
j
std::ptrdiff_t j
Definition: tut_arithmetic_redux_minmax.cpp:2
gtsam::allocAligned
std::unique_ptr< internal::ExecutionTraceStorage[]> allocAligned(size_t size)
Definition: Expression-inl.h:198
gtsam::make_shared
gtsam::enable_if_t< needs_eigen_aligned_allocator< T >::value, std::shared_ptr< T > > make_shared(Args &&... args)
Definition: make_shared.h:56
gtsam::internal::ExecutionTraceStorage
std::aligned_storage< 1, TraceAlignment >::type ExecutionTraceStorage
Definition: ExecutionTrace.h:48
gtsam::internal::JacobianMap
Definition: JacobianMap.h:32
ExpressionNode.h
ExpressionNode class.
A2
static const double A2[]
Definition: expn.h:7
gtsam::symbol
Key symbol(unsigned char c, std::uint64_t j)
Definition: inference/Symbol.h:139
gtsam::createUnknowns
std::vector< Expression< T > > createUnknowns(size_t n, char c, size_t start)
Construct an array of leaves.
Definition: Expression-inl.h:284
gtsam::Expression::Expression
Expression()
Default constructor, for serialization.
Definition: Expression.h:188
Eigen::Triplet< double >
gtsam::internal::apply_compose< double >::operator()
double operator()(const double &x, const double &y, OptionalJacobian< 1, 1 > H1={}, OptionalJacobian< 1, 1 > H2={}) const
Definition: Expression-inl.h:258
gtsam::internal::apply_compose::operator()
T operator()(const T &x, const T &y, OptionalJacobian< Dim, Dim > H1={}, OptionalJacobian< Dim, Dim > H2={}) const
Definition: Expression-inl.h:250
anyset::size
size_t size() const
Definition: pytypes.h:2220
gtsam::Expression::dims
void dims(std::map< Key, int > &map) const
Return dimensions for each argument, as a map.
Definition: Expression-inl.h:133
y
Scalar * y
Definition: level1_cplx_impl.h:124
key
const gtsam::Symbol key('X', 0)
gtsam
traits
Definition: SFMdata.h:40
gtsam::traits
Definition: Group.h:36
gtsam::OptionalJacobian
Definition: OptionalJacobian.h:38
gtsam::Values
Definition: Values.h:65
gtsam::Expression::traceSize
size_t traceSize() const
Return size needed for memory buffer in traceExecution.
Definition: Expression-inl.h:161
gtsam::DenseIndex
ptrdiff_t DenseIndex
The index type for Eigen objects.
Definition: types.h:103
std
Definition: BFloat16.h:88
A1
static const double A1[]
Definition: expn.h:6
exampleQR::Ab
Matrix Ab
Definition: testNoiseModel.cpp:207
function
Definition: pytypes.h:2252
gtsam::Expression::traceExecution
T traceExecution(const Values &values, internal::ExecutionTrace< T > &trace, char *traceStorage) const
trace execution, very unsafe
Definition: Expression-inl.h:192
uint64_t
unsigned __int64 uint64_t
Definition: ms_stdint.h:95
internal
Definition: BandTriangularSolver.h:13
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
gtsam::Expression::operator+=
Expression< T > & operator+=(const Expression< T > &e)
Add another expression to this expression.
Definition: Expression-inl.h:302
test_callbacks.value
value
Definition: test_callbacks.py:160
i
int i
Definition: BiCGSTAB_step_by_step.cpp:9
Eigen::UniformScaling::operator*
operator*(const MatrixBase< Derived > &matrix, const UniformScaling< Scalar > &s)
Definition: Eigen/src/Geometry/Scaling.h:135
gtsam::Symbol
Definition: inference/Symbol.h:37


gtsam
Author(s):
autogenerated on Sun Dec 22 2024 04:11:31