]> defiant.homedns.org Git - ros_wild_thumper.git/blob - scripts/dwm1000.py
dwm1000: Added service call to calibrate center
[ros_wild_thumper.git] / scripts / dwm1000.py
1 #!/usr/bin/env python
2 # -*- coding: iso-8859-15 -*-
3
4 VISULAIZE = False
5
6 import threading
7 import struct
8 import rospy
9 import tf
10 import numpy as np
11 from math import *
12 from datetime import datetime
13 from i2c import i2c
14 from time import sleep
15 from std_msgs.msg import Float32
16 from nav_msgs.msg import Odometry
17 from wild_thumper.srv import DWM1000Center, DWM1000CenterResponse
18 if VISULAIZE:
19         import matplotlib.pyplot as plt
20
21 class simple_kalman:
22         def __init__(self, x_est, P_est, Q, R):
23                 self.x_est = x_est # Systemzustand
24                 self.P_est = P_est # Fehlerkovarianz
25                 self.Q = Q # Systemrauschen
26                 self.R = R # Varianz des Messfehlers
27
28         def run(self, y):
29                 # Korrektur mit der Messung
30                 # (1) Berechnung der Kalman Verstärkung
31                 K = self.P_est/(self.R + self.P_est)
32                 # (2) Korrektur der Schätzung mit der Messung y
33                 x = self.x_est + K*(y - self.x_est)
34                 # (3) Korrektur der Fehlerkovarianzmatrix
35                 P = (1-K)*self.P_est
36                 #
37                 # Prädiktion
38                 # (1) Prädiziere den Systemzustand
39                 self.x_est = x
40                 # (2) Präzidiere die Fehlerkovarianzmatrix
41                 self.P_est = P + self.Q
42
43                 return x
44
45 class DW1000(threading.Thread):
46         def __init__(self, name, addr, offset):
47                 threading.Thread.__init__(self)
48                 self.setDaemon(1)
49                 self.dist = 0
50                 self.offset = offset
51                 self.addr = addr
52                 self.name = name
53                 self.last_update = datetime.min
54
55                 self.pub = rospy.Publisher(name, Float32, queue_size=16)
56
57                 self.start()
58
59         def get_value(self):
60                 dev = i2c(self.addr)
61                 ret = struct.unpack("f", dev.read(4))
62                 dev.close()
63                 return ret[0]
64
65         def distance(self):
66                 return self.dist
67
68         # Returns each distance only if current
69         def distance_valid(self):
70                 if (datetime.now() - self.last_update).seconds < 1:
71                         return self.dist
72                 return None
73
74         def run(self):
75                 last_val = 10
76                 while True:
77                         val = self.get_value()
78                         if abs(val - last_val)  > 10:
79                                 print "Ignoring values too far apart %s: %.2f - %.2f" % (self.name, val, last_val)
80                         elif not isnan(val):
81                                 self.dist = val + self.offset
82                                 self.last_update = datetime.now()
83                                 self.pub.publish(self.distance())
84                                 last_val = val
85                         sleep(0.1)
86
87 class Position:
88         def __init__(self):
89                 # Varianz des Messfehlers
90                 Rx = 0.2
91                 Ry = 0.05
92                 # Fehlerkovarianz
93                 P_est_x = 0.02
94                 P_est_y = 0.01
95                 # Systemrauschen
96                 Q = 0.002
97                 self.filter_x = simple_kalman(1.0, P_est_x, Q, Rx)
98                 self.filter_y = simple_kalman(0.0, P_est_y, Q, Ry)
99                 self.speed_x = 0
100                 self.speed_y = 0
101                 self.speed_z = 0
102                 self.last_time = rospy.Time.now()
103                 rospy.Subscriber("/odom_combined", Odometry, self.odomReceived)
104
105         def odomReceived(self, msg):
106                 self.speed_x = msg.twist.twist.linear.x
107                 self.speed_y = msg.twist.twist.linear.y
108                 self.speed_z = msg.twist.twist.angular.z
109
110         """
111         TODO:
112         - variance of kalman should be dependant on distance
113         """
114         def filter(self, x, y):
115                 # Correct estimation with speed
116                 current_time = rospy.Time.now()
117                 dt = (current_time - self.last_time).to_sec()
118                 # Subtract vehicle speed
119                 pos = np.array([self.filter_x.x_est, self.filter_y.x_est])
120                 # translation
121                 pos -= np.array([self.speed_x*dt, self.speed_y*dt])
122                 # rotation
123                 rot = np.array([[np.cos(self.speed_z*dt), -np.sin(self.speed_z*dt)],
124                                 [np.sin(self.speed_z*dt),  np.cos(self.speed_z*dt)]])
125                 pos = np.dot(pos, rot)
126                 # copy back
127                 self.filter_x.x_est = pos[0]
128                 self.filter_y.x_est = pos[1]
129
130                 # run kalman if new measurements are valid
131                 if x != None and y != None:
132                         x = self.filter_x.run(x)
133                         y = self.filter_y.run(y)
134                 else:
135                         x = self.filter_x.x_est
136                         y = self.filter_y.x_est
137
138                 self.last_time = current_time
139                 return x,y
140
141
142 def handle_center_call(req):
143         diff = dwleft.distance_valid() - dwright.distance_valid()
144         dwleft.offset -= diff/2
145         dwright.offset += diff/2
146         print "Centering to %.2f %.2f" % (dwleft.offset, dwright.offset)
147         return DWM1000CenterResponse()
148
149 if __name__ == "__main__":
150         rospy.init_node('DWM1000')
151         dwleft  = DW1000("uwb_dist_left",  0xc2, +0.02)
152         dwright = DW1000("uwb_dist_right", 0xc0, -0.02)
153         dist_l_r = 0.285
154         rate = rospy.Rate(10)
155         pos = Position()
156         tf_broadcaster = tf.broadcaster.TransformBroadcaster()
157         rospy.Service('/DWM1000/center', DWM1000Center, handle_center_call)
158
159         while not rospy.is_shutdown() and dwleft.is_alive() and dwright.is_alive():
160                 dist_left = dwleft.distance_valid()
161                 dist_right = dwright.distance_valid()
162                 if dist_left == None or dist_right == None:
163                         print "no valid sensor update"
164                         # run kalman prediction only
165                         pos.filter(None, None)
166                 else:
167                         dir = "left" if (dist_left < dist_right) else "right"
168
169                         diff = abs(dist_left - dist_right)
170                         if diff >= dist_l_r:
171                                 # difference to high, correct to maximum
172                                 off = diff - dist_l_r + 0.01
173                                 if dist_left > dist_right:
174                                         dist_left -= off/2
175                                         dist_right += off/2
176                                 else:
177                                         dist_left += off/2
178                                         dist_right -= off/2
179                         print "%.2f %.2f %.2f %.2f %s" % (dwleft.distance(), dwright.distance(), dist_left, dist_right, dir)
180
181                         a_r = (-dist_right**2 + dist_left**2 - dist_l_r**2) / (-2*dist_l_r)
182                         x = dist_l_r/2 - a_r
183                         t = dist_right**2 - a_r**2
184                         if t >= 0:
185                                 y = sqrt(t)
186                                 print x,y
187                                 # Rotate 90 deg
188                                 x, y = (y, -x)
189
190                                 x, y = pos.filter(x, y)
191                                 tf_broadcaster.sendTransform((x, y, 0.0), (0, 0, 0, 1), rospy.Time.now(), "uwb_beacon", "base_footprint")
192
193                                 if VISULAIZE:
194                                         circle_left = plt.Circle((-dist_l_r/2, 0), dwleft.distance, color='red', fill=False)
195                                         circle_right = plt.Circle((dist_l_r/2, 0), dwright.distance, color='green', fill=False)
196                                         plt.gca().add_patch(circle_left)
197                                         plt.gca().add_patch(circle_right)
198                                         plt.grid(True)
199                                         plt.axis('scaled')
200                                         plt.show()
201                         else:
202                                 # No current position, still need up update kalman prediction
203                                 pos.filter(None, None)
204
205                 rate.sleep()