19 CPPUNIT_ASSERT_EQUAL(2*v-v,v);
20 CPPUNIT_ASSERT_EQUAL(v*2-v,v);
21 CPPUNIT_ASSERT_EQUAL(v+v+v-2*v,v);
23 CPPUNIT_ASSERT_EQUAL(v,v2);
25 CPPUNIT_ASSERT_EQUAL(2*v,v2);
27 CPPUNIT_ASSERT_EQUAL(v,v2);
29 CPPUNIT_ASSERT_EQUAL(v,-v2);
39 CPPUNIT_ASSERT_EQUAL(nu.
Norm(),0.0);
41 CPPUNIT_ASSERT_EQUAL(nu2.
Norm(),10.0);
46 CPPUNIT_ASSERT_EQUAL(nu.
Norm(), 0.0);
57 CPPUNIT_ASSERT_EQUAL(2*t-t,t);
58 CPPUNIT_ASSERT_EQUAL(t*2-t,t);
59 CPPUNIT_ASSERT_EQUAL(t+t+t-2*t,t);
61 CPPUNIT_ASSERT_EQUAL(t,t2);
63 CPPUNIT_ASSERT_EQUAL(2*t,t2);
65 CPPUNIT_ASSERT_EQUAL(t,t2);
67 CPPUNIT_ASSERT_EQUAL(t,-t2);
82 CPPUNIT_ASSERT_EQUAL(2*w-w,w);
83 CPPUNIT_ASSERT_EQUAL(w*2-w,w);
84 CPPUNIT_ASSERT_EQUAL(w+w+w-2*w,w);
86 CPPUNIT_ASSERT_EQUAL(w,w2);
88 CPPUNIT_ASSERT_EQUAL(2*w,w2);
90 CPPUNIT_ASSERT_EQUAL(w,w2);
92 CPPUNIT_ASSERT_EQUAL(w,-w2);
124 CPPUNIT_ASSERT_EQUAL(R,R2);
125 CPPUNIT_ASSERT_DOUBLES_EQUAL((R*v).
Norm(),v.Norm(),
epsilon);
126 CPPUNIT_ASSERT_EQUAL(R.
Inverse(R*v),v);
127 CPPUNIT_ASSERT_EQUAL(R.
Inverse(R*t),t);
128 CPPUNIT_ASSERT_EQUAL(R.
Inverse(R*w),w);
129 CPPUNIT_ASSERT_EQUAL(R*R.
Inverse(v),v);
132 CPPUNIT_ASSERT_EQUAL(R*(R*(R*v)),(R*R*R)*v);
133 CPPUNIT_ASSERT_EQUAL(R*(R*(R*t)),(R*R*R)*t);
134 CPPUNIT_ASSERT_EQUAL(R*(R*(R*w)),(R*R*R)*w);
137 CPPUNIT_ASSERT_EQUAL(R.Inverse()*v,R.Inverse(v));
139 CPPUNIT_ASSERT_DOUBLES_EQUAL(ra,a,
epsilon);
140 CPPUNIT_ASSERT_DOUBLES_EQUAL(rb,b,
epsilon);
141 CPPUNIT_ASSERT_DOUBLES_EQUAL(rc,c,
epsilon);
143 R.GetEulerZYX(ra,rb,rc);
144 CPPUNIT_ASSERT_DOUBLES_EQUAL(ra,a,
epsilon);
145 CPPUNIT_ASSERT_DOUBLES_EQUAL(rb,b,
epsilon);
146 CPPUNIT_ASSERT_DOUBLES_EQUAL(rc,c,
epsilon);
148 R.GetEulerZYZ(ra,rb,rc);
149 CPPUNIT_ASSERT_DOUBLES_EQUAL(ra,a,
epsilon);
150 CPPUNIT_ASSERT_DOUBLES_EQUAL(rb,b,
epsilon);
151 CPPUNIT_ASSERT_DOUBLES_EQUAL(rc,c,
epsilon);
152 double angle= R.GetRotAngle(v2);
154 CPPUNIT_ASSERT_EQUAL(R2,R);
156 CPPUNIT_ASSERT_EQUAL(R,R2);
165 const double expectedAngle,
172 CPPUNIT_ASSERT_DOUBLES_EQUAL_MESSAGE(msg, expectedAngle, angle,
epsilon);
173 CPPUNIT_ASSERT_EQUAL_MESSAGE(msg, expectedAxis, axis);
174 CPPUNIT_ASSERT_EQUAL_MESSAGE(msg, expectedAngle * expectedAxis, R.
GetRot());
175 CPPUNIT_ASSERT_EQUAL_MESSAGE(msg,
Rotation::Rot(axis, angle), R);
177 CPPUNIT_ASSERT_EQUAL_MESSAGE(msg,
Rotation::Rot2(axis, angle), R);
185 const double expectedAngle,
188 std::stringstream ss;
189 ss <<
"rot(" << msg <<
"],(" << angle <<
")";
194 #define TESTEULERZYX(a,b,g) \ 197 Rotation R = Rotation::EulerZYX((a),(b),(g));\ 198 double alpha,beta,gamma;\ 199 R.GetEulerZYX(alpha,beta,gamma);\ 200 CPPUNIT_ASSERT_DOUBLES_EQUAL((a),alpha,eps);\ 201 CPPUNIT_ASSERT_DOUBLES_EQUAL((b),beta,eps);\ 202 CPPUNIT_ASSERT_DOUBLES_EQUAL((g),gamma,eps);\ 205 #define TESTEULERZYZ(a,b,g) \ 208 Rotation R = Rotation::EulerZYZ((a),(b),(g));\ 209 double alpha,beta,gamma;\ 210 R.GetEulerZYZ(alpha,beta,gamma);\ 211 CPPUNIT_ASSERT_DOUBLES_EQUAL((a),alpha,eps);\ 212 CPPUNIT_ASSERT_DOUBLES_EQUAL((b),beta,eps);\ 213 CPPUNIT_ASSERT_DOUBLES_EQUAL((g),gamma,eps);\ 215 #define TESTEULERZYX_INVARIANT(a,b,g,a2,b2,g2)\ 218 Rotation R1=Rotation::EulerZYX(a,b,g);\ 219 Rotation R2=Rotation::EulerZYX(a2,b2,g2);\ 220 CPPUNIT_ASSERT_DOUBLES_EQUAL(0,diff(R2,R1).Norm(),eps);\ 222 #define TESTEULERZYZ_INVARIANT(a,b,g,a2,b2,g2)\ 225 Rotation R1=Rotation::EulerZYZ(a,b,g);\ 226 Rotation R2=Rotation::EulerZYZ(a2,b2,g2);\ 227 CPPUNIT_ASSERT_DOUBLES_EQUAL(0,diff(R2,R1).Norm(),eps);\ 303 TestArbitraryRotation(msg, v, 0, 0,
Vector(0,0,1));
304 TestArbitraryRotation(msg, v, 45, 45, expectedVector);
305 TestArbitraryRotation(msg, v, 90, 90, expectedVector);
306 TestArbitraryRotation(msg, v, 179, 179, expectedVector);
311 TestArbitraryRotation(msg, v, 181, 179, -expectedVector);
312 TestArbitraryRotation(msg, v, 270, 90, -expectedVector);
313 TestArbitraryRotation(msg, v, 359, 1, -expectedVector);
314 TestArbitraryRotation(msg, v, 360, 0,
Vector(0,0,1));
315 TestArbitraryRotation(msg, v, 361, 1, expectedVector);
316 TestArbitraryRotation(msg, v, 450, 90, expectedVector);
317 TestArbitraryRotation(msg, v, 539, 179, expectedVector);
319 TestArbitraryRotation(msg, v, 541, 179, -expectedVector);
320 TestArbitraryRotation(msg, v, 630, 90, -expectedVector);
321 TestArbitraryRotation(msg, v, 719, 1, -expectedVector);
322 TestArbitraryRotation(msg, v, 720, 0,
Vector(0,0,1));
324 TestArbitraryRotation(msg, v, -45, 45, -expectedVector);
325 TestArbitraryRotation(msg, v, -90, 90, -expectedVector);
326 TestArbitraryRotation(msg, v, -179, 179, -expectedVector);
328 TestArbitraryRotation(msg, v, -181, 179, expectedVector);
329 TestArbitraryRotation(msg, v, -270, 90, expectedVector);
330 TestArbitraryRotation(msg, v, -359, 1, expectedVector);
331 TestArbitraryRotation(msg, v, -360, 0,
Vector(0,0,1));
332 TestArbitraryRotation(msg, v, -361, 1, -expectedVector);
333 TestArbitraryRotation(msg, v, -450, 90, -expectedVector);
334 TestArbitraryRotation(msg, v, -539, 179, -expectedVector);
336 TestArbitraryRotation(msg, v, -541, 179, expectedVector);
337 TestArbitraryRotation(msg, v, -630, 90, expectedVector);
338 TestArbitraryRotation(msg, v, -719, 1, expectedVector);
339 TestArbitraryRotation(msg, v, -720, 0,
Vector(0,0,1));
346 TestRangeArbitraryRotation(
"[1,0,0]",
Vector(1,0,0),
Vector(1,0,0));
347 TestRangeArbitraryRotation(
"[-1,0,0]",
Vector(-1,0,0),
Vector(-1,0,0));
349 TestRangeArbitraryRotation(
"[0,1,0]",
Vector(0,1,0),
Vector(0,1,0));
350 TestRangeArbitraryRotation(
"[0,-1,0]",
Vector(0,-1,0),
Vector(0,-1,0));
352 TestRangeArbitraryRotation(
"[0,0,1]",
Vector(0,0,1),
Vector(0,0,1));
353 TestRangeArbitraryRotation(
"[0,0,-1]",
Vector(0,0,-1),
Vector(0,0,-1));
355 TestRangeArbitraryRotation(
"[1,1,0]",
Vector(1,1,0),
Vector(1,1,0)/
sqrt(2.0));
356 TestRangeArbitraryRotation(
"[-1,-1,0]",
Vector(-1,-1,0),
Vector(-1,-1,0)/
sqrt(2.0));
358 TestRangeArbitraryRotation(
"[1,0,1]",
Vector(1,0,1),
Vector(1,0,1)/
sqrt(2.0));
359 TestRangeArbitraryRotation(
"[-1,0,-1]",
Vector(-1,0,-1),
Vector(-1,0,-1)/
sqrt(2.0));
361 TestRangeArbitraryRotation(
"[0,1,1]",
Vector(0,1,1),
Vector(0,1,1)/
sqrt(2.0));
362 TestRangeArbitraryRotation(
"[0,-1,-1]",
Vector(0,-1,-1),
Vector(0,-1,-1)/
sqrt(2.0));
364 TestRangeArbitraryRotation(
"[1,1,1]",
Vector(1,1,1),
Vector(1,1,1)/
sqrt(3.0));
365 TestRangeArbitraryRotation(
"[-1,-1,-1]",
Vector(-1,-1,-1),
Vector(-1,-1,-1)/
sqrt(3.0));
369 TestOneRotation(
"rot([1,0,0],180)",
KDL::Rotation::Rot(
KDL::Vector(1,0,0),180*
deg2rad), 180*
deg2rad,
Vector(1,0,0));
371 TestOneRotation(
"rot([-1,0,0],180)",
KDL::Rotation::Rot(
KDL::Vector(-1,0,0),180*
deg2rad), 180*
deg2rad,
Vector(1,0,0));
372 TestOneRotation(
"rot([0,1,0],180)",
KDL::Rotation::Rot(
KDL::Vector(0,1,0),180*
deg2rad), 180*
deg2rad,
Vector(0,1,0));
374 TestOneRotation(
"rot([0,-1,0],180)",
KDL::Rotation::Rot(
KDL::Vector(0,-1,0),180*
deg2rad), 180*
deg2rad,
Vector(0,1,0));
376 TestOneRotation(
"rot([0,0,1],180)",
KDL::Rotation::Rot(
KDL::Vector(0,0,1),180*
deg2rad), 180*
deg2rad,
Vector(0,0,1));
378 TestOneRotation(
"rot([0,0,-1],180)",
KDL::Rotation::Rot(
KDL::Vector(0,0,-1),180*
deg2rad), 180*
deg2rad,
Vector(0,0,1));
380 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));
382 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));
383 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));
385 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));
387 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));
389 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));
390 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));
392 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));
394 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));
396 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));
397 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));
399 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));
401 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));
403 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));
404 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));
406 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));
412 double roll = -2.9811968953315162;
413 double pitch = -
PI_2;
414 double yaw = -0.1603957582582825;
424 CPPUNIT_ASSERT(0==isnan(theta));
425 CPPUNIT_ASSERT(0==isnan(kdlAxis[0]));
426 CPPUNIT_ASSERT(0==isnan(kdlAxis[1]));
427 CPPUNIT_ASSERT(0==isnan(kdlAxis[2]));
433 CPPUNIT_ASSERT_DOUBLES_EQUAL_MESSAGE(
"rot(NON-ORTHOGONAL, 0)", 0.0, angle,
epsilon);
439 CPPUNIT_ASSERT_DOUBLES_EQUAL_MESSAGE(
"rot(NON-ORTHOGONAL, PI)",
PI, angle,
epsilon);
451 det = +R(0,0)*(R(1,1)*R(2,2)-R(2,1)*R(1,2))-R(0,1)*(R(1,0)*R(2,2)-R(2,0)*R(1,2))+R(0,2)*(R(1,0)*R(2,1)-R(2,0)*R(1,1));
452 CPPUNIT_ASSERT_EQUAL(det,-1.0);
455 CPPUNIT_ASSERT_ASSERTION_FAIL(CPPUNIT_ASSERT_EQUAL(R,Rout));
458 det = +R(0,0)*(R(1,1)*R(2,2)-R(2,1)*R(1,2))-R(0,1)*(R(1,0)*R(2,2)-R(2,0)*R(1,2))+R(0,2)*(R(1,0)*R(2,1)-R(2,0)*R(1,1));
459 CPPUNIT_ASSERT_EQUAL(det,-1.0);
462 CPPUNIT_ASSERT_ASSERTION_FAIL(CPPUNIT_ASSERT_EQUAL(R,Rout));
476 CPPUNIT_ASSERT_EQUAL(R,R2);
482 CPPUNIT_ASSERT_DOUBLES_EQUAL(y, 0,
epsilon);
483 CPPUNIT_ASSERT_DOUBLES_EQUAL(z, 0,
epsilon);
486 CPPUNIT_ASSERT_EQUAL(R,R2);
490 CPPUNIT_ASSERT_EQUAL(R,R2);
492 CPPUNIT_ASSERT_DOUBLES_EQUAL(x, x2,
epsilon);
493 CPPUNIT_ASSERT_DOUBLES_EQUAL(y, y2,
epsilon);
494 CPPUNIT_ASSERT_DOUBLES_EQUAL(z, z2,
epsilon);
495 CPPUNIT_ASSERT_DOUBLES_EQUAL(w, w2,
epsilon);
501 CPPUNIT_ASSERT_EQUAL(R,R2);
503 CPPUNIT_ASSERT_DOUBLES_EQUAL(x, x2,
epsilon);
504 CPPUNIT_ASSERT_DOUBLES_EQUAL(y, y2,
epsilon);
505 CPPUNIT_ASSERT_DOUBLES_EQUAL(z, z2,
epsilon);
506 CPPUNIT_ASSERT_DOUBLES_EQUAL(w, w2,
epsilon);
510 const std::string& msg,
513 const Vector& expectedDiff) {
514 CPPUNIT_ASSERT_EQUAL_MESSAGE(msg,
diff(R_a_b1, R_a_b2), expectedDiff);
515 CPPUNIT_ASSERT_EQUAL_MESSAGE(msg,
addDelta(R_a_b1, expectedDiff), R_a_b2);
520 TestOneRotationDiff(
"diff(RotX(0*deg2rad),RotX(0*deg2rad))",
522 TestOneRotationDiff(
"diff(RotX(0*deg2rad),RotX(90*deg2rad))",
524 TestOneRotationDiff(
"diff(RotX(0*deg2rad),RotX(180*deg2rad))",
526 TestOneRotationDiff(
"diff(RotX(0*deg2rad),RotX(270*deg2rad))",
528 TestOneRotationDiff(
"diff(RotX(0*deg2rad),RotX(360*deg2rad))",
530 TestOneRotationDiff(
"diff(RotX(0*deg2rad),RotX(-360*deg2rad))",
532 TestOneRotationDiff(
"diff(RotX(0*deg2rad),RotX(-270*deg2rad))",
534 TestOneRotationDiff(
"diff(RotX(0*deg2rad),RotX(-180*deg2rad))",
536 TestOneRotationDiff(
"diff(RotX(0*deg2rad),RotX(-90*deg2rad))",
538 TestOneRotationDiff(
"diff(RotX(0*deg2rad),RotX(-0*deg2rad))",
541 TestOneRotationDiff(
"diff(RotY(0*deg2rad),RotY(0*deg2rad))",
543 TestOneRotationDiff(
"diff(RotY(0*deg2rad),RotY(90*deg2rad))",
545 TestOneRotationDiff(
"diff(RotY(0*deg2rad),RotY(180*deg2rad))",
547 TestOneRotationDiff(
"diff(RotY(0*deg2rad),RotY(270*deg2rad))",
549 TestOneRotationDiff(
"diff(RotY(0*deg2rad),RotY(360*deg2rad))",
551 TestOneRotationDiff(
"diff(RotY(0*deg2rad),RotY(-360*deg2rad))",
553 TestOneRotationDiff(
"diff(RotY(0*deg2rad),RotY(-270*deg2rad))",
555 TestOneRotationDiff(
"diff(RotY(0*deg2rad),RotY(-180*deg2rad))",
557 TestOneRotationDiff(
"diff(RotY(0*deg2rad),RotY(-90*deg2rad))",
559 TestOneRotationDiff(
"diff(RotY(0*deg2rad),RotY(-0*deg2rad))",
562 TestOneRotationDiff(
"diff(RotZ(0*deg2rad),RotZ(0*deg2rad))",
564 TestOneRotationDiff(
"diff(RotZ(0*deg2rad),RotZ(90*deg2rad))",
566 TestOneRotationDiff(
"diff(RotZ(0*deg2rad),RotZ(180*deg2rad))",
568 TestOneRotationDiff(
"diff(RotZ(0*deg2rad),RotZ(270*deg2rad))",
570 TestOneRotationDiff(
"diff(RotZ(0*deg2rad),RotZ(360*deg2rad))",
572 TestOneRotationDiff(
"diff(RotZ(0*deg2rad),RotZ(-360*deg2rad))",
574 TestOneRotationDiff(
"diff(RotZ(0*deg2rad),RotZ(-270*deg2rad))",
576 TestOneRotationDiff(
"diff(RotZ(0*deg2rad),RotZ(-180*deg2rad))",
578 TestOneRotationDiff(
"diff(RotZ(0*deg2rad),RotZ(-90*deg2rad))",
580 TestOneRotationDiff(
"diff(RotZ(0*deg2rad),RotZ(-0*deg2rad))",
583 TestOneRotationDiff(
"diff(RotX(0*deg2rad),RotZ(90*deg2rad))",
585 TestOneRotationDiff(
"diff(RotX(0*deg2rad),RotY(90*deg2rad))",
587 TestOneRotationDiff(
"diff(RotY(0*deg2rad),RotZ(90*deg2rad))",
590 TestOneRotationDiff(
"diff(Identity(),RotX(90*deg2rad))",
592 TestOneRotationDiff(
"diff(Identity(),RotY(0*deg2rad))",
594 TestOneRotationDiff(
"diff(Identity(),RotZ(0*deg2rad))",
597 TestOneRotationDiff(
"diff(Rotation::RPY(+0*deg2rad,0,-90*deg2rad),Rotation::RPY(-0*deg2rad,0,+90*deg2rad))",
601 TestOneRotationDiff(
"diff(Rotation::RPY(+5*deg2rad,0,-0*deg2rad),Rotation::RPY(-5*deg2rad,0,+0*deg2rad))",
607 TestOneRotationDiff(
"diff(Rotation::RPY(+5*deg2rad,0,-90*deg2rad),Rotation::RPY(-5*deg2rad,0,+90*deg2rad))",
621 CPPUNIT_ASSERT_EQUAL(F,F2);
622 CPPUNIT_ASSERT_EQUAL(F.
Inverse(F*v),v);
623 CPPUNIT_ASSERT_EQUAL(F.
Inverse(F*t),t);
624 CPPUNIT_ASSERT_EQUAL(F.
Inverse(F*w),w);
625 CPPUNIT_ASSERT_EQUAL(F*F.
Inverse(v),v);
626 CPPUNIT_ASSERT_EQUAL(F*F.
Inverse(t),t);
627 CPPUNIT_ASSERT_EQUAL(F*F.
Inverse(w),w);
630 CPPUNIT_ASSERT_EQUAL(F*(F*(F*v)),(F*F*F)*v);
631 CPPUNIT_ASSERT_EQUAL(F*(F*(F*t)),(F*F*F)*t);
632 CPPUNIT_ASSERT_EQUAL(F*(F*(F*w)),(F*F*F)*w);
635 CPPUNIT_ASSERT_EQUAL(F.Inverse()*v,F.Inverse(v));
641 for (
int i = 0; i<size; ++i)
650 CPPUNIT_ASSERT(
Equal(random1_copy,random1));
654 CPPUNIT_ASSERT(!
Equal(random1,zero_set_to_zero));
657 CPPUNIT_ASSERT(
Equal(zero_set_to_zero,zero));
660 almost_zero(0) = almost_zero(0)*1e-7;
661 almost_zero(1) = almost_zero(1)*1e-7;
662 almost_zero(2) = almost_zero(2)*1e-7;
663 almost_zero(3) = almost_zero(3)*1e-7;
666 CPPUNIT_ASSERT(
Equal(almost_zero,zero,1));
667 CPPUNIT_ASSERT(
Equal(almost_zero,zero,1e-6));
668 CPPUNIT_ASSERT(!
Equal(almost_zero,zero,1e-8));
672 Add(random1,zero_set_to_zero,sum_random_zero);
673 CPPUNIT_ASSERT(
Equal(random1,sum_random_zero));
678 Add(random1,random2,add_subtract);
679 Subtract(add_subtract,random2,add_subtract);
680 CPPUNIT_ASSERT(
Equal(random1,add_subtract));
684 Multiply(random1,2,random_multiply_by_2);
685 Add(random1,random1,sum_random_same_random);
686 CPPUNIT_ASSERT(
Equal(sum_random_same_random,random_multiply_by_2));
692 Multiply(random1,a,random_multiply_devide);
693 Divide(random_multiply_devide,a,random_multiply_devide);
694 CPPUNIT_ASSERT(
Equal(random_multiply_devide,random1));
705 CPPUNIT_ASSERT_EQUAL((
unsigned int)0,a1.
rows());
706 CPPUNIT_ASSERT(
Equal(a2,a1));
709 CPPUNIT_ASSERT(
Equal(a2,a1));
712 CPPUNIT_ASSERT(
Equal(a2,a1));
715 CPPUNIT_ASSERT(
Equal(a1,a3));
718 CPPUNIT_ASSERT(
Equal(a1,a3));
721 CPPUNIT_ASSERT(
Equal(a1,a3));
724 CPPUNIT_ASSERT(
Equal(a1,a3));
736 CPPUNIT_ASSERT_EQUAL((
unsigned int)3,a1.
rows());
737 CPPUNIT_ASSERT(
Equal(a2,a1));
743 CPPUNIT_ASSERT(
Equal(a1,a2));
744 CPPUNIT_ASSERT_EQUAL(a1(1),a2(1));
749 CPPUNIT_ASSERT(
Equal(a1,a3));
void TestOneRotationDiff(const std::string &msg, const KDL::Rotation &R_a_b1, const KDL::Rotation &R_a_b2, const KDL::Vector &expectedDiff)
void Subtract(const JntArray &src1, const JntArray &src2, JntArray &dest)
void TestWrench2(Wrench &w)
#define TESTEULERZYZ(a, b, g)
represents rotations in 3 dimensional space.
void Divide(const JntArray &src, const double &factor, JntArray &dest)
Vector UnitX() const
Access to the underlying unitvectors of the rotation matrix.
Vector UnitZ() const
Access to the underlying unitvectors of the rotation matrix.
double GetRotAngle(Vector &axis, double eps=epsilon) const
INLINE S Norm(const Rall1d< T, V, S > &value)
const double PI_2
the value of pi/2
void ReverseSign()
Reverses the sign of the twist.
unsigned int rows() const
Vector UnitY() const
Access to the underlying unitvectors of the rotation matrix.
static Rotation RotX(double angle)
The Rot... static functions give the value of the appropriate rotation matrix back.
Rotation Inverse() const
Gives back the inverse rotation matrix of *this.
#define TESTEULERZYZ_INVARIANT(a, b, g, a2, b2, g2)
#define TESTEULERZYX(a, b, g)
double Normalize(double eps=epsilon)
const double PI
the value of pi
static Rotation RotZ(double angle)
The Rot... static functions give the value of the appropriate rotation matrix back.
IMETHOD Vector diff(const Vector &p_w_a, const Vector &p_w_b, double dt=1)
static Rotation Quaternion(double x, double y, double z, double w)
This class represents an fixed size array containing joint values of a KDL::Chain.
JntArray CreateRandomJntArray(int size)
CPPUNIT_TEST_SUITE_REGISTRATION(FramesTest)
static Rotation RotY(double angle)
The Rot... static functions give the value of the appropriate rotation matrix back.
void ReverseSign()
Reverses the sign of the Vector object itself.
doubleAcc dot(const VectorAcc &lhs, const VectorAcc &rhs)
void ReverseSign()
Reverses the sign of the current Wrench.
void Add(const JntArray &src1, const JntArray &src2, JntArray &dest)
#define TESTEULERZYX_INVARIANT(a, b, g, a2, b2, g2)
void GetQuaternion(double &x, double &y, double &z, double &w) const
double Norm(double eps=epsilon) const
void TestArbitraryRotation(const std::string &msg, const KDL::Vector &v, const double angle, const double expectedAngle, const KDL::Vector &expectedVector)
static Rotation EulerZYX(double Alfa, double Beta, double Gamma)
represents both translational and rotational velocities.
IMETHOD void SetToZero(Vector &v)
IMETHOD bool Equal(const FrameAcc &r1, const FrameAcc &r2, double eps=epsilon)
INLINE Rall1d< T, V, S > atan(const Rall1d< T, V, S > &x)
A concrete implementation of a 3 dimensional vector class.
static Rotation RPY(double roll, double pitch, double yaw)
void TestRangeArbitraryRotation(const std::string &msg, const KDL::Vector &v, const KDL::Vector &expectedVector)
double epsilon
default precision while comparing with Equal(..,..) functions. Initialized at 0.0000001.
static Rotation Identity()
Gives back an identity rotaton matrix.
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
Frame Inverse() const
Gives back inverse transformation of a Frame.
double Norm(double eps=epsilon) const
void TestOneRotation(const std::string &msg, const KDL::Rotation &R, const double expectedAngle, const KDL::Vector &expectedAxis)
void resize(unsigned int newSize)
void TestJntArrayWhenEmpty()
static Rotation EulerZYZ(double Alfa, double Beta, double Gamma)
represents a frame transformation in 3D space (rotation + translation)
represents both translational and rotational acceleration.
IMETHOD Vector addDelta(const Vector &p_w_a, const Vector &p_w_da, double dt=1)
adds vector da to vector a. see also the corresponding diff() routine.
void TestVector2(Vector &v)
static Rotation Rot(const Vector &rotvec, double angle)
const double deg2rad
the value pi/180
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
static Rotation Rot2(const Vector &rotvec, double angle)
Along an arbitrary axes. rotvec should be normalized.
void TestRotation2(const Vector &v, double a, double b, double c)
IMETHOD void random(Vector &a)
addDelta operator for displacement rotational velocity.
void TestTwist2(Twist &t)
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)
void Multiply(const JntArray &src, const double &factor, JntArray &dest)