27 #include <boost/math/constants/constants.hpp> 32 using namespace gtsam;
38 static
Point3 P(0.2, 0.7, -2.0);
51 Matrix R = (
Matrix(3, 3) << 0, 1, 0, 1, 0, 0, 0, 0, -1).finished();
67 Matrix R = (
Matrix(3, 3) << 0, 1, 0, 1, 0, 0, 0, 0, -1).finished();
85 Rot3 R(0, 1, 0, 1, 0, 0, 0, 0, -1);
102 if (t < 1
e-5)
return Rot3();
103 Matrix3
R = I_3x3 +
sin(t) * J + (1.0 -
cos(t)) * (J * J);
111 double angle = 3.14 / 4.0;
114 -0.706825, 0, 0.707388);
115 Rot3 actual = Rot3::AxisAngle(axis, angle);
117 Rot3 actual2 = Rot3::AxisAngle(axis, angle-2*
M_PI);
121 Rot3 actual3 = Rot3::AxisAngle(axis, angle);
138 double angle = 3.14 / 4.0;
141 -0.706825, 0, 0.707388);
142 Rot3 actual = Rot3::AxisAngle(axis, angle);
144 Rot3 actual2 = Rot3::Rodrigues(angle*axis);
152 Rot3 R1 = Rot3::AxisAngle(w / w.norm(), w.norm());
161 double angle =
M_PI/2.0;
162 Rot3 actual = Rot3::AxisAngle(axis, angle);
185 static const double PI = boost::math::constants::pi<double>();
189 #define CHECK_OMEGA(X, Y, Z) \ 190 w = (Vector(3) << X, Y, Z).finished(); \ 191 R = Rot3::Rodrigues(w); \ 192 EXPECT(assert_equal(w, Rot3::Logmap(R), 1e-12)); 198 double norm =
sqrt(1.0 + 16.0 + 4.0);
199 double x = 1.0 / norm,
y = 4.0 / norm,
z = 2.0 / norm;
222 #if !defined(__APPLE__) && defined(GTSAM_USE_QUATERNIONS) 223 w = (
Vector(3) << x * PI, y * PI, z * PI).finished();
224 R = Rot3::Rodrigues(w);
231 #define CHECK_OMEGA_ZERO(X, Y, Z) \ 232 w = (Vector(3) << X, Y, Z).finished(); \ 233 R = Rot3::Rodrigues(w); \ 234 EXPECT(assert_equal((Vector)Z_3x1, Rot3::Logmap(R))); 243 Rot3 Rlund(-0.98582676, -0.03958746, -0.16303092,
244 -0.03997006, -0.88835923, 0.45740671,
245 -0.16293753, 0.45743998, 0.87418537);
250 #if defined(GTSAM_USE_QUATERNIONS) 253 (
Vector)Rot3::Logmap(Rlund), 1
e-8));
257 (
Vector)Rot3::Logmap(Rlund), 1
e-8));
264 Vector3 d12 = Vector3::Constant(0.1);
271 Vector d12 = Vector3::Constant(0.1);
282 Vector d21 = t2.localCoordinates(t1);
289 Rot3 gR1 = Rot3::Rodrigues(0.1, 0.4, 0.2);
290 Rot3 gR2 = Rot3::Rodrigues(0.3, 0.1, 0.7);
319 template <
typename Derived>
346 Matrix actualDrotate1a, actualDrotate1b, actualDrotate2;
347 R.
rotate(
P, actualDrotate1a, actualDrotate2);
375 Rot3 R1 = Rot3::Rodrigues(0.1, 0.2, 0.3);
376 Rot3 R2 = Rot3::Rodrigues(0.2, 0.3, 0.5);
379 Matrix actualH1, actualH2;
395 Rot3 R = Rot3::Rodrigues(0.1, 0.2, 0.3);
415 0.5, -
sqrt(3.0)/2.0, 0.0,
416 sqrt(3.0)/2.0, 0.5, 0.0,
417 0.0, 0.0, 1.0).finished();
420 Rot3 R = Rot3::Rodrigues(0.1, 0.4, 0.2);
425 Rot3 R1 = Rot3::Rodrigues(0.1, 0.2, 0.3);
426 Rot3 R2 = Rot3::Rodrigues(0.2, 0.3, 0.5);
429 Matrix actualH1, actualH2;
443 double t = 0.1, st =
sin(t), ct =
cos(t);
451 Rot3 expected1(1, 0, 0, 0, ct, -st, 0, st, ct);
457 Rot3 expected2(ct, 0, st, 0, 1, 0, -st, 0, ct);
463 Rot3 expected3(ct, -st, 0, st, ct, 0, 0, 0, 1);
467 Rot3 expected = Rot3::Rz(0.3) * Rot3::Ry(0.2) * Rot3::Rx(0.1);
486 Rot3 expected = Rot3::Yaw(0.1) * Rot3::Pitch(0.2) * Rot3::Roll(0.3);
498 boost::tie(actualK, actual) =
RQ(
R.
matrix());
517 Matrix K = (
Matrix(3, 3) << 500.0, 0.0, 320.0, 0.0, 500.0, 240.0, 0.0, 0.0, 1.0).finished();
519 boost::tie(actualK, actual) =
RQ(A);
527 double theta = w.norm();
528 double theta2 = theta*
theta;
532 -
w(1),
w(0), 0.0 ).finished();
534 Matrix Rmat = I_3x3 + (1.0-theta2/6.0 + theta2*theta2/120.0
535 - theta2*theta2*theta2/5040.0)*W + (0.5 - theta2/24.0 + theta2*theta2/720.0)*W2 ;
549 Vector actualw = Rot3::Logmap(R);
556 Quaternion q1(0.710997408193224, 0.360544029310185, 0.594459869568306, 0.105395217842782);
557 Rot3 R1(0.271018623057411, 0.278786459830371, 0.921318086098018,
558 0.578529366719085, 0.717799701969298, -0.387385285854279,
559 -0.769319620053772, 0.637998195662053, 0.033250932803219);
561 Quaternion q2(0.263360579192421, 0.571813128030932, 0.494678363680335,
563 Rot3 R2(-0.207341903877828, 0.250149415542075, 0.945745528564780,
564 0.881304914479026, -0.371869043667957, 0.291573424846290,
565 0.424630407073532, 0.893945571198514, -0.143353873763946);
594 const Matrix I = Matrix::Identity(n,n);
609 std::ostringstream
os;
611 string expected =
"[\n\t1, 0, 0;\n\t0, 1, 0;\n\t0, 0, 1\n]";
619 Rot3 R1 = Rot3::Rz(1),
R2 = Rot3::Rz(2),
R3 = Rot3::Rz(1.5);
635 EXPECT(check_group_invariants(
id,
id));
636 EXPECT(check_group_invariants(
id,T1));
637 EXPECT(check_group_invariants(T2,
id));
638 EXPECT(check_group_invariants(T2,T1));
639 EXPECT(check_group_invariants(T1,T2));
641 EXPECT(check_manifold_invariants(
id,
id));
642 EXPECT(check_manifold_invariants(
id,T1));
643 EXPECT(check_manifold_invariants(T2,
id));
644 EXPECT(check_manifold_invariants(T2,T1));
645 EXPECT(check_manifold_invariants(T1,T2));
674 M << 0.79067393, 0.6051136, -0.0930814,
675 0.4155925, -0.64214347, -0.64324489,
676 -0.44948549, 0.47046326, -0.75917576;
679 expected << 0.790687, 0.605096, -0.0931312,
680 0.415746, -0.642355, -0.643844,
681 -0.449411, 0.47036, -0.759468;
683 auto actual = Rot3::ClosestTo(3*M);
693 #define CHECK_AXIS_ANGLE(expectedAxis, expectedAngle, rotation) \ 694 std::tie(actualAxis, actualAngle) = rotation.axisAngle(); \ 695 EXPECT(assert_equal(expectedAxis, actualAxis, 1e-9)); \ 696 EXPECT_DOUBLES_EQUAL(expectedAngle, actualAngle, 1e-9); \ 697 EXPECT(assert_equal(rotation, Rot3::AxisAngle(expectedAxis, expectedAngle))) 701 Unit3 axis(omega), _axis(-omega);
717 const double theta270 =
M_PI +
M_PI / 2;
724 const double theta_270 = -(
M_PI +
M_PI / 2);
730 const double theta195 = 195 *
M_PI / 180;
731 const double theta165 = 165 *
M_PI / 180;
748 return Rot3::RzRyRx(a, b, c);
752 const auto x = 0.1,
y = 0.4,
z = 0.2;
758 Rot3::RzRyRx(
x,
y,
z, act_x, act_y, act_z);
769 const auto xyz =
Vector3{-0.3, 0.1, 0.7};
773 Rot3::RzRyRx(xyz, act);
780 return Rot3::Ypr(y, p, r);
784 const auto y = 0.7,
p = -0.3, r = 0.1;
790 Rot3::Ypr(
y,
p, r, act_y, act_p, act_r);
799 const auto RQ_ypr =
RQ(R);
800 return RQ_ypr.second;
804 using VecAndErr = std::pair<Vector3, double>;
805 std::vector<VecAndErr> test_xyz;
807 test_xyz.push_back(VecAndErr{{0, 0, 0},
error});
808 test_xyz.push_back(VecAndErr{{0, 0.5, -0.5},
error});
809 test_xyz.push_back(VecAndErr{{0.3, 0, 0.2},
error});
810 test_xyz.push_back(VecAndErr{{-0.6, 1.3, 0}, 1
e-8});
811 test_xyz.push_back(VecAndErr{{1.0, 0.7, 0.8},
error});
812 test_xyz.push_back(VecAndErr{{3.0, 0.7, -0.6},
error});
813 test_xyz.push_back(VecAndErr{{
M_PI / 2, 0, 0},
error});
814 test_xyz.push_back(VecAndErr{{0, 0,
M_PI / 2},
error});
817 test_xyz.push_back(VecAndErr{{0,
M_PI / 2 - 1
e-1, 0}, 1
e-7});
818 test_xyz.push_back(VecAndErr{{0, 3 *
M_PI / 2 + 1
e-1, 0}, 1
e-7});
819 test_xyz.push_back(VecAndErr{{0,
M_PI / 2 - 1.1e-2, 0}, 1
e-4});
820 test_xyz.push_back(VecAndErr{{0, 3 *
M_PI / 2 + 1.1e-2, 0}, 1
e-4});
822 for (
auto const& vec_err : test_xyz) {
823 auto const& xyz = vec_err.first;
825 const auto R = Rot3::RzRyRx(xyz).
matrix();
830 const auto err = vec_err.second;
839 const auto aa =
Vector3{-0.6, 0.3, 0.2};
852 const auto aa =
Vector3{0.1, -0.3, -0.2};
865 const auto aa =
Vector3{1.2, 0.3, -0.9};
878 const auto aa =
Vector3{0.8, -0.8, 0.8};
891 const auto aa =
Vector3{0.01, 0.1, 0.0};
904 const auto aa =
Vector3{0.0, 0.1, 0.6};
917 Rot3 R_w1 = Rot3::Ry(degree *
M_PI / 180);
922 for (
size_t i = 2;
i < 360; ++
i) {
927 actual = R_w2.
matrix().determinant();
#define CHECK_OMEGA_ZERO(X, Y, Z)
EIGEN_DEVICE_FUNC Coefficients & coeffs()
Rot3 RzRyRx_proxy(double const &a, double const &b, double const &c)
Matrix< RealScalar, Dynamic, Dynamic > M
double yaw(OptionalJacobian< 1, 3 > H=boost::none) const
static const Eigen::MatrixBase< Vector3 >::ConstantReturnType Z_3x1
double pitch(OptionalJacobian< 1, 3 > H=boost::none) const
EIGEN_DEVICE_FUNC CoeffReturnType x() const
Concept check for values that can be used in unit tests.
AngularVelocity bracket(const AngularVelocity &X, const AngularVelocity &Y)
Provides convenient mappings of common member functions for testing.
static int runAllTests(TestResult &result)
T between(const T &t1, const T &t2)
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 y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set origin
Q id(Eigen::AngleAxisd(0, Q_z_axis))
EIGEN_DEVICE_FUNC CoeffReturnType y() const
Rot3 slerp(double t, const Rot3 &other) const
Spherical Linear intERPolation between *this and other.
double roll(OptionalJacobian< 1, 3 > H=boost::none) const
void determinant(const MatrixType &m)
static Point3 P(0.2, 0.7,-2.0)
EIGEN_DONT_INLINE Scalar zero()
Matrix Cayley(const Matrix &A)
Vector3 xyz_proxy(Rot3 const &R)
BOOST_CONCEPT_ASSERT((boost::RandomAccessRangeConcept< ListOfOneContainer< int > >))
Point3 unrotate(const Point3 &p, OptionalJacobian< 3, 3 > H1=boost::none, OptionalJacobian< 3, 3 > H2=boost::none) const
rotate point from world to rotated frame
EIGEN_DEVICE_FUNC const LogReturnType log() const
EIGEN_DEVICE_FUNC const SqrtReturnType sqrt() const
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
Pose2_ Expmap(const Vector3_ &xi)
internal::FixedSizeMatrix< Y, X3 >::type numericalDerivative33(boost::function< Y(const X1 &, const X2 &, const X3 &)> h, const X1 &x1, const X2 &x2, const X3 &x3, double delta=1e-5)
Some functions to compute numerical derivatives.
internal::FixedSizeMatrix< Y, X1 >::type numericalDerivative31(boost::function< Y(const X1 &, const X2 &, const X3 &)> h, const X1 &x1, const X2 &x2, const X3 &x3, double delta=1e-5)
T BCH(const T &X, const T &Y)
AGC: bracket() only appears in Rot3 tests, should this be used elsewhere?
internal::FixedSizeMatrix< Y, X1 >::type numericalDerivative21(const boost::function< Y(const X1 &, const X2 &)> &h, const X1 &x1, const X2 &x2, double delta=1e-5)
Vector3 ypr(OptionalJacobian< 3, 3 > H=boost::none) const
Point3 rotate(const Point3 &p, OptionalJacobian< 3, 3 > H1=boost::none, OptionalJacobian< 3, 3 > H2=boost::none) const
#define GTSAM_CONCEPT_LIE_INST(T)
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
T compose(const T &t1, const T &t2)
Rot3 inverse() const
inverse of a rotation
Vector3 RQ_proxy(Matrix3 const &R)
EIGEN_DEVICE_FUNC CoeffReturnType w() const
#define CHECK_LIE_GROUP_DERIVATIVES(t1, t2)
EIGEN_DEVICE_FUNC CoeffReturnType z() const
Vector3 xyz(OptionalJacobian< 3, 3 > H=boost::none) const
#define CHECK_OMEGA(X, Y, Z)
Represents a 3D point on a unit sphere.
EIGEN_DEVICE_FUNC const CosReturnType cos() const
internal::FixedSizeMatrix< Y, X2 >::type numericalDerivative32(boost::function< Y(const X1 &, const X2 &, const X3 &)> h, const X1 &x1, const X2 &x2, const X3 &x3, double delta=1e-5)
pair< Matrix3, Vector3 > RQ(const Matrix3 &A, OptionalJacobian< 3, 9 > H)
Class compose(const Class &g) const
internal::FixedSizeMatrix< Y, X2 >::type numericalDerivative22(boost::function< Y(const X1 &, const X2 &)> h, const X1 &x1, const X2 &x2, double delta=1e-5)
bool equals(const Rot3 &p, double tol=1e-9) const
P unrotate(const T &r, const P &pt)
Class expmap(const TangentVector &v) const
double roll_proxy(Rot3 const &R)
AngularVelocity(const Eigen::MatrixBase< Derived > &v)
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
#define EXPECT(condition)
Vector3 ypr_proxy(Rot3 const &R)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Rot3 slow_but_correct_Rodrigues(const Vector &w)
#define ROT3_DEFAULT_COORDINATES_MODE
JacobiRotation< float > J
Q R1(Eigen::AngleAxisd(1, Q_z_axis))
TangentVector logmap(const Class &g) const
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Class retract(const TangentVector &v) const
retract as required by manifold concept: applies v at *this
double yaw_proxy(Rot3 const &R)
Matrix3 skewSymmetric(double wx, double wy, double wz)
ofstream os("timeSchurFactors.csv")
The quaternion class used to represent 3D orientations and rotations.
Rot3 T1(Rot3::AxisAngle(Vector3(0, 0, 1), 1))
#define CHECK_AXIS_ANGLE(expectedAxis, expectedAngle, rotation)
Rot3 Ypr_proxy(double const &y, double const &p, double const &r)
#define CHECK_CHART_DERIVATIVES(t1, t2)
Class between(const Class &g) const
Rot3 T2(Rot3::AxisAngle(Vector3(0, 1, 0), 2))
Vector3 rpy(OptionalJacobian< 3, 3 > H=boost::none) const
EIGEN_DEVICE_FUNC const SinReturnType sin() const
Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor > Matrix
internal::FixedSizeMatrix< Y, X >::type numericalDerivative11(boost::function< Y(const X &)> h, const X &x, double delta=1e-5)
New-style numerical derivatives using manifold_traits.
AngularVelocity(double wx, double wy, double wz)
double pitch_proxy(Rot3 const &R)
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
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
Base class for all dense matrices, vectors, and expressions.
Q R2(Eigen::AngleAxisd(2, Vector3(0, 1, 0)))
gtsam::Quaternion toQuaternion() const
EIGEN_DEVICE_FUNC const InverseReturnType inverse() const
#define GTSAM_CONCEPT_TESTABLE_INST(T)
3D rotation represented as a rotation matrix or quaternion
TangentVector localCoordinates(const Class &g) const
localCoordinates as required by manifold concept: finds tangent vector between *this and g ...
Eigen::Quaternion< double, Eigen::DontAlign > Quaternion
Vector3 rpy_proxy(Rot3 const &R)