@@ -595,7 +595,44 @@ def test_SampleTimeGenerator_EndPointLessThanHalfStepSize(self):
595
595
decimal = 7 , err_msg = error , \
596
596
verbose = True )
597
597
598
+
599
+ # GetForwardKinematics()
600
+
601
+ def test_GetForwardKinematics (self ):
602
+ # Zero configuration, use thes the active manipulator by default
603
+ q0 = numpy .array ([0.0 , 0.0 , 0.0 , 0.0 , 0.0 , 0.0 , 0.0 ])
604
+ T_ee = prpy .util .GetForwardKinematics (self .robot , q0 )
605
+
606
+ expected_T_ee0 = numpy .array ([[1.0 , 0.0 , 0.0 , 0.07 ],
607
+ [0.0 , 1.0 , 0.0 , 0.0 ],
608
+ [0.0 , 0.0 , 1.0 , 2.168 ],
609
+ [0.0 , 0.0 , 0.0 , 1.0 ]])
610
+ error = 'The end-effector transform ' + str (T_ee ) + \
611
+ ' does not equal the expected end-effector' + \
612
+ ' transform ' + str (expected_T_ee0 )
613
+ numpy .testing .assert_array_almost_equal (T_ee , expected_T_ee0 , decimal = 7 , \
614
+ err_msg = error , verbose = True )
615
+
616
+ # A different configuration, specifying the manipulator to use
617
+ q1 = numpy .array ([- 1.8 , 0.0 , - 0.7 , 2.0 , 0.5 , 0.2 , 0.0 ])
618
+ manip = self .robot .GetActiveManipulator ()
619
+ T_ee = prpy .util .GetForwardKinematics (self .robot , q1 , manip )
620
+
621
+ expected_T_ee1 = numpy .array ([[ 0.7126777 , 0.3653714 , - 0.5988272 , - 0.3313395 ],
622
+ [- 0.0541115 , - 0.8224716 , - 0.5662263 , - 0.3259651 ],
623
+ [- 0.6994014 , 0.4359404 , - 0.5663864 , 1.4394693 ],
624
+ [ 0.0 , 0.0 , 0.0 , 1.0 ]])
625
+ error = 'The end-effector transform ' + str (T_ee ) + \
626
+ ' does not equal the expected end-effector' + \
627
+ ' transform ' + str (expected_T_ee1 )
628
+ numpy .testing .assert_array_almost_equal (T_ee , expected_T_ee1 , decimal = 7 , \
629
+ err_msg = error , verbose = True )
630
+
631
+
598
632
class Test_GetPointFrom (unittest .TestCase ):
633
+ """
634
+ Unit Tests for GetPointFrom()
635
+ """
599
636
def setUp (self ):
600
637
self .env = openravepy .Environment ()
601
638
@@ -641,38 +678,6 @@ def test_GetPointFrom_List(self):
641
678
list_result = prpy .util .GetPointFrom (list_coord )
642
679
numpy .testing .assert_array_almost_equal (list_result , expected_coord )
643
680
644
- # GetForwardKinematics()
645
-
646
- def test_GetForwardKinematics (self ):
647
- # Zero configuration, use thes the active manipulator by default
648
- q0 = numpy .array ([0.0 , 0.0 , 0.0 , 0.0 , 0.0 , 0.0 , 0.0 ])
649
- T_ee = prpy .util .GetForwardKinematics (self .robot , q0 )
650
-
651
- expected_T_ee0 = numpy .array ([[1.0 , 0.0 , 0.0 , 0.07 ],
652
- [0.0 , 1.0 , 0.0 , 0.0 ],
653
- [0.0 , 0.0 , 1.0 , 2.168 ],
654
- [0.0 , 0.0 , 0.0 , 1.0 ]])
655
- error = 'The end-effector transform ' + str (T_ee ) + \
656
- ' does not equal the expected end-effector' + \
657
- ' transform ' + str (expected_T_ee0 )
658
- numpy .testing .assert_array_almost_equal (T_ee , expected_T_ee0 , decimal = 7 , \
659
- err_msg = error , verbose = True )
660
-
661
- # A different configuration, specifying the manipulator to use
662
- q1 = numpy .array ([- 1.8 , 0.0 , - 0.7 , 2.0 , 0.5 , 0.2 , 0.0 ])
663
- manip = self .robot .GetActiveManipulator ()
664
- T_ee = prpy .util .GetForwardKinematics (self .robot , q1 , manip )
665
-
666
- expected_T_ee1 = numpy .array ([[ 0.7126777 , 0.3653714 , - 0.5988272 , - 0.3313395 ],
667
- [- 0.0541115 , - 0.8224716 , - 0.5662263 , - 0.3259651 ],
668
- [- 0.6994014 , 0.4359404 , - 0.5663864 , 1.4394693 ],
669
- [ 0.0 , 0.0 , 0.0 , 1.0 ]])
670
- error = 'The end-effector transform ' + str (T_ee ) + \
671
- ' does not equal the expected end-effector' + \
672
- ' transform ' + str (expected_T_ee1 )
673
- numpy .testing .assert_array_almost_equal (T_ee , expected_T_ee1 , decimal = 7 , \
674
- err_msg = error , verbose = True )
675
-
676
681
677
682
if __name__ == '__main__' :
678
683
unittest .main ()
0 commit comments