Classes | Macros | Functions | Variables
testRot3.cpp File Reference

Unit tests for Rot3 class - common between Matrix and Quaternion. More...

#include <gtsam/geometry/Point3.h>
#include <gtsam/geometry/Rot3.h>
#include <gtsam/base/testLie.h>
#include <gtsam/base/Testable.h>
#include <gtsam/base/numericalDerivative.h>
#include <gtsam/base/lieProxies.h>
#include <boost/math/constants/constants.hpp>
#include <CppUnitLite/TestHarness.h>
Include dependency graph for testRot3.cpp:

Go to the source code of this file.

Classes

class  AngularVelocity
 

Macros

#define CHECK_AXIS_ANGLE(expectedAxis, expectedAngle, rotation)
 
#define CHECK_OMEGA(X, Y, Z)
 
#define CHECK_OMEGA_ZERO(X, Y, Z)
 

Functions

AngularVelocity bracket (const AngularVelocity &X, const AngularVelocity &Y)
 
Matrix Cayley (const Matrix &A)
 
int main ()
 
static Point3 P (0.2, 0.7,-2.0)
 
double pitch_proxy (Rot3 const &R)
 
double roll_proxy (Rot3 const &R)
 
Vector3 rpy_proxy (Rot3 const &R)
 
Vector3 RQ_proxy (Matrix3 const &R)
 
Rot3 RzRyRx_proxy (double const &a, double const &b, double const &c)
 
Rot3 RzRyRx_proxy (Vector3 const &xyz)
 
Rot3 slow_but_correct_Rodrigues (const Vector &w)
 
 TEST (Rot3, Concept)
 
 TEST (Rot3, chart)
 
 TEST (Rot3, constructor)
 
 TEST (Rot3, constructor2)
 
 TEST (Rot3, constructor3)
 
 TEST (Rot3, transpose)
 
 TEST (Rot3, equals)
 
 TEST (Rot3, AxisAngle)
 
 TEST (Rot3, Rodrigues)
 
 TEST (Rot3, Rodrigues2)
 
 TEST (Rot3, Rodrigues3)
 
 TEST (Rot3, Rodrigues4)
 
 TEST (Rot3, retract)
 
 TEST (Rot3, log)
 
 TEST (Rot3, retract_localCoordinates)
 
 TEST (Rot3, expmap_logmap)
 
 TEST (Rot3, retract_localCoordinates2)
 
 TEST (Rot3, manifold_expmap)
 
 TEST (Rot3, BCH)
 
 TEST (Rot3, rotate_derivatives)
 
 TEST (Rot3, unrotate)
 
 TEST (Rot3, compose)
 
 TEST (Rot3, inverse)
 
 TEST (Rot3, between)
 
 TEST (Rot3, xyz)
 
 TEST (Rot3, yaw_pitch_roll)
 
 TEST (Rot3, RQ)
 
 TEST (Rot3, expmapStability)
 
 TEST (Rot3, logmapStability)
 
 TEST (Rot3, quaternion)
 
 TEST (Rot3, Cayley)
 
 TEST (Rot3, stream)
 
 TEST (Rot3, slerp)
 
 TEST (Rot3, Invariants)
 
 TEST (Rot3, LieGroupDerivatives)
 
 TEST (Rot3, ChartDerivatives)
 
 TEST (Rot3, ClosestTo)
 
 TEST (Rot3, axisAngle)
 
 TEST (Rot3, RzRyRx_scalars_derivative)
 
 TEST (Rot3, RzRyRx_vector_derivative)
 
 TEST (Rot3, Ypr_derivative)
 
 TEST (Rot3, RQ_derivative)
 
 TEST (Rot3, xyz_derivative)
 
 TEST (Rot3, ypr_derivative)
 
 TEST (Rot3, rpy_derivative)
 
 TEST (Rot3, roll_derivative)
 
 TEST (Rot3, pitch_derivative)
 
 TEST (Rot3, yaw_derivative)
 
 TEST (Rot3, determinant)
 
Vector3 xyz_proxy (Rot3 const &R)
 
double yaw_proxy (Rot3 const &R)
 
Rot3 Ypr_proxy (double const &y, double const &p, double const &r)
 
Vector3 ypr_proxy (Rot3 const &R)
 

Variables

static double epsilon = 0.001
 
static double error = 1e-9
 
static Rot3 R = Rot3::Rodrigues(0.1, 0.4, 0.2)
 
Rot3 T1 (Rot3::AxisAngle(Vector3(0, 0, 1), 1))
 
Rot3 T2 (Rot3::AxisAngle(Vector3(0, 1, 0), 2))
 

Detailed Description

Unit tests for Rot3 class - common between Matrix and Quaternion.

Unit tests for Rot3Q class.

Unit tests for Rot3 class, Quaternion specific.

Author
Alireza Fathi
Frank Dellaert
Varun Agrawal
Alireza Fathi
Richard Roberts

