basic_localization.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 from __future__ import print_function
4 
5 import sys
6 import time
7 from math import fmod, pi
8 
9 import unittest
10 import rospy
11 import rostest
12 
13 import tf2_py as tf2
14 import tf2_ros
15 import PyKDL
16 from std_srvs.srv import Empty
17 
18 
19 class TestBasicLocalization(unittest.TestCase):
20  def setUp(self):
21  self.tf = None
22  self.target_x = None
23  self.target_y = None
24  self.target_a = None
25  self.tfBuffer = None
26 
27  def print_pose_diff(self):
28  a_curr = self.compute_angle()
29  a_diff = self.wrap_angle(a_curr - self.target_a)
30  print('Curr:\t %16.6f %16.6f %16.6f' % (self.tf.translation.x, self.tf.translation.y, a_curr))
31  print('Target:\t %16.6f %16.6f %16.6f' % (self.target_x, self.target_y, self.target_a))
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))
34 
35  def get_pose(self):
36  try:
37  tf_stamped = self.tfBuffer.lookup_transform("map", "base_link", rospy.Time())
38  self.tf = tf_stamped.transform
39  self.print_pose_diff()
41  pass
42 
43  @staticmethod
44  def wrap_angle(angle):
45  """
46  Wrap angle to [-pi, pi)
47  :param angle: Angle to be wrapped
48  :return: wrapped angle
49  """
50  angle += pi
51  while angle < 0:
52  angle += 2*pi
53  return fmod(angle, 2*pi) - pi
54 
55  def compute_angle(self):
56  rot = self.tf.rotation
57  a_curr = PyKDL.Rotation.Quaternion(rot.x, rot.y, rot.z, rot.w).GetRPY()[2]
58  a_diff = self.wrap_angle(a_curr - self.target_a)
59  return self.target_a + a_diff
60 
62  global_localization = int(sys.argv[1])
63  self.target_x = float(sys.argv[2])
64  self.target_y = float(sys.argv[3])
65  self.target_a = self.wrap_angle(float(sys.argv[4]))
66  tolerance_d = float(sys.argv[5])
67  tolerance_a = float(sys.argv[6])
68  target_time = float(sys.argv[7])
69 
70  rospy.init_node('test', anonymous=True)
71  while rospy.rostime.get_time() == 0.0:
72  print('Waiting for initial time publication')
73  time.sleep(0.1)
74 
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)
79  global_localization()
80 
81  start_time = rospy.rostime.get_time()
82  self.tfBuffer = tf2_ros.Buffer()
83  listener = tf2_ros.TransformListener(self.tfBuffer)
84 
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)))
87  self.get_pose()
88  time.sleep(0.1)
89 
90  print("Final pose:")
91  self.get_pose()
92  a_curr = self.compute_angle()
93 
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)
98 
99 
100 if __name__ == '__main__':
101  rostest.run('amcl', 'amcl_localization', TestBasicLocalization, sys.argv)


amcl
Author(s): Brian P. Gerkey, contradict@gmail.com
autogenerated on Thu Jan 21 2021 04:05:36