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