drift_estimation.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 #
3 # License: BSD
4 # https://raw.github.com/yujinrobot/kobuki/hydro-devel/kobuki_testsuite/LICENSE
5 #
6 ##############################################################################
7 # Imports
8 ##############################################################################
9 
10 import math
11 import threading
12 import PyKDL
13 import rospy
14 from sensor_msgs.msg import LaserScan, Imu
15 from geometry_msgs.msg import Twist
16 from kobuki_msgs.msg import ScanAngle
17 
18 ##############################################################################
19 # Utilities
20 ##############################################################################
21 
22 def quat_to_angle(quat):
23  rot = PyKDL.Rotation.Quaternion(quat.x, quat.y, quat.z, quat.w)
24  return rot.GetRPY()[2]
25 
26 def wrap_angle(angle):
27  if angle <= math.pi and angle >= -math.pi:
28  return angle
29  elif angle < 0.0:
30  return math.fmod(angle-math.pi,2.0*math.pi)+math.pi
31  else:
32  return math.fmod(angle+math.pi,2.0*math.pi)-math.pi;
33 
34 ##############################################################################
35 # Classes
36 ##############################################################################
37 
38 class ScanToAngle(object):
39  def __init__(self, scan_topic, scan_angle_topic):
40  self.min_angle = -0.3
41  self.max_angle = 0.3
42  self.lock = threading.Lock() # make sure we don't publish if the publisher is not there
43  self._laser_scan_angle_publisher = rospy.Publisher(scan_angle_topic, ScanAngle, queue_size=10)
44  self.scan_subscriber = rospy.Subscriber(scan_topic, LaserScan, self.scan_callback)
45 
46  def init(self, min_angle=-0.3, max_angle=0.3):
47  self.min_angle = min_angle
48  self.max_angle = max_angle
49 
50  def shutdown(self):
51  print "Killing off scan angle publisher"
52  if not rospy.is_shutdown():
53  with self.lock:
54  self.scan_subscriber.unregister()
55  self.scan_subscriber = None
56  self._laser_scan_angle_publisher.unregister()
58  self._laser_scan_angle_publisher = None
59 
60  def scan_callback(self, msg):
61  angle = msg.angle_min
62  d_angle = msg.angle_increment
63  sum_x = 0
64  sum_y = 0
65  sum_xx = 0
66  sum_xy = 0
67  num = 0
68  for r in msg.ranges:
69  if angle > self.min_angle and angle < self.max_angle and r < msg.range_max:
70  x = math.sin(angle) * r
71  y = math.cos(angle) * r
72  sum_x += x
73  sum_y += y
74  sum_xx += x*x
75  sum_xy += x*y
76  num += 1
77  angle += d_angle
78  if num > 0:
79  denominator = num*sum_xx-sum_x*sum_x
80  if denominator != 0:
81  angle=math.atan2((-sum_x*sum_y+num*sum_xy)/(denominator), 1)
82  #print("Scan Angle: %s"%str(angle))
83  relay = ScanAngle()
84  relay.header = msg.header
85  relay.scan_angle = angle
86  with self.lock:
88  self._laser_scan_angle_publisher.publish(relay)
89  else:
90  rospy.logerr("Please point me at a wall.")
91 
92 class DriftEstimation(object):
93  def __init__(self, laser_scan_angle_topic, gyro_scan_angle_topic, error_scan_angle_topic, cmd_vel_topic, gyro_topic):
94  self.lock = threading.Lock()
95 
96  self._gyro_scan_angle_publisher = rospy.Publisher(gyro_scan_angle_topic, ScanAngle, queue_size=10)
97  self._laser_scan_angle_subscriber = rospy.Subscriber(laser_scan_angle_topic, ScanAngle, self.scan_callback)
98  self._error_scan_angle_publisher = rospy.Publisher(error_scan_angle_topic, ScanAngle, queue_size=10)
99  self.gyro_subscriber = rospy.Subscriber(gyro_topic, Imu, self.gyro_callback)
100  self.cmd_vel_publisher = rospy.Publisher(cmd_vel_topic, Twist, queue_size=10)
101 
102  self.rate = rospy.Rate(30)
103 
104  self._gyro_angle = 0
105  self._gyro_time = rospy.Time.now()
106  self._scan_angle = 0
107  self._scan_time = rospy.Time.now()
108 
109  ##############################
110  # Parameters
111  ##############################
113  self._max_angle = 0.4
114  self._abs_yaw_rate = 0.3
115  self._epsilon = 0.5 # radians value above which increasing difference in scan and gyro angle will be ignored
116 
119 
120  self._stop = False
121  self._running = False
122 
123  def init(self, yaw_rate):
124  self._abs_yaw_rate = yaw_rate
125 
126  def shutdown(self):
127  self.stop()
128  while self._running:
129  self.rate.sleep()
130  if not rospy.is_shutdown():
131  print "Shutting down drift estimation"
132  self._gyro_scan_angle_publisher.unregister()
133  self._gyro_scan_angle_publisher = None
134  self._laser_scan_angle_subscriber.unregister()
135  self._laser_scan_angle_subscriber = None
136  self._error_scan_angle_publisher.unregister()
137  self._error_scan_angle_publisher = None
138  self.gyro_subscriber.unregister()
139  self.gyro_subscriber = None
140  self.cmd_vel_publisher.unregister()
141  self.cmd_vel_publisher = None
142 
143  def stop(self):
144  self._stop = True
145 
146  def execute(self):
147  '''
148  Drop this into threading.Thread or QThread for execution
149  '''
150  if self._running:
151  rospy.logerr("Kobuki TestSuite: already executing, ignoring the request")
152  return
153  self._stop = False
154  self._running = True
155  if not self.align(): # centred_gyro_angle set in here
156  rospy.loginfo("Kobuki Testsuite: could not align, please point me at a wall.")
157  self._initial_gyro_offset = None
158  self._running = False
159  return
160  with self.lock:
161  if not self._initial_gyro_offset:
162  self._initial_gyro_offset = self._gyro_angle - self._scan_angle
163  print("Kobuki Testsuite: initial centre [%s]"%self._centred_gyro_angle)
164  print("Kobuki Testsuite: initial offset [%s]"%self._initial_gyro_offset)
165  last_gyro_time = rospy.get_rostime()
166  last_scan_time = rospy.get_rostime()
167  yaw_rate_cmd = self._abs_yaw_rate
168  turn_count = 0
169  gyro_timeout_count = 0
170  while not self._stop and not rospy.is_shutdown():
171  with self.lock:
172  gyro_time = self._gyro_time
173  scan_time = self._scan_time
174  gyro_angle = self._gyro_angle
175  scan_angle = self._scan_angle
176  if gyro_time > last_gyro_time:
177  last_gyro_time = gyro_time
178  if wrap_angle(gyro_angle - self._centred_gyro_angle) > self._max_angle:
179  if yaw_rate_cmd > 0:
180  turn_count = turn_count + 1
181  yaw_rate_cmd = -self._abs_yaw_rate
182  elif wrap_angle(gyro_angle - self._centred_gyro_angle) < -self._max_angle:
183  yaw_rate_cmd = self._abs_yaw_rate
184  else:
185  yaw_rate_cmd = cmp(yaw_rate_cmd,0)*self._abs_yaw_rate
186  cmd = Twist()
187  cmd.angular.z = yaw_rate_cmd
188  self.cmd_vel_publisher.publish(cmd)
189  if scan_time > last_scan_time:
190  rospy.loginfo("Kobuki Testsuite: gyro, laser angle comparison [%s,%s]"%(gyro_angle - self._initial_gyro_offset, scan_angle))
191  last_scan_time = scan_time
192  else:
193  gyro_timeout_count = gyro_timeout_count + 1
194  if gyro_timeout_count > 50:
195  rospy.logerr("Kobuki Testsuite: no gyro data for a long time.")
196  break
197  if turn_count > 4:
198  rospy.loginfo("Kobuki Testsuite: aligning.....")
199  self.align()
200  turn_count = 0
201  rospy.sleep(0.05)
202  if not rospy.is_shutdown():
203  cmd = Twist()
204  cmd.angular.z = 0.0
205  self.cmd_vel_publisher.publish(cmd)
206  self._initial_gyro_offset = None
207  self._running = False
208 
209  def align(self):
210  with self.lock:
211  angle = self._scan_angle
212  no_data_count = 0
213  count = 0
214  epsilon = 0.05
215  cmd = Twist()
216  while True: #self._inital_wall_angle:
217  if angle == 0: # magic number, means we have no data yet
218  no_data_count += 1
219  if no_data_count == 40:
220  return False
221  if self._stop or rospy.is_shutdown():
222  return False
223  elif count > 20:
224  with self.lock:
225  self._centred_gyro_angle = self._gyro_angle
226  cmd.angular.z = 0.0
227  self.cmd_vel_publisher.publish(cmd)
228  return True
229  if math.fabs(angle) < 0.05:
230  count = count + 1
231  # The work
232  if angle > 0:
233  cmd.angular.z = -0.2
234  else:
235  cmd.angular.z = 0.2
236  self.cmd_vel_publisher.publish(cmd)
237  rospy.sleep(0.05)
238  with self.lock:
239  angle = self._scan_angle
240  print "end of align"
241 
242  ##########################################################################
243  # Ros Callbacks
244  ##########################################################################
245 
246  def gyro_callback(self, msg):
247  with self.lock:
248  angle = quat_to_angle(msg.orientation)
249  self._gyro_angle = angle
250  self._gyro_time = msg.header.stamp
251  if self._initial_gyro_offset:
252  gyro_scan_angle = ScanAngle()
253  gyro_scan_angle.header = msg.header
254  gyro_scan_angle.scan_angle = angle - self._initial_gyro_offset
255  self._gyro_scan_angle_publisher.publish(gyro_scan_angle)
256  if self._running:
257  error_scan_angle = ScanAngle()
258  error_scan_angle.header = msg.header
259  error_scan_angle.scan_angle = math.fabs(angle - self._initial_gyro_offset - self._scan_angle)
260  #if error_scan_angle.scan_angle < self._epsilon: # don't spam with errors greater than what we're looking for
261  self._error_scan_angle_publisher.publish(error_scan_angle)
262 
263  def scan_callback(self, msg):
264  with self.lock:
265  #rospy.loginfo("Kobuki Testsuite: scan angle [%s]"%msg.scan_angle)
266  self._scan_angle = msg.scan_angle
267  self._scan_time = msg.header.stamp
268 
269 
def __init__(self, scan_topic, scan_angle_topic)
def quat_to_angle(quat)
Utilities.
def __init__(self, laser_scan_angle_topic, gyro_scan_angle_topic, error_scan_angle_topic, cmd_vel_topic, gyro_topic)
def init(self, min_angle=-0.3, max_angle=0.3)


kobuki_testsuite
Author(s): Jorge Santos Simon
autogenerated on Mon Jun 10 2019 13:45:22