3 from __future__
import print_function
7 from math
import fmod, pi
16 from std_srvs.srv
import Empty
30 print(
'Curr:\t %16.6f %16.6f %16.6f' % (self.tf.translation.x, self.tf.translation.y, a_curr))
32 print(
'Diff:\t %16.6f %16.6f %16.6f' % (
33 abs(self.tf.translation.x - self.
target_x), abs(self.tf.translation.y - self.
target_y), a_diff))
37 tf_stamped = self.tfBuffer.lookup_transform(
"map",
"base_link", rospy.Time())
38 self.
tf = tf_stamped.transform
46 Wrap angle to [-pi, pi) 47 :param angle: Angle to be wrapped 48 :return: wrapped angle 53 return fmod(angle, 2*pi) - pi
56 rot = self.tf.rotation
57 a_curr = PyKDL.Rotation.Quaternion(rot.x, rot.y, rot.z, rot.w).GetRPY()[2]
62 global_localization = int(sys.argv[1])
66 tolerance_d = float(sys.argv[5])
67 tolerance_a = float(sys.argv[6])
68 target_time = float(sys.argv[7])
70 rospy.init_node(
'test', anonymous=
True)
71 while rospy.rostime.get_time() == 0.0:
72 print(
'Waiting for initial time publication')
75 if global_localization == 1:
76 print(
'Waiting for service global_localization')
77 rospy.wait_for_service(
'global_localization')
78 global_localization = rospy.ServiceProxy(
'global_localization', Empty)
81 start_time = rospy.rostime.get_time()
85 while (rospy.rostime.get_time() - start_time) < target_time:
86 print(
'Waiting for end time %.6f (current: %.6f)' % (target_time, (rospy.rostime.get_time() - start_time)))
94 self.assertNotEqual(self.
tf,
None)
95 self.assertAlmostEqual(self.tf.translation.x, self.
target_x, delta=tolerance_d)
96 self.assertAlmostEqual(self.tf.translation.y, self.
target_y, delta=tolerance_d)
97 self.assertAlmostEqual(a_curr, self.
target_a, delta=tolerance_a)
100 if __name__ ==
'__main__':
101 rostest.run(
'amcl',
'amcl_localization', TestBasicLocalization, sys.argv)
def print_pose_diff(self)
def test_basic_localization(self)