]> defiant.homedns.org Git - ros_wild_thumper.git/commitdiff
dwm1000: Ignore outdated distance values
authorErik Andresen <erik@vontaene.de>
Sun, 8 Jul 2018 08:34:10 +0000 (10:34 +0200)
committerErik Andresen <erik@vontaene.de>
Sun, 8 Jul 2018 08:34:10 +0000 (10:34 +0200)
scripts/dwm1000.py

index d36a5d2f7e683fbc9e96e773ac874aa91821c2b9..a1dac533a75fdff3df52e15de79150042db8869f 100755 (executable)
@@ -9,6 +9,7 @@ import rospy
 import tf
 import numpy as np
 from math import *
+from datetime import datetime
 from i2c import i2c
 from time import sleep
 from std_msgs.msg import Float32
@@ -48,6 +49,7 @@ class DW1000(threading.Thread):
                self.offset = offset
                self.addr = addr
                self.name = name
+               self.last_update = datetime.min
 
                self.pub = rospy.Publisher(name, Float32, queue_size=16)
 
@@ -62,6 +64,12 @@ class DW1000(threading.Thread):
        def distance(self):
                return self.dist
 
+       # Returns each distance only if current
+       def distance_valid(self):
+               if (datetime.now() - self.last_update).seconds < 1:
+                       return self.dist
+               return None
+
        def run(self):
                last_val = 10
                while True:
@@ -70,6 +78,7 @@ class DW1000(threading.Thread):
                                print "Ignoring values too far apart %s: %.2f - %.2f" % (self.name, val, last_val)
                        elif not isnan(val):
                                self.dist = val + self.offset
+                               self.last_update = datetime.now()
                                self.pub.publish(self.distance())
                                last_val = val
                        sleep(0.1)
@@ -97,6 +106,10 @@ class Position:
                self.speed_y = msg.twist.twist.linear.y
                self.speed_z = msg.twist.twist.angular.z
 
+       """
+       TODO:
+       - variance of kalman should be dependant on distance
+       """
        def filter(self, x, y):
                # Correct estimation with speed
                current_time = rospy.Time.now()
@@ -113,9 +126,13 @@ class Position:
                self.filter_x.x_est = pos[0]
                self.filter_y.x_est = pos[1]
 
-               # run kalman
-               x = self.filter_x.run(x)
-               y = self.filter_y.run(y)
+               # run kalman if new measurements are valid
+               if x != None and y != None:
+                       x = self.filter_x.run(x)
+                       y = self.filter_y.run(y)
+               else:
+                       x = self.filter_x.x_est
+                       y = self.filter_y.x_est
 
                self.last_time = current_time
                return x,y
@@ -123,49 +140,57 @@ class Position:
 
 if __name__ == "__main__":
        rospy.init_node('DW1000')
-       dwleft  = DW1000("uwb_dist_left",  0xc2, +0.0)
-       dwright = DW1000("uwb_dist_right", 0xc0, -0.0)
+       dwleft  = DW1000("uwb_dist_left",  0xc2, +0.02)
+       dwright = DW1000("uwb_dist_right", 0xc0, -0.02)
        dist_l_r = 0.285
        rate = rospy.Rate(10)
        pos = Position()
        tf_broadcaster = tf.broadcaster.TransformBroadcaster()
 
        while not rospy.is_shutdown() and dwleft.is_alive() and dwright.is_alive():
-               dist_left = dwleft.distance()
-               dist_right = dwright.distance()
-               dir = "left" if (dist_left < dist_right) else "right"
-
-               diff = abs(dist_left - dist_right)
-               if diff >= dist_l_r:
-                       # difference to high, correct to maximum
-                       off = diff - dist_l_r + 0.01
-                       if dist_left > dist_right:
-                               dist_left -= off/2
-                               dist_right += off/2
+               dist_left = dwleft.distance_valid()
+               dist_right = dwright.distance_valid()
+               if dist_left == None or dist_right == None:
+                       print "no valid sensor update"
+                       # run kalman prediction only
+                       pos.filter(None, None)
+               else:
+                       dir = "left" if (dist_left < dist_right) else "right"
+
+                       diff = abs(dist_left - dist_right)
+                       if diff >= dist_l_r:
+                               # difference to high, correct to maximum
+                               off = diff - dist_l_r + 0.01
+                               if dist_left > dist_right:
+                                       dist_left -= off/2
+                                       dist_right += off/2
+                               else:
+                                       dist_left += off/2
+                                       dist_right -= off/2
+                       print "%.2f %.2f %.2f %.2f %s" % (dwleft.distance(), dwright.distance(), dist_left, dist_right, dir)
+
+                       a_r = (-dist_right**2 + dist_left**2 - dist_l_r**2) / (-2*dist_l_r)
+                       x = dist_l_r/2 - a_r
+                       t = dist_right**2 - a_r**2
+                       if t >= 0:
+                               y = sqrt(t)
+                               print x,y
+                               # Rotate 90 deg
+                               x, y = (y, -x)
+
+                               x, y = pos.filter(x, y)
+                               tf_broadcaster.sendTransform((x, y, 0.0), (0, 0, 0, 1), rospy.Time.now(), "uwb_beacon", "base_footprint")
+
+                               if VISULAIZE:
+                                       circle_left = plt.Circle((-dist_l_r/2, 0), dwleft.distance, color='red', fill=False)
+                                       circle_right = plt.Circle((dist_l_r/2, 0), dwright.distance, color='green', fill=False)
+                                       plt.gca().add_patch(circle_left)
+                                       plt.gca().add_patch(circle_right)
+                                       plt.grid(True)
+                                       plt.axis('scaled')
+                                       plt.show()
                        else:
-                               dist_left += off/2
-                               dist_right -= off/2
-               print "%.2f %.2f %.2f %.2f %s" % (dwleft.distance(), dwright.distance(), dist_left, dist_right, dir)
-
-               a_r = (-dist_right**2 + dist_left**2 - dist_l_r**2) / (-2*dist_l_r)
-               x = dist_l_r/2 - a_r
-               t = dist_right**2 - a_r**2
-               if t >= 0:
-                       y = sqrt(t)
-                       print x,y
-                       # Rotate 90 deg
-                       x, y = (y, -x)
-
-                       x, y = pos.filter(x, y)
-                       tf_broadcaster.sendTransform((x, y, 0.0), (0, 0, 0, 1), rospy.Time.now(), "uwb_beacon", "base_footprint")
-
-                       if VISULAIZE:
-                               circle_left = plt.Circle((-dist_l_r/2, 0), dwleft.distance, color='red', fill=False)
-                               circle_right = plt.Circle((dist_l_r/2, 0), dwright.distance, color='green', fill=False)
-                               plt.gca().add_patch(circle_left)
-                               plt.gca().add_patch(circle_right)
-                               plt.grid(True)
-                               plt.axis('scaled')
-                               plt.show()
+                               # No current position, still need up update kalman prediction
+                               pos.filter(None, None)
 
                rate.sleep()