3D Point to 3D Point Pose Estimation Explained
3D Point to 3D Point Pose Estimation Explained Read More »
In the following code, I have implemented an Extended Kalman Filter for modeling the movement of a car with constant turn rate and velocity. The code is mainly based on this work (I did some bug fixing and some adaptation such that the code runs similar to the Kalman filter that I have earlier implemented).
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 |
import matplotlib.dates as mdates import numpy as np np.set_printoptions(threshold=3) np.set_printoptions(suppress=True) from numpy import genfromtxt import matplotlib.pyplot as plt from scipy.stats import norm from sympy import Symbol, symbols, Matrix, sin, cos from sympy import init_printing from sympy.utilities.codegen import codegen init_printing(use_latex=True) x0 = [] x1 = [] x2 = [] def prediction(X_hat_t_1,P_t_1,Q_t,drivingStraight): X_hat_t=X_hat_t_1 if drivingStraight: # Driving straight X_hat_t[0] = X_hat_t_1[0] + X_hat_t_1[3]*dt * np.cos(X_hat_t_1[2]) X_hat_t[1] = X_hat_t_1[1] + X_hat_t_1[3]*dt * np.sin(X_hat_t_1[2]) X_hat_t[2] = X_hat_t_1[2] X_hat_t[3] = X_hat_t_1[3] + X_hat_t_1[5]*dt X_hat_t[4] = 0.0000001 # avoid numerical issues in Jacobians X_hat_t[5] = X_hat_t_1[5] else: # otherwise X_hat_t[0] = X_hat_t_1[0] + (X_hat_t_1[3]/X_hat_t_1[4]) * (np.sin(X_hat_t_1[4]*dt+X_hat_t_1[2]) - np.sin(X_hat_t_1[2])) X_hat_t[1] = X_hat_t_1[1] + (X_hat_t_1[3]/X_hat_t_1[4]) * (-np.cos(X_hat_t_1[4]*dt+X_hat_t_1[2])+ np.cos(X_hat_t_1[2])) X_hat_t[2] = (X_hat_t_1[2] + X_hat_t_1[4]*dt + np.pi) % (2.0*np.pi) - np.pi X_hat_t[3] = X_hat_t_1[3] + X_hat_t_1[5]*dt X_hat_t[4] = X_hat_t_1[4] # Constant Turn Rate X_hat_t[5] = X_hat_t_1[5] # Constant Acceleration # Calculate the Jacobian of the Dynamic Matrix A # see "Calculate the Jacobian of the Dynamic Matrix with respect to the state vector" a13 = float((X_hat_t[3]/X_hat_t[4]) * (np.cos(X_hat_t[4]*dt+X_hat_t[2]) - np.cos(X_hat_t[2]))) a14 = float((1.0/X_hat_t[4]) * (np.sin(X_hat_t[4]*dt+X_hat_t[2]) - np.sin(X_hat_t[2]))) a15 = float((dt*X_hat_t[3]/X_hat_t[4])*np.cos(X_hat_t[4]*dt+X_hat_t[2]) - (X_hat_t[3]/X_hat_t[4]**2)*(np.sin(X_hat_t[4]*dt+X_hat_t[2]) - np.sin(X_hat_t[2]))) a23 = float((X_hat_t[3]/X_hat_t[4]) * (np.sin(X_hat_t[4]*dt+X_hat_t[2]) - np.sin(X_hat_t[2]))) a24 = float((1.0/X_hat_t[4]) * (-np.cos(X_hat_t[4]*dt+X_hat_t[2]) + np.cos(X_hat_t[2]))) a25 = float((dt*X_hat_t[3]/X_hat_t[4])*np.sin(X_hat_t[4]*dt+X_hat_t[2]) - (X_hat_t[3]/X_hat_t[4]**2)*(-np.cos(X_hat_t[4]*dt+X_hat_t[2]) + np.cos(X_hat_t[2]))) JA = np.matrix([[1.0, 0.0, a13, a14, a15, 0.0], [0.0, 1.0, a23, a24, a25, 0.0], [0.0, 0.0, 1.0, 0.0, dt, 0.0], [0.0, 0.0, 0.0, 1.0, 0.0, dt], [0.0, 0.0, 0.0, 0.0, 1.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 1.0]]) # Project the error covariance ahead P_t_1 = JA*P_t_1*JA.T + Q_t return X_hat_t,P_t_1 def update(X_hat_t,P_t,Z_t,R_t,GPSAvailable): hx = np.matrix([[float(X_hat_t[0])], [float(X_hat_t[1])], [float(X_hat_t[3])], [float(X_hat_t[4])], [float(X_hat_t[5])]]) if GPSAvailable: # with 10Hz, every 5th step JH = np.matrix([[1.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 1.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 1.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 1.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 1.0]]) else: # every other step JH = np.matrix([[0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 1.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 1.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 1.0]]) S = JH*P_t*JH.T + R_t K = (P_t*JH.T) * np.linalg.inv(S) #print("K:\n",K) # Update the estimate via Z = Z_t.reshape(JH.shape[0],1) #print("Z:\n",Z) y = Z - (hx) # Innovation or Residual X_t = X_hat_t + (K*y) # Update the error covariance I = np.eye(X_hat_t.shape[0]) P_t = (I - (K*JH))*P_t x0.append(float(X_t[0])) x1.append(float(X_t[1])) x2.append(float(X_t[2])) return X_t,P_t numstates=6 # States dt = 1.0/50.0 # Sample Rate of the Measurements is 50Hz dtGPS=1.0/10.0 # Sample Rate of GPS is 10Hz vs, psis, dpsis, dts, xs, ys, lats, lons, axs = symbols('v \psi \dot\psi T x y lat lon a') gs = Matrix([[xs+(vs/dpsis)*(sin(psis+dpsis*dts)-sin(psis))], [ys+(vs/dpsis)*(-cos(psis+dpsis*dts)+cos(psis))], [psis+dpsis*dts], [axs*dts + vs], [dpsis], [axs]]) state = Matrix([xs,ys,psis,vs,dpsis,axs]) #Initial State cov P_t = np.diag([1000.0, 1000.0, 1000.0, 1000.0, 1000.0, 1000.0]) #Measurment cov varGPS = 5.0 # Standard Deviation of GPS Measurement varspeed = 3.0 # Variance of the speed measurement varyaw = 0.1 # Variance of the yawrate measurement varacc = 1.0 # Variance of the longitudinal Acceleration R_t = np.diag([varGPS**2, varGPS**2, varspeed**2, varyaw**2, varacc**2]) #Measurment Matrix hs = Matrix([[xs], [ys], [vs], [dpsis], [axs]]) #Process cov sGPS = 0.5*8.8*dt**2 # assume 8.8m/s2 as maximum acceleration, forcing the vehicle sCourse = 0.1*dt # assume 0.1rad/s as maximum turn rate for the vehicle sVelocity= 8.8*dt # assume 8.8m/s2 as maximum acceleration, forcing the vehicle sYaw = 1.0*dt # assume 1.0rad/s2 as the maximum turn rate acceleration for the vehicle sAccel = 0.5 Q_t = np.diag([sGPS**2, sGPS**2, sCourse**2, sVelocity**2, sYaw**2, sAccel**2]) path="data/" datafile = '2014-03-26-000-Data.csv' fullPath=path+datafile def bytespdate2num(fmt, encoding='utf-8'): strconverter = mdates.strpdate2num(fmt) def bytesconverter(b): s = b.decode(encoding) return strconverter(s) return bytesconverter date, time, millis, ax, ay, az, rollrate, pitchrate, yawrate, roll, pitch, yaw, speed, course, latitude, longitude, altitude, pdop, hdop, vdop, epe, fix, satellites_view, satellites_used, temp = np.loadtxt(fullPath, delimiter=',', unpack=True, converters={1:bytespdate2num('%H%M%S%f'), 0: bytespdate2num('%y%m%d')}, skiprows=1) # A course of 0 means the Car is traveling north bound # and 90 means it is traveling east bound. # In the Calculation following, East is Zero and North is 90 # We need an offset. course =(-course+90.0) # ## Approx. Lat/Lon to Meters to check Location # In[17]: RadiusEarth = 6378388.0 # m arc= 2.0*np.pi*(RadiusEarth+altitude)/360.0 # m/ dx = arc * np.cos(latitude*np.pi/180.0) * np.hstack((0.0, np.diff(longitude))) # in m dy = arc * np.hstack((0.0, np.diff(latitude))) # in m mx = np.cumsum(dx) my = np.cumsum(dy) ds = np.sqrt(dx**2+dy**2) GPS=(ds!=0.0).astype('bool') # GPS Trigger for Kalman Filter # ## Initial State X_hat_t = np.matrix([[mx[0], my[0], course[0]/180.0*np.pi, speed[0]/3.6+0.001, yawrate[0]/180.0*np.pi, ax[0]]]).T measurements = np.vstack((mx, my, speed/3.6, yawrate/180.0*np.pi, ax)) # Lenth of the measurement m = measurements.shape[1] for i in range(measurements.shape[1]): #for i in range(3): if np.abs(yawrate[i])<0.0001: drivingStraight=True else: drivingStraight=False X_hat_t,P_hat_t = prediction(X_hat_t,P_t,Q_t,drivingStraight) #print("Prediction:") #print("X_hat_t:\n",X_hat_t,"\nP_t:\n",P_hat_t) Z_t=measurements[:,i] if GPS[i]: GPSAvailable=True else: GPSAvailable=False X_t,P_t=update(X_hat_t,P_hat_t,Z_t,R_t,GPSAvailable) #print("Update:") #print("X_t:\n",X_t,"\nP_t:\n",P_t) X_hat_t=X_t P_hat_t=P_t fig = plt.figure(figsize=(16,9)) # EKF State plt.quiver(x0,x1,np.cos(x2), np.sin(x2), color='#94C600', units='xy', width=0.05, scale=0.5) plt.plot(x0,x1, label='EKF Position', c='k', lw=5) # Measurements plt.scatter(mx[::5],my[::5], s=50, label='GPS Measurements', marker='+') # Start/Goal plt.scatter(x0[0],x1[0], s=60, label='Start', c='g') plt.scatter(x0[-1],x1[-1], s=60, label='Goal', c='r') plt.xlabel('X [m]') plt.ylabel('Y [m]') plt.title('Position') plt.legend(loc='best') plt.axis('equal') plt.show() |
Extended Kalman Filter Explained with Python Code Read More »
In the following code I have implemented a localization algorithm based on particle filter. I have used conda to run my code, you can run the following for installation of dependencies:
1 2 3 4 |
conda create -n Filters python=3 conda activate Filters conda install -c menpo opencv3 conda install numpy scipy matplotlib sympy |
and the code:
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 |
import numpy as np import scipy as scipy from numpy.random import uniform import scipy.stats np.set_printoptions(threshold=3) np.set_printoptions(suppress=True) import cv2 def drawLines(img, points, r, g, b): cv2.polylines(img, [np.int32(points)], isClosed=False, color=(r, g, b)) def drawCross(img, center, r, g, b): d = 5 t = 2 LINE_AA = cv2.LINE_AA if cv2.__version__[0] == '3' else cv2.CV_AA color = (r, g, b) ctrx = center[0,0] ctry = center[0,1] cv2.line(img, (ctrx - d, ctry - d), (ctrx + d, ctry + d), color, t, LINE_AA) cv2.line(img, (ctrx + d, ctry - d), (ctrx - d, ctry + d), color, t, LINE_AA) def mouseCallback(event, x, y, flags,null): global center global trajectory global previous_x global previous_y global zs center=np.array([[x,y]]) trajectory=np.vstack((trajectory,np.array([x,y]))) #noise=sensorSigma * np.random.randn(1,2) + sensorMu if previous_x >0: heading=np.arctan2(np.array([y-previous_y]), np.array([previous_x-x ])) if heading>0: heading=-(heading-np.pi) else: heading=-(np.pi+heading) distance=np.linalg.norm(np.array([[previous_x,previous_y]])-np.array([[x,y]]) ,axis=1) std=np.array([2,4]) u=np.array([heading,distance]) predict(particles, u, std, dt=1.) zs = (np.linalg.norm(landmarks - center, axis=1) + (np.random.randn(NL) * sensor_std_err)) update(particles, weights, z=zs, R=50, landmarks=landmarks) indexes = systematic_resample(weights) resample_from_index(particles, weights, indexes) previous_x=x previous_y=y WIDTH=800 HEIGHT=600 WINDOW_NAME="Particle Filter" #sensorMu=0 #sensorSigma=3 sensor_std_err=5 def create_uniform_particles(x_range, y_range, N): particles = np.empty((N, 2)) particles[:, 0] = uniform(x_range[0], x_range[1], size=N) particles[:, 1] = uniform(y_range[0], y_range[1], size=N) return particles def predict(particles, u, std, dt=1.): N = len(particles) dist = (u[1] * dt) + (np.random.randn(N) * std[1]) particles[:, 0] += np.cos(u[0]) * dist particles[:, 1] += np.sin(u[0]) * dist def update(particles, weights, z, R, landmarks): weights.fill(1.) for i, landmark in enumerate(landmarks): distance=np.power((particles[:,0] - landmark[0])**2 +(particles[:,1] - landmark[1])**2,0.5) weights *= scipy.stats.norm(distance, R).pdf(z[i]) weights += 1.e-300 # avoid round-off to zero weights /= sum(weights) def neff(weights): return 1. / np.sum(np.square(weights)) def systematic_resample(weights): N = len(weights) positions = (np.arange(N) + np.random.random()) / N indexes = np.zeros(N, 'i') cumulative_sum = np.cumsum(weights) i, j = 0, 0 while i < N and j<N: if positions[i] < cumulative_sum[j]: indexes[i] = j i += 1 else: j += 1 return indexes def estimate(particles, weights): pos = particles[:, 0:1] mean = np.average(pos, weights=weights, axis=0) var = np.average((pos - mean)**2, weights=weights, axis=0) return mean, var def resample_from_index(particles, weights, indexes): particles[:] = particles[indexes] weights[:] = weights[indexes] weights /= np.sum(weights) x_range=np.array([0,800]) y_range=np.array([0,600]) #Number of partciles N=400 landmarks=np.array([ [144,73], [410,13], [336,175], [718,159], [178,484], [665,464] ]) NL = len(landmarks) particles=create_uniform_particles(x_range, y_range, N) weights = np.array([1.0]*N) # Create a black image, a window and bind the function to window img = np.zeros((HEIGHT,WIDTH,3), np.uint8) cv2.namedWindow(WINDOW_NAME) cv2.setMouseCallback(WINDOW_NAME,mouseCallback) center=np.array([[-10,-10]]) trajectory=np.zeros(shape=(0,2)) robot_pos=np.zeros(shape=(0,2)) previous_x=-1 previous_y=-1 DELAY_MSEC=50 while(1): cv2.imshow(WINDOW_NAME,img) img = np.zeros((HEIGHT,WIDTH,3), np.uint8) drawLines(img, trajectory, 0, 255, 0) drawCross(img, center, r=255, g=0, b=0) #landmarks for landmark in landmarks: cv2.circle(img,tuple(landmark),10,(255,0,0),-1) #draw_particles: for particle in particles: cv2.circle(img,tuple((int(particle[0]),int(particle[1]))),1,(255,255,255),-1) if cv2.waitKey(DELAY_MSEC) & 0xFF == 27: break cv2.circle(img,(10,10),10,(255,0,0),-1) cv2.circle(img,(10,30),3,(255,255,255),-1) cv2.putText(img,"Landmarks",(30,20),1,1.0,(255,0,0)) cv2.putText(img,"Particles",(30,40),1,1.0,(255,255,255)) cv2.putText(img,"Robot Trajectory(Ground truth)",(30,60),1,1.0,(0,255,0)) drawLines(img, np.array([[10,55],[25,55]]), 0, 255, 0) cv2.destroyAllWindows() |
Parcticle Filter Explained With Python Code From Scratch Read More »
This snippet shows tracking mouse cursor with Python code from scratch and comparing the result with OpenCV. The CSV file that has been used are being created with below c++ code. A sample could be downloaded from here 1, 2, 3. Python Kalman Filter
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 |
import numpy as np np.set_printoptions(threshold=3) np.set_printoptions(suppress=True) from numpy import genfromtxt #Notation used coming from: https://www.bzarg.com/p/how-a-kalman-filter-works-in-pictures/ def prediction(X_hat_t_1,P_t_1,F_t,B_t,U_t,Q_t): X_hat_t=F_t.dot(X_hat_t_1)+(B_t.dot(U_t).reshape(B_t.shape[0],-1) ) P_t=np.diag(np.diag(F_t.dot(P_t_1).dot(F_t.transpose())))+Q_t return X_hat_t,P_t def update(X_hat_t,P_t,Z_t,R_t,H_t): K_prime=P_t.dot(H_t.transpose()).dot( np.linalg.inv ( H_t.dot(P_t).dot(H_t.transpose()) +R_t ) ) print("K:\n",K_prime) X_t=X_hat_t+K_prime.dot(Z_t-H_t.dot(X_hat_t)) P_t=P_t-K_prime.dot(H_t).dot(P_t) return X_t,P_t acceleration=0 delta_t=1/20#milisecond groundTruth = genfromtxt('data/groundTruth.csv', delimiter=',',skip_header=1) #Observations: position_X, position_Y measurmens = genfromtxt('data/measurmens.csv', delimiter=',',skip_header=1) #Checking our result with OpenCV opencvKalmanOutput = genfromtxt('data/kalmanv.csv', delimiter=',',skip_header=1) #Transition matrix F_t=np.array([ [1 ,0,delta_t,0] , [0,1,0,delta_t] , [0,0,1,0] , [0,0,0,1] ]) #Initial State cov P_t= np.identity(4)*0.2 #Process cov Q_t= np.identity(4) #Control matrix B_t=np.array( [ [0] , [0], [0] , [0] ]) #Control vector U_t=acceleration #Measurment Matrix H_t = np.array([ [1, 0, 0, 0], [ 0, 1, 0, 0]]) #Measurment cov R_t= np.identity(2)*5 # Initial State X_hat_t = np.array( [[0],[0],[0],[0]] ) print("X_hat_t",X_hat_t.shape) print("P_t",P_t.shape) print("F_t",F_t.shape) print("B_t",B_t.shape) print("Q_t",Q_t.shape) print("R_t",R_t.shape) print("H_t",H_t.shape) for i in range(measurmens.shape[0]): X_hat_t,P_hat_t = prediction(X_hat_t,P_t,F_t,B_t,U_t,Q_t) print("Prediction:") print("X_hat_t:\n",X_hat_t,"\nP_t:\n",P_t) Z_t=measurmens[i].transpose() Z_t=Z_t.reshape(Z_t.shape[0],-1) print(Z_t.shape) X_t,P_t=update(X_hat_t,P_hat_t,Z_t,R_t,H_t) print("Update:") print("X_t:\n",X_t,"\nP_t:\n",P_t) X_hat_t=X_t P_hat_t=P_t print("=========================================") print("Opencv Kalman Output:") print("X_t:\n",opencvKalmanOutput[i]) |
C++ and OpenCV Kalman Filter Rapidcsv has been downloaded from
Kalman Filter Explained With Python Code From Scratch Read More »