2 # -*- coding: iso-8859-15 -*-
13 from time import sleep
14 from std_msgs.msg import Float32
15 from nav_msgs.msg import Odometry
17 import matplotlib.pyplot as plt
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
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
36 # (1) Prädiziere den Systemzustand
38 # (2) Präzidiere die Fehlerkovarianzmatrix
39 self.P_est = P + self.Q
43 class DW1000(threading.Thread):
44 def __init__(self, name, addr, offset):
45 threading.Thread.__init__(self)
52 self.pub = rospy.Publisher(name, Float32, queue_size=16)
58 ret = struct.unpack("f", dev.read(4))
68 val = self.get_value()
69 if abs(val - last_val) > 10:
70 print "Ignoring values too far apart %s: %.2f - %.2f" % (self.name, val, last_val)
72 self.dist = val + self.offset
73 self.pub.publish(self.distance())
79 # Varianz des Messfehlers
87 self.filter_x = simple_kalman(1.0, P_est_x, Q, Rx)
88 self.filter_y = simple_kalman(0.0, P_est_y, Q, Ry)
92 self.last_time = rospy.Time.now()
93 rospy.Subscriber("/odom_combined", Odometry, self.odomReceived)
95 def odomReceived(self, msg):
96 self.speed_x = msg.twist.twist.linear.x
97 self.speed_y = msg.twist.twist.linear.y
98 self.speed_z = msg.twist.twist.angular.z
100 def filter(self, x, y):
101 # Correct estimation with speed
102 current_time = rospy.Time.now()
103 dt = (current_time - self.last_time).to_sec()
104 # Subtract vehicle speed
105 pos = np.array([self.filter_x.x_est, self.filter_y.x_est])
107 pos -= np.array([self.speed_x*dt, self.speed_y*dt])
109 rot = np.array([[np.cos(self.speed_z*dt), -np.sin(self.speed_z*dt)],
110 [np.sin(self.speed_z*dt), np.cos(self.speed_z*dt)]])
111 pos = np.dot(pos, rot)
113 self.filter_x.x_est = pos[0]
114 self.filter_y.x_est = pos[1]
117 x = self.filter_x.run(x)
118 y = self.filter_y.run(y)
120 self.last_time = current_time
124 if __name__ == "__main__":
125 rospy.init_node('DW1000')
126 dwleft = DW1000("uwb_dist_left", 0xc2, +0.0)
127 dwright = DW1000("uwb_dist_right", 0xc0, -0.0)
129 rate = rospy.Rate(10)
131 tf_broadcaster = tf.broadcaster.TransformBroadcaster()
133 while not rospy.is_shutdown() and dwleft.is_alive() and dwright.is_alive():
134 dist_left = dwleft.distance()
135 dist_right = dwright.distance()
136 dir = "left" if (dist_left < dist_right) else "right"
138 diff = abs(dist_left - dist_right)
140 # difference to high, correct to maximum
141 off = diff - dist_l_r + 0.01
142 if dist_left > dist_right:
148 print "%.2f %.2f %.2f %.2f %s" % (dwleft.distance(), dwright.distance(), dist_left, dist_right, dir)
150 a_r = (-dist_right**2 + dist_left**2 - dist_l_r**2) / (-2*dist_l_r)
152 t = dist_right**2 - a_r**2
159 x, y = pos.filter(x, y)
160 tf_broadcaster.sendTransform((x, y, 0.0), (0, 0, 0, 1), rospy.Time.now(), "uwb_beacon", "base_footprint")
163 circle_left = plt.Circle((-dist_l_r/2, 0), dwleft.distance, color='red', fill=False)
164 circle_right = plt.Circle((dist_l_r/2, 0), dwright.distance, color='green', fill=False)
165 plt.gca().add_patch(circle_left)
166 plt.gca().add_patch(circle_right)