00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 import math
00038 import unittest
00039
00040 from geometry_msgs.msg import Pose
00041 import rospy
00042 import tf
00043 from tf.transformations import quaternion_from_euler
00044
00045 class TestArAlvarRos(unittest.TestCase):
00046 '''
00047 Tests are based on http://download.ros.org/data/ar_track_alvar/ar_track_alvar_4markers_tork_2017-01-30-15-03-19.bag
00048 '''
00049
00050 def setUp(self):
00051 rospy.init_node('test_armarker_ros_detect')
00052 self.tflistener = tf.TransformListener()
00053
00054 def tearDown(self):
00055 True
00056
00057 def _lookup_tf(self, origin, target):
00058 '''
00059 DEPRECATED: This does not return meaningful values for some reason.
00060 @param origin: lookupTransform's 1st argument.
00061 @param target: lookupTransform's 2nd argument.
00062 @rtype: ([str], [str])
00063 @return: Translation and rotation.
00064 '''
00065 while not rospy.is_shutdown():
00066 try:
00067 (trans,rot) = self.tflistener.lookupTransform(origin, target, rospy.Time(0))
00068 break
00069 except (tf.LookupException, tf.ConnectivityException, tf.ExtrapolationException) as e:
00070 rospy.logerr(str(e) + ' target={}'.format(target))
00071 continue
00072 return (trans, rot)
00073
00074 def test_markers(self):
00075 '''
00076 Aiming the real output taken from a bag file.
00077 '''
00078
00079 tf_expected = [[[0.04464459977845401, 0.05341412598745035, 0.26796900627543024], [0.6726999185589797, 0.7391474391806558, -0.01739267319701629, -0.028868280906256056]],
00080 [[-0.04805772245624329, 0.039528315926071665, 0.26775882622136327], [0.48207151562664247, 0.8758763282975102, -0.016363763970395625, -0.013414118615296202]],
00081 [[0.007233278235745441, 0.015615692018491452, 0.26619586686955365], [0.08546919545682985, 0.9959809257461487, -0.0001615529469785548, -0.02677659572186436]],
00082 [[0.06223014382428272, 0.014613815037010106, 0.26226145707174475], [-0.46400320825216246, 0.8850390875261293, 0.032644264656690035, -0.018471282241381157]]]
00083 for i in range (0, len(tf_expected)):
00084 while not rospy.is_shutdown():
00085 try:
00086 target_frame = '/ar_marker_{}'.format(i)
00087 (trans, rot) = self.tflistener.lookupTransform('/camera', target_frame, rospy.Time(0))
00088 break
00089 except (tf.LookupException, tf.ConnectivityException, tf.ExtrapolationException) as e:
00090 rospy.logerr(str(e) + ' target_frame={}'.format(target_frame))
00091 continue
00092
00093 for v_ret, v_expected in zip(trans, tf_expected[i][0]):
00094 self.assertAlmostEqual(v_ret, v_expected, 2)
00095
00096 for v_ret, v_expected in zip(rot, tf_expected[i][1]):
00097 self.assertAlmostEqual(v_ret, v_expected, 2)
00098
00099 if __name__ == '__main__':
00100 import rostest
00101 rostest.rosrun('ar_track_alvar', 'test_ar_alvar_ros', TestArAlvarRos)