testOrientedPlane3.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 
12 /*
13  * @file testOrientedPlane3.cpp
14  * @date Dec 19, 2012
15  * @author Alex Trevor
16  * @author Zhaoyang Lv
17  * @brief Tests the OrientedPlane3 class
18  */
19 
23 
24 using namespace std::placeholders;
25 using namespace gtsam;
26 
29 
30 //*******************************************************************************
31 TEST(OrientedPlane3, getMethods) {
32  Vector4 c;
33  c << -1, 0, 0, 5;
34  OrientedPlane3 plane1(c);
35  OrientedPlane3 plane2(c[0], c[1], c[2], c[3]);
36  Vector4 coefficient1 = plane1.planeCoefficients();
37  double distance1 = plane1.distance();
38  EXPECT(assert_equal(coefficient1, c, 1e-8));
39  EXPECT(assert_equal(Unit3(-1,0,0).unitVector(), plane1.normal().unitVector()));
40  EXPECT_DOUBLES_EQUAL(distance1, 5, 1e-8);
41  Vector4 coefficient2 = plane2.planeCoefficients();
42  double distance2 = plane2.distance();
43  EXPECT(assert_equal(coefficient2, c, 1e-8));
45  EXPECT(assert_equal(Unit3(-1,0,0).unitVector(), plane2.normal().unitVector()));
46 }
47 
48 
49 //*******************************************************************************
50 OrientedPlane3 transform_(const OrientedPlane3& plane, const Pose3& xr) {
51  return plane.transform(xr);
52 }
53 
55  gtsam::Pose3 pose(gtsam::Rot3::Ypr(-M_PI / 4.0, 0.0, 0.0),
56  gtsam::Point3(2.0, 3.0, 4.0));
57  OrientedPlane3 plane(-1, 0, 0, 5);
58  OrientedPlane3 expectedPlane(-sqrt(2.0) / 2.0, -sqrt(2.0) / 2.0, 0.0, 3);
59  OrientedPlane3 transformedPlane = plane.transform(pose, {}, {});
60  EXPECT(assert_equal(expectedPlane, transformedPlane, 1e-5));
61 
62  // Test the jacobians of transform
63  Matrix actualH1, expectedH1, actualH2, expectedH2;
64  expectedH1 = numericalDerivative21(transform_, plane, pose);
65  plane.transform(pose, actualH1, {});
66  EXPECT(assert_equal(expectedH1, actualH1, 1e-5));
67 
68  expectedH2 = numericalDerivative22(transform_, plane, pose);
69  plane.transform(pose, {}, actualH2);
70  EXPECT(assert_equal(expectedH2, actualH2, 1e-5));
71 }
72 
73 //*******************************************************************************
74 // Returns a any size random vector
75 inline static Vector randomVector(const Vector& minLimits,
76  const Vector& maxLimits) {
77 
78  // Get the number of dimensions and create the return vector
79  size_t numDims = minLimits.size();
80  Vector vector = Vector::Zero(numDims);
81 
82  // Create the random vector
83  for (size_t i = 0; i < numDims; i++) {
84  double range = maxLimits(i) - minLimits(i);
85  vector(i) = (((double) rand()) / RAND_MAX) * range + minLimits(i);
86  }
87  return vector;
88 }
89 
90 //*******************************************************************************
91 TEST(OrientedPlane3, localCoordinates_retract) {
92  size_t numIterations = 10000;
93  Vector4 minPlaneLimit, maxPlaneLimit;
94  minPlaneLimit << -1.0, -1.0, -1.0, 0.01;
95  maxPlaneLimit << 1.0, 1.0, 1.0, 10.0;
96 
97  Vector3 minXiLimit, maxXiLimit;
98  minXiLimit << -M_PI, -M_PI, -10.0;
99  maxXiLimit << M_PI, M_PI, 10.0;
100  for (size_t i = 0; i < numIterations; i++) {
101  // Create a Plane
102  OrientedPlane3 p1(randomVector(minPlaneLimit, maxPlaneLimit));
103  Vector v12 = randomVector(minXiLimit, maxXiLimit);
104 
105  // Magnitude of the rotation can be at most pi
106  if (v12.head<3>().norm() > M_PI)
107  v12.head<3>() = v12.head<3>() / M_PI;
108  OrientedPlane3 p2 = p1.retract(v12);
109 
110  // Check if the local coordinates and retract return the same results.
111  Vector actual_v12 = p1.localCoordinates(p2);
112  EXPECT(assert_equal(v12, actual_v12, 1e-6));
113  OrientedPlane3 actual_p2 = p1.retract(actual_v12);
114  EXPECT(assert_equal(p2, actual_p2, 1e-6));
115  }
116 }
117 
118 //*******************************************************************************
119 TEST(OrientedPlane3, errorVector) {
120  OrientedPlane3 plane1(-1, 0.1, 0.2, 5);
121  OrientedPlane3 plane2(-1.1, 0.2, 0.3, 5.4);
122 
123  // Hard-coded regression values, to ensure the result doesn't change.
124  EXPECT(assert_equal((Vector) Z_3x1, plane1.errorVector(plane1), 1e-8));
125  EXPECT(assert_equal(Vector3(-0.0677674148, -0.0760543588, -0.4),
126  plane1.errorVector(plane2), 1e-5));
127 
128  // Test the jacobians of transform
129  Matrix33 actualH1, expectedH1, actualH2, expectedH2;
130 
131  Vector3 actual = plane1.errorVector(plane2, actualH1, actualH2);
132  EXPECT(assert_equal(plane1.normal().errorVector(plane2.normal()),
133  Vector2(actual[0], actual[1])));
134  EXPECT(assert_equal(plane1.distance() - plane2.distance(), actual[2]));
135 
136  std::function<Vector3(const OrientedPlane3&, const OrientedPlane3&)> f =
137  [](const OrientedPlane3& p1, const OrientedPlane3& p2) {
138  return p1.errorVector(p2);
139  };
140  expectedH1 = numericalDerivative21(f, plane1, plane2);
141  expectedH2 = numericalDerivative22(f, plane1, plane2);
142  EXPECT(assert_equal(expectedH1, actualH1, 1e-5));
143  EXPECT(assert_equal(expectedH2, actualH2, 1e-5));
144 }
145 
146 //*******************************************************************************
147 TEST(OrientedPlane3, jacobian_retract) {
148  OrientedPlane3 plane(-1, 0.1, 0.2, 5);
149  Matrix33 H_actual;
150  std::function<OrientedPlane3(const Vector3&)> f = [&plane](const Vector3& v) {
151  return plane.retract(v);
152  };
153 
154  {
155  Vector3 v(-0.1, 0.2, 0.3);
156  plane.retract(v, H_actual);
157  Matrix H_expected_numerical = numericalDerivative11(f, v);
158  EXPECT(assert_equal(H_expected_numerical, H_actual, 1e-5));
159  }
160  {
161  Vector3 v(0, 0, 0);
162  plane.retract(v, H_actual);
163  Matrix H_expected_numerical = numericalDerivative11(f, v);
164  EXPECT(assert_equal(H_expected_numerical, H_actual, 1e-5));
165  }
166 }
167 
168 //*******************************************************************************
169 TEST(OrientedPlane3, jacobian_normal) {
170  Matrix23 H_actual, H_expected;
171  OrientedPlane3 plane(-1, 0.1, 0.2, 5);
172 
173  std::function<Unit3(const OrientedPlane3&)> f = [](const OrientedPlane3& p) {
174  return p.normal();
175  };
176 
177  H_expected = numericalDerivative11(f, plane);
178  plane.normal(H_actual);
179  EXPECT(assert_equal(H_actual, H_expected, 1e-5));
180 }
181 
182 //*******************************************************************************
183 TEST(OrientedPlane3, jacobian_distance) {
184  Matrix13 H_actual, H_expected;
185  OrientedPlane3 plane(-1, 0.1, 0.2, 5);
186 
187  std::function<double(const OrientedPlane3&)> f = [](const OrientedPlane3& p) {
188  return p.distance();
189  };
190 
191  H_expected = numericalDerivative11(f, plane);
192  plane.distance(H_actual);
193  EXPECT(assert_equal(H_actual, H_expected, 1e-5));
194 }
195 
196 //*******************************************************************************
197 TEST(OrientedPlane3, getMethodJacobians) {
198  OrientedPlane3 plane(-1, 0.1, 0.2, 5);
199  Matrix33 H_retract, H_getters;
200  Matrix23 H_normal;
201  Matrix13 H_distance;
202 
203  // confirm the getters are exactly on the tangent space
204  Vector3 v(0, 0, 0);
205  plane.retract(v, H_retract);
206  plane.normal(H_normal);
207  plane.distance(H_distance);
208  H_getters << H_normal, H_distance;
209  EXPECT(assert_equal(H_retract, H_getters, 1e-5));
210 }
211 
212 /* ************************************************************************* */
213 int main() {
214  srand(time(nullptr));
215  TestResult tr;
216  return TestRegistry::runAllTests(tr);
217 }
218 /* ************************************************************************* */
TestRegistry::runAllTests
static int runAllTests(TestResult &result)
Definition: TestRegistry.cpp:27
gtsam::OrientedPlane3::transform
OrientedPlane3 transform(const Pose3 &xr, OptionalJacobian< 3, 3 > Hp={}, OptionalJacobian< 3, 6 > Hr={}) const
Definition: OrientedPlane3.cpp:35
pose
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
GTSAM_CONCEPT_TESTABLE_INST
#define GTSAM_CONCEPT_TESTABLE_INST(T)
Definition: Testable.h:176
EXPECT
#define EXPECT(condition)
Definition: Test.h:150
gtsam::Z_3x1
static const Eigen::MatrixBase< Vector3 >::ConstantReturnType Z_3x1
Definition: Vector.h:46
TestHarness.h
gtsam::distance2
double distance2(const Point2 &p, const Point2 &q, OptionalJacobian< 1, 2 > H1, OptionalJacobian< 1, 2 > H2)
distance between two points
Definition: Point2.cpp:39
c
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
gtsam::numericalDerivative11
internal::FixedSizeMatrix< Y, X >::type numericalDerivative11(std::function< Y(const X &)> h, const X &x, double delta=1e-5)
New-style numerical derivatives using manifold_traits.
Definition: numericalDerivative.h:110
gtsam::numericalDerivative22
internal::FixedSizeMatrix< Y, X2 >::type numericalDerivative22(std::function< Y(const X1 &, const X2 &)> h, const X1 &x1, const X2 &x2, double delta=1e-5)
Definition: numericalDerivative.h:195
gtsam::Matrix
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
gtsam::Vector3
Eigen::Vector3d Vector3
Definition: Vector.h:43
transform_
OrientedPlane3 transform_(const OrientedPlane3 &plane, const Pose3 &xr)
Definition: testOrientedPlane3.cpp:50
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:38
gtsam::Rot3::Ypr
static Rot3 Ypr(double y, double p, double r, OptionalJacobian< 3, 1 > Hy={}, OptionalJacobian< 3, 1 > Hp={}, OptionalJacobian< 3, 1 > Hr={})
Definition: Rot3.h:196
gtsam::OrientedPlane3
Represents an infinite plane in 3D, which is composed of a planar normal and its perpendicular distan...
Definition: OrientedPlane3.h:36
OrientedPlane3.h
gtsam::range
Double_ range(const Point2_ &p, const Point2_ &q)
Definition: slam/expressions.h:30
simple::p2
static Point3 p2
Definition: testInitializePose3.cpp:51
numericalDerivative.h
Some functions to compute numerical derivatives.
randomVector
static Vector randomVector(const Vector &minLimits, const Vector &maxLimits)
Definition: testOrientedPlane3.cpp:75
gtsam::Pose3
Definition: Pose3.h:37
gtsam::OrientedPlane3::distance
double distance(OptionalJacobian< 1, 3 > H={}) const
Return the perpendicular distance to the origin.
Definition: OrientedPlane3.h:134
gtsam::OrientedPlane3::normal
Unit3 normal(OptionalJacobian< 2, 3 > H={}) const
Return the normal.
Definition: OrientedPlane3.h:128
Vector2
Definition: test_operator_overloading.cpp:18
transform
EIGEN_DONT_INLINE void transform(const Transformation &t, Data &data)
Definition: geometry.cpp:25
time
#define time
Definition: timeAdaptAutoDiff.cpp:31
EXPECT_DOUBLES_EQUAL
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
Definition: Test.h:161
p1
Vector3f p1
Definition: MatrixBase_all.cpp:2
TestResult
Definition: TestResult.h:26
tree::f
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Definition: testExpression.cpp:218
gtsam::OrientedPlane3::planeCoefficients
Vector4 planeCoefficients() const
Returns the plane coefficients.
Definition: OrientedPlane3.h:122
gtsam::Unit3::errorVector
Vector2 errorVector(const Unit3 &q, OptionalJacobian< 2, 2 > H_p={}, OptionalJacobian< 2, 2 > H_q={}) const
Definition: Unit3.cpp:209
main
int main()
Definition: testOrientedPlane3.cpp:213
gtsam
traits
Definition: SFMdata.h:40
gtsam::numericalDerivative21
internal::FixedSizeMatrix< Y, X1 >::type numericalDerivative21(const std::function< Y(const X1 &, const X2 &)> &h, const X1 &x1, const X2 &x2, double delta=1e-5)
Definition: numericalDerivative.h:166
p
float * p
Definition: Tutorial_Map_using.cpp:9
TEST
TEST(OrientedPlane3, getMethods)
Definition: testOrientedPlane3.cpp:31
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:40
GTSAM_CONCEPT_MANIFOLD_INST
#define GTSAM_CONCEPT_MANIFOLD_INST(T)
‍**
Definition: Manifold.h:177
gtsam::Point3
Vector3 Point3
Definition: Point3.h:38
gtsam::OrientedPlane3::errorVector
Vector3 errorVector(const OrientedPlane3 &other, OptionalJacobian< 3, 3 > H1={}, OptionalJacobian< 3, 3 > H2={}) const
Definition: OrientedPlane3.cpp:61
gtsam::Unit3
Represents a 3D point on a unit sphere.
Definition: Unit3.h:42
M_PI
#define M_PI
Definition: mconf.h:117
gtsam::Unit3::unitVector
Vector3 unitVector(OptionalJacobian< 3, 2 > H={}) const
Return unit-norm Vector.
Definition: Unit3.cpp:151
ceres::sqrt
Jet< T, N > sqrt(const Jet< T, N > &f)
Definition: jet.h:418
i
int i
Definition: BiCGSTAB_step_by_step.cpp:9
gtsam::OrientedPlane3::retract
OrientedPlane3 retract(const Vector3 &v, OptionalJacobian< 3, 3 > H={}) const
The retract function.
Definition: OrientedPlane3.cpp:81


gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:08:04