| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | /**
 | 
					
						
							|  |  |  |  * @file    testRot3.cpp | 
					
						
							|  |  |  |  * @brief   Unit tests for Rot3 class | 
					
						
							|  |  |  |  * @author  Alireza Fathi | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-20 01:23:19 +08:00
										 |  |  | #include <gtsam/CppUnitLite/TestHarness.h>
 | 
					
						
							| 
									
										
										
										
											2010-01-11 07:36:37 +08:00
										 |  |  | #include <boost/math/constants/constants.hpp>
 | 
					
						
							| 
									
										
										
										
											2010-08-20 01:23:19 +08:00
										 |  |  | #include <gtsam/base/numericalDerivative.h>
 | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  | #include <gtsam/base/lieProxies.h>
 | 
					
						
							| 
									
										
										
										
											2010-08-20 01:23:19 +08:00
										 |  |  | #include <gtsam/geometry/Point3.h>
 | 
					
						
							|  |  |  | #include <gtsam/geometry/Rot3.h>
 | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | using namespace gtsam; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-20 04:03:06 +08:00
										 |  |  | Rot3 R = Rot3::rodriguez(0.1, 0.4, 0.2); | 
					
						
							| 
									
										
										
										
											2010-02-27 22:58:54 +08:00
										 |  |  | Point3 P(0.2, 0.7, -2.0); | 
					
						
							|  |  |  | double error = 1e-9, epsilon = 0.001; | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-02-27 22:58:54 +08:00
										 |  |  | TEST( Rot3, constructor) | 
					
						
							|  |  |  | { | 
					
						
							|  |  |  | 	Rot3 expected(eye(3, 3)); | 
					
						
							|  |  |  | 	Vector r1(3), r2(3), r3(3); | 
					
						
							|  |  |  | 	r1(0) = 1; | 
					
						
							|  |  |  | 	r1(1) = 0; | 
					
						
							|  |  |  | 	r1(2) = 0; | 
					
						
							|  |  |  | 	r2(0) = 0; | 
					
						
							|  |  |  | 	r2(1) = 1; | 
					
						
							|  |  |  | 	r2(2) = 0; | 
					
						
							|  |  |  | 	r3(0) = 0; | 
					
						
							|  |  |  | 	r3(1) = 0; | 
					
						
							|  |  |  | 	r3(2) = 1; | 
					
						
							|  |  |  | 	Rot3 actual(r1, r2, r3); | 
					
						
							|  |  |  | 	CHECK(assert_equal(actual,expected)); | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-02-27 22:58:54 +08:00
										 |  |  | TEST( Rot3, constructor2) | 
					
						
							|  |  |  | { | 
					
						
							|  |  |  | 	Matrix R = Matrix_(3, 3, 11., 12., 13., 21., 22., 23., 31., 32., 33.); | 
					
						
							|  |  |  | 	Rot3 actual(R); | 
					
						
							|  |  |  | 	Rot3 expected(11, 12, 13, 21, 22, 23, 31, 32, 33); | 
					
						
							|  |  |  | 	CHECK(assert_equal(actual,expected)); | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-09-14 12:39:36 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-02-27 22:58:54 +08:00
										 |  |  | TEST( Rot3, constructor3) | 
					
						
							|  |  |  | { | 
					
						
							|  |  |  | 	Rot3 expected(1, 2, 3, 4, 5, 6, 7, 8, 9); | 
					
						
							|  |  |  | 	Point3 r1(1, 4, 7), r2(2, 5, 8), r3(3, 6, 9); | 
					
						
							|  |  |  | 	CHECK(assert_equal(Rot3(r1,r2,r3),expected)); | 
					
						
							| 
									
										
										
										
											2009-09-14 12:39:36 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-02-27 22:58:54 +08:00
										 |  |  | TEST( Rot3, transpose) | 
					
						
							|  |  |  | { | 
					
						
							|  |  |  | 	Rot3 R(1, 2, 3, 4, 5, 6, 7, 8, 9); | 
					
						
							|  |  |  | 	Point3 r1(1, 2, 3), r2(4, 5, 6), r3(7, 8, 9); | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  | 	CHECK(assert_equal(R.inverse(),Rot3(r1,r2,r3))); | 
					
						
							| 
									
										
										
										
											2009-09-14 12:39:36 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-02-27 22:58:54 +08:00
										 |  |  | TEST( Rot3, equals) | 
					
						
							|  |  |  | { | 
					
						
							|  |  |  | 	CHECK(R.equals(R)); | 
					
						
							|  |  |  | 	Rot3 zero; | 
					
						
							|  |  |  | 	CHECK(!R.equals(zero)); | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-02 22:28:18 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-03-02 13:45:19 +08:00
										 |  |  | // Notice this uses J^2 whereas fast uses w*w', and has cos(t)*I + ....
 | 
					
						
							| 
									
										
										
										
											2010-01-02 22:28:18 +08:00
										 |  |  | Rot3 slow_but_correct_rodriguez(const Vector& w) { | 
					
						
							|  |  |  | 	double t = norm_2(w); | 
					
						
							| 
									
										
										
										
											2010-02-27 22:58:54 +08:00
										 |  |  | 	Matrix J = skewSymmetric(w / t); | 
					
						
							| 
									
										
										
										
											2010-01-02 22:28:18 +08:00
										 |  |  | 	if (t < 1e-5) return Rot3(); | 
					
						
							| 
									
										
										
										
											2010-03-02 13:45:19 +08:00
										 |  |  | 	Matrix R = eye(3) + sin(t) * J + (1.0 - cos(t)) * (J * J); | 
					
						
							|  |  |  | 	return R; | 
					
						
							| 
									
										
										
										
											2010-01-02 22:28:18 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-02-27 22:58:54 +08:00
										 |  |  | TEST( Rot3, rodriguez) | 
					
						
							|  |  |  | { | 
					
						
							| 
									
										
										
										
											2010-08-20 04:03:06 +08:00
										 |  |  | 	Rot3 R1 = Rot3::rodriguez(epsilon, 0, 0); | 
					
						
							| 
									
										
										
										
											2010-02-27 22:58:54 +08:00
										 |  |  | 	Vector w = Vector_(3, epsilon, 0., 0.); | 
					
						
							|  |  |  | 	Rot3 R2 = slow_but_correct_rodriguez(w); | 
					
						
							| 
									
										
										
										
											2010-03-02 13:45:19 +08:00
										 |  |  | 	CHECK(assert_equal(R2,R1)); | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-09-04 01:43:02 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-02-27 22:58:54 +08:00
										 |  |  | TEST( Rot3, rodriguez2) | 
					
						
							|  |  |  | { | 
					
						
							| 
									
										
										
										
											2010-03-02 13:45:19 +08:00
										 |  |  | 	Vector axis = Vector_(3,0.,1.,0.); // rotation around Y
 | 
					
						
							|  |  |  | 	double angle = 3.14 / 4.0; | 
					
						
							| 
									
										
										
										
											2010-08-20 04:03:06 +08:00
										 |  |  | 	Rot3 actual = Rot3::rodriguez(axis, angle); | 
					
						
							| 
									
										
										
										
											2010-03-02 13:45:19 +08:00
										 |  |  | 	Rot3 expected(0.707388, 0, 0.706825, | 
					
						
							|  |  |  | 			                 0, 1,        0, | 
					
						
							|  |  |  | 			         -0.706825, 0, 0.707388); | 
					
						
							|  |  |  | 	CHECK(assert_equal(expected,actual,1e-5)); | 
					
						
							| 
									
										
										
										
											2010-01-02 22:28:18 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-02-27 22:58:54 +08:00
										 |  |  | TEST( Rot3, rodriguez3) | 
					
						
							|  |  |  | { | 
					
						
							|  |  |  | 	Vector w = Vector_(3, 0.1, 0.2, 0.3); | 
					
						
							| 
									
										
										
										
											2010-08-20 04:03:06 +08:00
										 |  |  | 	Rot3 R1 = Rot3::rodriguez(w / norm_2(w), norm_2(w)); | 
					
						
							| 
									
										
										
										
											2010-02-27 22:58:54 +08:00
										 |  |  | 	Rot3 R2 = slow_but_correct_rodriguez(w); | 
					
						
							| 
									
										
										
										
											2010-03-02 13:45:19 +08:00
										 |  |  | 	CHECK(assert_equal(R2,R1)); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST( Rot3, rodriguez4) | 
					
						
							|  |  |  | { | 
					
						
							|  |  |  | 	Vector axis = Vector_(3,0.,0.,1.); // rotation around Z
 | 
					
						
							|  |  |  | 	double angle = M_PI_2; | 
					
						
							| 
									
										
										
										
											2010-08-20 04:03:06 +08:00
										 |  |  | 	Rot3 actual = Rot3::rodriguez(axis, angle); | 
					
						
							| 
									
										
										
										
											2010-03-02 13:45:19 +08:00
										 |  |  | 	double c=cos(angle),s=sin(angle); | 
					
						
							|  |  |  | 	Rot3 expected(c,-s, 0, | 
					
						
							|  |  |  | 			          s, c, 0, | 
					
						
							|  |  |  | 			          0, 0, 1); | 
					
						
							|  |  |  | 	CHECK(assert_equal(expected,actual,1e-5)); | 
					
						
							|  |  |  | 	CHECK(assert_equal(slow_but_correct_rodriguez(axis*angle),actual,1e-5)); | 
					
						
							| 
									
										
										
										
											2009-09-04 01:43:02 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-06 23:52:43 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-01-08 08:40:17 +08:00
										 |  |  | TEST( Rot3, expmap) | 
					
						
							| 
									
										
										
										
											2010-01-07 03:29:41 +08:00
										 |  |  | { | 
					
						
							| 
									
										
										
										
											2010-02-27 22:58:54 +08:00
										 |  |  | 	Vector v(3); | 
					
						
							|  |  |  | 	fill(v.begin(), v.end(), 0); | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  | 	CHECK(assert_equal(R.expmap(v), R)); | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-09 08:03:47 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST(Rot3, log) | 
					
						
							|  |  |  | { | 
					
						
							|  |  |  | 	Vector w1 = Vector_(3, 0.1, 0.0, 0.0); | 
					
						
							| 
									
										
										
										
											2010-08-20 04:03:06 +08:00
										 |  |  | 	Rot3 R1 = Rot3::rodriguez(w1); | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  | 	CHECK(assert_equal(w1, Rot3::Logmap(R1))); | 
					
						
							| 
									
										
										
										
											2010-01-09 08:03:47 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	Vector w2 = Vector_(3, 0.0, 0.1, 0.0); | 
					
						
							| 
									
										
										
										
											2010-08-20 04:03:06 +08:00
										 |  |  | 	Rot3 R2 = Rot3::rodriguez(w2); | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  | 	CHECK(assert_equal(w2, Rot3::Logmap(R2))); | 
					
						
							| 
									
										
										
										
											2010-01-09 08:03:47 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	Vector w3 = Vector_(3, 0.0, 0.0, 0.1); | 
					
						
							| 
									
										
										
										
											2010-08-20 04:03:06 +08:00
										 |  |  | 	Rot3 R3 = Rot3::rodriguez(w3); | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  | 	CHECK(assert_equal(w3, Rot3::Logmap(R3))); | 
					
						
							| 
									
										
										
										
											2010-01-09 08:03:47 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	Vector w = Vector_(3, 0.1, 0.4, 0.2); | 
					
						
							| 
									
										
										
										
											2010-08-20 04:03:06 +08:00
										 |  |  | 	Rot3 R = Rot3::rodriguez(w); | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  | 	CHECK(assert_equal(w, Rot3::Logmap(R))); | 
					
						
							| 
									
										
										
										
											2010-01-11 06:58:30 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	Vector w5 = Vector_(3, 0.0, 0.0, 0.0); | 
					
						
							| 
									
										
										
										
											2010-08-20 04:03:06 +08:00
										 |  |  | 	Rot3 R5 = Rot3::rodriguez(w5); | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  | 	CHECK(assert_equal(w5, Rot3::Logmap(R5))); | 
					
						
							| 
									
										
										
										
											2010-01-11 06:58:30 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-11 07:36:37 +08:00
										 |  |  | 	Vector w6 = Vector_(3, boost::math::constants::pi<double>(), 0.0, 0.0); | 
					
						
							| 
									
										
										
										
											2010-08-20 04:03:06 +08:00
										 |  |  | 	Rot3 R6 = Rot3::rodriguez(w6); | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  | 	CHECK(assert_equal(w6, Rot3::Logmap(R6))); | 
					
						
							| 
									
										
										
										
											2010-01-11 07:36:37 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-02-27 22:58:54 +08:00
										 |  |  | 	Vector w7 = Vector_(3, 0.0, boost::math::constants::pi<double>(), 0.0); | 
					
						
							| 
									
										
										
										
											2010-08-20 04:03:06 +08:00
										 |  |  | 	Rot3 R7 = Rot3::rodriguez(w7); | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  | 	CHECK(assert_equal(w7, Rot3::Logmap(R7))); | 
					
						
							| 
									
										
										
										
											2010-01-11 07:36:37 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-02-27 22:58:54 +08:00
										 |  |  | 	Vector w8 = Vector_(3, 0.0, 0.0, boost::math::constants::pi<double>()); | 
					
						
							| 
									
										
										
										
											2010-08-20 04:03:06 +08:00
										 |  |  | 	Rot3 R8 = Rot3::rodriguez(w8); | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  | 	CHECK(assert_equal(w8, Rot3::Logmap(R8))); | 
					
						
							| 
									
										
										
										
											2010-01-09 08:03:47 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-02-27 22:58:54 +08:00
										 |  |  | TEST(Rot3, manifold) | 
					
						
							| 
									
										
										
										
											2010-01-09 08:03:47 +08:00
										 |  |  | { | 
					
						
							| 
									
										
										
										
											2010-08-20 04:03:06 +08:00
										 |  |  | 	Rot3 gR1 = Rot3::rodriguez(0.1, 0.4, 0.2); | 
					
						
							|  |  |  | 	Rot3 gR2 = Rot3::rodriguez(0.3, 0.1, 0.7); | 
					
						
							| 
									
										
										
										
											2010-01-09 08:03:47 +08:00
										 |  |  | 	Rot3 origin; | 
					
						
							| 
									
										
										
										
											2010-01-10 20:25:46 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	// log behaves correctly
 | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  | 	Vector d12 = gR1.logmap(gR2); | 
					
						
							|  |  |  | 	CHECK(assert_equal(gR2, gR1.expmap(d12))); | 
					
						
							|  |  |  | 	CHECK(assert_equal(gR2, gR1*Rot3::Expmap(d12))); | 
					
						
							|  |  |  | 	Vector d21 = gR2.logmap(gR1); | 
					
						
							|  |  |  | 	CHECK(assert_equal(gR1, gR2.expmap(d21))); | 
					
						
							|  |  |  | 	CHECK(assert_equal(gR1, gR2*Rot3::Expmap(d21))); | 
					
						
							| 
									
										
										
										
											2010-01-10 20:25:46 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	// Check that log(t1,t2)=-log(t2,t1)
 | 
					
						
							|  |  |  | 	CHECK(assert_equal(d12,-d21)); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	// lines in canonical coordinates correspond to Abelian subgroups in SO(3)
 | 
					
						
							| 
									
										
										
										
											2010-02-27 22:58:54 +08:00
										 |  |  | 	Vector d = Vector_(3, 0.1, 0.2, 0.3); | 
					
						
							| 
									
										
										
										
											2010-01-10 20:25:46 +08:00
										 |  |  | 	// exp(-d)=inverse(exp(d))
 | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  | 	CHECK(assert_equal(Rot3::Expmap(-d),Rot3::Expmap(d).inverse())); | 
					
						
							| 
									
										
										
										
											2010-01-10 20:25:46 +08:00
										 |  |  | 	// exp(5d)=exp(2*d+3*d)=exp(2*d)exp(3*d)=exp(3*d)exp(2*d)
 | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  | 	Rot3 R2 = Rot3::Expmap (2 * d); | 
					
						
							|  |  |  | 	Rot3 R3 = Rot3::Expmap (3 * d); | 
					
						
							|  |  |  | 	Rot3 R5 = Rot3::Expmap (5 * d); | 
					
						
							| 
									
										
										
										
											2010-01-10 20:25:46 +08:00
										 |  |  | 	CHECK(assert_equal(R5,R2*R3)); | 
					
						
							|  |  |  | 	CHECK(assert_equal(R5,R3*R2)); | 
					
						
							| 
									
										
										
										
											2010-01-09 08:03:47 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-02-27 22:58:54 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | class AngularVelocity: public Point3 { | 
					
						
							|  |  |  | public: | 
					
						
							|  |  |  | 	AngularVelocity(const Point3& p) : | 
					
						
							|  |  |  | 		Point3(p) { | 
					
						
							|  |  |  | 	} | 
					
						
							|  |  |  | 	AngularVelocity(double wx, double wy, double wz) : | 
					
						
							|  |  |  | 		Point3(wx, wy, wz) { | 
					
						
							|  |  |  | 	} | 
					
						
							|  |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | AngularVelocity bracket(const AngularVelocity& X, const AngularVelocity& Y) { | 
					
						
							| 
									
										
										
										
											2010-08-23 05:45:53 +08:00
										 |  |  | 	return X.cross(Y); | 
					
						
							| 
									
										
										
										
											2010-02-27 22:58:54 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST(Rot3, BCH) | 
					
						
							|  |  |  | { | 
					
						
							|  |  |  | 	// Approximate exmap by BCH formula
 | 
					
						
							|  |  |  | 	AngularVelocity w1(0.2, -0.1, 0.1); | 
					
						
							|  |  |  | 	AngularVelocity w2(0.01, 0.02, -0.03); | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  | 	Rot3 R1 = Rot3::Expmap (w1.vector()), R2 = Rot3::Expmap (w2.vector()); | 
					
						
							| 
									
										
										
										
											2010-02-27 22:58:54 +08:00
										 |  |  | 	Rot3 R3 = R1 * R2; | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  | 	Vector expected = Rot3::Logmap(R3); | 
					
						
							| 
									
										
										
										
											2010-02-27 22:58:54 +08:00
										 |  |  | 	Vector actual = BCH(w1, w2).vector(); | 
					
						
							|  |  |  | 	CHECK(assert_equal(expected, actual,1e-5)); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-08-20 23:17:13 +08:00
										 |  |  | TEST( Rot3, rotate_derivatives) | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | { | 
					
						
							| 
									
										
										
										
											2010-08-20 23:17:13 +08:00
										 |  |  | 	Matrix actualDrotate1a, actualDrotate1b, actualDrotate2; | 
					
						
							| 
									
										
										
										
											2010-08-23 05:45:53 +08:00
										 |  |  | 	R.rotate(P, actualDrotate1a, actualDrotate2); | 
					
						
							|  |  |  | 	R.inverse().rotate(P, actualDrotate1b, boost::none); | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  | 	Matrix numerical1 = numericalDerivative21(testing::rotate<Rot3,Point3>, R, P); | 
					
						
							|  |  |  | 	Matrix numerical2 = numericalDerivative21(testing::rotate<Rot3,Point3>, R.inverse(), P); | 
					
						
							|  |  |  | 	Matrix numerical3 = numericalDerivative22(testing::rotate<Rot3,Point3>, R, P); | 
					
						
							| 
									
										
										
										
											2010-08-20 23:17:13 +08:00
										 |  |  | 	EXPECT(assert_equal(numerical1,actualDrotate1a,error)); | 
					
						
							|  |  |  | 	EXPECT(assert_equal(numerical2,actualDrotate1b,error)); | 
					
						
							|  |  |  | 	EXPECT(assert_equal(numerical3,actualDrotate2, error)); | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST( Rot3, unrotate) | 
					
						
							|  |  |  | { | 
					
						
							| 
									
										
										
										
											2010-02-27 22:58:54 +08:00
										 |  |  | 	Point3 w = R * P; | 
					
						
							| 
									
										
										
										
											2010-03-01 09:36:27 +08:00
										 |  |  | 	Matrix H1,H2; | 
					
						
							| 
									
										
										
										
											2010-08-23 05:45:53 +08:00
										 |  |  | 	Point3 actual = R.unrotate(w,H1,H2); | 
					
						
							| 
									
										
										
										
											2010-03-01 09:36:27 +08:00
										 |  |  | 	CHECK(assert_equal(P,actual)); | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  | 	Matrix numerical1 = numericalDerivative21(testing::unrotate<Rot3,Point3>, R, w); | 
					
						
							| 
									
										
										
										
											2010-03-01 09:36:27 +08:00
										 |  |  | 	CHECK(assert_equal(numerical1,H1,error)); | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  | 	Matrix numerical2 = numericalDerivative22(testing::unrotate<Rot3,Point3>, R, w); | 
					
						
							| 
									
										
										
										
											2010-03-01 09:36:27 +08:00
										 |  |  | 	CHECK(assert_equal(numerical2,H2,error)); | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-06 23:52:43 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-01-08 08:40:17 +08:00
										 |  |  | TEST( Rot3, compose ) | 
					
						
							|  |  |  | { | 
					
						
							| 
									
										
										
										
											2010-08-20 04:03:06 +08:00
										 |  |  | 	Rot3 R1 = Rot3::rodriguez(0.1, 0.2, 0.3); | 
					
						
							|  |  |  | 	Rot3 R2 = Rot3::rodriguez(0.2, 0.3, 0.5); | 
					
						
							| 
									
										
										
										
											2010-01-08 08:40:17 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-02-27 22:58:54 +08:00
										 |  |  | 	Rot3 expected = R1 * R2; | 
					
						
							| 
									
										
										
										
											2010-08-20 23:17:13 +08:00
										 |  |  | 	Matrix actualH1, actualH2; | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  | 	Rot3 actual = R1.compose(R2, actualH1, actualH2); | 
					
						
							| 
									
										
										
										
											2010-01-08 08:40:17 +08:00
										 |  |  | 	CHECK(assert_equal(expected,actual)); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  | 	Matrix numericalH1 = numericalDerivative21(testing::compose<Rot3>, R1, | 
					
						
							| 
									
										
										
										
											2010-02-27 22:58:54 +08:00
										 |  |  | 			R2, 1e-5); | 
					
						
							| 
									
										
										
										
											2010-01-08 08:40:17 +08:00
										 |  |  | 	CHECK(assert_equal(numericalH1,actualH1)); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  | 	Matrix numericalH2 = numericalDerivative22(testing::compose<Rot3>, R1, | 
					
						
							| 
									
										
										
										
											2010-02-27 22:58:54 +08:00
										 |  |  | 			R2, 1e-5); | 
					
						
							| 
									
										
										
										
											2010-01-08 08:40:17 +08:00
										 |  |  | 	CHECK(assert_equal(numericalH2,actualH2)); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-27 04:00:17 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST( Rot3, inverse ) | 
					
						
							|  |  |  | { | 
					
						
							| 
									
										
										
										
											2010-08-20 04:03:06 +08:00
										 |  |  | 	Rot3 R = Rot3::rodriguez(0.1, 0.2, 0.3); | 
					
						
							| 
									
										
										
										
											2010-01-27 04:00:17 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	Rot3 I; | 
					
						
							| 
									
										
										
										
											2010-08-20 23:17:13 +08:00
										 |  |  | 	Matrix actualH; | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  | 	CHECK(assert_equal(I,R*R.inverse(actualH))); | 
					
						
							|  |  |  | 	CHECK(assert_equal(I,R.inverse()*R)); | 
					
						
							| 
									
										
										
										
											2010-01-27 04:00:17 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  | 	Matrix numericalH = numericalDerivative11(testing::inverse<Rot3>, R, 1e-5); | 
					
						
							| 
									
										
										
										
											2010-01-27 04:00:17 +08:00
										 |  |  | 	CHECK(assert_equal(numericalH,actualH)); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-08 08:40:17 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST( Rot3, between ) | 
					
						
							| 
									
										
										
										
											2010-01-06 23:52:43 +08:00
										 |  |  | { | 
					
						
							| 
									
										
										
										
											2010-08-20 04:03:06 +08:00
										 |  |  | 	Rot3 R = Rot3::rodriguez(0.1, 0.4, 0.2); | 
					
						
							| 
									
										
										
										
											2010-01-09 08:03:47 +08:00
										 |  |  | 	Rot3 origin; | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  | 	CHECK(assert_equal(R, origin.between(R))); | 
					
						
							|  |  |  | 	CHECK(assert_equal(R.inverse(), R.between(origin))); | 
					
						
							| 
									
										
										
										
											2010-01-09 08:03:47 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-20 04:03:06 +08:00
										 |  |  | 	Rot3 R1 = Rot3::rodriguez(0.1, 0.2, 0.3); | 
					
						
							|  |  |  | 	Rot3 R2 = Rot3::rodriguez(0.2, 0.3, 0.5); | 
					
						
							| 
									
										
										
										
											2010-01-08 08:40:17 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  | 	Rot3 expected = R1.inverse() * R2; | 
					
						
							| 
									
										
										
										
											2010-08-20 23:17:13 +08:00
										 |  |  | 	Matrix actualH1, actualH2; | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  | 	Rot3 actual = R1.between(R2, actualH1, actualH2); | 
					
						
							| 
									
										
										
										
											2010-01-08 08:40:17 +08:00
										 |  |  | 	CHECK(assert_equal(expected,actual)); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  | 	Matrix numericalH1 = numericalDerivative21(testing::between<Rot3> , R1, R2, 1e-5); | 
					
						
							| 
									
										
										
										
											2010-01-08 08:40:17 +08:00
										 |  |  | 	CHECK(assert_equal(numericalH1,actualH1)); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  | 	Matrix numericalH2 = numericalDerivative22(testing::between<Rot3> , R1, R2, 1e-5); | 
					
						
							| 
									
										
										
										
											2010-01-08 08:40:17 +08:00
										 |  |  | 	CHECK(assert_equal(numericalH2,actualH2)); | 
					
						
							| 
									
										
										
										
											2010-01-06 23:52:43 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-09 08:03:47 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST( Rot3, xyz ) | 
					
						
							|  |  |  | { | 
					
						
							|  |  |  | 	double t = 0.1, st = sin(t), ct = cos(t); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-10 20:25:46 +08:00
										 |  |  | 	// Make sure all counterclockwise
 | 
					
						
							|  |  |  | 	// Diagrams below are all from from unchanging axis
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	// z
 | 
					
						
							|  |  |  | 	// |   * Y=(ct,st)
 | 
					
						
							|  |  |  | 	// x----y
 | 
					
						
							| 
									
										
										
										
											2010-02-27 22:58:54 +08:00
										 |  |  | 	Rot3 expected1(1, 0, 0, 0, ct, -st, 0, st, ct); | 
					
						
							| 
									
										
										
										
											2010-01-09 08:03:47 +08:00
										 |  |  | 	CHECK(assert_equal(expected1,Rot3::Rx(t))); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-10 20:25:46 +08:00
										 |  |  | 	// x
 | 
					
						
							|  |  |  | 	// |   * Z=(ct,st)
 | 
					
						
							|  |  |  | 	// y----z
 | 
					
						
							| 
									
										
										
										
											2010-02-27 22:58:54 +08:00
										 |  |  | 	Rot3 expected2(ct, 0, st, 0, 1, 0, -st, 0, ct); | 
					
						
							| 
									
										
										
										
											2010-01-09 08:03:47 +08:00
										 |  |  | 	CHECK(assert_equal(expected2,Rot3::Ry(t))); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-10 20:25:46 +08:00
										 |  |  | 	// y
 | 
					
						
							|  |  |  | 	// |   X=* (ct,st)
 | 
					
						
							|  |  |  | 	// z----x
 | 
					
						
							| 
									
										
										
										
											2010-02-27 22:58:54 +08:00
										 |  |  | 	Rot3 expected3(ct, -st, 0, st, ct, 0, 0, 0, 1); | 
					
						
							| 
									
										
										
										
											2010-01-09 08:03:47 +08:00
										 |  |  | 	CHECK(assert_equal(expected3,Rot3::Rz(t))); | 
					
						
							| 
									
										
										
										
											2010-01-10 20:25:46 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	// Check compound rotation
 | 
					
						
							| 
									
										
										
										
											2010-02-27 22:58:54 +08:00
										 |  |  | 	Rot3 expected = Rot3::Rz(0.3) * Rot3::Ry(0.2) * Rot3::Rx(0.1); | 
					
						
							| 
									
										
										
										
											2010-01-10 20:25:46 +08:00
										 |  |  | 	CHECK(assert_equal(expected,Rot3::RzRyRx(0.1,0.2,0.3))); | 
					
						
							| 
									
										
										
										
											2010-01-09 08:03:47 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST( Rot3, yaw_pitch_roll ) | 
					
						
							|  |  |  | { | 
					
						
							|  |  |  | 	double t = 0.1; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	// yaw is around z axis
 | 
					
						
							|  |  |  | 	CHECK(assert_equal(Rot3::Rz(t),Rot3::yaw(t))); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	// pitch is around y axis
 | 
					
						
							|  |  |  | 	CHECK(assert_equal(Rot3::Ry(t),Rot3::pitch(t))); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	// roll is around x axis
 | 
					
						
							|  |  |  | 	CHECK(assert_equal(Rot3::Rx(t),Rot3::roll(t))); | 
					
						
							| 
									
										
										
										
											2010-01-10 20:25:46 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	// Check compound rotation
 | 
					
						
							| 
									
										
										
										
											2010-02-27 22:58:54 +08:00
										 |  |  | 	Rot3 expected = Rot3::yaw(0.1) * Rot3::pitch(0.2) * Rot3::roll(0.3); | 
					
						
							| 
									
										
										
										
											2010-01-10 20:25:46 +08:00
										 |  |  | 	CHECK(assert_equal(expected,Rot3::ypr(0.1,0.2,0.3))); | 
					
						
							| 
									
										
										
										
											2010-01-09 08:03:47 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST( Rot3, RQ) | 
					
						
							|  |  |  | { | 
					
						
							|  |  |  | 	// Try RQ on a pure rotation
 | 
					
						
							| 
									
										
										
										
											2010-02-27 22:58:54 +08:00
										 |  |  | 	Matrix actualK; | 
					
						
							|  |  |  | 	Vector actual; | 
					
						
							|  |  |  | 	boost::tie(actualK, actual) = RQ(R.matrix()); | 
					
						
							|  |  |  | 	Vector expected = Vector_(3, 0.14715, 0.385821, 0.231671); | 
					
						
							|  |  |  | 	CHECK(assert_equal(eye(3),actualK)); | 
					
						
							|  |  |  | 	CHECK(assert_equal(expected,actual,1e-6)); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	// Try using xyz call, asserting that Rot3::RzRyRx(x,y,z).xyz()==[x;y;z]
 | 
					
						
							|  |  |  | 	CHECK(assert_equal(expected,R.xyz(),1e-6)); | 
					
						
							|  |  |  | 	CHECK(assert_equal(Vector_(3,0.1,0.2,0.3),Rot3::RzRyRx(0.1,0.2,0.3).xyz())); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	// Try using ypr call, asserting that Rot3::ypr(y,p,r).ypr()==[y;p;r]
 | 
					
						
							|  |  |  | 	CHECK(assert_equal(Vector_(3,0.1,0.2,0.3),Rot3::ypr(0.1,0.2,0.3).ypr())); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	// Try ypr for pure yaw-pitch-roll matrices
 | 
					
						
							|  |  |  | 	CHECK(assert_equal(Vector_(3,0.1,0.0,0.0),Rot3::yaw (0.1).ypr())); | 
					
						
							|  |  |  | 	CHECK(assert_equal(Vector_(3,0.0,0.1,0.0),Rot3::pitch(0.1).ypr())); | 
					
						
							|  |  |  | 	CHECK(assert_equal(Vector_(3,0.0,0.0,0.1),Rot3::roll (0.1).ypr())); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	// Try RQ to recover calibration from 3*3 sub-block of projection matrix
 | 
					
						
							|  |  |  | 	Matrix K = Matrix_(3, 3, 500.0, 0.0, 320.0, 0.0, 500.0, 240.0, 0.0, 0.0, 1.0); | 
					
						
							|  |  |  | 	Matrix A = K * R.matrix(); | 
					
						
							|  |  |  | 	boost::tie(actualK, actual) = RQ(A); | 
					
						
							|  |  |  | 	CHECK(assert_equal(K,actualK)); | 
					
						
							|  |  |  | 	CHECK(assert_equal(expected,actual,1e-6)); | 
					
						
							| 
									
										
										
										
											2010-01-09 08:03:47 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-02-27 22:58:54 +08:00
										 |  |  | int main() { | 
					
						
							|  |  |  | 	TestResult tr; | 
					
						
							|  |  |  | 	return TestRegistry::runAllTests(tr); | 
					
						
							|  |  |  | } | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | 
 |