Go to the documentation of this file.00001
00002
00003 import rospy
00004 import rostest
00005 import unittest
00006 from sr_utilities.hand_finder import HandFinder
00007
00008
00009 class TestHandFinder(unittest.TestCase):
00010 def test_no_hand_finder(self):
00011 if rospy.has_param("hand"):
00012 rospy.delete_param("hand")
00013
00014 hand_finder = HandFinder()
00015
00016 self.assertEqual(len(hand_finder.get_hand_parameters().joint_prefix),
00017 0, "correct parameters without a hand")
00018 self.assertEqual(len(hand_finder.get_hand_parameters().mapping),
00019 0, "correct parameters without a hand")
00020 self.assertEqual(len(hand_finder.get_hand_joints()), 0,
00021 "correct joints without a hand")
00022 self.assertEqual(len(hand_finder.get_calibration_path()), 0,
00023 "correct calibration path without a hand")
00024 self.assertEqual(len(hand_finder.get_hand_control_tuning().
00025 friction_compensation), 0,
00026 "correct tuning without a hands")
00027 self.assertEqual(len(hand_finder.get_hand_control_tuning().
00028 host_control), 0,
00029 "correct tuning without a hands")
00030 self.assertEqual(len(hand_finder.get_hand_control_tuning().
00031 motor_control), 0,
00032 "correct tuning without a hands")
00033
00034 def test_one_hand_finder(self):
00035 rospy.set_param("hand/joint_prefix/1", "rh_")
00036 rospy.set_param("hand/mapping/1", "rh")
00037
00038 hand_finder = HandFinder()
00039 self.assertIsNotNone(hand_finder.get_hand_parameters(),
00040 "Parameters extracted.")
00041 self.assertIsNotNone(hand_finder.get_hand_joints(),
00042 "Joints extracted.")
00043 self.assertIsNotNone(hand_finder.get_calibration_path(),
00044 "Calibration extracted.")
00045 self.assertIsNotNone(hand_finder.get_hand_control_tuning(),
00046 "Control tuning parameters extracted.")
00047
00048 def test_two_hand_finder(self):
00049 rospy.set_param("hand/joint_prefix/1", "rh_")
00050 rospy.set_param("hand/mapping/1", "rh")
00051 rospy.set_param("hand/joint_prefix/2", "lh_")
00052 rospy.set_param("hand/mapping/2", "lh")
00053
00054 hand_finder = HandFinder()
00055 self.assertIsNotNone(hand_finder.get_hand_parameters(),
00056 "Parameters extracted.")
00057 self.assertIsNotNone(hand_finder.get_hand_joints(),
00058 "Joints extracted.")
00059 self.assertIsNotNone(hand_finder.get_calibration_path(),
00060 "Calibration extracted.")
00061 self.assertIsNotNone(hand_finder.get_hand_control_tuning(),
00062 "Control tuning parameters extracted.")
00063
00064
00065 if __name__ == "__main__":
00066 rospy.init_node("test_hand_finder")
00067 rostest.rosrun("sr_utilities", "test_hand_finder", TestHandFinder)