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 
21 // \callgraph
22 
23 #pragma once
24 #ifndef MKL_BLAS
25 #define MKL_BLAS MKL_DOMAIN_BLAS
26 #endif
27 
28 #include <gtsam/global_includes.h>
29 #include <Eigen/Core>
30 #include <iosfwd>
31 #include <list>
32 
33 namespace gtsam {
34 
35 // Vector is just a typedef of the Eigen dynamic vector type
36 
37 // Typedef arbitary length vector
38 typedef Eigen::VectorXd Vector;
39 
40 // Commonly used fixed size vectors
42 typedef Eigen::Vector2d Vector2;
43 typedef Eigen::Vector3d Vector3;
44 
47 
48 // Create handy typedefs and constants for vectors with N>3
49 // VectorN and Z_Nx1, for N=1..9
50 #define GTSAM_MAKE_VECTOR_DEFS(N) \
51  using Vector##N = Eigen::Matrix<double, N, 1>; \
52  static const Eigen::MatrixBase<Vector##N>::ConstantReturnType Z_##N##x1 = Vector##N::Zero();
53 
64 
65 typedef Eigen::VectorBlock<Vector> SubVector;
66 typedef Eigen::VectorBlock<const Vector> ConstSubVector;
67 
73 #if defined(GTSAM_EIGEN_VERSION_WORLD)
74 static_assert(
75  GTSAM_EIGEN_VERSION_WORLD==EIGEN_WORLD_VERSION &&
76  GTSAM_EIGEN_VERSION_MAJOR==EIGEN_MAJOR_VERSION,
77  "Error: GTSAM was built against a different version of Eigen");
78 #endif
79 
96 GTSAM_EXPORT bool fpEqual(double a, double b, double tol,
97  bool check_relative_also = true);
98 
102 GTSAM_EXPORT void print(const Vector& v, const std::string& s, std::ostream& stream);
103 
107 GTSAM_EXPORT void print(const Vector& v, const std::string& s = "");
108 
112 GTSAM_EXPORT void save(const Vector& A, const std::string &s, const std::string& filename);
113 
117 GTSAM_EXPORT bool operator==(const Vector& vec1,const Vector& vec2);
118 
124 GTSAM_EXPORT bool greaterThanOrEqual(const Vector& v1, const Vector& v2);
125 
129 GTSAM_EXPORT bool equal_with_abs_tol(const Vector& vec1, const Vector& vec2, double tol=1e-9);
130 GTSAM_EXPORT bool equal_with_abs_tol(const SubVector& vec1, const SubVector& vec2, double tol=1e-9);
131 
135 inline bool equal(const Vector& vec1, const Vector& vec2, double tol) {
136  return equal_with_abs_tol(vec1, vec2, tol);
137 }
138 
142 inline bool equal(const Vector& vec1, const Vector& vec2) {
143  return equal_with_abs_tol(vec1, vec2);
144 }
145 
153 GTSAM_EXPORT bool assert_equal(const Vector& vec1, const Vector& vec2, double tol=1e-9);
154 
162 GTSAM_EXPORT bool assert_inequal(const Vector& vec1, const Vector& vec2, double tol=1e-9);
163 
171 GTSAM_EXPORT bool assert_equal(const SubVector& vec1, const SubVector& vec2, double tol=1e-9);
172 GTSAM_EXPORT bool assert_equal(const ConstSubVector& vec1, const ConstSubVector& vec2, double tol=1e-9);
173 
181 GTSAM_EXPORT bool linear_dependent(const Vector& vec1, const Vector& vec2, double tol=1e-9);
182 
189 GTSAM_EXPORT Vector ediv_(const Vector &a, const Vector &b);
190 
194 template<class V1, class V2>
195 inline double dot(const V1 &a, const V2& b) {
196  assert (b.size()==a.size());
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  assert (b.size()==a.size());
204  return a.dot(b);
205 }
206 
212 GTSAM_EXPORT std::pair<double,Vector> house(const Vector &x);
213 
215 GTSAM_EXPORT double houseInPlace(Vector &x);
216 
227 GTSAM_EXPORT std::pair<Vector, double>
228 weightedPseudoinverse(const Vector& v, const Vector& weights);
229 
230 /*
231  * Fast version *no error checking* !
232  * Pass in initialized vector pseudo of size(weights) or will crash !
233  * @return the precision, pseudoinverse in third argument
234  */
235 GTSAM_EXPORT double weightedPseudoinverse(const Vector& a, const Vector& weights, Vector& pseudo);
236 
240 GTSAM_EXPORT Vector concatVectors(const std::list<Vector>& vs);
241 
245 GTSAM_EXPORT Vector concatVectors(size_t nrVectors, ...);
246 } // namespace gtsam
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
Generic expression of a matrix where all coefficients are defined by a functor.
void save(const Matrix &A, const string &s, const string &filename)
Definition: Matrix.cpp:166
double weightedPseudoinverse(const Vector &a, const Vector &weights, Vector &pseudo)
Definition: Vector.cpp:245
static const Eigen::MatrixBase< Vector3 >::ConstantReturnType Z_3x1
Definition: Vector.h:46
Vector v2
Eigen::Vector3d Vector3
Definition: Vector.h:43
double dot(const V1 &a, const V2 &b)
Definition: Vector.h:195
Vector v1
Vector ediv_(const Vector &a, const Vector &b)
Definition: Vector.cpp:198
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:40
Namespace containing all symbols from the Eigen library.
Definition: jet.h:637
bool operator==(const Matrix &A, const Matrix &B)
Definition: base/Matrix.h:99
bool greaterThanOrEqual(const Vector &vec1, const Vector &vec2)
Definition: Vector.cpp:113
Included from all GTSAM files.
bool linear_dependent(const Matrix &A, const Matrix &B, double tol)
Definition: Matrix.cpp:114
bool fpEqual(double a, double b, double tol, bool check_relative_also)
Definition: Vector.cpp:41
Expression of a fixed-size or dynamic-size sub-vector.
pair< double, Vector > house(const Vector &x)
Definition: Vector.cpp:236
bool assert_inequal(const Matrix &A, const Matrix &B, double tol)
Definition: Matrix.cpp:60
Eigen::VectorXd Vector
Definition: Vector.h:38
#define EIGEN_WORLD_VERSION
Definition: Macros.h:18
Array< int, Dynamic, 1 > v
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
const G & b
Definition: Group.h:86
bool equal_with_abs_tol(const Eigen::DenseBase< MATRIX > &A, const Eigen::DenseBase< MATRIX > &B, double tol=1e-9)
Definition: base/Matrix.h:80
Eigen::Matrix< double, 1, 1 > Vector1
Definition: Vector.h:41
traits
Definition: chartTesting.h:28
RowVectorXd vec1(3)
Eigen::Vector2d Vector2
Definition: Vector.h:42
#define EIGEN_MAJOR_VERSION
Definition: Macros.h:19
double houseInPlace(Vector &v)
Definition: Vector.cpp:211
double inner_prod(const V1 &a, const V2 &b)
Definition: Vector.h:202
const G double tol
Definition: Group.h:86
The matrix class, also used for vectors and row-vectors.
bool equal(const T &obj1, const T &obj2, double tol)
Definition: Testable.h:85
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
Vector concatVectors(const std::list< Vector > &vs)
Definition: Vector.cpp:301
static const Eigen::MatrixBase< Vector2 >::ConstantReturnType Z_2x1
Definition: Vector.h:45
#define GTSAM_MAKE_VECTOR_DEFS(N)
Definition: Vector.h:50


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:40:43