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 <memory>
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;
79 
81  std::map<Key, Vector> sorted() const;
82 
83  public:
84  typedef Values::iterator iterator;
85  typedef Values::const_iterator const_iterator;
86  typedef std::shared_ptr<This> shared_ptr;
89  typedef std::map<Key, size_t> Dims;
90 
93 
96 
98  VectorValues(std::initializer_list<std::pair<Key, Vector>> init)
99  : values_(init.begin(), init.end()) {}
100 
103  VectorValues(const VectorValues& first, const VectorValues& second);
104 
106  template<class CONTAINER>
107  explicit VectorValues(const CONTAINER& c) : values_(c.begin(), c.end()) {}
108 
110  VectorValues(const VectorValues& c) : values_(c.values_) {}
111 
113  template<typename ITERATOR>
114  VectorValues(ITERATOR first, ITERATOR last) : values_(first, last) {}
115 
117  VectorValues(const Vector& c, const Dims& dims);
118 
120  VectorValues(const Vector& c, const Scatter& scatter);
121 
122  VectorValues& operator=(const VectorValues& other) = default;
123 
125  static VectorValues Zero(const VectorValues& other);
126 
130 
132  size_t size() const { return values_.size(); }
133 
135  size_t dim(Key j) const { return at(j).rows(); }
136 
138  bool exists(Key j) const { return find(j) != end(); }
139 
145  iterator item = find(j);
146  if (item == end())
147  throw std::out_of_range(
148  "Requested variable '" + DefaultKeyFormatter(j) + "' is not in this VectorValues.");
149  else
150  return item->second;
151  }
152 
157  const Vector& at(Key j) const {
158  const_iterator item = find(j);
159  if (item == end())
160  throw std::out_of_range(
161  "Requested variable '" + DefaultKeyFormatter(j) + "' is not in this VectorValues.");
162  else
163  return item->second;
164  }
165 
168  Vector& operator[](Key j) { return at(j); }
169 
172  const Vector& operator[](Key j) const { return at(j); }
173 
178 
183  iterator insert(const std::pair<Key, Vector>& key_value);
184 
189  template<class... Args>
190  inline std::pair<VectorValues::iterator, bool> emplace(Key j, Args&&... args) {
191 #if ! defined(GTSAM_USE_TBB) || defined (TBB_GREATER_EQUAL_2020)
192  return values_.emplace(std::piecewise_construct, std::forward_as_tuple(j), std::forward_as_tuple(args...));
193 #else
194  return values_.insert({j, Vector(std::forward<Args>(args)...)});
195 #endif
196  }
197 
203  return insert({j, value});
204  }
205 
209 
214  inline std::pair<iterator, bool> tryInsert(Key j, const Vector& value) {
215 #ifdef TBB_GREATER_EQUAL_2020
216  return values_.emplace(j, value);
217 #else
218  return values_.insert({j, value});
219 #endif
220  }
221 
225  if (!tryInsert(j, value).second) {
226  (*this)[j] = value;
227  }
228  }
229 
231  void erase(Key var) {
232  if (values_.unsafe_erase(var) == 0)
233  throw std::invalid_argument("Requested variable '" +
234  DefaultKeyFormatter(var) +
235  "', is not in this VectorValues.");
236  }
237 
239  void setZero();
240 
241  iterator begin() { return values_.begin(); }
242  const_iterator begin() const { return values_.begin(); }
243  iterator end() { return values_.end(); }
244  const_iterator end() const { return values_.end(); }
245 
250  iterator find(Key j) { return values_.find(j); }
251 
256  const_iterator find(Key j) const { return values_.find(j); }
257 
259  GTSAM_EXPORT friend std::ostream& operator<<(std::ostream&, const VectorValues&);
260 
262  void print(const std::string& str = "VectorValues",
264 
266  bool equals(const VectorValues& x, double tol = 1e-9) const;
267 
271 
273  Vector vector() const;
274 
276  template <typename CONTAINER>
277  Vector vector(const CONTAINER& keys) const {
278  DenseIndex totalDim = 0;
280  items.reserve(keys.end() - keys.begin());
281  for (Key key : keys) {
282  const Vector* v = &at(key);
283  totalDim += v->size();
284  items.push_back(v);
285  }
286 
287  Vector result(totalDim);
288  DenseIndex pos = 0;
289  for (const Vector* v : items) {
290  result.segment(pos, v->size()) = *v;
291  pos += v->size();
292  }
293 
294  return result;
295  }
296 
298  Vector vector(const Dims& dims) const;
299 
301  void swap(VectorValues& other);
302 
304  bool hasSameStructure(const VectorValues other) const;
305 
309 
313  double dot(const VectorValues& v) const;
314 
316  double norm() const;
317 
319  double squaredNorm() const;
320 
323  VectorValues operator+(const VectorValues& c) const;
324 
327  VectorValues add(const VectorValues& c) const;
328 
332 
335  VectorValues& addInPlace(const VectorValues& c);
336 
338  VectorValues& addInPlace_(const VectorValues& c);
339 
342  VectorValues operator-(const VectorValues& c) const;
343 
346  VectorValues subtract(const VectorValues& c) const;
347 
349  friend GTSAM_EXPORT VectorValues operator*(const double a, const VectorValues &v);
350 
352  VectorValues scale(const double a) const;
353 
355  VectorValues& operator*=(double alpha);
356 
358  VectorValues& scaleInPlace(double alpha);
359 
361 
364 
370  std::string html(
371  const KeyFormatter& keyFormatter = DefaultKeyFormatter) const;
372 
374 
375  private:
376 #if GTSAM_ENABLE_BOOST_SERIALIZATION
377 
378  friend class boost::serialization::access;
379  template<class ARCHIVE>
380  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
381  ar & BOOST_SERIALIZATION_NVP(values_);
382  }
383 #endif
384  }; // VectorValues definition
385 
387  template<>
388  struct traits<VectorValues> : public Testable<VectorValues> {
389  };
390 
391 } // \namespace gtsam
gtsam::VectorValues::Dims
std::map< Key, size_t > Dims
Keyed vector dimensions.
Definition: VectorValues.h:89
gtsam::ConcurrentMap< Key, Vector >
relicense.update
def update(text)
Definition: relicense.py:46
gtsam::add
static Y add(const Y &y1, const Y &y2)
Definition: HybridGaussianProductFactor.cpp:32
Vector.h
typedef and functions to augment Eigen's VectorXd
alpha
RealScalar alpha
Definition: level1_cplx_impl.h:147
FastVector.h
A thin wrapper around std::vector that uses a custom allocator.
global_includes.h
Included from all GTSAM files.
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
gtsam::operator<<
std::ostream & operator<<(std::ostream &os, const Dih6 &m)
Definition: testGroup.cpp:109
keys
const KeyVector keys
Definition: testRegularImplicitSchurFactor.cpp:40
gtsam::operator-
Errors operator-(const Errors &a, const Errors &b)
Subtraction.
Definition: Errors.cpp:74
gtsam::VectorValues::find
iterator find(Key j)
Definition: VectorValues.h:250
c
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
gtsam::FastVector
std::vector< T, typename internal::FastDefaultVectorAllocator< T >::type > FastVector
Definition: FastVector.h:34
gtsam::VectorValues::at
Vector & at(Key j)
Definition: VectorValues.h:144
gtsam::VectorValues::iterator
Values::iterator iterator
Iterator over vector values.
Definition: VectorValues.h:84
gtsam::VectorValues::at
const Vector & at(Key j) const
Definition: VectorValues.h:157
ConcurrentMap.h
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
gtsam::VectorValues::values_
Values values_
Vectors making up this VectorValues.
Definition: VectorValues.h:78
formatter
const KeyFormatter & formatter
Definition: treeTraversal-inst.h:204
different_sigmas::values
HybridValues values
Definition: testHybridBayesNet.cpp:245
Ordering.h
Variable ordering for the elimination algorithm.
Eigen::bfloat16_impl::operator*=
EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bfloat16 & operator*=(bfloat16 &a, const bfloat16 &b)
Definition: BFloat16.h:188
iterator
Definition: pytypes.h:1460
Eigen::last
static const symbolic::SymbolExpr< internal::symbolic_last_tag > last
Definition: IndexedViewHelper.h:38
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:39
result
Values result
Definition: OdometryOptimize.cpp:8
gtsam::VectorValues::VectorValues
VectorValues()
Default constructor creates an empty VectorValues.
Definition: VectorValues.h:95
gtsam::DefaultKeyFormatter
KeyFormatter DefaultKeyFormatter
Assign default key formatter.
Definition: Key.cpp:30
gtsam::operator*
Point2 operator*(double s, const Point2 &p)
multiply with scalar
Definition: Point2.h:52
gtsam::VectorValues::const_iterator
Values::const_iterator const_iterator
Const iterator over vector values.
Definition: VectorValues.h:85
gtsam::Dims
std::vector< Key > Dims
Definition: HessianFactor.cpp:42
gtsam::VectorValues::VectorValues
VectorValues(const CONTAINER &c)
Definition: VectorValues.h:107
gtsam::print
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:156
gtsam::VectorValues::VectorValues
VectorValues(ITERATOR first, ITERATOR last)
Definition: VectorValues.h:114
gtsam::VectorValues
Definition: VectorValues.h:74
j
std::ptrdiff_t j
Definition: tut_arithmetic_redux_minmax.cpp:2
gtsam::KeyFormatter
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
gtsam::dot
double dot(const V1 &a, const V2 &b)
Definition: Vector.h:196
gtsam::VectorValues::VectorValues
VectorValues(const VectorValues &c)
Definition: VectorValues.h:110
gtsam::Scatter
Definition: Scatter.h:49
gtsam::VectorValues::tryInsert
std::pair< iterator, bool > tryInsert(Key j, const Vector &value)
Definition: VectorValues.h:214
gtsam::ConcurrentMap::unsafe_erase
void unsafe_erase(typename Base::iterator position)
Definition: ConcurrentMap.h:96
gtsam::VectorValues::shared_ptr
std::shared_ptr< This > shared_ptr
shared_ptr to this class
Definition: VectorValues.h:86
gtsam::VectorValues::dim
size_t dim(Key j) const
Definition: VectorValues.h:135
gtsam::equals
Definition: Testable.h:112
gtsam::operator+
HybridGaussianProductFactor operator+(const HybridGaussianProductFactor &a, const HybridGaussianProductFactor &b)
Definition: HybridGaussianProductFactor.cpp:39
str
Definition: pytypes.h:1558
key
const gtsam::Symbol key('X', 0)
gtsam::VectorValues::operator[]
Vector & operator[](Key j)
Definition: VectorValues.h:168
a
ArrayXXi a
Definition: Array_initializer_list_23_cxx11.cpp:1
gtsam::VectorValues::Values
ConcurrentMap< Key, Vector > Values
Collection of Vectors making up a VectorValues.
Definition: VectorValues.h:77
gtsam
traits
Definition: SFMdata.h:40
gtsam::Testable
Definition: Testable.h:152
gtsam::traits
Definition: Group.h:36
gtsam::VectorValues::insert_or_assign
void insert_or_assign(Key j, const Vector &value)
Definition: VectorValues.h:224
gtsam::DenseIndex
ptrdiff_t DenseIndex
The index type for Eigen objects.
Definition: types.h:103
args
Definition: pytypes.h:2210
gtsam::VectorValues::exists
bool exists(Key j) const
Definition: VectorValues.h:138
gtsam::VectorValues::size
size_t size() const
Definition: VectorValues.h:132
v
Array< int, Dynamic, 1 > v
Definition: Array_initializer_list_vector_cxx11.cpp:1
gtsam::scale
static double scale(double x, double a, double b, double t1, double t2)
Scale x from [a, b] to [t1, t2].
Definition: Chebyshev.cpp:35
gtsam::Values::value_type
KeyValuePair value_type
Definition: Values.h:106
gtsam::tol
const G double tol
Definition: Group.h:79
setZero
v setZero(3)
gtsam::VectorValues::find
const_iterator find(Key j) const
Definition: VectorValues.h:256
gtsam::html
string html(const DiscreteValues &values, const KeyFormatter &keyFormatter, const DiscreteValues::Names &names)
Free version of html.
Definition: DiscreteValues.cpp:135
gtsam::VectorValues::erase
void erase(Key var)
Definition: VectorValues.h:231
gtsam::VectorValues::This
VectorValues This
Definition: VectorValues.h:76
Eigen::placeholders::end
static const EIGEN_DEPRECATED end_t end
Definition: IndexedViewHelper.h:181
gtsam::VectorValues::KeyValuePair
value_type KeyValuePair
Typedef to pair<Key, Vector>
Definition: VectorValues.h:88
pos
Definition: example-NearestNeighbor.cpp:32
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
gtsam::VectorValues::vector
Vector vector(const CONTAINER &keys) const
Definition: VectorValues.h:277
gtsam::VectorValues::emplace
std::pair< VectorValues::iterator, bool > emplace(Key j, Args &&... args)
Definition: VectorValues.h:190
insert
A insert(1, 2)=0
swap
int EIGEN_BLAS_FUNC() swap(int *n, RealScalar *px, int *incx, RealScalar *py, int *incy)
Definition: level1_impl.h:130
init
Definition: TutorialInplaceLU.cpp:2
Eigen::bfloat16_impl::operator+=
EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bfloat16 & operator+=(bfloat16 &a, const bfloat16 &b)
Definition: BFloat16.h:184
Scatter.h
Maps global variable indices to slot indices.
test_callbacks.value
value
Definition: test_callbacks.py:160
gtsam::VectorValues::VectorValues
VectorValues(std::initializer_list< std::pair< Key, Vector >> init)
Construct from initializer list.
Definition: VectorValues.h:98
pybind_wrapper_test_script.other
other
Definition: pybind_wrapper_test_script.py:42
gtsam::VectorValues::insert
iterator insert(Key j, const Vector &value)
Definition: VectorValues.h:202
gtsam::VectorValues::value_type
Values::value_type value_type
Typedef to pair<Key, Vector>
Definition: VectorValues.h:87
gtsam::VectorValues::operator[]
const Vector & operator[](Key j) const
Definition: VectorValues.h:172


gtsam
Author(s):
autogenerated on Tue Jan 7 2025 04:09:30