Vector.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 
22 // \callgraph
23 
24 #pragma once
25 #ifndef MKL_BLAS
26 #define MKL_BLAS MKL_DOMAIN_BLAS
27 #endif
28 
29 #include <gtsam/global_includes.h>
30 #include <Eigen/Core>
31 #include <iosfwd>
32 #include <list>
33 
34 namespace gtsam {
35 
36 // Vector is just a typedef of the Eigen dynamic vector type
37 
38 // Typedef arbitary length vector
39 typedef Eigen::VectorXd Vector;
40 
41 // Commonly used fixed size vectors
43 typedef Eigen::Vector2d Vector2;
44 typedef Eigen::Vector3d Vector3;
45 
48 
49 // Create handy typedefs and constants for vectors with N>3
50 // VectorN and Z_Nx1, for N=1..9
51 #define GTSAM_MAKE_VECTOR_DEFS(N) \
52  using Vector##N = Eigen::Matrix<double, N, 1>; \
53  static const Eigen::MatrixBase<Vector##N>::ConstantReturnType Z_##N##x1 = Vector##N::Zero();
54 
65 
66 typedef Eigen::VectorBlock<Vector> SubVector;
67 typedef Eigen::VectorBlock<const Vector> ConstSubVector;
68 
74 #if defined(GTSAM_EIGEN_VERSION_WORLD)
75 static_assert(
76  GTSAM_EIGEN_VERSION_WORLD==EIGEN_WORLD_VERSION &&
77  GTSAM_EIGEN_VERSION_MAJOR==EIGEN_MAJOR_VERSION,
78  "Error: GTSAM was built against a different version of Eigen");
79 #endif
80 
97 GTSAM_EXPORT bool fpEqual(double a, double b, double tol,
98  bool check_relative_also = true);
99 
103 GTSAM_EXPORT void print(const Vector& v, const std::string& s, std::ostream& stream);
104 
108 GTSAM_EXPORT void print(const Vector& v, const std::string& s = "");
109 
113 GTSAM_EXPORT void save(const Vector& A, const std::string &s, const std::string& filename);
114 
118 GTSAM_EXPORT bool operator==(const Vector& vec1,const Vector& vec2);
119 
125 GTSAM_EXPORT bool greaterThanOrEqual(const Vector& v1, const Vector& v2);
126 
130 GTSAM_EXPORT bool equal_with_abs_tol(const Vector& vec1, const Vector& vec2, double tol=1e-9);
131 GTSAM_EXPORT bool equal_with_abs_tol(const SubVector& vec1, const SubVector& vec2, double tol=1e-9);
132 
136 inline bool equal(const Vector& vec1, const Vector& vec2, double tol) {
137  return equal_with_abs_tol(vec1, vec2, tol);
138 }
139 
143 inline bool equal(const Vector& vec1, const Vector& vec2) {
144  return equal_with_abs_tol(vec1, vec2);
145 }
146 
154 GTSAM_EXPORT bool assert_equal(const Vector& vec1, const Vector& vec2, double tol=1e-9);
155 
163 GTSAM_EXPORT bool assert_inequal(const Vector& vec1, const Vector& vec2, double tol=1e-9);
164 
172 GTSAM_EXPORT bool assert_equal(const SubVector& vec1, const SubVector& vec2, double tol=1e-9);
173 GTSAM_EXPORT bool assert_equal(const ConstSubVector& vec1, const ConstSubVector& vec2, double tol=1e-9);
174 
182 GTSAM_EXPORT bool linear_dependent(const Vector& vec1, const Vector& vec2, double tol=1e-9);
183 
190 GTSAM_EXPORT Vector ediv_(const Vector &a, const Vector &b);
191 
195 template<class V1, class V2>
196 inline double dot(const V1 &a, const V2& b) {
197  return a.dot(b);
198 }
199 
201 template<class V1, class V2>
202 inline double inner_prod(const V1 &a, const V2& b) {
203  return a.dot(b);
204 }
205 
211 GTSAM_EXPORT std::pair<double,Vector> house(const Vector &x);
212 
214 GTSAM_EXPORT double houseInPlace(Vector &x);
215 
226 GTSAM_EXPORT std::pair<Vector, double>
227 weightedPseudoinverse(const Vector& v, const Vector& weights);
228 
229 /*
230  * Fast version *no error checking* !
231  * Pass in initialized vector pseudo of size(weights) or will crash !
232  * @return the precision, pseudoinverse in third argument
233  */
234 GTSAM_EXPORT double weightedPseudoinverse(const Vector& a, const Vector& weights, Vector& pseudo);
235 
239 GTSAM_EXPORT Vector concatVectors(const std::list<Vector>& vs);
240 
244 GTSAM_EXPORT Vector concatVectors(size_t nrVectors, ...);
245 } // namespace gtsam
gtsam::Vector1
Eigen::Matrix< double, 1, 1 > Vector1
Definition: Vector.h:42
Eigen
Namespace containing all symbols from the Eigen library.
Definition: jet.h:637
EIGEN_MAJOR_VERSION
#define EIGEN_MAJOR_VERSION
Definition: Macros.h:19
global_includes.h
Included from all GTSAM files.
s
RealScalar s
Definition: level1_cplx_impl.h:126
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
gtsam::ediv_
Vector ediv_(const Vector &a, const Vector &b)
Definition: Vector.cpp:199
gtsam::weightedPseudoinverse
double weightedPseudoinverse(const Vector &a, const Vector &weights, Vector &pseudo)
Definition: Vector.cpp:246
gtsam::Vector2
Eigen::Vector2d Vector2
Definition: Vector.h:43
gtsam::Z_3x1
static const Eigen::MatrixBase< Vector3 >::ConstantReturnType Z_3x1
Definition: Vector.h:47
gtsam::SubVector
Eigen::VectorBlock< Vector > SubVector
Definition: Vector.h:66
gtsam.examples.SFMExample_bal.stream
stream
Definition: SFMExample_bal.py:24
gtsam::houseInPlace
double houseInPlace(Vector &v)
Definition: Vector.cpp:212
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::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
test_cases::vs
std::vector< Vector3 > vs
Definition: testPose3.cpp:880
gtsam::Vector3
Eigen::Vector3d Vector3
Definition: Vector.h:44
gtsam::operator==
bool operator==(const Matrix &A, const Matrix &B)
Definition: base/Matrix.h:99
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:39
gtsam::concatVectors
Vector concatVectors(const std::list< Vector > &vs)
Definition: Vector.cpp:302
Eigen::CwiseNullaryOp
Generic expression of a matrix where all coefficients are defined by a functor.
Definition: CwiseNullaryOp.h:60
gtsam::print
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:156
A
Definition: test_numpy_dtypes.cpp:298
relicense.filename
filename
Definition: relicense.py:57
gtsam::dot
double dot(const V1 &a, const V2 &b)
Definition: Vector.h:196
gtsam::fpEqual
bool fpEqual(double a, double b, double tol, bool check_relative_also)
Definition: Vector.cpp:42
GTSAM_MAKE_VECTOR_DEFS
#define GTSAM_MAKE_VECTOR_DEFS(N)
Definition: Vector.h:51
gtsam::ConstSubVector
Eigen::VectorBlock< const Vector > ConstSubVector
Definition: Vector.h:67
gtsam::b
const G & b
Definition: Group.h:79
gtsam::save
void save(const Matrix &A, const string &s, const string &filename)
Definition: Matrix.cpp:167
V2
static const Point3 V2(-6.5, 3.5, 6.2)
gtsam::greaterThanOrEqual
bool greaterThanOrEqual(const Vector &vec1, const Vector &vec2)
Definition: Vector.cpp:114
a
ArrayXXi a
Definition: Array_initializer_list_23_cxx11.cpp:1
gtsam
traits
Definition: SFMdata.h:40
gtsam::inner_prod
double inner_prod(const V1 &a, const V2 &b)
Definition: Vector.h:202
v2
Vector v2
Definition: testSerializationBase.cpp:39
Eigen::VectorBlock
Expression of a fixed-size or dynamic-size sub-vector.
Definition: ForwardDeclarations.h:85
gtsam::Z_2x1
static const Eigen::MatrixBase< Vector2 >::ConstantReturnType Z_2x1
Definition: Vector.h:46
v
Array< int, Dynamic, 1 > v
Definition: Array_initializer_list_vector_cxx11.cpp:1
gtsam::assert_equal
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:41
gtsam::tol
const G double tol
Definition: Group.h:79
gtsam::house
pair< double, Vector > house(const Vector &x)
Definition: Vector.cpp:237
gtsam::assert_inequal
bool assert_inequal(const Matrix &A, const Matrix &B, double tol)
Definition: Matrix.cpp:61
Eigen::Matrix
The matrix class, also used for vectors and row-vectors.
Definition: 3rdparty/Eigen/Eigen/src/Core/Matrix.h:178
EIGEN_WORLD_VERSION
#define EIGEN_WORLD_VERSION
Definition: Macros.h:18
gtsam::equal
bool equal(const T &obj1, const T &obj2, double tol)
Definition: Testable.h:85
vec1
RowVectorXd vec1(3)
gtsam::linear_dependent
bool linear_dependent(const Matrix &A, const Matrix &B, double tol)
Definition: Matrix.cpp:115
v1
Vector v1
Definition: testSerializationBase.cpp:38


gtsam
Author(s):
autogenerated on Wed Jan 1 2025 04:08:21