VectorValues.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 
18 #pragma once
19 
20 #include <gtsam/linear/Scatter.h>
22 #include <gtsam/base/Vector.h>
24 #include <gtsam/base/FastVector.h>
25 #include <gtsam/global_includes.h>
26 
27 #include <boost/shared_ptr.hpp>
28 
29 
30 #include <map>
31 #include <string>
32 #include <iosfwd>
33 
34 namespace gtsam {
35 
74  class GTSAM_EXPORT VectorValues {
75  protected:
76  typedef VectorValues This;
78  Values values_;
79 
80  public:
83  typedef boost::shared_ptr<This> shared_ptr;
85  typedef value_type KeyValuePair;
86  typedef std::map<Key, size_t> Dims;
87 
90 
95 
98  VectorValues(const VectorValues& first, const VectorValues& second);
99 
101  template<class CONTAINER>
102  explicit VectorValues(const CONTAINER& c) : values_(c.begin(), c.end()) {}
103 
105  VectorValues(const VectorValues& c) : values_(c.values_) {}
106 
108  template<typename ITERATOR>
109  VectorValues(ITERATOR first, ITERATOR last) : values_(first, last) {}
110 
112  VectorValues(const Vector& c, const Dims& dims);
113 
115  VectorValues(const Vector& c, const Scatter& scatter);
116 
118  static VectorValues Zero(const VectorValues& other);
119 
123 
125  size_t size() const { return values_.size(); }
126 
128  size_t dim(Key j) const { return at(j).rows(); }
129 
131  bool exists(Key j) const { return find(j) != end(); }
132 
138  iterator item = find(j);
139  if (item == end())
140  throw std::out_of_range(
141  "Requested variable '" + DefaultKeyFormatter(j) + "' is not in this VectorValues.");
142  else
143  return item->second;
144  }
145 
150  const Vector& at(Key j) const {
151  const_iterator item = find(j);
152  if (item == end())
153  throw std::out_of_range(
154  "Requested variable '" + DefaultKeyFormatter(j) + "' is not in this VectorValues.");
155  else
156  return item->second;
157  }
158 
161  Vector& operator[](Key j) { return at(j); }
162 
165  const Vector& operator[](Key j) const { return at(j); }
166 
170  void update(const VectorValues& values);
171 
176  iterator insert(const std::pair<Key, Vector>& key_value);
177 
182  template<class... Args>
183  inline std::pair<VectorValues::iterator, bool> emplace(Key j, Args&&... args) {
184 #if ! defined(GTSAM_USE_TBB) || defined (TBB_GREATER_EQUAL_2020)
185  return values_.emplace(std::piecewise_construct, std::forward_as_tuple(j), std::forward_as_tuple(args...));
186 #else
187  return values_.insert(std::make_pair(j, Vector(std::forward<Args>(args)...)));
188 #endif
189  }
190 
195  iterator insert(Key j, const Vector& value) {
196  return insert(std::make_pair(j, value));
197  }
198 
201  void insert(const VectorValues& values);
202 
207  inline std::pair<iterator, bool> tryInsert(Key j, const Vector& value) {
208 #ifdef TBB_GREATER_EQUAL_2020
209  return values_.emplace(j, value);
210 #else
211  return values_.insert(std::make_pair(j, value));
212 #endif
213  }
214 
216  void erase(Key var) {
217  if (values_.unsafe_erase(var) == 0)
218  throw std::invalid_argument("Requested variable '" +
219  DefaultKeyFormatter(var) +
220  "', is not in this VectorValues.");
221  }
222 
224  void setZero();
225 
226  iterator begin() { return values_.begin(); }
227  const_iterator begin() const { return values_.begin(); }
228  iterator end() { return values_.end(); }
229  const_iterator end() const { return values_.end(); }
230 
235  iterator find(Key j) { return values_.find(j); }
236 
241  const_iterator find(Key j) const { return values_.find(j); }
242 
244  GTSAM_EXPORT friend std::ostream& operator<<(std::ostream&, const VectorValues&);
245 
247  void print(const std::string& str = "VectorValues",
249 
251  bool equals(const VectorValues& x, double tol = 1e-9) const;
252 
256 
258  Vector vector() const;
259 
261  template <typename CONTAINER>
262  Vector vector(const CONTAINER& keys) const {
263  DenseIndex totalDim = 0;
265  items.reserve(keys.end() - keys.begin());
266  for (Key key : keys) {
267  const Vector* v = &at(key);
268  totalDim += v->size();
269  items.push_back(v);
270  }
271 
272  Vector result(totalDim);
273  DenseIndex pos = 0;
274  for (const Vector* v : items) {
275  result.segment(pos, v->size()) = *v;
276  pos += v->size();
277  }
278 
279  return result;
280  }
281 
283  Vector vector(const Dims& dims) const;
284 
286  void swap(VectorValues& other);
287 
289  bool hasSameStructure(const VectorValues other) const;
290 
294 
298  double dot(const VectorValues& v) const;
299 
301  double norm() const;
302 
304  double squaredNorm() const;
305 
308  VectorValues operator+(const VectorValues& c) const;
309 
312  VectorValues add(const VectorValues& c) const;
313 
317 
320  VectorValues& addInPlace(const VectorValues& c);
321 
323  VectorValues& addInPlace_(const VectorValues& c);
324 
327  VectorValues operator-(const VectorValues& c) const;
328 
331  VectorValues subtract(const VectorValues& c) const;
332 
334  friend GTSAM_EXPORT VectorValues operator*(const double a, const VectorValues &v);
335 
337  VectorValues scale(const double a) const;
338 
340  VectorValues& operator*=(double alpha);
341 
343  VectorValues& scaleInPlace(double alpha);
344 
346 
350 
351  //inline VectorValues scale(const double a, const VectorValues& c) const { return a * (*this); }
352 
354 
355  private:
357  friend class boost::serialization::access;
358  template<class ARCHIVE>
359  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
360  ar & BOOST_SERIALIZATION_NVP(values_);
361  }
362  }; // VectorValues definition
363 
365  template<>
366  struct traits<VectorValues> : public Testable<VectorValues> {
367  };
368 
369 } // \namespace gtsam
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
iterator find(Key j)
Definition: VectorValues.h:235
constexpr int last(int, int result)
A insert(1, 2)=0
iterator insert(Key j, const Vector &value)
Definition: VectorValues.h:195
VectorValues(const CONTAINER &c)
Definition: VectorValues.h:102
std::ostream & operator<<(std::ostream &os, const Dih6 &m)
Definition: testGroup.cpp:109
Values::iterator iterator
Iterator over vector values.
Definition: VectorValues.h:81
EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half & operator*=(half &a, const half &b)
Definition: Half.h:289
def update(text)
Definition: relicense.py:46
double dot(const V1 &a, const V2 &b)
Definition: Vector.h:194
Vector & operator[](Key j)
Definition: VectorValues.h:161
bool exists(Key j) const
Definition: VectorValues.h:131
ArrayXcf v
Definition: Cwise_arg.cpp:1
Definition: pytypes.h:1322
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
const_iterator find(Key j) const
Definition: VectorValues.h:241
leaf::MyValues values
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
Definition: VectorValues.h:83
size_t size() const
Definition: VectorValues.h:125
Values::value_type value_type
Typedef to pair<Key, Vector>
Definition: VectorValues.h:84
iterator end()
Iterator over variables.
Definition: VectorValues.h:228
std::map< Key, size_t > Dims
Keyed vector dimensions.
Definition: VectorValues.h:86
Vector & at(Key j)
Definition: VectorValues.h:137
Point2 operator*(double s, const Point2 &p)
multiply with scalar
Definition: Point2.h:45
static const KeyFormatter DefaultKeyFormatter
Definition: Key.h:43
ptrdiff_t DenseIndex
The index type for Eigen objects.
Definition: types.h:67
const KeyFormatter & formatter
graph add(boost::make_shared< UnaryFactor >(1, 0.0, 0.0, unaryNoise))
std::pair< iterator, bool > tryInsert(Key j, const Vector &value)
Definition: VectorValues.h:207
Included from all GTSAM files.
Array33i a
ConcurrentMap< Key, Vector > Values
Collection of Vectors making up a VectorValues.
Definition: VectorValues.h:77
boost::transform_iterator< boost::function1< KeyValuePair, const KeyValuePtrPair & >, KeyValueMap::iterator > iterator
Mutable forward iterator, with value type KeyValuePair.
Definition: Values.h:120
int EIGEN_BLAS_FUNC() swap(int *n, RealScalar *px, int *incx, RealScalar *py, int *incy)
Definition: level1_impl.h:152
KeyValuePair value_type
Definition: Values.h:134
constexpr int first(int i)
Implementation details for constexpr functions.
Eigen::VectorXd Vector
Definition: Vector.h:38
Values result
Definition: pytypes.h:928
VectorValues(ITERATOR first, ITERATOR last)
Definition: VectorValues.h:109
Values values_
Vectors making up this VectorValues.
Definition: VectorValues.h:78
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Definition: Key.h:35
const_iterator begin() const
Iterator over variables.
Definition: VectorValues.h:227
const Vector & operator[](Key j) const
Definition: VectorValues.h:165
RealScalar alpha
Array< double, 1, 3 > e(1./3., 0.5, 2.)
boost::transform_iterator< boost::function1< ConstKeyValuePair, const ConstKeyValuePtrPair & >, KeyValueMap::const_iterator > const_iterator
Const forward iterator, with value type ConstKeyValuePair.
Definition: Values.h:124
value_type KeyValuePair
Typedef to pair<Key, Vector>
Definition: VectorValues.h:85
BinarySumExpression< T > operator-(const Expression< T > &e1, const Expression< T > &e2)
Construct an expression that subtracts one expression from another.
Definition: Expression.h:279
Values::const_iterator const_iterator
Const iterator over vector values.
Definition: VectorValues.h:82
EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half & operator+=(half &a, const half &b)
Definition: Half.h:285
Maps global variable indices to slot indices.
VectorValues(const VectorValues &c)
Definition: VectorValues.h:105
A thin wrapper around std::vector that uses a custom allocator.
traits
Definition: chartTesting.h:28
typedef and functions to augment Eigen&#39;s VectorXd
Vector vector(const CONTAINER &keys) const
Definition: VectorValues.h:262
void unsafe_erase(typename Base::iterator position)
Definition: ConcurrentMap.h:93
BinarySumExpression< T > operator+(const Expression< T > &e1, const Expression< T > &e2)
Definition: Expression.h:273
void erase(Key var)
Definition: VectorValues.h:216
std::vector< T, typename internal::FastDefaultVectorAllocator< T >::type > FastVector
Definition: FastVector.h:34
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 scale
const_iterator end() const
Iterator over variables.
Definition: VectorValues.h:229
size_t dim(Key j) const
Definition: VectorValues.h:128
const G double tol
Definition: Group.h:83
const KeyVector keys
std::pair< VectorValues::iterator, bool > emplace(Key j, Args &&...args)
Definition: VectorValues.h:183
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
iterator begin()
Iterator over variables.
Definition: VectorValues.h:226
void serialize(ARCHIVE &ar, const unsigned int)
Definition: VectorValues.h:359
const Vector & at(Key j) const
Definition: VectorValues.h:150
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
std::ptrdiff_t j
VectorValues This
Definition: VectorValues.h:76
v setZero(3)


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