testVector.cpp
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 #include <gtsam/base/Vector.h>
19 #include <gtsam/base/VectorSpace.h>
20 #include <gtsam/base/testLie.h>
22 #include <iostream>
23 
24 using namespace std;
25 using namespace gtsam;
26 
27 namespace {
28  /* ************************************************************************* */
29  template<typename Derived>
30  Vector testFcn1(const Eigen::DenseBase<Derived>& in)
31  {
32  return in;
33  }
34 
35  /* ************************************************************************* */
36  template<typename Derived>
37  Vector testFcn2(const Eigen::MatrixBase<Derived>& in)
38  {
39  return in;
40  }
41 }
42 
43 /* ************************************************************************* */
44 TEST(Vector, special_comma_initializer)
45 {
46  Vector expected(3);
47  expected(0) = 1;
48  expected(1) = 2;
49  expected(2) = 3;
50 
51  Vector actual1 = Vector3(1, 2, 3);
52  Vector actual2(Vector3(1, 2, 3));
53 
54  Vector subvec1 = Vector2(2, 3);
55  Vector actual4 = (Vector(3) << 1, subvec1).finished();
56 
57  Vector subvec2 = Vector2(1, 2);
58  Vector actual5 = (Vector(3) << subvec2, 3).finished();
59 
60  Vector actual6 = testFcn1(Vector3(1, 2, 3));
61  Vector actual7 = testFcn2(Vector3(1, 2, 3));
62 
63  EXPECT(assert_equal(expected, actual1));
64  EXPECT(assert_equal(expected, actual2));
65  EXPECT(assert_equal(expected, actual4));
66  EXPECT(assert_equal(expected, actual5));
67  EXPECT(assert_equal(expected, actual6));
68  EXPECT(assert_equal(expected, actual7));
69 }
70 
71 /* ************************************************************************* */
72 TEST(Vector, copy )
73 {
74  Vector a(2); a(0) = 10; a(1) = 20;
75  double data[] = {10,20};
76  Vector b(2);
77  copy(data,data+2,b.data());
79 }
80 
81 /* ************************************************************************* */
82 TEST(Vector, scalar_multiply )
83 {
84  Vector a(2); a(0) = 10; a(1) = 20;
85  Vector b(2); b(0) = 1; b(1) = 2;
86  EXPECT(assert_equal(a,b*10.0));
87 }
88 
89 /* ************************************************************************* */
90 TEST(Vector, scalar_divide )
91 {
92  Vector a(2); a(0) = 10; a(1) = 20;
93  Vector b(2); b(0) = 1; b(1) = 2;
94  EXPECT(assert_equal(b,a/10.0));
95 }
96 
97 /* ************************************************************************* */
99 {
100  Vector a(2); a(0) = 10; a(1) = 20;
101  Vector b(2); b(0) = -10; b(1) = -20;
102  EXPECT(assert_equal(b, -a));
103 }
104 
105 /* ************************************************************************* */
107 {
108  Vector x(4);
109  x(0) = 3; x(1) = 1; x(2) = 5; x(3) = 1;
110 
111  Vector expected(4);
112  expected(0) = 1.0; expected(1) = -0.333333; expected(2) = -1.66667; expected(3) = -0.333333;
113 
114  pair<double, Vector> result = house(x);
115 
116  EXPECT(result.first==0.5);
118 }
119 
120 /* ************************************************************************* */
122 {
123  Vector A(2);
124  for(int i = 0; i < 2; i++)
125  A(i) = i;
126  Vector B(5);
127  for(int i = 0; i < 5; i++)
128  B(i) = i;
129 
130  Vector C(7);
131  for(int i = 0; i < 2; i++) C(i) = A(i);
132  for(int i = 0; i < 5; i++) C(i+2) = B(i);
133 
134  list<Vector> vs;
135  vs.push_back(A);
136  vs.push_back(B);
137  Vector AB1 = concatVectors(vs);
138  EXPECT(AB1 == C);
139 
140  Vector AB2 = concatVectors(2, &A, &B);
141  EXPECT(AB2 == C);
142 }
143 
144 /* ************************************************************************* */
146 {
147  // column from a matrix
148  Vector x(2);
149  x(0) = 1.0; x(1) = 2.0;
150 
151  // create sigmas
152  Vector sigmas(2);
153  sigmas(0) = 0.1; sigmas(1) = 0.2;
154  Vector weights = sigmas.array().square().inverse();
155 
156  // perform solve
157  const auto [actual, precision] = weightedPseudoinverse(x, weights);
158 
159  // construct expected
160  Vector expected(2);
161  expected(0) = 0.5; expected(1) = 0.25;
162  double expPrecision = 200.0;
163 
164  // verify
165  EXPECT(assert_equal(expected,actual));
166  EXPECT(std::abs(expPrecision-precision) < 1e-5);
167 }
168 
169 /* ************************************************************************* */
170 TEST(Vector, weightedPseudoinverse_constraint )
171 {
172  // column from a matrix
173  Vector x(2);
174  x(0) = 1.0; x(1) = 2.0;
175 
176  // create sigmas
177  Vector sigmas(2);
178  sigmas(0) = 0.0; sigmas(1) = 0.2;
179  Vector weights = sigmas.array().square().inverse();
180  // perform solve
181  const auto [actual, precision] = weightedPseudoinverse(x, weights);
182 
183  // construct expected
184  Vector expected(2);
185  expected(0) = 1.0; expected(1) = 0.0;
186 
187  // verify
188  EXPECT(assert_equal(expected,actual));
190 }
191 
192 /* ************************************************************************* */
193 TEST(Vector, weightedPseudoinverse_nan )
194 {
195  Vector a = (Vector(4) << 1., 0., 0., 0.).finished();
196  Vector sigmas = (Vector(4) << 0.1, 0.1, 0., 0.).finished();
197  Vector weights = sigmas.array().square().inverse();
198  const auto [pseudo, precision] = weightedPseudoinverse(a, weights);
199 
200  Vector expected = (Vector(4) << 1., 0., 0.,0.).finished();
201  EXPECT(assert_equal(expected, pseudo));
202  DOUBLES_EQUAL(100, precision, 1e-5);
203 }
204 
205 /* ************************************************************************* */
207 {
208  Vector a = Vector3(10., 20., 30.);
209  Vector b = Vector3(2.0, 5.0, 6.0);
210  DOUBLES_EQUAL(20+100+180,dot(a,b),1e-9);
211 }
212 
213 /* ************************************************************************* */
215 {
216  Vector x = Vector3(10., 20., 30.);
217  Vector y0 = Vector3(2.0, 5.0, 6.0);
218  Vector y1 = y0, y2 = y0;
219  y1 += 0.1 * x;
220  y2.head(3) += 0.1 * x;
221  Vector expected = Vector3(3.0, 7.0, 9.0);
224 }
225 
226 /* ************************************************************************* */
228 {
229  Vector v1 = (Vector(1) << 0.0/std::numeric_limits<double>::quiet_NaN()).finished(); //testing nan
230  Vector v2 = (Vector(1) << 1.0).finished();
231  double tol = 1.;
233 }
234 
235 /* ************************************************************************* */
236 TEST(Vector, greater_than )
237 {
238  Vector v1 = Vector3(1.0, 2.0, 3.0),
239  v2 = Z_3x1;
240  EXPECT(greaterThanOrEqual(v1, v1)); // test basic greater than
241  EXPECT(greaterThanOrEqual(v1, v2)); // test equals
242 }
243 
244 /* ************************************************************************* */
246 {
247  Vector v1 = Vector3(1.0, 2.0, 3.0);
248  Vector v2 = Vector3(-2.0, -4.0, -6.0);
250 }
251 
252 /* ************************************************************************* */
253 TEST(Vector, linear_dependent2 )
254 {
255  Vector v1 = Vector3(0.0, 2.0, 0.0);
256  Vector v2 = Vector3(0.0, -4.0, 0.0);
258 }
259 
260 /* ************************************************************************* */
261 TEST(Vector, linear_dependent3 )
262 {
263  Vector v1 = Vector3(0.0, 2.0, 0.0);
264  Vector v2 = Vector3(0.1, -4.1, 0.0);
266 }
267 
268 //******************************************************************************
269 TEST(Vector, VectorIsVectorSpace) {
272 }
273 
274 TEST(Vector, RowVectorIsVectorSpace) {
275 #ifdef GTSAM_USE_BOOST_FEATURES
276  typedef Eigen::Matrix<double,1,-1> RowVector;
278 #endif
279 }
280 
281 /* ************************************************************************* */
282 int main() { TestResult tr; return TestRegistry::runAllTests(tr); }
283 /* ************************************************************************* */
TestRegistry::runAllTests
static int runAllTests(TestResult &result)
Definition: TestRegistry.cpp:27
B
Matrix< SCALARB, Dynamic, Dynamic, opt_B > B
Definition: bench_gemm.cpp:49
Vector.h
typedef and functions to augment Eigen's VectorXd
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
gtsam::weightedPseudoinverse
double weightedPseudoinverse(const Vector &a, const Vector &weights, Vector &pseudo)
Definition: Vector.cpp:245
EXPECT
#define EXPECT(condition)
Definition: Test.h:150
gtsam::Vector2
Eigen::Vector2d Vector2
Definition: Vector.h:42
gtsam::Z_3x1
static const Eigen::MatrixBase< Vector3 >::ConstantReturnType Z_3x1
Definition: Vector.h:46
TestHarness.h
gtsam::RowVector
Eigen::RowVectorXd RowVector
Definition: LinearCost.h:25
b
Scalar * b
Definition: benchVecAdd.cpp:17
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
copy
int EIGEN_BLAS_FUNC() copy(int *n, RealScalar *px, int *incx, RealScalar *py, int *incy)
Definition: level1_impl.h:29
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
gtsam::Vector3
Eigen::Vector3d Vector3
Definition: Vector.h:43
testLie.h
TEST
TEST(Vector, special_comma_initializer)
Definition: testVector.cpp:44
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:38
result
Values result
Definition: OdometryOptimize.cpp:8
gtsam::concatVectors
Vector concatVectors(const std::list< Vector > &vs)
Definition: Vector.cpp:301
gtsam::IsVectorSpace
Vector Space concept.
Definition: VectorSpace.h:470
y0
double y0(double x)
Definition: j0.c:220
A
Matrix< SCALARA, Dynamic, Dynamic, opt_A > A
Definition: bench_gemm.cpp:48
dot
Scalar EIGEN_BLAS_FUNC() dot(int *n, RealScalar *px, int *incx, RealScalar *py, int *incy)
Definition: level1_real_impl.h:49
householder
void householder(const MatrixType &m)
Definition: householder.cpp:13
y1
double y1(double x)
Definition: j1.c:199
data
int data[]
Definition: Map_placement_new.cpp:1
Eigen::internal::negate
T negate(const T &x)
Definition: packetmath_test_shared.h:24
main
int main()
Definition: testVector.cpp:282
DOUBLES_EQUAL
#define DOUBLES_EQUAL(expected, actual, threshold)
Definition: Test.h:141
axpy
int EIGEN_BLAS_FUNC() axpy(const int *n, const RealScalar *palpha, const RealScalar *px, const int *incx, RealScalar *py, const int *incy)
Definition: level1_impl.h:12
exampleQR::sigmas
Vector sigmas
Definition: testNoiseModel.cpp:212
cholesky::expected
Matrix expected
Definition: testMatrix.cpp:971
gtsam::equals
Definition: Testable.h:112
TestResult
Definition: TestResult.h:26
gtsam::greaterThanOrEqual
bool greaterThanOrEqual(const Vector &vec1, const Vector &vec2)
Definition: Vector.cpp:113
a
ArrayXXi a
Definition: Array_initializer_list_23_cxx11.cpp:1
C
Matrix< Scalar, Dynamic, Dynamic > C
Definition: bench_gemm.cpp:50
gtsam
traits
Definition: chartTesting.h:28
precision
cout precision(2)
Eigen::DenseBase
Base class for all dense matrices, vectors, and arrays.
Definition: DenseBase.h:41
std
Definition: BFloat16.h:88
v2
Vector v2
Definition: testSerializationBase.cpp:39
gtsam::assert_equal
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:40
gtsam::tol
const G double tol
Definition: Group.h:79
gtsam::house
pair< double, Vector > house(const Vector &x)
Definition: Vector.cpp:236
Eigen::Matrix
The matrix class, also used for vectors and row-vectors.
Definition: 3rdparty/Eigen/Eigen/src/Core/Matrix.h:178
abs
#define abs(x)
Definition: datatypes.h:17
Eigen::MatrixBase
Base class for all dense matrices, vectors, and expressions.
Definition: MatrixBase.h:48
ceres::Vector
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
Definition: gtsam/3rdparty/ceres/eigen.h:38
VectorSpace.h
GTSAM_CONCEPT_ASSERT
#define GTSAM_CONCEPT_ASSERT(concept)
Definition: base/concepts.h:22
i
int i
Definition: BiCGSTAB_step_by_step.cpp:9
gtsam::linear_dependent
bool linear_dependent(const Matrix &A, const Matrix &B, double tol)
Definition: Matrix.cpp:114
v1
Vector v1
Definition: testSerializationBase.cpp:38
isinf
#define isinf(X)
Definition: main.h:94


gtsam
Author(s):
autogenerated on Thu Jun 13 2024 03:10:46