Definition in file testRot3.cpp.

Macro Definition Documentation

#define CHECK_AXIS_ANGLE (   expectedAxis,
  expectedAngle,
  rotation 
)
Value:
std::tie(actualAxis, actualAngle) = rotation.axisAngle(); \
EXPECT(assert_equal(expectedAxis, actualAxis, 1e-9)); \
EXPECT_DOUBLES_EQUAL(expectedAngle, actualAngle, 1e-9); \
EXPECT(assert_equal(rotation, Rot3::AxisAngle(expectedAxis, expectedAngle)))
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
Definition: Test.h:162
#define EXPECT(condition)
Definition: Test.h:151
Array< double, 1, 3 > e(1./3., 0.5, 2.)
std::pair< Unit3, double > axisAngle() const
Definition: Rot3.cpp:242
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:42
Rot3 rotation(const Pose3 &pose, OptionalJacobian< 3, 6 > H)
#define CHECK_OMEGA (   X,
  Y,
  Z 
)
Value:
w = (Vector(3) << X, Y, Z).finished(); \
R = Rot3::Rodrigues(w); \
EXPECT(assert_equal(w, Rot3::Logmap(R), 1e-12));
#define Z
Definition: icosphere.cpp:21
#define EXPECT(condition)
Definition: Test.h:151
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RowVector3d w
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:42
#define X
Definition: icosphere.cpp:20
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
static Rot3 R
Definition: testRot3.cpp:37
#define CHECK_OMEGA_ZERO (   X,
  Y,
  Z 
)
Value:
w = (Vector(3) << X, Y, Z).finished(); \
R = Rot3::Rodrigues(w); \
EXPECT(assert_equal((Vector)Z_3x1, Rot3::Logmap(R)));
static const Eigen::MatrixBase< Vector3 >::ConstantReturnType Z_3x1
Definition: Vector.h:46
#define Z
Definition: icosphere.cpp:21
Eigen::VectorXd Vector
Definition: Vector.h:38
#define EXPECT(condition)
Definition: Test.h:151
RowVector3d w
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:42
#define X
Definition: icosphere.cpp:20
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
static Rot3 R
Definition: testRot3.cpp:37

Function Documentation

AngularVelocity bracket ( const AngularVelocity X,
const AngularVelocity Y 
)

Definition at line 326 of file testRot3.cpp.

Matrix Cayley ( const Matrix A)

Definition at line 592 of file testRot3.cpp.

int main ( void  )

Definition at line 934 of file testRot3.cpp.

static Point3 P ( 0.  2,
0.  7,
-2.  0 
)
static
double pitch_proxy ( Rot3 const &  R)

Definition at line 888 of file testRot3.cpp.

double roll_proxy ( Rot3 const &  R)

Definition at line 875 of file testRot3.cpp.

Vector3 rpy_proxy ( Rot3 const &  R)

Definition at line 862 of file testRot3.cpp.

Vector3 RQ_proxy ( Matrix3 const &  R)

Definition at line 798 of file testRot3.cpp.

Rot3 RzRyRx_proxy ( double const &  a,
double const &  b,
double const &  c 
)

Definition at line 747 of file testRot3.cpp.

Rot3 RzRyRx_proxy ( Vector3 const &  xyz)

Definition at line 766 of file testRot3.cpp.

Rot3 slow_but_correct_Rodrigues ( const Vector w)

Definition at line 99 of file testRot3.cpp.

TEST ( Rot3  ,
Concept   
)

Definition at line 42 of file testRot3.cpp.

TEST ( Rot3  ,
chart   
)

Definition at line 49 of file testRot3.cpp.

TEST ( Rot3  ,
constructor   
)

Definition at line 56 of file testRot3.cpp.

TEST ( Rot3  ,
constructor2   
)

Definition at line 65 of file testRot3.cpp.

TEST ( Rot3  ,
constructor3   
)

Definition at line 74 of file testRot3.cpp.

TEST ( Rot3  ,
transpose   
)

Definition at line 82 of file testRot3.cpp.

TEST ( Rot3  ,
equals   
)

Definition at line 90 of file testRot3.cpp.

TEST ( Rot3  ,
AxisAngle   
)

Definition at line 108 of file testRot3.cpp.

TEST ( Rot3  ,
Rodrigues   
)

Definition at line 126 of file testRot3.cpp.

TEST ( Rot3  ,
Rodrigues2   
)

Definition at line 135 of file testRot3.cpp.

TEST ( Rot3  ,
Rodrigues3   
)

Definition at line 149 of file testRot3.cpp.

TEST ( Rot3  ,
Rodrigues4   
)

Definition at line 158 of file testRot3.cpp.

TEST ( Rot3  ,
retract   
)

Definition at line 172 of file testRot3.cpp.

TEST ( Rot3  ,
log   
)

