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
18 from pyshared.simple_kalman import simple_kalman
20 import matplotlib.pyplot as plt
23 class DW1000(threading.Thread):
24 def __init__(self, name, addr, offset):
25 threading.Thread.__init__(self)
31 self.last_update = datetime.min
33 self.pub = rospy.Publisher(name, Float32, queue_size=16)
39 ret = struct.unpack("f", dev.read(4))
46 # Returns each distance only if current
47 def distance_valid(self):
48 if (datetime.now() - self.last_update).seconds < 1:
54 while not rospy.is_shutdown():
55 val = self.get_value()
56 if abs(val - last_val) > 50:
57 rospy.logwarn("Ignoring values too far apart %s: %.2f - %.2f", self.name, val, last_val)
59 self.dist = val + self.offset
60 self.last_update = datetime.now()
61 self.pub.publish(self.distance())
67 R = np.matrix([[0.5, 0.0], [0.0, 0.2]]) # Varianz des Messfehlers
68 P_est = 1e50 * np.eye(2) # Fehlerkovarianz
69 Q = np.matrix([[0.001, 0.0], [0.0, 0.0001]]) # Systemrauschen
70 self.filter_xy = simple_kalman(np.array([[1.0, 0.0]]).T, P_est, Q, R)
74 self.last_time = rospy.Time.now()
75 rospy.Subscriber("/odom_combined", Odometry, self.odomReceived)
77 def odomReceived(self, msg):
78 self.speed_x = msg.twist.twist.linear.x
79 self.speed_y = msg.twist.twist.linear.y
80 self.speed_z = msg.twist.twist.angular.z
82 def filter(self, x, y):
83 # Correct estimation with speed
84 current_time = rospy.Time.now()
85 dt = (current_time - self.last_time).to_sec()
86 # Subtract vehicle speed
87 pos = self.filter_xy.x_est.T
89 pos -= np.array([self.speed_x*dt, self.speed_y*dt])
91 rot = np.array([[np.cos(self.speed_z*dt), -np.sin(self.speed_z*dt)],
92 [np.sin(self.speed_z*dt), np.cos(self.speed_z*dt)]])
93 pos = np.dot(pos, rot)
95 self.filter_xy.x_est = pos.T
97 # run kalman if new measurements are valid
99 if x != None and y != None:
100 pos = self.filter_xy.run(np.array([[x, y]]).T)
103 dist = np.linalg.norm([x, y])
104 cov_00 = np.polyval([0.018, 0.0, 0.0], dist)
105 cov_11 = np.polyval([0.006, 0.0, 0.0], dist)
106 self.filter_xy.set_measure_cov(np.matrix([[cov_00, 0.0], [0.0, cov_11]]))
108 pos = self.filter_xy.x_est
109 self.filter_xy.P_est = np.matrix(1e50 * np.eye(2)) # reset estimate when lost
115 self.last_time = current_time
119 def handle_center_call(req):
120 diff = dwleft.distance_valid() - dwright.distance_valid()
121 dwleft.offset -= diff/2
122 dwright.offset += diff/2
123 rospy.loginfo("Centering to %.2f %.2f", dwleft.offset, dwright.offset)
124 return DWM1000CenterResponse()
126 if __name__ == "__main__":
127 rospy.init_node('DWM1000', log_level=rospy.DEBUG)
128 dwleft = DW1000("uwb_dist_left", 0xc2, -0.04)
129 dwright = DW1000("uwb_dist_right", 0xc0, +0.04)
130 dist_l_r = 0.285 # Distance between both DWM1000
131 rate = rospy.Rate(10)
133 tf_broadcaster = tf.broadcaster.TransformBroadcaster()
134 rospy.Service('/DWM1000/center', DWM1000Center, handle_center_call)
136 while not rospy.is_shutdown() and dwleft.is_alive() and dwright.is_alive():
137 dist_left = dwleft.distance_valid()
138 dist_right = dwright.distance_valid()
141 if dist_left == None or dist_right == None:
142 rospy.logerr_throttle(10, "no valid sensor update %r %r" % (dist_left, dist_right))
143 # run kalman prediction only
144 x,y = pos.filter(None, None)
146 dir = "left" if (dist_left < dist_right) else "right"
148 diff = abs(dist_left - dist_right)
150 # difference to high, correct to maximum
151 off = diff - dist_l_r + 0.01
152 if dist_left > dist_right:
158 rospy.logdebug("%.2f %.2f %.2f %.2f %s", dwleft.distance(), dwright.distance(), dist_left, dist_right, dir)
160 a_r = (-dist_right**2 + dist_left**2 - dist_l_r**2) / (-2*dist_l_r)
162 t = dist_right**2 - a_r**2
165 rospy.logdebug("x=%.2f, y=%.2f", x, y)
169 x, y = pos.filter(x, y)
172 circle_left = plt.Circle((-dist_l_r/2, 0), dwleft.distance, color='red', fill=False)
173 circle_right = plt.Circle((dist_l_r/2, 0), dwright.distance, color='green', fill=False)
174 plt.gca().add_patch(circle_left)
175 plt.gca().add_patch(circle_right)
180 # No current position, still need up update kalman prediction
181 x, y = pos.filter(None, None)
182 tf_broadcaster.sendTransform((x, y, 0.0), (0, 0, 0, 1), rospy.Time.now(), "uwb_beacon", "base_footprint")