From: Erik Andresen Date: Sun, 15 Jul 2018 09:32:35 +0000 (+0200) Subject: dwm1000: variance dependant on distance X-Git-Url: https://defiant.homedns.org/gitweb/?p=ros_wild_thumper.git;a=commitdiff_plain;h=721db3c859a69179a9f956a53ae7e40cf0ca655b dwm1000: variance dependant on distance --- diff --git a/scripts/dwm1000.py b/scripts/dwm1000.py index bf58657..15c4025 100755 --- a/scripts/dwm1000.py +++ b/scripts/dwm1000.py @@ -73,10 +73,10 @@ class DW1000(threading.Thread): def run(self): last_val = 10 - while True: + while not rospy.is_shutdown(): val = self.get_value() if abs(val - last_val) > 10: - print "Ignoring values too far apart %s: %.2f - %.2f" % (self.name, val, last_val) + rospy.logwarn("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() @@ -107,10 +107,6 @@ 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() @@ -129,8 +125,14 @@ class Position: # run kalman if new measurements are valid if x != None and y != None: + print "Var", self.filter_x.R, self.filter_y.R x = self.filter_x.run(x) y = self.filter_y.run(y) + + # Update covariance + dist = np.linalg.norm([x, y]) + self.filter_x.R = np.polyval([0.017795, -0.021832, 0.010968], dist) + self.filter_y.R = np.polyval([0.0060314, -0.013387, 0.0065049], dist) else: x = self.filter_x.x_est y = self.filter_y.x_est @@ -143,14 +145,14 @@ def handle_center_call(req): diff = dwleft.distance_valid() - dwright.distance_valid() dwleft.offset -= diff/2 dwright.offset += diff/2 - print "Centering to %.2f %.2f" % (dwleft.offset, dwright.offset) + rospy.loginfo("Centering to %.2f %.2f", dwleft.offset, dwright.offset) return DWM1000CenterResponse() if __name__ == "__main__": - rospy.init_node('DWM1000') - dwleft = DW1000("uwb_dist_left", 0xc2, +0.02) - dwright = DW1000("uwb_dist_right", 0xc0, -0.02) - dist_l_r = 0.285 + rospy.init_node('DWM1000', log_level=rospy.DEBUG) + dwleft = DW1000("uwb_dist_left", 0xc2, +0.00) + dwright = DW1000("uwb_dist_right", 0xc0, -0.00) + dist_l_r = 0.285 # Distance between both DWM1000 rate = rospy.Rate(10) pos = Position() tf_broadcaster = tf.broadcaster.TransformBroadcaster() @@ -160,7 +162,7 @@ if __name__ == "__main__": dist_left = dwleft.distance_valid() dist_right = dwright.distance_valid() if dist_left == None or dist_right == None: - print "no valid sensor update" + rospy.logerr("no valid sensor update") # run kalman prediction only pos.filter(None, None) else: @@ -176,14 +178,14 @@ if __name__ == "__main__": else: dist_left += off/2 dist_right -= off/2 - print "%.2f %.2f %.2f %.2f %s" % (dwleft.distance(), dwright.distance(), dist_left, dist_right, dir) + rospy.logdebug("%.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 + rospy.logdebug("x=%.2f, y=%.2f", x, y) # Rotate 90 deg x, y = (y, -x)