2 # -*- coding: iso-8859-15 -*-
12 from datetime import datetime
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
19 import matplotlib.pyplot as plt
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
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
38 # (1) Prädiziere den Systemzustand
40 # (2) Präzidiere die Fehlerkovarianzmatrix
41 self.P_est = P + self.Q
45 def set_measure_cov(self, R):
49 class DW1000(threading.Thread):
50 def __init__(self, name, addr, offset):
51 threading.Thread.__init__(self)
57 self.last_update = datetime.min
59 self.pub = rospy.Publisher(name, Float32, queue_size=16)
65 ret = struct.unpack("f", dev.read(4))
72 # Returns each distance only if current
73 def distance_valid(self):
74 if (datetime.now() - self.last_update).seconds < 1:
80 while not rospy.is_shutdown():
81 val = self.get_value()
82 if abs(val - last_val) > 50:
83 rospy.logwarn("Ignoring values too far apart %s: %.2f - %.2f", self.name, val, last_val)
85 self.dist = val + self.offset
86 self.last_update = datetime.now()
87 self.pub.publish(self.distance())
93 # Varianz des Messfehlers
102 # TODO: Replace 2x 1d kalman with 2d kalman
103 # so the polyfit variance can be replaced with a covariance matrix
104 self.filter_x = simple_kalman(1.0, P_est_x, Qx, Rx)
105 self.filter_y = simple_kalman(0.0, P_est_y, Qy, Ry)
109 self.last_time = rospy.Time.now()
110 rospy.Subscriber("/odom_combined", Odometry, self.odomReceived)
112 def odomReceived(self, msg):
113 self.speed_x = msg.twist.twist.linear.x
114 self.speed_y = msg.twist.twist.linear.y
115 self.speed_z = msg.twist.twist.angular.z
117 def filter(self, x, y):
118 # Correct estimation with speed
119 current_time = rospy.Time.now()
120 dt = (current_time - self.last_time).to_sec()
121 # Subtract vehicle speed
122 pos = np.array([self.filter_x.x_est, self.filter_y.x_est])
124 pos -= np.array([self.speed_x*dt, self.speed_y*dt])
126 rot = np.array([[np.cos(self.speed_z*dt), -np.sin(self.speed_z*dt)],
127 [np.sin(self.speed_z*dt), np.cos(self.speed_z*dt)]])
128 pos = np.dot(pos, rot)
130 self.filter_x.x_est = pos[0]
131 self.filter_y.x_est = pos[1]
133 # run kalman if new measurements are valid
134 if x != None and y != None:
135 x = self.filter_x.run(x)
136 y = self.filter_y.run(y)
139 dist = np.linalg.norm([x, y])
140 self.filter_x.set_measure_cov(np.polyval([0.018, 0.0, 0.0], dist))
141 self.filter_y.set_measure_cov(np.polyval([0.006, 0.0, 0.0], dist))
143 x = self.filter_x.x_est
144 y = self.filter_y.x_est
146 self.last_time = current_time
150 def handle_center_call(req):
151 diff = dwleft.distance_valid() - dwright.distance_valid()
152 dwleft.offset -= diff/2
153 dwright.offset += diff/2
154 rospy.loginfo("Centering to %.2f %.2f", dwleft.offset, dwright.offset)
155 return DWM1000CenterResponse()
157 if __name__ == "__main__":
158 rospy.init_node('DWM1000', log_level=rospy.DEBUG)
159 dwleft = DW1000("uwb_dist_left", 0xc2, +0.0)
160 dwright = DW1000("uwb_dist_right", 0xc0, -0.0)
161 dist_l_r = 0.285 # Distance between both DWM1000
162 rate = rospy.Rate(10)
164 tf_broadcaster = tf.broadcaster.TransformBroadcaster()
165 rospy.Service('/DWM1000/center', DWM1000Center, handle_center_call)
167 while not rospy.is_shutdown() and dwleft.is_alive() and dwright.is_alive():
168 dist_left = dwleft.distance_valid()
169 dist_right = dwright.distance_valid()
172 if dist_left == None or dist_right == None:
173 rospy.logerr_throttle(10, "no valid sensor update %r %r" % (dist_left, dist_right))
174 # run kalman prediction only
175 x,y = pos.filter(None, None)
177 dir = "left" if (dist_left < dist_right) else "right"
179 diff = abs(dist_left - dist_right)
181 # difference to high, correct to maximum
182 off = diff - dist_l_r + 0.01
183 if dist_left > dist_right:
189 rospy.logdebug("%.2f %.2f %.2f %.2f %s", dwleft.distance(), dwright.distance(), dist_left, dist_right, dir)
191 a_r = (-dist_right**2 + dist_left**2 - dist_l_r**2) / (-2*dist_l_r)
193 t = dist_right**2 - a_r**2
196 rospy.logdebug("x=%.2f, y=%.2f", x, y)
200 x, y = pos.filter(x, y)
203 circle_left = plt.Circle((-dist_l_r/2, 0), dwleft.distance, color='red', fill=False)
204 circle_right = plt.Circle((dist_l_r/2, 0), dwright.distance, color='green', fill=False)
205 plt.gca().add_patch(circle_left)
206 plt.gca().add_patch(circle_right)
211 # No current position, still need up update kalman prediction
212 x, y = pos.filter(None, None)
213 tf_broadcaster.sendTransform((x, y, 0.0), (0, 0, 0, 1), rospy.Time.now(), "uwb_beacon", "base_footprint")