FixedVector.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 <stdarg.h>
21 #include <gtsam/base/Vector.h>
22 
23 namespace gtsam {
24 
29 template<size_t N>
30 class FixedVector : public Eigen::Matrix<double, N, 1> {
31 public:
33 
36 
38  FixedVector(const FixedVector& v) : Base(v) {}
39 
40  FixedVector& operator=(const FixedVector& other) = default;
41 
43  FixedVector(const Vector& v) : Base(v) {}
44 
46  FixedVector(const double* values) {
47  std::copy(values, values+N, this->data());
48  }
49 
54  inline static FixedVector repeat(double value) {
55  return FixedVector(Base::Constant(value));
56  }
57 
65  inline static FixedVector delta(size_t i, double value) {
66  return FixedVector(Base::Unit(i) * value);
67  }
68 
75  inline static FixedVector basis(size_t i) { return FixedVector(Base::Unit(i)); }
76 
80  inline static FixedVector zero() { return FixedVector(Base::Zero());}
81 
85  inline static FixedVector ones() { return FixedVector(FixedVector::Ones());}
86 
87  static size_t dim() { return Base::max_size; }
88 
89  void print(const std::string& name="") const { gtsam::print(Vector(*this), name); }
90 
91  template<size_t M>
92  bool equals(const FixedVector<M>& other, double tol=1e-9) const {
93  return false;
94  }
95 
96  bool equals(const FixedVector& other, double tol=1e-9) const {
97  return equal_with_abs_tol(*this,other,tol);
98  }
99 
100 };
101 
102 
103 } // \namespace
gtsam::FixedVector::ones
static FixedVector ones()
Definition: FixedVector.h:85
gtsam::FixedVector::equals
bool equals(const FixedVector &other, double tol=1e-9) const
Definition: FixedVector.h:96
Eigen
Namespace containing all symbols from the Eigen library.
Definition: jet.h:637
gtsam::FixedVector::Base
Eigen::Matrix< double, N, 1 > Base
Definition: FixedVector.h:32
name
Annotation for function names.
Definition: attr.h:51
gtsam::FixedVector
Definition: FixedVector.h:30
Vector.h
typedef and functions to augment Eigen's VectorXd
gtsam::FixedVector::repeat
static FixedVector repeat(double value)
Definition: FixedVector.h:54
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
gtsam::FixedVector::equals
bool equals(const FixedVector< M > &other, double tol=1e-9) const
Definition: FixedVector.h:92
gtsam::equal_with_abs_tol
bool equal_with_abs_tol(const Eigen::DenseBase< MATRIX > &A, const Eigen::DenseBase< MATRIX > &B, double tol=1e-9)
Definition: base/Matrix.h:80
different_sigmas::values
HybridValues values
Definition: testHybridBayesNet.cpp:247
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:39
gtsam::FixedVector::FixedVector
FixedVector(const double *values)
Definition: FixedVector.h:46
gtsam::FixedVector::FixedVector
FixedVector(const Vector &v)
Definition: FixedVector.h:43
gtsam::FixedVector::delta
static FixedVector delta(size_t i, double value)
Definition: FixedVector.h:65
gtsam::print
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:145
gtsam::FixedVector::zero
static FixedVector zero()
Definition: FixedVector.h:80
gtsam::FixedVector::FixedVector
FixedVector(const FixedVector &v)
Definition: FixedVector.h:38
gtsam
traits
Definition: SFMdata.h:40
gtsam::FixedVector::print
void print(const std::string &name="") const
Definition: FixedVector.h:89
gtsam::FixedVector::dim
static size_t dim()
Definition: FixedVector.h:87
v
Array< int, Dynamic, 1 > v
Definition: Array_initializer_list_vector_cxx11.cpp:1
Eigen::PlainObjectBase< Matrix< double, _Rows, _Cols, _Options, _MaxRows, _MaxCols > >::data
EIGEN_DEVICE_FUNC const EIGEN_STRONG_INLINE Scalar * data() const
Definition: PlainObjectBase.h:247
gtsam::tol
const G double tol
Definition: Group.h:79
Eigen::Matrix
The matrix class, also used for vectors and row-vectors.
Definition: 3rdparty/Eigen/Eigen/src/Core/Matrix.h:178
gtsam::FixedVector::basis
static FixedVector basis(size_t i)
Definition: FixedVector.h:75
N
#define N
Definition: igam.h:9
gtsam::FixedVector::operator=
FixedVector & operator=(const FixedVector &other)=default
test_callbacks.value
value
Definition: test_callbacks.py:160
i
int i
Definition: BiCGSTAB_step_by_step.cpp:9
pybind_wrapper_test_script.other
other
Definition: pybind_wrapper_test_script.py:42
gtsam::FixedVector::FixedVector
FixedVector()
Definition: FixedVector.h:35


gtsam
Author(s):
autogenerated on Sun Feb 16 2025 04:01:22