From 1713a06fdfc45670fb8c0c6efb8c158fad083968 Mon Sep 17 00:00:00 2001 From: Erik Andresen Date: Mon, 30 Jul 2018 10:15:56 +0200 Subject: [PATCH] dwm1000: use 2d kalman instead of 2x 1d --- scripts/dwm1000.py | 70 +++++++++++++--------------------------------- scripts/pyshared | 2 +- 2 files changed, 20 insertions(+), 52 deletions(-) diff --git a/scripts/dwm1000.py b/scripts/dwm1000.py index 707dff1..535d81e 100755 --- a/scripts/dwm1000.py +++ b/scripts/dwm1000.py @@ -15,36 +15,10 @@ from time import sleep from std_msgs.msg import Float32 from nav_msgs.msg import Odometry from wild_thumper.srv import DWM1000Center, DWM1000CenterResponse +from pyshared.simple_kalman import simple_kalman if VISULAIZE: import matplotlib.pyplot as plt -class simple_kalman: - def __init__(self, x_est, P_est, Q, R): - self.x_est = x_est # Systemzustand - self.P_est = P_est # Fehlerkovarianz - self.Q = Q # Systemrauschen - self.R = R # Varianz des Messfehlers - - def run(self, y): - # Korrektur mit der Messung - # (1) Berechnung der Kalman Verstärkung - K = self.P_est/(self.R + self.P_est) - # (2) Korrektur der Schätzung mit der Messung y - x = self.x_est + K*(y - self.x_est) - # (3) Korrektur der Fehlerkovarianzmatrix - P = (1-K)*self.P_est - # - # Prädiktion - # (1) Prädiziere den Systemzustand - self.x_est = x - # (2) Präzidiere die Fehlerkovarianzmatrix - self.P_est = P + self.Q - - return x - - def set_measure_cov(self, R): - if R > 0: - self.R = R class DW1000(threading.Thread): def __init__(self, name, addr, offset): @@ -90,19 +64,10 @@ class DW1000(threading.Thread): class Position: def __init__(self): - # Varianz des Messfehlers - Rx = 0.2 - Ry = 0.05 - # Fehlerkovarianz - P_est_x = 0.02 - P_est_y = 0.01 - # Systemrauschen - Qx = 0.001 - Qy = 0.00001 - # TODO: Replace 2x 1d kalman with 2d kalman - # so the polyfit variance can be replaced with a covariance matrix - self.filter_x = simple_kalman(1.0, P_est_x, Qx, Rx) - self.filter_y = simple_kalman(0.0, P_est_y, Qy, Ry) + R = np.matrix([[0.045, 0.5], [0.0, 0.008]]) # Varianz des Messfehlers + P_est = 1e-3 * np.eye(2) # Fehlerkovarianz + Q = np.matrix([[0.001, 0.0], [0.0, 0.00001]]) # Systemrauschen + self.filter_xy = simple_kalman(np.array([[1.0, 0.0]]).T, P_est, Q, R) self.speed_x = 0 self.speed_y = 0 self.speed_z = 0 @@ -119,7 +84,7 @@ class Position: current_time = rospy.Time.now() dt = (current_time - self.last_time).to_sec() # Subtract vehicle speed - pos = np.array([self.filter_x.x_est, self.filter_y.x_est]) + pos = self.filter_xy.x_est.T # translation pos -= np.array([self.speed_x*dt, self.speed_y*dt]) # rotation @@ -127,21 +92,24 @@ class Position: [np.sin(self.speed_z*dt), np.cos(self.speed_z*dt)]]) pos = np.dot(pos, rot) # copy back - self.filter_x.x_est = pos[0] - self.filter_y.x_est = pos[1] + self.filter_xy.x_est = pos.T # run kalman if new measurements are valid + pos = None if x != None and y != None: - x = self.filter_x.run(x) - y = self.filter_y.run(y) + pos = self.filter_xy.run(np.array([[x, y]]).T) # Update variance dist = np.linalg.norm([x, y]) - self.filter_x.set_measure_cov(np.polyval([0.018, 0.0, 0.0], dist)) - self.filter_y.set_measure_cov(np.polyval([0.006, 0.0, 0.0], dist)) + cov_00 = np.polyval([0.018, 0.0, 0.0], dist) + cov_11 = np.polyval([0.006, 0.0, 0.0], dist) + self.filter_xy.set_measure_cov(np.matrix([[cov_00, 0.0], [0.0, cov_11]])) else: - x = self.filter_x.x_est - y = self.filter_y.x_est + pos = self.filter_xy.x_est + + + x = pos.item((0, 0)) + y = pos.item((1, 0)) self.last_time = current_time return x,y @@ -156,8 +124,8 @@ def handle_center_call(req): if __name__ == "__main__": rospy.init_node('DWM1000', log_level=rospy.DEBUG) - dwleft = DW1000("uwb_dist_left", 0xc2, +0.0) - dwright = DW1000("uwb_dist_right", 0xc0, -0.0) + dwleft = DW1000("uwb_dist_left", 0xc2, -0.04) + dwright = DW1000("uwb_dist_right", 0xc0, +0.04) dist_l_r = 0.285 # Distance between both DWM1000 rate = rospy.Rate(10) pos = Position() diff --git a/scripts/pyshared b/scripts/pyshared index 355fa0b..2056613 160000 --- a/scripts/pyshared +++ b/scripts/pyshared @@ -1 +1 @@ -Subproject commit 355fa0b4fe7e4aacea13edf177d20a83e9c347b1 +Subproject commit 2056613e07dc73a25e8426a6ca67fccc88e13fee -- 2.39.2