Definition at line 184 of file testRot3.cpp.

TEST ( Rot3  ,
retract_localCoordinates   
)

Definition at line 262 of file testRot3.cpp.

TEST ( Rot3  ,
expmap_logmap   
)

Definition at line 269 of file testRot3.cpp.

TEST ( Rot3  ,
retract_localCoordinates2   
)

Definition at line 277 of file testRot3.cpp.

TEST ( Rot3  ,
manifold_expmap   
)

Definition at line 287 of file testRot3.cpp.

TEST ( Rot3  ,
BCH   
)

Definition at line 331 of file testRot3.cpp.

TEST ( Rot3  ,
rotate_derivatives   
)

Definition at line 344 of file testRot3.cpp.

TEST ( Rot3  ,
unrotate   
)

Definition at line 358 of file testRot3.cpp.

TEST ( Rot3  ,
compose   
)

Definition at line 373 of file testRot3.cpp.

TEST ( Rot3  ,
inverse   
)

Definition at line 393 of file testRot3.cpp.

TEST ( Rot3  ,
between   
)

Definition at line 409 of file testRot3.cpp.

TEST ( Rot3  ,
xyz   
)

Definition at line 441 of file testRot3.cpp.

TEST ( Rot3  ,
yaw_pitch_roll   
)

Definition at line 472 of file testRot3.cpp.

TEST ( Rot3  ,
RQ   
)

Definition at line 493 of file testRot3.cpp.

TEST ( Rot3  ,
expmapStability   
)

Definition at line 525 of file testRot3.cpp.

TEST ( Rot3  ,
logmapStability   
)

Definition at line 541 of file testRot3.cpp.

TEST ( Rot3  ,
quaternion   
)

Definition at line 554 of file testRot3.cpp.

TEST ( Rot3  ,
Cayley   
)

Definition at line 598 of file testRot3.cpp.

TEST ( Rot3  ,
stream   
)

Definition at line 606 of file testRot3.cpp.

TEST ( Rot3  ,
slerp   
)

Definition at line 616 of file testRot3.cpp.

TEST ( Rot3  ,
Invariants   
)

Definition at line 632 of file testRot3.cpp.

TEST ( Rot3  ,
LieGroupDerivatives   
)

Definition at line 649 of file testRot3.cpp.

TEST ( Rot3  ,
ChartDerivatives   
)

Definition at line 660 of file testRot3.cpp.

TEST ( Rot3  ,
ClosestTo   
)

Definition at line 672 of file testRot3.cpp.

TEST ( Rot3  ,
axisAngle   
)

Non-trivial angle 165

Non-trivial angle 195

Definition at line 688 of file testRot3.cpp.

TEST ( Rot3  ,
RzRyRx_scalars_derivative   
)

Definition at line 751 of file testRot3.cpp.

TEST ( Rot3  ,
RzRyRx_vector_derivative   
)

Definition at line 768 of file testRot3.cpp.

TEST ( Rot3  ,
Ypr_derivative   
)

Definition at line 783 of file testRot3.cpp.

TEST ( Rot3  ,
RQ_derivative   
)

Definition at line 803 of file testRot3.cpp.

TEST ( Rot3  ,
xyz_derivative   
)

Definition at line 838 of file testRot3.cpp.

TEST ( Rot3  ,
ypr_derivative   
)

Definition at line 851 of file testRot3.cpp.

TEST ( Rot3  ,
rpy_derivative   
)

Definition at line 864 of file testRot3.cpp.

TEST ( Rot3  ,
roll_derivative   
)

Definition at line 877 of file testRot3.cpp.

TEST ( Rot3  ,
pitch_derivative   
)

Definition at line 890 of file testRot3.cpp.

TEST ( Rot3  ,
yaw_derivative   
)

Definition at line 903 of file testRot3.cpp.

TEST ( Rot3  ,
determinant   
)

Definition at line 914 of file testRot3.cpp.

Vector3 xyz_proxy ( Rot3 const &  R)

Definition at line 836 of file testRot3.cpp.

double yaw_proxy ( Rot3 const &  R)

Definition at line 901 of file testRot3.cpp.

Rot3 Ypr_proxy ( double const &  y,
double const &  p,
double const &  r 
)

Definition at line 779 of file testRot3.cpp.

Vector3 ypr_proxy ( Rot3 const &  R)

Definition at line 849 of file testRot3.cpp.

Variable Documentation

double epsilon = 0.001
static

Definition at line 39 of file testRot3.cpp.

double error = 1e-9
static

Definition at line 39 of file testRot3.cpp.

Rot3 R = Rot3::Rodrigues(0.1, 0.4, 0.2)
static

Definition at line 37 of file testRot3.cpp.

Rot3 T1(Rot3::AxisAngle(Vector3(0, 0, 1), 1))
Rot3 T2(Rot3::AxisAngle(Vector3(0, 1, 0), 2))


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:51:42