]> defiant.homedns.org Git - ros_wild_thumper.git/blob - scripts/dwm1000.py
69ce1c09bd493d0cb6cd7e4887fe364c59c07a25
[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 i2c import i2c
13 from time import sleep
14 from std_msgs.msg import Float32
15 from nav_msgs.msg import Odometry
16 if VISULAIZE:
17         import matplotlib.pyplot as plt
18
19 class simple_kalman:
20         def __init__(self, x_est, P_est, Q, R):
21                 self.x_est = x_est # Systemzustand
22                 self.P_est = P_est # Fehlerkovarianz
23                 self.Q = Q # Systemrauschen
24                 self.R = R # Varianz des Messfehlers
25
26         def run(self, y):
27                 # Korrektur mit der Messung
28                 # (1) Berechnung der Kalman Verstärkung
29                 K = self.P_est/(self.R + self.P_est)
30                 # (2) Korrektur der Schätzung mit der Messung y
31                 x = self.x_est + K*(y - self.x_est)
32                 # (3) Korrektur der Fehlerkovarianzmatrix
33                 P = (1-K)*self.P_est
34                 #
35                 # Prädiktion
36                 # (1) Prädiziere den Systemzustand
37                 self.x_est = x
38                 # (2) Präzidiere die Fehlerkovarianzmatrix
39                 self.P_est = P + self.Q
40
41                 return x
42
43 class DW1000(threading.Thread):
44         def __init__(self, name, addr, offset):
45                 threading.Thread.__init__(self)
46                 self.setDaemon(1)
47                 self.dist = 0
48                 self.offset = offset
49                 self.addr = addr
50
51                 self.pub = rospy.Publisher(name, Float32, queue_size=16)
52
53                 self.start()
54
55         def get_value(self):
56                 dev = i2c(self.addr)
57                 ret = struct.unpack("f", dev.read(4))
58                 dev.close()
59                 return ret[0]
60
61         def distance(self):
62                 return self.dist
63
64         def run(self):
65                 while True:
66                         self.dist = self.get_value() + self.offset
67                         self.pub.publish(self.distance())
68                         sleep(0.1)
69
70 class Position:
71         def __init__(self):
72                 P_est = 0.003 # Fehlerkovarianz
73                 Q = 10e-4 # Systemrauschen
74                 R = 0.1 # Varianz des Messfehlers
75                 self.filter_x = simple_kalman(1.0, P_est, Q, R)
76                 self.filter_y = simple_kalman(0.0, P_est, Q, R)
77                 self.speed_x = 0
78                 self.speed_y = 0
79                 self.speed_z = 0
80                 self.last_time = rospy.Time.now()
81                 rospy.Subscriber("/odom_combined", Odometry, self.odomReceived)
82
83         def odomReceived(self, msg):
84                 self.speed_x = msg.twist.twist.linear.x
85                 self.speed_y = msg.twist.twist.linear.y
86                 self.speed_z = msg.twist.twist.angular.z
87
88         def filter(self, x, y):
89                 # Correct estimation with speed
90                 current_time = rospy.Time.now()
91                 dt = (current_time - self.last_time).to_sec()
92                 # Subtract vehicle speed
93                 pos = np.array([self.filter_x.x_est, self.filter_y.x_est])
94                 # translation
95                 pos -= np.array([self.speed_x*dt, self.speed_y*dt])
96                 # rotation
97                 rot = np.array([[np.cos(self.speed_z*dt), -np.sin(self.speed_z*dt)],
98                                 [np.sin(self.speed_z*dt),  np.cos(self.speed_z*dt)]])
99                 pos = np.dot(pos, rot)
100                 # copy back
101                 self.filter_x.x_est = pos[0]
102                 self.filter_y.x_est = pos[1]
103
104                 # run kalman
105                 x = self.filter_x.run(x)
106                 y = self.filter_y.run(y)
107
108                 self.last_time = current_time
109                 return x,y
110
111
112 if __name__ == "__main__":
113         rospy.init_node('DW1000')
114         dwleft  = DW1000("uwb_dist_left",  0xc2, +0.0)
115         dwright = DW1000("uwb_dist_right", 0xc0, -0.0)
116         dist_l_r = 0.285
117         rate = rospy.Rate(10)
118         pos = Position()
119         tf_broadcaster = tf.broadcaster.TransformBroadcaster()
120
121         while not rospy.is_shutdown() and dwleft.is_alive() and dwright.is_alive():
122                 dist_left = dwleft.distance()
123                 dist_right = dwright.distance()
124                 dir = "left" if (dist_left < dist_right) else "right"
125
126                 diff = abs(dist_left - dist_right)
127                 if diff >= dist_l_r:
128                         # difference to high, correct to maximum
129                         off = diff - dist_l_r + 0.01
130                         if dist_left > dist_right:
131                                 dist_left -= off/2
132                                 dist_right += off/2
133                         else:
134                                 dist_left += off/2
135                                 dist_right -= off/2
136                 print "%.2f %.2f %.2f %.2f %s" % (dwleft.distance(), dwright.distance(), dist_left, dist_right, dir)
137
138                 a_r = (-dist_right**2 + dist_left**2 - dist_l_r**2) / (-2*dist_l_r)
139                 x = dist_l_r/2 - a_r
140                 t = dist_right**2 - a_r**2
141                 if t >= 0:
142                         y = sqrt(t)
143                         print x,y
144                         # Rotate 90 deg
145                         x, y = (y, -x)
146
147                         x, y = pos.filter(x, y)
148                         tf_broadcaster.sendTransform((x, y, 0.0), (0, 0, 0, 1), rospy.Time.now(), "uwb_beacon", "base_footprint")
149
150                         if VISULAIZE:
151                                 circle_left = plt.Circle((-dist_l_r/2, 0), dwleft.distance, color='red', fill=False)
152                                 circle_right = plt.Circle((dist_l_r/2, 0), dwright.distance, color='green', fill=False)
153                                 plt.gca().add_patch(circle_left)
154                                 plt.gca().add_patch(circle_right)
155                                 plt.grid(True)
156                                 plt.axis('scaled')
157                                 plt.show()
158
159                 rate.sleep()