$search
00001 #include <math.h> 00002 #include "framestest.hpp" 00003 #include <frames_io.hpp> 00004 CPPUNIT_TEST_SUITE_REGISTRATION( FramesTest ); 00005 00006 using namespace KDL; 00007 00008 void FramesTest::setUp() 00009 { 00010 } 00011 00012 void FramesTest::tearDown() 00013 { 00014 } 00015 00016 void FramesTest::TestVector2(Vector& v) { 00017 Vector v2; 00018 CPPUNIT_ASSERT_EQUAL(2*v-v,v); 00019 CPPUNIT_ASSERT_EQUAL(v*2-v,v); 00020 CPPUNIT_ASSERT_EQUAL(v+v+v-2*v,v); 00021 v2=v; 00022 CPPUNIT_ASSERT_EQUAL(v,v2); 00023 v2+=v; 00024 CPPUNIT_ASSERT_EQUAL(2*v,v2); 00025 v2-=v; 00026 CPPUNIT_ASSERT_EQUAL(v,v2); 00027 v2.ReverseSign(); 00028 CPPUNIT_ASSERT_EQUAL(v,-v2); 00029 } 00030 00031 void FramesTest::TestVector() { 00032 Vector v(3,4,5); 00033 TestVector2(v); 00034 Vector v2(0,0,0); 00035 TestVector2(v2); 00036 00037 Vector nu(0,0,0); 00038 CPPUNIT_ASSERT_EQUAL(nu.Norm(),0.0); 00039 Vector nu2(10,0,0); 00040 CPPUNIT_ASSERT_EQUAL(nu2.Norm(),10.0); 00041 } 00042 00043 void FramesTest::TestTwist2(Twist& t) { 00044 Twist t2(Vector(16,-3,5),Vector(-4,2,1)); 00045 00046 CPPUNIT_ASSERT_EQUAL(2*t-t,t); 00047 CPPUNIT_ASSERT_EQUAL(t*2-t,t); 00048 CPPUNIT_ASSERT_EQUAL(t+t+t-2*t,t); 00049 t2=t; 00050 CPPUNIT_ASSERT_EQUAL(t,t2); 00051 t2+=t; 00052 CPPUNIT_ASSERT_EQUAL(2*t,t2); 00053 t2-=t; 00054 CPPUNIT_ASSERT_EQUAL(t,t2); 00055 t.ReverseSign(); 00056 CPPUNIT_ASSERT_EQUAL(t,-t2); 00057 } 00058 00059 void FramesTest::TestTwist() { 00060 Twist t(Vector(6,3,5),Vector(4,-2,7)); 00061 TestTwist2(t); 00062 Twist t2(Vector(0,0,0),Vector(0,0,0)); 00063 TestTwist2(t2); 00064 Twist t3(Vector(0,-9,-3),Vector(1,-2,-4)); 00065 TestTwist2(t3); 00066 } 00067 00068 void FramesTest::TestWrench2(Wrench& w) { 00069 // Wrench 00070 Wrench w2; 00071 CPPUNIT_ASSERT_EQUAL(2*w-w,w); 00072 CPPUNIT_ASSERT_EQUAL(w*2-w,w); 00073 CPPUNIT_ASSERT_EQUAL(w+w+w-2*w,w); 00074 w2=w; 00075 CPPUNIT_ASSERT_EQUAL(w,w2); 00076 w2+=w; 00077 CPPUNIT_ASSERT_EQUAL(2*w,w2); 00078 w2-=w; 00079 CPPUNIT_ASSERT_EQUAL(w,w2); 00080 w.ReverseSign(); 00081 CPPUNIT_ASSERT_EQUAL(w,-w2); 00082 } 00083 00084 void FramesTest::TestWrench() { 00085 Wrench w(Vector(7,-1,3),Vector(2,-3,3)); 00086 TestWrench2(w); 00087 Wrench w2(Vector(0,0,0),Vector(0,0,0)); 00088 TestWrench2(w2); 00089 Wrench w3(Vector(2,1,4),Vector(5,3,1)); 00090 TestWrench2(w3); 00091 } 00092 00093 void FramesTest::TestRotation2(const Vector& v,double a,double b,double c) { 00094 Vector v2; 00095 // Wrench 00096 Wrench w(Vector(7,-1,3),Vector(2,-3,3)); 00097 Twist t(Vector(6,3,5),Vector(4,-2,7)); 00098 // Rotation 00099 Rotation R; 00100 Rotation R2; 00101 double ra; 00102 double rb; 00103 double rc; 00104 R = Rotation::RPY(a,b,c); 00105 00106 CPPUNIT_ASSERT_DOUBLES_EQUAL(dot(R.UnitX(),R.UnitX()),1.0,epsilon); 00107 CPPUNIT_ASSERT_DOUBLES_EQUAL(dot(R.UnitY(),R.UnitY()),1.0,epsilon); 00108 CPPUNIT_ASSERT_DOUBLES_EQUAL(dot(R.UnitZ(),R.UnitZ()),1.0,epsilon); 00109 CPPUNIT_ASSERT_DOUBLES_EQUAL(dot(R.UnitX(),R.UnitY()),0.0,epsilon); 00110 CPPUNIT_ASSERT_DOUBLES_EQUAL(dot(R.UnitX(),R.UnitZ()),0.0,epsilon); 00111 CPPUNIT_ASSERT_DOUBLES_EQUAL(dot(R.UnitY(),R.UnitZ()),0.0,epsilon); 00112 R2=R; 00113 CPPUNIT_ASSERT_EQUAL(R,R2); 00114 CPPUNIT_ASSERT_DOUBLES_EQUAL((R*v).Norm(),v.Norm(),epsilon); 00115 CPPUNIT_ASSERT_EQUAL(R.Inverse(R*v),v); 00116 CPPUNIT_ASSERT_EQUAL(R.Inverse(R*t),t); 00117 CPPUNIT_ASSERT_EQUAL(R.Inverse(R*w),w); 00118 CPPUNIT_ASSERT_EQUAL(R*R.Inverse(v),v); 00119 CPPUNIT_ASSERT_EQUAL(R*Rotation::Identity(),R); 00120 CPPUNIT_ASSERT_EQUAL(Rotation::Identity()*R,R); 00121 CPPUNIT_ASSERT_EQUAL(R*(R*(R*v)),(R*R*R)*v); 00122 CPPUNIT_ASSERT_EQUAL(R*(R*(R*t)),(R*R*R)*t); 00123 CPPUNIT_ASSERT_EQUAL(R*(R*(R*w)),(R*R*R)*w); 00124 CPPUNIT_ASSERT_EQUAL(R*R.Inverse(),Rotation::Identity()); 00125 CPPUNIT_ASSERT_EQUAL(R.Inverse()*R,Rotation::Identity()); 00126 CPPUNIT_ASSERT_EQUAL(R.Inverse()*v,R.Inverse(v)); 00127 R.GetRPY(ra,rb,rc); 00128 CPPUNIT_ASSERT_DOUBLES_EQUAL(ra,a,epsilon); 00129 CPPUNIT_ASSERT_DOUBLES_EQUAL(rb,b,epsilon); 00130 CPPUNIT_ASSERT_DOUBLES_EQUAL(rc,c,epsilon); 00131 R = Rotation::EulerZYX(a,b,c); 00132 R.GetEulerZYX(ra,rb,rc); 00133 CPPUNIT_ASSERT_DOUBLES_EQUAL(ra,a,epsilon); 00134 CPPUNIT_ASSERT_DOUBLES_EQUAL(rb,b,epsilon); 00135 CPPUNIT_ASSERT_DOUBLES_EQUAL(rc,c,epsilon); 00136 R = Rotation::EulerZYZ(a,b,c); 00137 R.GetEulerZYZ(ra,rb,rc); 00138 CPPUNIT_ASSERT_DOUBLES_EQUAL(ra,a,epsilon); 00139 CPPUNIT_ASSERT_DOUBLES_EQUAL(rb,b,epsilon); 00140 CPPUNIT_ASSERT_DOUBLES_EQUAL(rc,c,epsilon); 00141 double angle= R.GetRotAngle(v2); 00142 R2=Rotation::Rot2(v2,angle); 00143 CPPUNIT_ASSERT_EQUAL(R2,R); 00144 R2=Rotation::Rot(v2*1E20,angle); 00145 CPPUNIT_ASSERT_EQUAL(R,R2); 00146 v2=Vector(6,2,4); 00147 CPPUNIT_ASSERT_DOUBLES_EQUAL((v2).Norm(),::sqrt(dot(v2,v2)),epsilon); 00148 } 00149 00150 00151 // compare a rotation R with the expected angle and axis 00152 void FramesTest::TestOneRotation(const std::string& msg, 00153 const KDL::Rotation& R, 00154 const double expectedAngle, 00155 const KDL::Vector& expectedAxis) 00156 { 00157 double angle =0; 00158 Vector axis; 00159 00160 angle = R.GetRotAngle(axis); 00161 CPPUNIT_ASSERT_DOUBLES_EQUAL_MESSAGE(msg, expectedAngle, angle, epsilon); 00162 CPPUNIT_ASSERT_EQUAL_MESSAGE(msg, expectedAxis, axis); 00163 CPPUNIT_ASSERT_EQUAL_MESSAGE(msg, expectedAngle * expectedAxis, R.GetRot()); 00164 CPPUNIT_ASSERT_EQUAL_MESSAGE(msg, Rotation::Rot(axis, angle), R); 00165 (void)axis.Normalize(); 00166 CPPUNIT_ASSERT_EQUAL_MESSAGE(msg, Rotation::Rot2(axis, angle), R); 00167 } 00168 00169 00170 00171 void FramesTest::TestArbitraryRotation(const std::string& msg, 00172 const KDL::Vector& v, 00173 const double angle, 00174 const double expectedAngle, 00175 const KDL::Vector& expectedVector) 00176 { 00177 std::stringstream ss; 00178 ss << "rot(" << msg << "],(" << angle << ")"; 00179 TestOneRotation(ss.str(), Rotation::Rot(v,angle*deg2rad), expectedAngle*deg2rad, expectedVector); 00180 } 00181 00182 00183 //std::cout << "-----\n" << R(0,0) << std::endl;\ 00184 //std::cout << R(0,1) << std::endl;\ 00185 //std::cout << R(0,2) << std::endl;\ 00186 //std::cout << R(1,0) << std::endl;\ 00187 //std::cout << R(1,1) << std::endl;\ 00188 //std::cout << R(1,2) << std::endl;\ 00189 //std::cout << R(2,0) << std::endl;\ 00190 //std::cout << R(2,1) << std::endl;\ 00191 //std::cout << R(2,2) << std::endl;\ 00192 00193 00194 #define TESTEULERZYX(a,b,g) \ 00195 {\ 00196 double eps=1E-14;\ 00197 Rotation R = Rotation::EulerZYX((a),(b),(g));\ 00198 double alpha,beta,gamma;\ 00199 R.GetEulerZYX(alpha,beta,gamma);\ 00200 CPPUNIT_ASSERT_DOUBLES_EQUAL((a),alpha,eps);\ 00201 CPPUNIT_ASSERT_DOUBLES_EQUAL((b),beta,eps);\ 00202 CPPUNIT_ASSERT_DOUBLES_EQUAL((g),gamma,eps);\ 00203 } 00204 00205 #define TESTEULERZYZ(a,b,g) \ 00206 {\ 00207 double eps=1E-14;\ 00208 Rotation R = Rotation::EulerZYZ((a),(b),(g));\ 00209 double alpha,beta,gamma;\ 00210 R.GetEulerZYZ(alpha,beta,gamma);\ 00211 CPPUNIT_ASSERT_DOUBLES_EQUAL((a),alpha,eps);\ 00212 CPPUNIT_ASSERT_DOUBLES_EQUAL((b),beta,eps);\ 00213 CPPUNIT_ASSERT_DOUBLES_EQUAL((g),gamma,eps);\ 00214 } 00215 #define TESTEULERZYX_INVARIANT(a,b,g,a2,b2,g2)\ 00216 {\ 00217 double eps=1E-14;\ 00218 Rotation R1=Rotation::EulerZYX(a,b,g);\ 00219 Rotation R2=Rotation::EulerZYX(a2,b2,g2);\ 00220 CPPUNIT_ASSERT_DOUBLES_EQUAL(0,diff(R2,R1).Norm(),eps);\ 00221 } 00222 #define TESTEULERZYZ_INVARIANT(a,b,g,a2,b2,g2)\ 00223 {\ 00224 double eps=1E-14;\ 00225 Rotation R1=Rotation::EulerZYZ(a,b,g);\ 00226 Rotation R2=Rotation::EulerZYZ(a2,b2,g2);\ 00227 CPPUNIT_ASSERT_DOUBLES_EQUAL(0,diff(R2,R1).Norm(),eps);\ 00228 } 00229 void FramesTest::TestEuler() { 00230 using namespace KDL; 00231 TESTEULERZYX(0.1,0.2,0.3) 00232 TESTEULERZYX(-0.1,0.2,0.3) 00233 TESTEULERZYX(0.1,-0.2,0.3) 00234 TESTEULERZYX(0.1,0.2,-0.3) 00235 TESTEULERZYX(0,0.2,0.3) 00236 TESTEULERZYX(0.1,0.2,0) 00237 TESTEULERZYX(0.1,0,0.3) 00238 TESTEULERZYX(0.1,0,0) 00239 TESTEULERZYX(0,0,0.3) 00240 TESTEULERZYX(0,0,0) 00241 TESTEULERZYX(0.3,0.999*M_PI/2,0.1) 00242 // if beta== +/- M_PI/2 => multiple solutions available, gamma will be choosen to be zero ! 00243 // so we test with gamma==0 ! 00244 TESTEULERZYX(0.3,0.9999999999*M_PI/2,0) 00245 TESTEULERZYX(0.3,0.99999999*M_PI/2,0) 00246 TESTEULERZYX(0.3,0.999999*M_PI/2,0) 00247 TESTEULERZYX(0.3,0.9999*M_PI/2,0) 00248 TESTEULERZYX(0.3,0.99*M_PI/2,0) 00249 //TESTEULERZYX(0.1,-M_PI/2,0.3) 00250 TESTEULERZYX(0,M_PI/2,0) 00251 00252 TESTEULERZYX(0.3,-M_PI/2,0) 00253 TESTEULERZYX(0.3,-0.9999999999*M_PI/2,0) 00254 TESTEULERZYX(0.3,-0.99999999*M_PI/2,0) 00255 TESTEULERZYX(0.3,-0.999999*M_PI/2,0) 00256 TESTEULERZYX(0.3,-0.9999*M_PI/2,0) 00257 TESTEULERZYX(0.3,-0.99*M_PI/2,0) 00258 TESTEULERZYX(0,-M_PI/2,0) 00259 00260 // extremes of the range: 00261 TESTEULERZYX(M_PI,-M_PI/2,0) 00262 TESTEULERZYX(-M_PI,-M_PI/2,0) 00263 TESTEULERZYX(M_PI,1,0) 00264 TESTEULERZYX(-M_PI,1,0) 00265 //TESTEULERZYX(0,-M_PI/2,M_PI) gamma will be chosen zero 00266 //TESTEULERZYX(0,M_PI/2,-M_PI) gamma will be chosen zero 00267 TESTEULERZYX(0,1,M_PI) 00268 00269 TESTEULERZYZ(0.1,0.2,0.3) 00270 TESTEULERZYZ(-0.1,0.2,0.3) 00271 TESTEULERZYZ(0.1,0.9*M_PI,0.3) 00272 TESTEULERZYZ(0.1,0.2,-0.3) 00273 TESTEULERZYZ(0,0,0) 00274 TESTEULERZYZ(0,0,0) 00275 TESTEULERZYZ(0,0,0) 00276 TESTEULERZYZ(PI,0,0) 00277 TESTEULERZYZ(0,0.2,PI) 00278 TESTEULERZYZ(0.4,PI,0) 00279 TESTEULERZYZ(0,PI,0) 00280 TESTEULERZYZ(PI,PI,0) 00281 TESTEULERZYX(0.3,M_PI/2,0) 00282 TESTEULERZYZ(0.3,0.9999999999*M_PI/2,0) 00283 TESTEULERZYZ(0.3,0.99999999*M_PI/2,0) 00284 TESTEULERZYZ(0.3,0.999999*M_PI/2,0) 00285 TESTEULERZYZ(0.3,0.9999*M_PI/2,0) 00286 TESTEULERZYZ(0.3,0.99*M_PI/2,0) 00287 00288 TESTEULERZYX_INVARIANT(0.1,0.2,0.3, 0.1+M_PI, M_PI-0.2, 0.3+M_PI); 00289 TESTEULERZYX_INVARIANT(0.1,0.2,0.3, 0.1-M_PI, M_PI-0.2, 0.3-M_PI); 00290 TESTEULERZYX_INVARIANT(0.1,0.2,0.3, 0.1-M_PI, M_PI-0.2, 0.3+M_PI); 00291 TESTEULERZYX_INVARIANT(0.1,0.2,0.3, 0.1+M_PI, M_PI-0.2, 0.3-M_PI); 00292 00293 TESTEULERZYZ_INVARIANT(0.1,0.2,0.3, 0.1+M_PI, -0.2, 0.3+M_PI); 00294 TESTEULERZYZ_INVARIANT(0.1,0.2,0.3, 0.1-M_PI, -0.2, 0.3+M_PI); 00295 TESTEULERZYZ_INVARIANT(0.1,0.2,0.3, 0.1+M_PI, -0.2, 0.3-M_PI); 00296 TESTEULERZYZ_INVARIANT(0.1,0.2,0.3, 0.1-M_PI, -0.2, 0.3-M_PI); 00297 } 00298 00299 void FramesTest::TestRangeArbitraryRotation(const std::string& msg, 00300 const KDL::Vector& v, 00301 const KDL::Vector& expectedVector) 00302 { 00303 TestArbitraryRotation(msg, v, 0, 0, Vector(0,0,1)); // no rotation 00304 TestArbitraryRotation(msg, v, 45, 45, expectedVector); 00305 TestArbitraryRotation(msg, v, 90, 90, expectedVector); 00306 TestArbitraryRotation(msg, v, 179, 179, expectedVector); 00307 // TestArbitraryRotation(msg, v, 180, 180, expectedVector); // sign VARIES by case because 180 degrees not 00308 // full determined: it can return +/- the axis 00309 // depending on what the original axis was. 00310 // BOTH RESULTS ARE CORRECT. 00311 TestArbitraryRotation(msg, v, 181, 179, -expectedVector); // >+180 rotation => <+180 + negative axis 00312 TestArbitraryRotation(msg, v, 270, 90, -expectedVector); 00313 TestArbitraryRotation(msg, v, 359, 1, -expectedVector); 00314 TestArbitraryRotation(msg, v, 360, 0, Vector(0,0,1)); // no rotation 00315 TestArbitraryRotation(msg, v, 361, 1, expectedVector); 00316 TestArbitraryRotation(msg, v, 450, 90, expectedVector); 00317 TestArbitraryRotation(msg, v, 539, 179, expectedVector); 00318 // TestArbitraryRotation(msg, v, 540, 180, expectedVector); // see above 00319 TestArbitraryRotation(msg, v, 541, 179, -expectedVector); // like 181 00320 TestArbitraryRotation(msg, v, 630, 90, -expectedVector); // like 270 00321 TestArbitraryRotation(msg, v, 719, 1, -expectedVector); // like 259 00322 TestArbitraryRotation(msg, v, 720, 0, Vector(0,0,1)); // no rotation 00323 00324 TestArbitraryRotation(msg, v, -45, 45, -expectedVector); 00325 TestArbitraryRotation(msg, v, -90, 90, -expectedVector); 00326 TestArbitraryRotation(msg, v, -179, 179, -expectedVector); 00327 // TestArbitraryRotation(msg, v, -180, 180, expectedVector); // see above 00328 TestArbitraryRotation(msg, v, -181, 179, expectedVector); 00329 TestArbitraryRotation(msg, v, -270, 90, expectedVector); 00330 TestArbitraryRotation(msg, v, -359, 1, expectedVector); 00331 TestArbitraryRotation(msg, v, -360, 0, Vector(0,0,1)); // no rotation 00332 TestArbitraryRotation(msg, v, -361, 1, -expectedVector); 00333 TestArbitraryRotation(msg, v, -450, 90, -expectedVector); 00334 TestArbitraryRotation(msg, v, -539, 179, -expectedVector); 00335 // TestArbitraryRotation(msg, v, -540, 180, -expectedVector); // see above 00336 TestArbitraryRotation(msg, v, -541, 179, expectedVector); 00337 TestArbitraryRotation(msg, v, -630, 90, expectedVector); 00338 TestArbitraryRotation(msg, v, -719, 1, expectedVector); 00339 TestArbitraryRotation(msg, v, -720, 0, Vector(0,0,1)); // no rotation 00340 } 00341 00342 void FramesTest::TestRotation() { 00343 TestRotation2(Vector(3,4,5),10*deg2rad,20*deg2rad,30*deg2rad); 00344 00345 // X axis 00346 TestRangeArbitraryRotation("[1,0,0]", Vector(1,0,0), Vector(1,0,0)); 00347 TestRangeArbitraryRotation("[-1,0,0]", Vector(-1,0,0), Vector(-1,0,0)); 00348 // Y axis 00349 TestRangeArbitraryRotation("[0,1,0]", Vector(0,1,0), Vector(0,1,0)); 00350 TestRangeArbitraryRotation("[0,-1,0]", Vector(0,-1,0), Vector(0,-1,0)); 00351 // Z axis 00352 TestRangeArbitraryRotation("[0,0,1]", Vector(0,0,1), Vector(0,0,1)); 00353 TestRangeArbitraryRotation("[0,0,-1]", Vector(0,0,-1), Vector(0,0,-1)); 00354 // X,Y axes 00355 TestRangeArbitraryRotation("[1,1,0]", Vector(1,1,0), Vector(1,1,0)/sqrt(2.0)); 00356 TestRangeArbitraryRotation("[-1,-1,0]", Vector(-1,-1,0), Vector(-1,-1,0)/sqrt(2.0)); 00357 // X,Z axes 00358 TestRangeArbitraryRotation("[1,0,1]", Vector(1,0,1), Vector(1,0,1)/sqrt(2.0)); 00359 TestRangeArbitraryRotation("[-1,0,-1]", Vector(-1,0,-1), Vector(-1,0,-1)/sqrt(2.0)); 00360 // Y,Z axes 00361 TestRangeArbitraryRotation("[0,1,1]", Vector(0,1,1), Vector(0,1,1)/sqrt(2.0)); 00362 TestRangeArbitraryRotation("[0,-1,-1]", Vector(0,-1,-1), Vector(0,-1,-1)/sqrt(2.0)); 00363 // X,Y,Z axes 00364 TestRangeArbitraryRotation("[1,1,1]", Vector(1,1,1), Vector(1,1,1)/sqrt(3.0)); 00365 TestRangeArbitraryRotation("[-1,-1,-1]", Vector(-1,-1,-1), Vector(-1,-1,-1)/sqrt(3.0)); 00366 00367 // these change ... some of the -180 are the same as the +180, and some 00368 // results are the opposite sign. 00369 TestOneRotation("rot([1,0,0],180)", KDL::Rotation::Rot(KDL::Vector(1,0,0),180*deg2rad), 180*deg2rad, Vector(1,0,0)); 00370 // same as +180 00371 TestOneRotation("rot([-1,0,0],180)", KDL::Rotation::Rot(KDL::Vector(-1,0,0),180*deg2rad), 180*deg2rad, Vector(1,0,0)); 00372 TestOneRotation("rot([0,1,0],180)", KDL::Rotation::Rot(KDL::Vector(0,1,0),180*deg2rad), 180*deg2rad, Vector(0,1,0)); 00373 // same as +180 00374 TestOneRotation("rot([0,-1,0],180)", KDL::Rotation::Rot(KDL::Vector(0,-1,0),180*deg2rad), 180*deg2rad, Vector(0,1,0)); 00375 00376 TestOneRotation("rot([0,0,1],180)", KDL::Rotation::Rot(KDL::Vector(0,0,1),180*deg2rad), 180*deg2rad, Vector(0,0,1)); 00377 // same as +180 00378 TestOneRotation("rot([0,0,-1],180)", KDL::Rotation::Rot(KDL::Vector(0,0,-1),180*deg2rad), 180*deg2rad, Vector(0,0,1)); 00379 00380 TestOneRotation("rot([1,0,1],180)", KDL::Rotation::Rot(KDL::Vector(1,0,1),180*deg2rad), 180*deg2rad, Vector(1,0,1)/sqrt(2.0)); 00381 // same as +180 00382 TestOneRotation("rot([1,0,1],-180)", KDL::Rotation::Rot(KDL::Vector(1,0,1),-180*deg2rad), 180*deg2rad, Vector(1,0,1)/sqrt(2.0)); 00383 TestOneRotation("rot([-1,0,-1],180)", KDL::Rotation::Rot(KDL::Vector(-1,0,-1),180*deg2rad), 180*deg2rad, Vector(1,0,1)/sqrt(2.0)); 00384 // same as +180 00385 TestOneRotation("rot([-1,0,-1],-180)", KDL::Rotation::Rot(KDL::Vector(-1,0,-1),-180*deg2rad), 180*deg2rad, Vector(1,0,1)/sqrt(2.0)); 00386 00387 TestOneRotation("rot([1,1,0],180)", KDL::Rotation::Rot(KDL::Vector(1,1,0),180*deg2rad), 180*deg2rad, Vector(1,1,0)/sqrt(2.0)); 00388 // opposite of +180 00389 TestOneRotation("rot([1,1,0],-180)", KDL::Rotation::Rot(KDL::Vector(1,1,0),-180*deg2rad), 180*deg2rad, -Vector(1,1,0)/sqrt(2.0)); 00390 TestOneRotation("rot([-1,-1,0],180)", KDL::Rotation::Rot(KDL::Vector(-1,-1,0),180*deg2rad), 180*deg2rad, -Vector(1,1,0)/sqrt(2.0)); 00391 // opposite of +180 00392 TestOneRotation("rot([-1,-1,0],-180)", KDL::Rotation::Rot(KDL::Vector(-1,-1,0),-180*deg2rad), 180*deg2rad, Vector(1,1,0)/sqrt(2.0)); 00393 00394 TestOneRotation("rot([0,1,1],180)", KDL::Rotation::Rot(KDL::Vector(0,1,1),180*deg2rad), 180*deg2rad, Vector(0,1,1)/sqrt(2.0)); 00395 // same as +180 00396 TestOneRotation("rot([0,1,1],-180)", KDL::Rotation::Rot(KDL::Vector(0,1,1),-180*deg2rad), 180*deg2rad, Vector(0,1,1)/sqrt(2.0)); 00397 TestOneRotation("rot([0,-1,-1],180)", KDL::Rotation::Rot(KDL::Vector(0,-1,-1),180*deg2rad), 180*deg2rad, Vector(0,1,1)/sqrt(2.0)); 00398 // same as +180 00399 TestOneRotation("rot([0,-1,-1],-180)", KDL::Rotation::Rot(KDL::Vector(0,-1,-1),-180*deg2rad), 180*deg2rad, Vector(0,1,1)/sqrt(2.0)); 00400 00401 TestOneRotation("rot([1,1,1],180)", KDL::Rotation::Rot(KDL::Vector(1,1,1),180*deg2rad), 180*deg2rad, Vector(1,1,1)/sqrt(3.0)); 00402 // same as +180 00403 TestOneRotation("rot([1,1,1],-180)", KDL::Rotation::Rot(KDL::Vector(1,1,1),-180*deg2rad), 180*deg2rad, Vector(1,1,1)/sqrt(3.0)); 00404 TestOneRotation("rot([-1,-1,-1],180)", KDL::Rotation::Rot(KDL::Vector(-1,-1,-1),180*deg2rad), 180*deg2rad, Vector(1,1,1)/sqrt(3.0)); 00405 // same as +180 00406 TestOneRotation("rot([-1,-1,-1],-180)", KDL::Rotation::Rot(KDL::Vector(-1,-1,-1),-180*deg2rad), 180*deg2rad, Vector(1,1,1)/sqrt(3.0)); 00407 } 00408 00409 void FramesTest::TestQuaternion() { 00410 Rotation R; 00411 Rotation R2; 00412 double x,y,z,w; 00413 double x2,y2,z2,w2; 00414 00415 // identity R -> quat -> R2 00416 R.GetQuaternion(x,y,z,w); 00417 R2.Quaternion(x,y,z,w); 00418 CPPUNIT_ASSERT_EQUAL(R,R2); 00419 00420 // 45 deg rotation in X 00421 R = Rotation::EulerZYX(0,0,45*deg2rad); 00422 R.GetQuaternion(x,y,z,w); 00423 CPPUNIT_ASSERT_DOUBLES_EQUAL(x, sin((45*deg2rad)/2), epsilon); 00424 CPPUNIT_ASSERT_DOUBLES_EQUAL(y, 0, epsilon); 00425 CPPUNIT_ASSERT_DOUBLES_EQUAL(z, 0, epsilon); 00426 CPPUNIT_ASSERT_DOUBLES_EQUAL(w, cos((45*deg2rad)/2), epsilon); 00427 R2 = Rotation::Quaternion(x,y,z,w); 00428 CPPUNIT_ASSERT_EQUAL(R,R2); 00429 00430 // direct 45 deg rotation in X 00431 R2 = Rotation::Quaternion(sin((45*deg2rad)/2), 0, 0, cos((45*deg2rad)/2)); 00432 CPPUNIT_ASSERT_EQUAL(R,R2); 00433 R2.GetQuaternion(x2,y2,z2,w2); 00434 CPPUNIT_ASSERT_DOUBLES_EQUAL(x, x2, epsilon); 00435 CPPUNIT_ASSERT_DOUBLES_EQUAL(y, y2, epsilon); 00436 CPPUNIT_ASSERT_DOUBLES_EQUAL(z, z2, epsilon); 00437 CPPUNIT_ASSERT_DOUBLES_EQUAL(w, w2, epsilon); 00438 00439 // 45 deg rotation in X and in Z 00440 R = Rotation::EulerZYX(45*deg2rad,0,45*deg2rad); 00441 R.GetQuaternion(x,y,z,w); 00442 R2 = Rotation::Quaternion(x,y,z,w); 00443 CPPUNIT_ASSERT_EQUAL(R,R2); 00444 R2.GetQuaternion(x2,y2,z2,w2); 00445 CPPUNIT_ASSERT_DOUBLES_EQUAL(x, x2, epsilon); 00446 CPPUNIT_ASSERT_DOUBLES_EQUAL(y, y2, epsilon); 00447 CPPUNIT_ASSERT_DOUBLES_EQUAL(z, z2, epsilon); 00448 CPPUNIT_ASSERT_DOUBLES_EQUAL(w, w2, epsilon); 00449 } 00450 00451 00452 void FramesTest::TestRotationDiff() { 00453 00454 CPPUNIT_ASSERT_EQUAL(KDL::diff(Rotation::RotX(0*deg2rad), Rotation::RotX(0*deg2rad)), Vector(0,0,0)); // no rotation 00455 CPPUNIT_ASSERT_EQUAL(KDL::diff(Rotation::RotX(0*deg2rad), Rotation::RotX(90*deg2rad)), Vector(M_PI/2,0,0)); 00456 CPPUNIT_ASSERT_EQUAL(KDL::diff(Rotation::RotX(0*deg2rad), Rotation::RotX(180*deg2rad)), Vector(M_PI,0,0)); 00457 CPPUNIT_ASSERT_EQUAL(KDL::diff(Rotation::RotX(0*deg2rad), Rotation::RotX(270*deg2rad)), Vector(-M_PI/2,0,0)); 00458 CPPUNIT_ASSERT_EQUAL(KDL::diff(Rotation::RotX(0*deg2rad), Rotation::RotX(360*deg2rad)), Vector(0,0,0)); // no rotation 00459 CPPUNIT_ASSERT_EQUAL(KDL::diff(Rotation::RotX(0*deg2rad), Rotation::RotX(-360*deg2rad)), Vector(0,0,0)); // no rotation 00460 CPPUNIT_ASSERT_EQUAL(KDL::diff(Rotation::RotX(0*deg2rad), Rotation::RotX(-270*deg2rad)), Vector(M_PI/2,0,0)); 00461 CPPUNIT_ASSERT_EQUAL(KDL::diff(Rotation::RotX(0*deg2rad), Rotation::RotX(-180*deg2rad)), Vector(M_PI,0,0)); 00462 CPPUNIT_ASSERT_EQUAL(KDL::diff(Rotation::RotX(0*deg2rad), Rotation::RotX(-90*deg2rad)), Vector(-M_PI/2,0,0)); 00463 CPPUNIT_ASSERT_EQUAL(KDL::diff(Rotation::RotX(0*deg2rad), Rotation::RotX(-0*deg2rad)), Vector(0,0,0)); // no rotation 00464 00465 CPPUNIT_ASSERT_EQUAL(KDL::diff(Rotation::RotY(0*deg2rad), Rotation::RotY(0*deg2rad)), Vector(0,0,0)); // no rotation 00466 CPPUNIT_ASSERT_EQUAL(KDL::diff(Rotation::RotY(0*deg2rad), Rotation::RotY(90*deg2rad)), Vector(0,M_PI/2,0)); 00467 CPPUNIT_ASSERT_EQUAL(KDL::diff(Rotation::RotY(0*deg2rad), Rotation::RotY(180*deg2rad)), Vector(0,M_PI,0)); 00468 CPPUNIT_ASSERT_EQUAL(KDL::diff(Rotation::RotY(0*deg2rad), Rotation::RotY(270*deg2rad)), Vector(0,-M_PI/2,0)); 00469 CPPUNIT_ASSERT_EQUAL(KDL::diff(Rotation::RotY(0*deg2rad), Rotation::RotY(360*deg2rad)), Vector(0,0,0)); // no rotation 00470 CPPUNIT_ASSERT_EQUAL(KDL::diff(Rotation::RotY(0*deg2rad), Rotation::RotY(-360*deg2rad)), Vector(0,0,0)); // no rotation 00471 CPPUNIT_ASSERT_EQUAL(KDL::diff(Rotation::RotY(0*deg2rad), Rotation::RotY(-270*deg2rad)), Vector(0,M_PI/2,0)); 00472 CPPUNIT_ASSERT_EQUAL(KDL::diff(Rotation::RotY(0*deg2rad), Rotation::RotY(-180*deg2rad)), Vector(0,M_PI,0)); 00473 CPPUNIT_ASSERT_EQUAL(KDL::diff(Rotation::RotY(0*deg2rad), Rotation::RotY(-90*deg2rad)), Vector(0,-M_PI/2,0)); 00474 CPPUNIT_ASSERT_EQUAL(KDL::diff(Rotation::RotY(0*deg2rad), Rotation::RotY(-0*deg2rad)), Vector(0,0,0)); // no rotation 00475 00476 CPPUNIT_ASSERT_EQUAL(KDL::diff(Rotation::RotZ(0*deg2rad), Rotation::RotZ(0*deg2rad)), Vector(0,0,0)); // no rotation 00477 CPPUNIT_ASSERT_EQUAL(KDL::diff(Rotation::RotZ(0*deg2rad), Rotation::RotZ(90*deg2rad)), Vector(0,0,M_PI/2)); 00478 CPPUNIT_ASSERT_EQUAL(KDL::diff(Rotation::RotZ(0*deg2rad), Rotation::RotZ(180*deg2rad)), Vector(0,0,M_PI)); 00479 CPPUNIT_ASSERT_EQUAL(KDL::diff(Rotation::RotZ(0*deg2rad), Rotation::RotZ(270*deg2rad)), Vector(0,0,-M_PI/2)); 00480 CPPUNIT_ASSERT_EQUAL(KDL::diff(Rotation::RotZ(0*deg2rad), Rotation::RotZ(360*deg2rad)), Vector(0,0,0)); // no rotation 00481 CPPUNIT_ASSERT_EQUAL(KDL::diff(Rotation::RotZ(0*deg2rad), Rotation::RotZ(-360*deg2rad)), Vector(0,0,0)); // no rotation 00482 CPPUNIT_ASSERT_EQUAL(KDL::diff(Rotation::RotZ(0*deg2rad), Rotation::RotZ(-270*deg2rad)), Vector(0,0,M_PI/2)); 00483 CPPUNIT_ASSERT_EQUAL(KDL::diff(Rotation::RotZ(0*deg2rad), Rotation::RotZ(-180*deg2rad)), Vector(0,0,M_PI)); 00484 CPPUNIT_ASSERT_EQUAL(KDL::diff(Rotation::RotZ(0*deg2rad), Rotation::RotZ(-90*deg2rad)), Vector(0,0,-M_PI/2)); 00485 CPPUNIT_ASSERT_EQUAL(KDL::diff(Rotation::RotZ(0*deg2rad), Rotation::RotZ(-0*deg2rad)), Vector(0,0,0)); // no rotation 00486 00487 CPPUNIT_ASSERT_EQUAL(KDL::diff(Rotation::RotX(0*deg2rad), Rotation::RotZ(90*deg2rad)), Vector(0,0,M_PI/2)); 00488 CPPUNIT_ASSERT_EQUAL(KDL::diff(Rotation::RotX(0*deg2rad), Rotation::RotY(90*deg2rad)), Vector(0,M_PI/2,0)); 00489 CPPUNIT_ASSERT_EQUAL(KDL::diff(Rotation::RotY(0*deg2rad), Rotation::RotZ(90*deg2rad)), Vector(0,0,M_PI/2)); 00490 00491 CPPUNIT_ASSERT_EQUAL(KDL::diff(Rotation::Identity(), Rotation::RotX(90*deg2rad)), Vector(M_PI/2,0,0)); 00492 CPPUNIT_ASSERT_EQUAL(KDL::diff(Rotation::Identity(), Rotation::RotY(90*deg2rad)), Vector(0,M_PI/2,0)); 00493 CPPUNIT_ASSERT_EQUAL(KDL::diff(Rotation::Identity(), Rotation::RotZ(90*deg2rad)), Vector(0,0,M_PI/2)); 00494 00495 CPPUNIT_ASSERT_EQUAL(KDL::diff(Rotation::RPY(+0*deg2rad,0,-90*deg2rad), 00496 Rotation::RPY(-0*deg2rad,0,+90*deg2rad)), 00497 Vector(0,0,M_PI)); 00498 CPPUNIT_ASSERT_EQUAL(KDL::diff(Rotation::RPY(+5*deg2rad,0,-0*deg2rad), 00499 Rotation::RPY(-5*deg2rad,0,+0*deg2rad)), 00500 Vector(-10*deg2rad,0,0)); 00501 00502 KDL::Rotation R1 = Rotation::RPY(+5*deg2rad,0,-90*deg2rad); 00503 CPPUNIT_ASSERT_EQUAL(KDL::diff(R1, Rotation::RPY(-5*deg2rad,0,+90*deg2rad)), 00504 R1*Vector(0, 0, 180*deg2rad)); 00505 } 00506 00507 void FramesTest::TestFrame() { 00508 Vector v(3,4,5); 00509 Wrench w(Vector(7,-1,3),Vector(2,-3,3)) ; 00510 Twist t(Vector(6,3,5),Vector(4,-2,7)) ; 00511 Rotation R ; 00512 Frame F; 00513 Frame F2 ; 00514 F = Frame(Rotation::EulerZYX(10*deg2rad,20*deg2rad,-10*deg2rad),Vector(4,-2,1)); 00515 F2=F ; 00516 CPPUNIT_ASSERT_EQUAL(F,F2); 00517 CPPUNIT_ASSERT_EQUAL(F.Inverse(F*v),v); 00518 CPPUNIT_ASSERT_EQUAL(F.Inverse(F*t),t); 00519 CPPUNIT_ASSERT_EQUAL(F.Inverse(F*w),w); 00520 CPPUNIT_ASSERT_EQUAL(F*F.Inverse(v),v); 00521 CPPUNIT_ASSERT_EQUAL(F*F.Inverse(t),t); 00522 CPPUNIT_ASSERT_EQUAL(F*F.Inverse(w),w); 00523 CPPUNIT_ASSERT_EQUAL(F*Frame::Identity(),F); 00524 CPPUNIT_ASSERT_EQUAL(Frame::Identity()*F,F); 00525 CPPUNIT_ASSERT_EQUAL(F*(F*(F*v)),(F*F*F)*v); 00526 CPPUNIT_ASSERT_EQUAL(F*(F*(F*t)),(F*F*F)*t); 00527 CPPUNIT_ASSERT_EQUAL(F*(F*(F*w)),(F*F*F)*w); 00528 CPPUNIT_ASSERT_EQUAL(F*F.Inverse(),Frame::Identity()); 00529 CPPUNIT_ASSERT_EQUAL(F.Inverse()*F,Frame::Identity()); 00530 CPPUNIT_ASSERT_EQUAL(F.Inverse()*v,F.Inverse(v)); 00531 } 00532 00533 void FramesTest::TestJntArray() 00534 { 00535 JntArray a1(4); 00536 random(a1(0)); 00537 random(a1(1)); 00538 random(a1(2)); 00539 random(a1(3)); 00540 JntArray a2(a1); 00541 CPPUNIT_ASSERT(Equal(a2,a1)); 00542 00543 SetToZero(a2); 00544 CPPUNIT_ASSERT(!Equal(a1,a2)); 00545 00546 JntArray a3(4); 00547 CPPUNIT_ASSERT(Equal(a2,a3)); 00548 00549 a1=a2; 00550 CPPUNIT_ASSERT(Equal(a1,a3)); 00551 00552 random(a1(0)); 00553 random(a1(1)); 00554 random(a1(2)); 00555 random(a1(3)); 00556 00557 Add(a1,a2,a3); 00558 CPPUNIT_ASSERT(Equal(a1,a3)); 00559 00560 random(a2(0)); 00561 random(a2(1)); 00562 random(a2(2)); 00563 random(a2(3)); 00564 Add(a1,a2,a3); 00565 Subtract(a3,a2,a3); 00566 CPPUNIT_ASSERT(Equal(a1,a3)); 00567 00568 Multiply(a1,2,a3); 00569 Add(a1,a1,a2); 00570 CPPUNIT_ASSERT(Equal(a2,a3)); 00571 00572 double a; 00573 random(a); 00574 Multiply(a1,a,a3); 00575 Divide(a3,a,a2); 00576 CPPUNIT_ASSERT(Equal(a2,a1)); 00577 } 00578 00579 00580 void FramesTest::TestJntArrayWhenEmpty() 00581 { 00582 JntArray a1; 00583 JntArray a2; 00584 JntArray a3(a2); 00585 00586 // won't assert() 00587 CPPUNIT_ASSERT_EQUAL((unsigned int)0,a1.rows()); 00588 CPPUNIT_ASSERT(Equal(a2,a1)); 00589 00590 a2 = a1; 00591 CPPUNIT_ASSERT(Equal(a2,a1)); 00592 00593 SetToZero(a2); 00594 CPPUNIT_ASSERT(Equal(a2,a1)); 00595 00596 Add(a1,a2,a3); 00597 CPPUNIT_ASSERT(Equal(a1,a3)); 00598 00599 Subtract(a1,a2,a3); 00600 CPPUNIT_ASSERT(Equal(a1,a3)); 00601 00602 Multiply(a1,3.1,a3); 00603 CPPUNIT_ASSERT(Equal(a1,a3)); 00604 00605 Divide(a1,3.1,a3); 00606 CPPUNIT_ASSERT(Equal(a1,a3)); 00607 00608 // MultiplyJacobian() - not tested here 00609 00610 00611 /* will assert() - not tested here 00612 double j1 = a1(0); 00613 */ 00614 00615 // and now resize, and do just a few tests 00616 a1.resize(3); 00617 a2.resize(3); 00618 CPPUNIT_ASSERT_EQUAL((unsigned int)3,a1.rows()); 00619 CPPUNIT_ASSERT(Equal(a2,a1)); 00620 00621 random(a1(0)); 00622 random(a1(1)); 00623 random(a1(2)); 00624 a1 = a2; 00625 CPPUNIT_ASSERT(Equal(a1,a2)); 00626 CPPUNIT_ASSERT_EQUAL(a1(1),a2(1)); 00627 00628 a3.resize(3); 00629 Subtract(a1,a2,a3); // a3 = a2 - a1 = {0} 00630 SetToZero(a1); 00631 CPPUNIT_ASSERT(Equal(a1,a3)); 00632 } 00633 00634