├── .gitattributes ├── requirements.txt ├── .gitignore ├── data └── motion-profiles │ ├── motion_agent1.csv │ ├── motion_agent2.csv │ └── motion_agent3.csv ├── README.md ├── Dockerfile ├── utils.py ├── sup ├── notes.txt ├── latex.ipynb ├── ekf_sim.py └── imu.ipynb ├── gen_data.py ├── ckf.py └── ckf_sim.py /.gitattributes: -------------------------------------------------------------------------------- 1 | *.ipynb linguist-vendored 2 | -------------------------------------------------------------------------------- /requirements.txt: -------------------------------------------------------------------------------- 1 | numpy>=1.21.5 2 | transforms3d>=0.4.1 3 | matplotlib>=3.5.1 4 | scipy>=1.8.0 -------------------------------------------------------------------------------- /.gitignore: -------------------------------------------------------------------------------- 1 | groves_005/ 2 | gnss-ins-sim/ 3 | *.pdf 4 | data/* 5 | rfloc/ 6 | .vscode 7 | report/ 8 | __pycache__ 9 | !/data/motion-profiles/ -------------------------------------------------------------------------------- /data/motion-profiles/motion_agent1.csv: -------------------------------------------------------------------------------- 1 | ini lat (deg),ini lon (deg),ini alt (m),ini vx_body (m/s),ini vy_body (m/s),ini vz_body (m/s),ini yaw (deg),ini pitch (deg),ini roll (deg) 2 | 32,120,20,0,0,0,0,0,0 3 | command type,yaw (deg),pitch (deg),roll (deg),vx_body (m/s),vy_body (m/s),vz_body (m/s),command duration (s),GPS visibility 4 | 1,0,0,0,0,0,0,1,0 5 | 1,0,0,0,0,0,-1,5,0 6 | 1,0,0,0,0,1,0,5,0 7 | 1,0,0,0,0,0,1,5,0 8 | 1,0,0,0,0,-1,0,5,0 9 | 1,0,0,0,1,0,0,5,0 10 | 1,0,0,0,0,1,0,5,0 11 | 1,0,0,0,-1,1,0,5,0 12 | 1,0,0,0,0,0,-.5,5,0 13 | 1,1,0,0,0,0,1,5,0 14 | 1,0,1,-3,0,0,1,5,0 15 | 1,0,0,0,.2,0,1,5,0 16 | 1,0,0,0,0,0,0,10,0 -------------------------------------------------------------------------------- /data/motion-profiles/motion_agent2.csv: -------------------------------------------------------------------------------- 1 | ini lat (deg),ini lon (deg),ini alt (m),ini vx_body (m/s),ini vy_body (m/s),ini vz_body (m/s),ini yaw (deg),ini pitch (deg),ini roll (deg) 2 | 32.0002,120.0003,0,0,0,0,0,0,0 3 | command type,yaw (deg),pitch (deg),roll (deg),vx_body (m/s),vy_body (m/s),vz_body (m/s),command duration (s),GPS visibility 4 | 1,0,0,0,0,0,0,1,0 5 | 1,0,0,0,0,0,-1,5,0 6 | 1,0,0,0,0,-1,0,5,0 7 | 1,0,0,0,0,0,-1,5,0 8 | 1,0,0,0,0,1,0,5,0 9 | 1,0,0,0,-1,0,0,5,0 10 | 1,0,0,0,0,1,0,5,0 11 | 1,0,0,1,1,1,0,5,0 12 | 1,0,0,0,0,.5,-.1,5,0 13 | 1,.5,.2,3,0,0,1,5,0 14 | 1,0,2,-3,0,0,1,5,0 15 | 1,1,0,0,2,0,1,5,0 16 | 1,0,0,0,0,0,0,10,0 -------------------------------------------------------------------------------- /data/motion-profiles/motion_agent3.csv: -------------------------------------------------------------------------------- 1 | ini lat (deg),ini lon (deg),ini alt (m),ini vx_body (m/s),ini vy_body (m/s),ini vz_body (m/s),ini yaw (deg),ini pitch (deg),ini roll (deg) 2 | 32.0004,120.0008,0,0,0,0,0,0,0 3 | command type,yaw (deg),pitch (deg),roll (deg),vx_body (m/s),vy_body (m/s),vz_body (m/s),command duration (s),GPS visibility 4 | 1,0,0,0,0,0,1,1,0 5 | 1,0,0,0,0,0,1,5,0 6 | 1,0,0,0,0,-1,0,5,0 7 | 1,0,0,0,0,0,1,5,0 8 | 1,0,0,0,1,1,0,5,0 9 | 1,0,0,0,-1,0,0,5,0 10 | 1,0,0,0,0,1,0,5,0 11 | 1,0,0,1,1,1,0,5,0 12 | 1,0,0,0,0,.5,-.1,5,0 13 | 1,.5,0,0,0,0,1,5,0 14 | 1,0,2,-3,0,0,1,5,0 15 | 1,0,0,0,2,0,1,5,0 16 | 1,0,0,0,0,0,0,10,0 -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | ## Collaborative EKF Localization 2 | 3 | Filter is implemented on UWB range measurements & IMU. The code is based mostly on these papers (with some trivial changes): 4 | 5 | 1. https://journals.sagepub.com/doi/abs/10.1177/0278364918760698 6 | 2. https://arxiv.org/abs/2104.14106 7 | 8 | Project depends on: https://github.com/Aceinna/gnss-ins-sim for generating simulated IMU data. 9 | 10 | ## Install with docker 11 | 12 | ```bash 13 | docker build -t myapp . 14 | docker run -it --rm -v "$(pwd)":/app -e DISPLAY=$DISPLAY -v /tmp/.X11-unix:/tmp/.X11-unix --user=$(id -u) myapp 15 | ``` 16 | 17 | ## Data 18 | 19 | Run `./gen_data.py` to generate data used for experiments. 20 | 21 | ## Run 22 | 23 | Execute `./ckf_sim.py` to run simulation. Main implementation is in `ckf.py` class. 24 | -------------------------------------------------------------------------------- /Dockerfile: -------------------------------------------------------------------------------- 1 | FROM ubuntu:latest 2 | 3 | ARG DEBIAN_FRONTEND=noninteractive 4 | 5 | # Install dependencies 6 | RUN apt-get update && \ 7 | apt-get install -y python3 python3-pip python3-tk && \ 8 | rm -rf /var/lib/apt/lists/* 9 | 10 | # Install required Python packages 11 | RUN pip3 install numpy>=1.21.5 transforms3d>=0.4.1 matplotlib>=3.5.1 scipy>=1.8.0 12 | 13 | # Configure Matplotlib to use Agg backend 14 | RUN mkdir -p /root/.config/matplotlib && \ 15 | echo "backend : Agg" >> /root/.config/matplotlib/matplotlibrc 16 | 17 | # Set working directory 18 | WORKDIR /app 19 | 20 | # Copy project files to working directory 21 | COPY . /app 22 | 23 | # Install dependencies 24 | RUN apt-get update && \ 25 | apt-get install -y git && \ 26 | rm -rf /var/lib/apt/lists/* 27 | 28 | RUN git clone https://github.com/Aceinna/gnss-ins-sim /app/gnss-ins-sim 29 | 30 | RUN pip3 install /app/gnss-ins-sim 31 | 32 | # Set the entrypoint for the container 33 | ENTRYPOINT [ "bash" ] 34 | -------------------------------------------------------------------------------- /utils.py: -------------------------------------------------------------------------------- 1 | import matplotlib.pyplot as plt 2 | import numpy as np 3 | import time 4 | import os 5 | 6 | 7 | def make_plots(static_beacons, global_agents, save=True): 8 | BEACONS_NUM = len(static_beacons) 9 | AGENTS_NUM = len(global_agents) 10 | """Plot the trajectories of the agents plus static beacons.""" 11 | print("Plotting...") 12 | # plot agents and static_beacons in map 13 | fig = plt.figure(figsize=(10, 10)) 14 | ax = fig.add_subplot(111, projection='3d') 15 | for beacon in static_beacons: 16 | position = beacon.get_pos() 17 | # increase scatter size 18 | ax.scatter(position[0], position[1], position[2], s=100) 19 | for agent in global_agents: 20 | ref_pos = agent.get_ref_pos() 21 | ax.plot(ref_pos[:, 0], ref_pos[:, 1], ref_pos[:, 2]) 22 | for agent in global_agents: 23 | traj = np.array(agent.trajectory) 24 | traj = traj.reshape(-1, 3) 25 | ax.plot(traj[:, 0], traj[:, 1], traj[:, 2], '--') 26 | legends = [f"beacon{i}" for i in range(BEACONS_NUM)] 27 | legends.extend(f"agent{i}" for i in range(AGENTS_NUM)) 28 | legends.extend(f"EKF_agent{i}" for i in range(AGENTS_NUM)) 29 | ax.set_xlabel('X (m)') 30 | ax.set_ylabel('Y (m)') 31 | ax.set_zlabel('Z (m)') 32 | ax.legend(legends) 33 | 34 | # create subplot for number of agents 35 | fig2, ax2 = plt.subplots(AGENTS_NUM, 1, figsize=(10, 10)) 36 | for index, agent in enumerate(global_agents): 37 | ref_att = agent.get_ref_att() 38 | att = np.array(agent.attitude) 39 | att = att.reshape(-1, 3) 40 | error = np.deg2rad(ref_att[:-1]) - att 41 | ax2[index].plot(error) 42 | legends = [f"yaw", f"pitch", f"roll"] 43 | ax2[index].legend(legends) 44 | 45 | if save: 46 | fig.savefig( 47 | f"report/figures/trajectory_{int(time.time())}.png", dpi=300) 48 | fig2.savefig( 49 | f"report/figures/attitude_{int(time.time())}.png", dpi=300) 50 | 51 | 52 | def plot_trajectories(static_beacons, global_agents): 53 | make_plots(static_beacons, global_agents, save=False) 54 | plt.show() 55 | 56 | 57 | def take_in_data(agent_dir): 58 | files = os.listdir(agent_dir) 59 | data = {} 60 | for file in files: 61 | if not file.endswith(".csv"): 62 | continue 63 | path = os.path.join(agent_dir, file) 64 | without_ext = os.path.splitext(file)[0] 65 | data[without_ext] = np.loadtxt(path, delimiter=',', skiprows=1) 66 | return data 67 | 68 | 69 | def print_error_metrics(agent): 70 | # compute position absolute error 71 | ref_pos = agent.get_ref_pos() 72 | traj = np.array(agent.trajectory) 73 | traj = traj.reshape(-1, 3) 74 | error = np.linalg.norm(ref_pos[:-1] - traj, axis=1) 75 | # compute attitude error 76 | ref_att = np.deg2rad(agent.get_ref_att()) 77 | att = np.array(agent.attitude) 78 | att = att.reshape(-1, 3) 79 | att_error = np.linalg.norm(ref_att[:-1] - att, axis=1) 80 | print( 81 | f"Error agent[{agent.id}] - Attitude: {att_error.mean():.2f} Pos: {error.mean():.2f}") 82 | -------------------------------------------------------------------------------- /sup/notes.txt: -------------------------------------------------------------------------------- 1 | 2 | NOT RELEVANT Cooperative Localization in Wireless Networks 3 | https://ieeexplore.ieee.org/document/4802193 4 | 5 | Recursive decentralized localization for multi-robot systems with asynchronous pairwise communication 6 | https://journals.sagepub.com/doi/10.1177/0278364918760698 7 | 8 | DECENTRALIZED COLLABORATIVE LOCALIZATION USING ULTRA-WIDEBAND RANGING 9 | This last one has algorithm in pseudo code, could start right there to simulate 10 | Also matlab implementation of it: 11 | https://github.com/unmannedlab/collab_localization/blob/main/matlab/algorithms/DCL.m 12 | https://jhartzer.github.io/assets/pdf/Hartzer_thesis.pdf 13 | 14 | 15 | https://nitinjsanket.github.io/tutorials/attitudeest/kf 16 | 17 | The goal of the special course is to investigate and develop a method for RF-based distributed localization in multi-robot systems.  18 | 19 | 1. Investigate state-of-the-art methods for RF-based distributed localization in multi-robot systems. 20 | 2. Develop a process model and a sensor model for robots equipped with RF-based range sensor(s) as well as standard sensors (IMU, altimeter, compass, etc.).  21 | 3. Develop a distributed localization method using the above-mentioned process and sensor model. Gather simulated data and apply the developed method.  22 | 4. Gather experimental data and apply the developed method on it offline. 23 | 5. Analyze the developed method's performance to alternative localization methods, e.g., GPS or optical tracking.  24 | 6. Optionally implement the method on hardware and test it online in a real-life scenario. 25 | 26 | Deliverable: Technical report in the form of a double column 6-page IEEE paper, documented code repository, and experimental data. 27 | 28 | TODO: 29 | - ... 30 | 31 | 32 | DUMP 33 | 34 | PROFILE = False 35 | if PROFILE: 36 | import cProfile 37 | from pstats import SortKey 38 | 39 | with cProfile.Profile() as pr: 40 | main(plot=True, regular=False) 41 | pr.print_stats(SortKey.CUMULATIVE) 42 | exit() 43 | 44 | """ 45 | pr - robot position 46 | pbi = beacon_i position 47 | J = [ 48 | d/dx h(x) = norm(pr - pb1), 49 | d/dx h(x) = norm(pr - pb2), 50 | ... 51 | d/dx h(x) = norm(pr - pbn), 52 | ] 53 | first row of J (distance function h(x) to the beacon 1): 54 | -(bx - x)/((bx - x)^2 + (by - y)^2 + (bz - z)^2)^(1/2) 55 | -(by - y)/((bx - x)^2 + (by - y)^2 + (bz - z)^2)^(1/2) 56 | -(bz - z)/((bx - x)^2 + (by - y)^2 + (bz - z)^2)^(1/2) 57 | or switch bx,x places and remove minus in front 58 | """ 59 | 60 | 61 | MAGNETOMETER BEARING 62 | 63 | import numpy as np 64 | 65 | def calibrate_magnetometer(raw_data, bias, scale): 66 | calibrated_data = (raw_data - bias) * scale 67 | return calibrated_data 68 | 69 | def calculate_bearing(magnetometer_data): 70 | bearing_rad = np.arctan2(magnetometer_data[1], magnetometer_data[0]) 71 | bearing_deg = np.degrees(bearing_rad) 72 | if bearing_deg < 0: 73 | bearing_deg += 360 74 | return bearing_deg 75 | 76 | # Raw magnetometer data (X, Y, Z) 77 | raw_magnetometer_data = np.array([100, 200, 300]) 78 | 79 | # Calibration parameters (obtained during calibration process) 80 | bias = np.array([10, 20, 30]) 81 | scale = np.array([1.1, 1.2, 1.3]) 82 | 83 | # Calibrate magnetometer data 84 | calibrated_magnetometer_data = calibrate_magnetometer(raw_magnetometer_data, bias, scale) 85 | 86 | # Calculate absolute bearing angle 87 | bearing_angle = calculate_bearing(calibrated_magnetometer_data) 88 | 89 | print(f"Absolute bearing angle: {bearing_angle} degrees") 90 | -------------------------------------------------------------------------------- /gen_data.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | """ 3 | https://github.com/Aceinna/gnss-ins-sim 4 | 5 | The simplest demo of Sim. 6 | Only generate reference trajectory (pos, vel, sensor output). No algorithm. 7 | Created on 2018-01-23 8 | @author: dongxiaoguang 9 | """ 10 | 11 | import os 12 | import math 13 | from gnss_ins_sim.sim import imu_model 14 | from gnss_ins_sim.sim import ins_sim 15 | import numpy as np 16 | import matplotlib.pyplot as plt 17 | 18 | # globals 19 | D2R = math.pi/180 20 | PLOT_UWB = False 21 | NUM_UWB_BEACONS = 5 22 | 23 | motion_def_path = os.path.abspath('.//data//motion-profiles//') 24 | fs = 100.0 # IMU sample frequency 25 | fs_gps = 10.0 # GPS sample frequency 26 | fs_mag = fs # magnetometer sample frequency, not used for now 27 | 28 | 29 | def test_path_gen(): 30 | ''' 31 | test only path generation in Sim. 32 | ''' 33 | # choose a built-in IMU model, typical for IMU381 34 | imu_err = 'low-accuracy' 35 | # generate GPS and magnetometer data 36 | imu = imu_model.IMU(accuracy=imu_err, axis=9, gps=True) 37 | # mag_error = {'si': np.eye(3) + np.random.randn(3, 3)*0.1, 38 | # 'hi': np.array([10.0, 10.0, 10.0])*1.0} 39 | # imu.set_mag_error(mag_error) 40 | 41 | # TODO: move motions profiles somewhere else 42 | NUM_OF_AGENTS = 3 43 | for i in range(NUM_OF_AGENTS): 44 | # start simulation 45 | sim = ins_sim.Sim([fs, fs_gps, fs_mag], 46 | motion_def_path+f"//motion_agent{i+1}.csv", 47 | ref_frame=1, 48 | imu=imu, 49 | mode=None, 50 | env=None, 51 | algorithm=None) 52 | 53 | sim.run(1) 54 | # save simulation data to files 55 | sim.results(data_dir=f'data/agent{i+1}') 56 | 57 | 58 | def uwb_gen(): 59 | data_dir = 'data' 60 | agents = os.listdir(data_dir) 61 | # trim agent if agent is not in name 62 | agents = [a for a in agents if 'agent' in a] 63 | ref_pos_files = [f'{data_dir}/{a}/ref_pos.csv' for a in agents] 64 | ref_pos = {} 65 | for refs in ref_pos_files: 66 | agent_dir = refs.split('/')[-2] 67 | data = np.genfromtxt(refs, delimiter=',')[1:] 68 | ref_pos[agent_dir] = data 69 | 70 | # generate uwb static beacons 71 | STATIC_STD_FROM_START = 300 72 | dict_items = ref_pos.items() 73 | a1, ref1 = next(iter(dict_items)) 74 | STARTING_POS = ref1[0] 75 | for i in range(NUM_UWB_BEACONS): 76 | ref_pos[f'static{i}'] = np.full( 77 | ref1.shape, STARTING_POS + np.random.normal(scale=STATIC_STD_FROM_START, size=3)) 78 | 79 | for a1, ref1 in ref_pos.items(): 80 | for a2, ref2 in ref_pos.items(): 81 | if ref1 is ref2: 82 | continue 83 | if "static" in a1: 84 | continue 85 | dist = np.linalg.norm(ref1 - ref2, axis=1) # ground truth 86 | if "static" in a2: 87 | np.savetxt(f'{data_dir}/{a1}/uwb-{a2}.csv', 88 | np.hstack((dist.reshape(-1, 1), ref2)), delimiter=',') 89 | else: 90 | np.savetxt(f'{data_dir}/{a1}/uwb-{a2}.csv', 91 | dist.reshape(-1, 1), delimiter=',') 92 | if PLOT_UWB: 93 | plt.figure() 94 | plt.plot(dist) 95 | 96 | 97 | if __name__ == '__main__': 98 | test_path_gen() 99 | uwb_gen() 100 | -------------------------------------------------------------------------------- /sup/latex.ipynb: -------------------------------------------------------------------------------- 1 | { 2 | "cells": [ 3 | { 4 | "cell_type": "code", 5 | "execution_count": 12, 6 | "metadata": {}, 7 | "outputs": [], 8 | "source": [ 9 | "import sympy as sp\n", 10 | "import numpy as np\n", 11 | "\n", 12 | "dt = sp.var(\"dt\")\n", 13 | "I = np.eye(3)\n", 14 | "Idt = np.eye(3) * dt\n", 15 | "Idt2 = .5 * np.eye(3) * dt**2\n", 16 | "from scipy.linalg import block_diag\n", 17 | "# F = block_diag(I, I, I)\n", 18 | "# F = sp.Matrix(F)\n", 19 | "# F[0:3, 3:6] = Idt\n", 20 | "# B = np.zeros((9, 6))\n", 21 | "# B = sp.Matrix(B)\n", 22 | "# B[0:3, 0:3] = Idt2\n", 23 | "# B[3:6, 0:3] = Idt\n", 24 | "# B[6:9, 3:6] = Idt\n", 25 | "# B" 26 | ] 27 | }, 28 | { 29 | "cell_type": "code", 30 | "execution_count": 13, 31 | "metadata": {}, 32 | "outputs": [], 33 | "source": [ 34 | "# sp.print_latex(sp.Matrix(B))" 35 | ] 36 | }, 37 | { 38 | "cell_type": "code", 39 | "execution_count": 14, 40 | "metadata": {}, 41 | "outputs": [ 42 | { 43 | "name": "stdout", 44 | "output_type": "stream", 45 | "text": [ 46 | "\\left[\\begin{matrix}0.5 I_{3x3} \\Delta t & I_{3x3} \\Delta t & 0\\\\0 & I_{3x3} & 0\\\\0 & 0 & I_{3x3}\\end{matrix}\\right]\n" 47 | ] 48 | }, 49 | { 50 | "data": { 51 | "text/latex": [ 52 | "$\\displaystyle \\left[\\begin{matrix}0.5 I_{3x3} \\Delta t & I_{3x3} \\Delta t & 0\\\\0 & I_{3x3} & 0\\\\0 & 0 & I_{3x3}\\end{matrix}\\right]$" 53 | ], 54 | "text/plain": [ 55 | "Matrix([\n", 56 | "[0.5*I_{3x3}*\\Delta t, I_{3x3}*\\Delta t, 0],\n", 57 | "[ 0, I_{3x3}, 0],\n", 58 | "[ 0, 0, I_{3x3}]])" 59 | ] 60 | }, 61 | "execution_count": 14, 62 | "metadata": {}, 63 | "output_type": "execute_result" 64 | } 65 | ], 66 | "source": [ 67 | "I = sp.var(\"I_{3x3}\")\n", 68 | "t = sp.Symbol(\"\\Delta t\")\n", 69 | "A = sp.Matrix([[1/2*I*t, I*t, 0],[0,I,0],[0,0,I]])\n", 70 | "sp.print_latex(sp.Matrix(A))\n", 71 | "A" 72 | ] 73 | }, 74 | { 75 | "cell_type": "code", 76 | "execution_count": 15, 77 | "metadata": {}, 78 | "outputs": [ 79 | { 80 | "name": "stdout", 81 | "output_type": "stream", 82 | "text": [ 83 | "\\left[\\begin{matrix}0.5 I_{3x3} \\Delta t & 0\\\\I_{3x3} \\Delta t & 0\\\\0 & I_{3x3} \\Delta t\\end{matrix}\\right]\n" 84 | ] 85 | }, 86 | { 87 | "data": { 88 | "text/latex": [ 89 | "$\\displaystyle \\left[\\begin{matrix}0.5 I_{3x3} \\Delta t & 0\\\\I_{3x3} \\Delta t & 0\\\\0 & I_{3x3} \\Delta t\\end{matrix}\\right]$" 90 | ], 91 | "text/plain": [ 92 | "Matrix([\n", 93 | "[0.5*I_{3x3}*\\Delta t, 0],\n", 94 | "[ I_{3x3}*\\Delta t, 0],\n", 95 | "[ 0, I_{3x3}*\\Delta t]])" 96 | ] 97 | }, 98 | "execution_count": 15, 99 | "metadata": {}, 100 | "output_type": "execute_result" 101 | } 102 | ], 103 | "source": [ 104 | "B = sp.Matrix([[1/2*I*t, 0],[I*t,0],[0,I*t]])\n", 105 | "sp.print_latex(sp.Matrix(B))\n", 106 | "B" 107 | ] 108 | } 109 | ], 110 | "metadata": { 111 | "kernelspec": { 112 | "display_name": "Python 3", 113 | "language": "python", 114 | "name": "python3" 115 | }, 116 | "language_info": { 117 | "codemirror_mode": { 118 | "name": "ipython", 119 | "version": 3 120 | }, 121 | "file_extension": ".py", 122 | "mimetype": "text/x-python", 123 | "name": "python", 124 | "nbconvert_exporter": "python", 125 | "pygments_lexer": "ipython3", 126 | "version": "3.10.6" 127 | }, 128 | "orig_nbformat": 4 129 | }, 130 | "nbformat": 4, 131 | "nbformat_minor": 2 132 | } 133 | -------------------------------------------------------------------------------- /sup/ekf_sim.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | import numpy as np 3 | import os 4 | from filterpy.kalman import ExtendedKalmanFilter 5 | import transforms3d as tf 6 | import matplotlib.pyplot as plt 7 | 8 | DEBUG = False 9 | BEACONS_NUM = 2 10 | AGENTS_NUM = 2 11 | GEN_DATA = False 12 | 13 | if GEN_DATA: 14 | import subprocess 15 | subprocess.call("./gen_data.py", shell=True) 16 | 17 | 18 | class Beacon: 19 | 20 | def __init__(self, id: str, x0: np.ndarray) -> None: 21 | if x0.shape == (3,) or x0.shape == (1, 3): 22 | x0 = x0.reshape((3, 1)) 23 | if x0.shape != (3, 1): 24 | raise Exception("Wrong state shape!") 25 | self.__x = x0 26 | 27 | def get_pos(self) -> np.array: 28 | return self.__x 29 | 30 | 31 | def getH(x_op: np.ndarray, beacons): 32 | """ 33 | pr - robot position 34 | pbi = beacon_i position 35 | J = [ 36 | d/dx h(x) = norm(pr - pb1), 37 | d/dx h(x) = norm(pr - pb2), 38 | ... 39 | d/dx h(x) = norm(pr - pbn), 40 | ] 41 | first row of J (distance function h(x) to the beacon 1): 42 | -(bx - x)/((bx - x)^2 + (by - y)^2 + (bz - z)^2)^(1/2) 43 | -(by - y)/((bx - x)^2 + (by - y)^2 + (bz - z)^2)^(1/2) 44 | -(bz - z)/((bx - x)^2 + (by - y)^2 + (bz - z)^2)^(1/2) 45 | or switch bx,x places and remove minus in front 46 | """ 47 | H = np.zeros((len(beacons), len(x_op))) 48 | for i, b in enumerate(beacons): 49 | diff = x_op[:3] - b.get_pos() 50 | the_norm = np.linalg.norm(diff) 51 | if (diff == 0.0).all(): 52 | raise Exception("Division by zero") 53 | H[i][:3] = (diff / the_norm).T 54 | return H 55 | 56 | 57 | def hx(x, beacons): 58 | """ 59 | non-linear measurement func 60 | """ 61 | h = np.zeros((len(beacons), 1)) 62 | for i, b in enumerate(beacons): 63 | h[i] = np.linalg.norm(x[:3] - b.get_pos()) 64 | return h 65 | 66 | 67 | class Agent: 68 | DIM_Z = BEACONS_NUM + (AGENTS_NUM - 1) 69 | DIM_X = 9 70 | DIM_U = 6 71 | 72 | def __init__(self, data) -> None: 73 | self.__data = data 74 | self.filter = ExtendedKalmanFilter( 75 | dim_x=self.DIM_X, dim_z=self.DIM_Z, dim_u=self.DIM_U) 76 | self.filter.x = np.array([data["ref_pos"][0][0], data["ref_pos"] 77 | [0][1], data["ref_pos"][0][2], 0, 0, 0, 0, 0, 0]).reshape(9, 1) 78 | print(f"filter init: {self.filter.x[:3]}") 79 | dt = 0.01 80 | I = np.eye(3) 81 | Idt = np.eye(3) * dt 82 | Idt2 = .5 * np.eye(3) * dt**2 83 | from scipy.linalg import block_diag 84 | F = block_diag(I, I, I) 85 | F[0:3, 3:6] = Idt 86 | B = np.zeros((9, 6)) 87 | B[0:3, 0:3] = Idt2 88 | B[3:6, 0:3] = Idt 89 | B[6:9, 3:6] = Idt 90 | self.filter.F = F 91 | self.filter.B = B 92 | self.filter.P = np.eye(9)*1e3 93 | self.filter.R = np.eye(self.DIM_Z) 94 | self.filter.Q = np.eye(9)*1e-3 95 | self.g = np.array([0, 0, 9.794841972265039942e+00]) 96 | self.trajectory = [] 97 | 98 | ## Collaborative 99 | 100 | 101 | def get_ref_pos(self): 102 | return self.__data["ref_pos"] 103 | 104 | def get_pos(self): 105 | return self.filter.x[:3].copy() 106 | 107 | def num_data(self): 108 | return len(self.__data["ref_pos"]) 109 | 110 | def kalman_update(self, beacons, agents, step_index, range_meas=False): 111 | # save position 112 | self.trajectory.append(self.filter.x[:3].copy()) 113 | 114 | # predict 115 | acc = self.__data["accel-0"][step_index] 116 | gyro = self.__data["gyro-0"][step_index] 117 | domega = gyro.copy() 118 | R_att = tf.euler.euler2mat( 119 | self.filter.x[6], self.filter.x[7], self.filter.x[8], axes='sxyz') 120 | acc = (R_att @ acc) + self.g 121 | theta = self.filter.x[7][0] 122 | phi = self.filter.x[6][0] 123 | Rw = np.array([[np.cos(theta), 0, -np.cos(phi)*np.sin(theta)], 124 | [0, 1, np.sin(phi)], 125 | [np.sin(theta), 0, np.cos(phi)*np.cos(theta)]]) 126 | domega = domega * np.pi / 180 127 | u = np.concatenate((acc, Rw @ domega)).reshape(6, 1) 128 | self.filter.predict(u=u) 129 | if DEBUG: 130 | print(f"filter predict: {self.filter.x}") 131 | 132 | if not range_meas: 133 | return 134 | 135 | # update 136 | NOISE_STD = 1 137 | gt_dists = [ 138 | self.__data[f"uwb-static{i}"][step_index][0] + 139 | np.random.normal(scale=NOISE_STD) for i in range(BEACONS_NUM)] 140 | 141 | for j in range(AGENTS_NUM+1): 142 | # check if self.__data has uwb-static key 143 | if f"uwb-agent{j+1}" not in self.__data.keys(): 144 | continue 145 | gt_dists.append( 146 | self.__data[f"uwb-agent{j+1}"][step_index] + 147 | np.random.normal(scale=NOISE_STD)) 148 | 149 | if DEBUG: 150 | print(f"True dists: {gt_dists}") 151 | z = np.array(gt_dists).reshape(-1, 1) 152 | to_pass_beacons = beacons.copy() 153 | to_pass_beacons.extend(agents) 154 | self.filter.update(z, getH, hx, args=( 155 | to_pass_beacons), hx_args=(to_pass_beacons)) 156 | 157 | 158 | def take_in_data(agent_dir): 159 | files = os.listdir(agent_dir) 160 | data = {} 161 | for file in files: 162 | if not file.endswith(".csv"): 163 | continue 164 | path = os.path.join(agent_dir, file) 165 | without_ext = os.path.splitext(file)[0] 166 | data[without_ext] = np.loadtxt(path, delimiter=',', skiprows=1) 167 | return data 168 | 169 | 170 | agent1_data = take_in_data("data/agent1") 171 | agent2_data = take_in_data("data/agent2") 172 | 173 | STARTING_POS = agent1_data["ref_pos"][0] 174 | 175 | agent1_data["ref_pos"] = agent1_data["ref_pos"] - STARTING_POS 176 | agent2_data["ref_pos"] = agent2_data["ref_pos"] - STARTING_POS 177 | 178 | static_beacons = [] 179 | for i in range(BEACONS_NUM): 180 | x0 = agent1_data[f"uwb-static{i}"][0][1:] - STARTING_POS 181 | static_beacons.append(Beacon(str(i), x0)) 182 | print(f"beacon{i}: {x0}") 183 | 184 | Agent1 = Agent(agent1_data) 185 | Agent2 = Agent(agent2_data) 186 | global_agents = [Agent1, Agent2] 187 | for i in range(Agent1.num_data()-1): 188 | range_meas = (i % 10 == 0) 189 | for current_agent in global_agents: 190 | agents_without_itself = [ 191 | a for a in global_agents if a is not current_agent] 192 | current_agent.kalman_update( 193 | static_beacons, agents_without_itself, i, range_meas) 194 | 195 | # plot agents and static_beacons in map 196 | fig = plt.figure() 197 | ax = fig.add_subplot(111, projection='3d') 198 | for beacon in static_beacons: 199 | position = beacon.get_pos() 200 | ax.scatter(position[0], position[1], position[2]) 201 | for agent in global_agents: 202 | ref_pos = agent.get_ref_pos() 203 | ax.plot(ref_pos[:, 0], ref_pos[:, 1], ref_pos[:, 2]) 204 | for agent in global_agents: 205 | traj = np.array(agent.trajectory) 206 | traj = traj.reshape(-1, 3) 207 | ax.plot(traj[:, 0], traj[:, 1], traj[:, 2], '--') 208 | legends = [f"beacon{i}" for i in range(BEACONS_NUM)] 209 | legends.extend(f"agent{i}" for i in range(AGENTS_NUM)) 210 | legends.extend(f"EKF_agent{i}" for i in range(AGENTS_NUM)) 211 | ax.set_xlabel('X (m)') 212 | ax.set_ylabel('Y (m)') 213 | ax.set_zlabel('Z (m)') 214 | plt.legend(legends) 215 | plt.show() 216 | -------------------------------------------------------------------------------- /ckf.py: -------------------------------------------------------------------------------- 1 | from __future__ import (absolute_import, division, unicode_literals) 2 | import numpy as np 3 | from numpy import dot, zeros, eye 4 | 5 | 6 | class CollaborativeKalmanFilter(object): 7 | 8 | """ Structure of filter highly based on: 9 | https://github.com/rlabbe/filterpy 10 | 11 | dim_a - extra agents besides the current one 12 | agent_id - 0...dim_a-1 13 | """ 14 | 15 | def __init__(self, dim_x, dim_z, dim_a, agent_id, dim_u=0): 16 | self.dim_x = dim_x 17 | self.dim_z = dim_z 18 | self.dim_u = dim_u 19 | self.dim_a = dim_a 20 | 21 | self.aid = agent_id 22 | 23 | self.x = zeros((dim_x, 1)) # state 24 | self.P = eye(dim_x) # uncertainty covariance 25 | # cross covariance of agents 26 | self.cP = [eye(dim_x) for _ in range(dim_a)] # TODO: configurable 27 | self.B = 0 # control transition matrix 28 | self.F = np.eye(dim_x) # state transition matrix 29 | self.R = eye(dim_z) # state uncertainty 30 | self.rR = eye(1) # TODO: 31 | self.Q = eye(dim_x) # process uncertainty 32 | self.y = zeros((dim_z, 1)) # residual 33 | 34 | # gain and residual are computed during the innovation step. We 35 | # save them so that in case you want to inspect them for various 36 | # purposes 37 | self.K = np.zeros(self.x.shape) # kalman gain 38 | self.y = zeros((dim_z, 1)) 39 | self.S = np.zeros((dim_z, dim_z)) # system uncertainty 40 | self.SI = np.zeros((dim_z, dim_z)) # inverse system uncertainty 41 | 42 | # identity matrix. Do not alter this. 43 | self._I = np.eye(dim_x) 44 | 45 | # these will always be a copy of x,P after predict() is called 46 | self.x_prior = self.x.copy() 47 | self.P_prior = self.P.copy() 48 | 49 | # these will always be a copy of x,P after update() is called 50 | self.x_post = self.x.copy() 51 | self.P_post = self.P.copy() 52 | 53 | def update(self, z, HJacobian, Hx, R=None, args=(), hx_args=(), 54 | residual=np.subtract): 55 | """ Performs the update innovation of the extended Kalman filter. 56 | 57 | Parameters 58 | ---------- 59 | 60 | z : np.array 61 | measurement for this step. 62 | If `None`, posterior is not computed 63 | 64 | HJacobian : function 65 | function which computes the Jacobian of the H matrix (measurement 66 | function). Takes state variable (self.x) as input, returns H. 67 | 68 | Hx : function 69 | function which takes as input the state variable (self.x) along 70 | with the optional arguments in hx_args, and returns the measurement 71 | that would correspond to that state. 72 | 73 | R : np.array, scalar, or None 74 | Optionally provide R to override the measurement noise for this 75 | one call, otherwise self.R will be used. 76 | 77 | args : tuple, optional, default (,) 78 | arguments to be passed into HJacobian after the required state 79 | variable. for robot localization you might need to pass in 80 | information about the map and time of day, so you might have 81 | `args=(map_data, time)`, where the signature of HJacobian will 82 | be `def HJacobian(x, map, t)` 83 | 84 | hx_args : tuple, optional, default (,) 85 | arguments to be passed into Hx function after the required state 86 | variable. 87 | 88 | residual : function (z, z2), optional 89 | Optional function that computes the residual (difference) between 90 | the two measurement vectors. If you do not provide this, then the 91 | built in minus operator will be used. You will normally want to use 92 | the built in unless your residual computation is nonlinear (for 93 | example, if they are angles) 94 | """ 95 | 96 | if not isinstance(args, tuple): 97 | args = (args,) 98 | 99 | if not isinstance(hx_args, tuple): 100 | hx_args = (hx_args,) 101 | 102 | if R is None: 103 | R = self.R 104 | elif np.isscalar(R): 105 | R = eye(self.dim_z) * R 106 | 107 | if np.isscalar(z) and self.dim_z == 1: 108 | z = np.asarray([z], float) 109 | 110 | H = HJacobian(self.x, *args) 111 | 112 | # check for inf in H 113 | if np.isinf(H).any(): 114 | raise ValueError("H contains inf") 115 | # check for nan in H 116 | if np.isnan(H).any(): 117 | raise ValueError("H contains nan") 118 | 119 | PHT = dot(self.P, H.T) 120 | self.S = dot(H, PHT) + R 121 | self.K = PHT.dot(np.linalg.inv(self.S)) 122 | 123 | hx = Hx(self.x, *hx_args) 124 | self.y = residual(z, hx) 125 | self.x = self.x + dot(self.K, self.y) 126 | 127 | # P = (I-KH)P(I-KH)' + KRK' is more numerically stable 128 | # and works for non-optimal K vs the equation 129 | # P = (I-KH)P usually seen in the literature. 130 | I_KH = self._I - dot(self.K, H) 131 | self.P = dot(I_KH, self.P).dot(I_KH.T) + dot(self.K, R).dot(self.K.T) 132 | 133 | # save posterior state 134 | self.x_post = self.x.copy() 135 | self.P_post = self.P.copy() 136 | 137 | for i in range(self.dim_a): 138 | if i == self.aid: 139 | continue 140 | self.cP[i] = I_KH @ self.cP[i] 141 | 142 | def rel_update(self, aid, ax, aP, aSji, z, HJacobian, Hx, R=None, args=(), hx_args=(), 143 | residual=np.subtract): 144 | """ Relative update between two agents using collaborative extended Kalman filter.""" 145 | Pii = self.P.copy() 146 | Pij = self.cP[aid].copy() @ aSji.T 147 | Paa = np.block([[Pii, Pij], 148 | [Pij.T, aP]]) 149 | 150 | if not isinstance(args, tuple): 151 | args = (args,) 152 | if not isinstance(hx_args, tuple): 153 | hx_args = (hx_args,) 154 | if R is None: 155 | R = self.R 156 | elif np.isscalar(R): 157 | R = eye(self.dim_z) * R 158 | if np.isscalar(z) and self.dim_z == 1: 159 | z = np.asarray([z], float) 160 | 161 | H = HJacobian(self.x, ax, *args) 162 | Hax = HJacobian(ax, self.x, *args) 163 | nz = Hx(self.x, *hx_args) 164 | 165 | Fa = np.block([H, Hax]) 166 | 167 | Ka = Paa @ Fa.T @ np.linalg.inv(Fa @ Paa @ Fa.T + self.rR) # TODO: 168 | Xij = np.block([[self.x], 169 | [ax]]) 170 | Xij += Ka @ (z - nz) 171 | # update the state 172 | self.x = Xij[:self.dim_x].copy() 173 | xj = Xij[self.dim_x:] 174 | Paa = (np.eye(self.dim_x * 2) - Ka @ Fa) @ Paa 175 | self.cP[aid] = Paa[:self.dim_x, self.dim_x:].copy() # update Sij 176 | 177 | Pii = Paa[:self.dim_x, :self.dim_x] 178 | self.P = Pii.copy() 179 | # enforce symmetry, solely for numerical stability 180 | self.P = (self.P + self.P.T)/2 181 | 182 | for i in range(self.dim_a): 183 | if i == self.aid: 184 | continue 185 | if i == aid: 186 | continue 187 | self.cP[i] = Pii @ np.linalg.inv(Pii) @ self.cP[i] 188 | 189 | # the rest will be outside of filter 190 | Pjj = Paa[self.dim_x:, self.dim_x:] 191 | return (xj.copy(), Pjj.copy()) 192 | 193 | def predict_x(self, u=0): 194 | """ 195 | Predicts the next state of X. If you need to 196 | compute the next state yourself, override this function. You would 197 | need to do this, for example, if the usual Taylor expansion to 198 | generate F is not providing accurate results for you. 199 | """ 200 | self.x = dot(self.F, self.x) + dot(self.B, u) 201 | 202 | def predict(self, u=0): 203 | """ 204 | Predict next state (prior) using the Kalman filter state propagation 205 | equations. 206 | 207 | Parameters 208 | ---------- 209 | 210 | u : np.array 211 | Optional control vector. If non-zero, it is multiplied by B 212 | to create the control input into the system. 213 | """ 214 | 215 | self.predict_x(u) 216 | self.P = dot(self.F, self.P).dot(self.F.T) + self.Q 217 | 218 | # save prior 219 | self.x_prior = np.copy(self.x) 220 | self.P_prior = np.copy(self.P) 221 | 222 | # CKF addition 223 | for i in range(self.dim_a): 224 | if i == self.aid: 225 | continue 226 | self.cP[i] = self.F @ self.cP[i] 227 | -------------------------------------------------------------------------------- /ckf_sim.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | import numpy as np 3 | from ckf import CollaborativeKalmanFilter 4 | import transforms3d as tf 5 | from utils import * 6 | from scipy.linalg import block_diag 7 | 8 | BEACONS_NUM = 2 9 | AGENTS_NUM = 3 10 | GEN_DATA = False 11 | NOISE_STD = 1 12 | DISABLE_IMU = False 13 | REG_EKF = True 14 | 15 | 16 | if GEN_DATA: 17 | import subprocess 18 | subprocess.call("./gen_data.py", shell=True) 19 | 20 | 21 | class Beacon: 22 | 23 | def __init__(self, id: str, x0: np.ndarray) -> None: 24 | if x0.shape == (3,) or x0.shape == (1, 3): 25 | x0 = x0.reshape((3, 1)) 26 | if x0.shape != (3, 1): 27 | raise Exception("Wrong state shape!") 28 | self.__x = x0 29 | 30 | def get_pos(self) -> np.array: 31 | return self.__x 32 | 33 | 34 | def getH(x_op: np.ndarray, beacons): 35 | H = np.zeros((len(beacons), len(x_op))) 36 | for i, b in enumerate(beacons): 37 | diff = x_op[:3] - b.get_pos() 38 | the_norm = np.linalg.norm(diff) 39 | if (the_norm == 0.0).any(): 40 | raise Exception("Division by zero. ANY") 41 | if (diff == 0.0).all(): 42 | raise Exception("Division by zero") 43 | H[i][:3] = (diff / the_norm).T 44 | # check for inf in H 45 | if np.isinf(H).any(): 46 | raise ValueError("H contains inf") 47 | # check for inf in H 48 | if np.isnan(H).any(): 49 | raise ValueError("H contains inf") 50 | return H 51 | 52 | 53 | def getHaug(x_op: np.ndarray, beacons): 54 | H = getH(x_op, beacons) 55 | H = np.vstack((H, np.zeros((2, len(x_op))))) 56 | H[-2, 2] = 1 57 | H[-1, -1] = 1 58 | return H 59 | 60 | 61 | def getHraw(x_op: np.ndarray, b_op: np.ndarray): 62 | H = np.zeros((1, len(x_op))) 63 | diff = x_op[:3] - b_op[:3] 64 | the_norm = np.linalg.norm(diff) 65 | if (diff == 0.0).all(): 66 | raise Exception("Division by zero") 67 | H[0][:3] = (diff / the_norm).T 68 | return H 69 | 70 | 71 | def hx(x, beacons): 72 | """ 73 | non-linear measurement func 74 | """ 75 | h = np.zeros((len(beacons), 1)) 76 | for i, b in enumerate(beacons): 77 | h[i] = np.linalg.norm(x[:3] - b.get_pos()) 78 | return h 79 | 80 | 81 | def hxaug(x, beacons, altitude, bearing): 82 | h = hx(x, beacons) 83 | addition = np.array([altitude, bearing]).reshape(2, 1) 84 | h = np.vstack((h, addition)) 85 | return h 86 | 87 | 88 | class Agent: 89 | DIM_X = 9 90 | DIM_U = 6 91 | 92 | def __init__(self, data, aid) -> None: 93 | global REG_EKF 94 | self.DIM_Z = (BEACONS_NUM + (AGENTS_NUM - 1)) \ 95 | if REG_EKF else (BEACONS_NUM + 2) 96 | self.__data = data 97 | self.id = aid 98 | self.filter = CollaborativeKalmanFilter( 99 | dim_x=self.DIM_X, dim_z=self.DIM_Z, 100 | dim_a=AGENTS_NUM, agent_id=aid, dim_u=self.DIM_U) 101 | self.filter.x = np.array([data["ref_pos"][0][0], data["ref_pos"] 102 | [0][1], data["ref_pos"][0][2], 0, 0, 0, 0, 0, 0]).reshape(9, 1) 103 | dt = 0.01 104 | I = np.eye(3) 105 | Idt = np.eye(3) * dt 106 | Idt2 = .5 * np.eye(3) * dt**2 107 | F = block_diag(I, I, I) 108 | F[0:3, 3:6] = Idt 109 | B = np.zeros((9, 6)) 110 | B[0:3, 0:3] = Idt2 111 | B[3:6, 0:3] = Idt 112 | B[6:9, 3:6] = Idt 113 | self.filter.F = F 114 | self.filter.B = B 115 | self.filter.P = np.eye(9) 116 | self.filter.R = np.diag([1.0] * BEACONS_NUM + [10.0] + [10000.0]) 117 | self.filter.rR *= 1e1 # relative 118 | self.filter.Q = np.eye(9) * 1e-2 119 | self.g = np.array([0, 0, 9.794841972265039942e+00]) 120 | self.trajectory = [] 121 | self.attitude = [] 122 | 123 | def get_ref_pos(self): 124 | return self.__data["ref_pos"] 125 | 126 | def get_ref_att(self): 127 | return self.__data["ref_att_euler"] 128 | 129 | def get_pos(self): 130 | return self.filter.x[:3].copy() 131 | 132 | def num_data(self): 133 | return len(self.__data["ref_pos"]) 134 | 135 | def kalman_update(self, beacons, agents, step_index, range_meas=False): 136 | # save position 137 | self.trajectory.append(self.filter.x[:3].copy()) 138 | self.attitude.append(self.filter.x[6:9][::-1].copy()) 139 | 140 | # predict 141 | acc = self.__data["accel-0"][step_index] 142 | gyro = self.__data["gyro-0"][step_index] 143 | R_att = tf.euler.euler2mat( 144 | float(self.filter.x[6]), float(self.filter.x[7]), float(self.filter.x[8])) 145 | acc = (R_att @ acc) + self.g 146 | theta = self.filter.x[7][0] 147 | phi = self.filter.x[6][0] 148 | Rw = np.array([[np.cos(theta), 0, -np.cos(phi)*np.sin(theta)], 149 | [0, 1, np.sin(phi)], 150 | [np.sin(theta), 0, np.cos(phi)*np.cos(theta)]]) 151 | u = np.concatenate( 152 | (acc, np.linalg.inv(Rw) @ np.deg2rad(gyro))).reshape(6, 1) 153 | if DISABLE_IMU: 154 | u *= 0 155 | self.filter.predict(u=u) 156 | 157 | if not range_meas: 158 | return 159 | 160 | if REG_EKF: 161 | gt_dists = [ 162 | self.__data[f"uwb-static{i}"][step_index][0] + 163 | np.random.normal(scale=NOISE_STD) for i in range(BEACONS_NUM)] 164 | for j in range(AGENTS_NUM+1): 165 | # check if self.__data has uwb-static key 166 | if f"uwb-agent{j+1}" not in self.__data.keys(): 167 | continue 168 | gt_dists.append( 169 | self.__data[f"uwb-agent{j+1}"][step_index] + 170 | np.random.normal(scale=NOISE_STD)) 171 | z = np.array(gt_dists).reshape(-1, 1) 172 | to_pass_beacons = beacons.copy() 173 | to_pass_beacons.extend(agents) 174 | self.filter.update(z, getH, hx, args=( 175 | to_pass_beacons), hx_args=(to_pass_beacons)) 176 | else: 177 | # static + TODO: add the bearing and altitude measurements 178 | gt_dists = [ 179 | self.__data[f"uwb-static{i}"][step_index][0] + 180 | np.random.normal(scale=NOISE_STD) for i in range(BEACONS_NUM)] 181 | z = np.array(gt_dists).reshape(-1, 1) 182 | # add altitude and bearing measurements 183 | altitude = self.__data["ref_pos"][step_index][-1] 184 | bearing = np.deg2rad( 185 | self.__data["ref_att_euler"][step_index][0]) 186 | addition = np.array([altitude, bearing]).reshape( 187 | 2, 1) + np.random.normal(scale=NOISE_STD, size=(2, 1)) 188 | z = np.concatenate((z, addition)).reshape(-1, 1) 189 | to_pass_beacons = beacons.copy() 190 | # TODO: augment with bearing and altitude measurements 191 | self.filter.update(z, getHaug, hxaug, args=( 192 | to_pass_beacons), hx_args=(to_pass_beacons, self.filter.x[2], self.filter.x[-1])) 193 | # dynamic 194 | for j in range(AGENTS_NUM): 195 | # check if self.__data has uwb-static key 196 | if f"uwb-agent{j+1}" not in self.__data.keys(): 197 | continue 198 | distance = self.__data[f"uwb-agent{j+1}"][step_index] + \ 199 | np.random.normal(scale=NOISE_STD) 200 | z = np.array(distance).reshape(-1, 1) 201 | agent = None 202 | for a in agents: 203 | if a.id == j: 204 | agent = a 205 | break 206 | to_pass_beacons = [agent] 207 | ax = agent.filter.x.copy() 208 | aP = agent.filter.P.copy() 209 | aid = agent.id 210 | aSji = agent.filter.cP[self.id] 211 | (xj, Pj) = self.filter.rel_update( 212 | aid, ax, aP, aSji, z, getHraw, hx, 213 | hx_args=(to_pass_beacons, )) 214 | agent.filter.x = xj 215 | agent.filter.P = Pj 216 | self.filter.cP[self.id] = np.eye(9) 217 | for k in range(AGENTS_NUM): 218 | if k == self.id: 219 | continue 220 | if k == aid: 221 | continue 222 | agent.filter.cP[k] = np.eye(9) 223 | 224 | 225 | def main(plot=True, regular=True): 226 | global REG_EKF 227 | REG_EKF = regular 228 | 229 | print("Loading data...") 230 | agent1_data = take_in_data("data/agent1") 231 | agent2_data = take_in_data("data/agent2") 232 | agent3_data = take_in_data("data/agent3") 233 | 234 | STARTING_POS = agent1_data["ref_pos"][0] 235 | agent1_data["ref_pos"] = agent1_data["ref_pos"] - STARTING_POS 236 | agent2_data["ref_pos"] = agent2_data["ref_pos"] - STARTING_POS 237 | agent3_data["ref_pos"] = agent3_data["ref_pos"] - STARTING_POS 238 | 239 | static_beacons = [] 240 | for i in range(BEACONS_NUM): 241 | x0 = agent1_data[f"uwb-static{i}"][0][1:] - STARTING_POS 242 | static_beacons.append(Beacon(str(i), x0)) 243 | 244 | Agent1 = Agent(agent1_data, 0) 245 | Agent2 = Agent(agent2_data, 1) 246 | Agent3 = Agent(agent3_data, 2) 247 | global_agents = [Agent1, Agent2, Agent3] 248 | 249 | which = "EKF" if REG_EKF else "CKF" 250 | print(f"Running {which}...") 251 | for i in range(Agent1.num_data()-1): 252 | range_meas = (i % 10 == 0) 253 | for _, current_agent in enumerate(global_agents): 254 | agents_without_itself = [ 255 | a for a in global_agents if a is not current_agent] 256 | current_agent.kalman_update( 257 | static_beacons, agents_without_itself, i, range_meas) 258 | 259 | for agent in global_agents: 260 | print_error_metrics(agent) 261 | 262 | if plot: 263 | plot_trajectories(static_beacons, global_agents) 264 | else: 265 | make_plots(static_beacons, global_agents, save=True) 266 | 267 | 268 | if __name__ == "__main__": 269 | np.random.seed(0) 270 | import time 271 | NRUN = 1 272 | times = [] 273 | for i in range(NRUN): 274 | start = time.time() 275 | main(plot=True, regular=False) 276 | end = time.time() 277 | times.append(end-start) 278 | print(f"Average time: {np.mean(times)}") 279 | -------------------------------------------------------------------------------- /sup/imu.ipynb: -------------------------------------------------------------------------------- 1 | { 2 | "cells": [ 3 | { 4 | "cell_type": "code", 5 | "execution_count": 1, 6 | "metadata": {}, 7 | "outputs": [], 8 | "source": [ 9 | "import numpy as np\n", 10 | "import transforms3d as tf\n", 11 | "import matplotlib.pyplot as plt" 12 | ] 13 | }, 14 | { 15 | "cell_type": "code", 16 | "execution_count": 2, 17 | "metadata": {}, 18 | "outputs": [ 19 | { 20 | "data": { 21 | "text/plain": [ 22 | "(4100, 3)" 23 | ] 24 | }, 25 | "execution_count": 2, 26 | "metadata": {}, 27 | "output_type": "execute_result" 28 | } 29 | ], 30 | "source": [ 31 | "data = np.genfromtxt('data/agent1/gyro-0.csv', delimiter=',')\n", 32 | "data = np.delete(data, (0), axis=0)\n", 33 | "acc_data = np.genfromtxt('data/agent1/accel-0.csv', delimiter=',')\n", 34 | "acc_data = np.delete(acc_data, (0), axis=0) \n", 35 | "ref_euler = np.genfromtxt('data/agent1/ref_att_euler.csv', delimiter=',')\n", 36 | "ref_euler = np.delete(ref_euler, (0), axis=0)\n", 37 | "ref_pos = np.genfromtxt('data/agent1/ref_pos.csv', delimiter=',')\n", 38 | "ref_pos = np.delete(ref_pos, (0), axis=0)\n", 39 | "ref_euler.shape" 40 | ] 41 | }, 42 | { 43 | "cell_type": "code", 44 | "execution_count": 3, 45 | "metadata": {}, 46 | "outputs": [], 47 | "source": [ 48 | "def skew(x):\n", 49 | " return np.array([[0, -x[2], x[1]],\n", 50 | " [x[2], 0, -x[0]],\n", 51 | " [-x[1], x[0], 0]])" 52 | ] 53 | }, 54 | { 55 | "cell_type": "code", 56 | "execution_count": 4, 57 | "metadata": {}, 58 | "outputs": [ 59 | { 60 | "data": { 61 | "text/plain": [ 62 | "Text(0.5, 0, 'time [s]')" 63 | ] 64 | }, 65 | "execution_count": 4, 66 | "metadata": {}, 67 | "output_type": "execute_result" 68 | }, 69 | { 70 | "data": { 71 | "image/png": "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", 72 | "text/plain": [ 73 | "
" 74 | ] 75 | }, 76 | "metadata": {}, 77 | "output_type": "display_data" 78 | }, 79 | { 80 | "data": { 81 | "image/png": "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", 82 | "text/plain": [ 83 | "
" 84 | ] 85 | }, 86 | "metadata": {}, 87 | "output_type": "display_data" 88 | } 89 | ], 90 | "source": [ 91 | "R_att = np.eye(3)\n", 92 | "v = np.zeros(3)\n", 93 | "p = ref_pos[0]\n", 94 | "tau = 0.01\n", 95 | "rec_err = []\n", 96 | "rec_pos_err = []\n", 97 | "rec_angles = []\n", 98 | "g = np.array([0, 0, 9.794841972265039942e+00])\n", 99 | "for i,w in enumerate(data):\n", 100 | " euler = np.array(tf.euler.mat2euler(R_att)) * 180 / np.pi\n", 101 | " error = euler - ref_euler[i]\n", 102 | " rec_err.append(error)\n", 103 | " skew_w = skew(w)\n", 104 | " R_att_prev = R_att.copy()\n", 105 | " accel = acc_data[i]\n", 106 | " R_att = R_att @ (np.eye(3) + skew_w * tau + .5 * skew_w**2 * tau**2)\n", 107 | " angles = tf.euler.mat2euler(R_att)\n", 108 | " rec_angles.append(angles)\n", 109 | " f = .5 * (R_att_prev + R_att) @ accel\n", 110 | " a = f + g\n", 111 | " v_prev = v.copy()\n", 112 | " v = v + a * tau # second order power series\n", 113 | " p = p + .5 * (v + v_prev) * tau\n", 114 | " pos_error = p - ref_pos[i]\n", 115 | " rec_pos_err.append(pos_error)\n", 116 | "time = np.arange(0, len(data) / 100, tau)\n", 117 | "plt.plot(time, rec_pos_err)\n", 118 | "plt.legend(['x', 'y', 'z'])\n", 119 | "plt.xlabel('time [s]')\n", 120 | "plt.ylabel('error [m]')\n", 121 | "plt.figure()\n", 122 | "plt.plot(time,rec_angles)\n", 123 | "plt.legend(['roll', 'pitch', 'yaw'])\n", 124 | "plt.xlabel('time [s]')" 125 | ] 126 | }, 127 | { 128 | "cell_type": "code", 129 | "execution_count": 5, 130 | "metadata": {}, 131 | "outputs": [], 132 | "source": [ 133 | "from sympy import Matrix, eye, cos, sin, pi, symbols, latex\n", 134 | "from scipy.linalg import block_diag" 135 | ] 136 | }, 137 | { 138 | "cell_type": "code", 139 | "execution_count": 6, 140 | "metadata": {}, 141 | "outputs": [ 142 | { 143 | "data": { 144 | "text/plain": [ 145 | "True" 146 | ] 147 | }, 148 | "execution_count": 6, 149 | "metadata": {}, 150 | "output_type": "execute_result" 151 | } 152 | ], 153 | "source": [ 154 | "# symbolic euler angles\n", 155 | "phi, theta, psi, dt = symbols('phi theta psi {\\Delta}t') \n", 156 | "\n", 157 | "# angular vector\n", 158 | "w = Matrix([[phi],\n", 159 | " [theta],\n", 160 | " [psi]])\n", 161 | "\n", 162 | "# rotation matrix\n", 163 | "R = Matrix([[cos(theta), 0, -cos(phi)*sin(theta)],\n", 164 | " [0 , 1, sin(phi)],\n", 165 | " [sin(theta), 0, cos(phi)*cos(theta)]])\n", 166 | "Rdt = Matrix([[cos(theta)*dt, 0, -cos(phi)*sin(theta)],\n", 167 | " [0 , dt, sin(phi)],\n", 168 | " [sin(theta), 0, dt*cos(phi)*cos(theta)]])\n", 169 | "\n", 170 | "B = Matrix([[1, 0, 0],\n", 171 | " [0, 1, 0],\n", 172 | " [0, 0, 1]])\n", 173 | "Bdt = Matrix([[dt, 0, 0],\n", 174 | " [0, dt, 0],\n", 175 | " [0, 0, dt]])\n", 176 | "Bdt @ R @ w == (B @ R * dt @ w)" 177 | ] 178 | }, 179 | { 180 | "cell_type": "code", 181 | "execution_count": 7, 182 | "metadata": {}, 183 | "outputs": [ 184 | { 185 | "name": "stdout", 186 | "output_type": "stream", 187 | "text": [ 188 | "[[1. 0. 0. 0.01 0. 0. 0. 0. 0. ]\n", 189 | " [0. 1. 0. 0. 0.01 0. 0. 0. 0. ]\n", 190 | " [0. 0. 1. 0. 0. 0.01 0. 0. 0. ]\n", 191 | " [0. 0. 0. 1. 0. 0. 0. 0. 0. ]\n", 192 | " [0. 0. 0. 0. 1. 0. 0. 0. 0. ]\n", 193 | " [0. 0. 0. 0. 0. 1. 0. 0. 0. ]\n", 194 | " [0. 0. 0. 0. 0. 0. 1. 0. 0. ]\n", 195 | " [0. 0. 0. 0. 0. 0. 0. 1. 0. ]\n", 196 | " [0. 0. 0. 0. 0. 0. 0. 0. 1. ]]\n", 197 | "[[5.e-05 0.e+00 0.e+00 0.e+00 0.e+00 0.e+00]\n", 198 | " [0.e+00 5.e-05 0.e+00 0.e+00 0.e+00 0.e+00]\n", 199 | " [0.e+00 0.e+00 5.e-05 0.e+00 0.e+00 0.e+00]\n", 200 | " [1.e-02 0.e+00 0.e+00 0.e+00 0.e+00 0.e+00]\n", 201 | " [0.e+00 1.e-02 0.e+00 0.e+00 0.e+00 0.e+00]\n", 202 | " [0.e+00 0.e+00 1.e-02 0.e+00 0.e+00 0.e+00]\n", 203 | " [0.e+00 0.e+00 0.e+00 1.e-02 0.e+00 0.e+00]\n", 204 | " [0.e+00 0.e+00 0.e+00 0.e+00 1.e-02 0.e+00]\n", 205 | " [0.e+00 0.e+00 0.e+00 0.e+00 0.e+00 1.e-02]]\n", 206 | "[[0. 0. 0. 0. 0. 0. 1. 0. 0.]\n", 207 | " [0. 0. 0. 0. 0. 0. 0. 1. 0.]]\n" 208 | ] 209 | } 210 | ], 211 | "source": [ 212 | "dt = 0.01\n", 213 | "I = np.eye(3)\n", 214 | "Idt = np.eye(3) * dt\n", 215 | "Idt2 = .5 * np.eye(3) * dt**2\n", 216 | "F = block_diag(I, I, I)\n", 217 | "F[0:3, 3:6] = Idt\n", 218 | "print(F)\n", 219 | "B = np.zeros((9,6))\n", 220 | "B[0:3, 0:3] = Idt2\n", 221 | "B[3:6, 0:3] = Idt\n", 222 | "B[6:9, 3:6] = Idt\n", 223 | "print(B)\n", 224 | "C = np.zeros((2,9))\n", 225 | "C[0, 6] = 1\n", 226 | "C[1, 7] = 1\n", 227 | "print(C)" 228 | ] 229 | }, 230 | { 231 | "cell_type": "code", 232 | "execution_count": 8, 233 | "metadata": {}, 234 | "outputs": [ 235 | { 236 | "data": { 237 | "text/plain": [ 238 | "Text(0, 0.5, 'angle [rad]')" 239 | ] 240 | }, 241 | "execution_count": 8, 242 | "metadata": {}, 243 | "output_type": "execute_result" 244 | }, 245 | { 246 | "data": { 247 | "image/png": "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", 248 | "text/plain": [ 249 | "
" 250 | ] 251 | }, 252 | "metadata": {}, 253 | "output_type": "display_data" 254 | }, 255 | { 256 | "data": { 257 | "image/png": "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", 258 | "text/plain": [ 259 | "
" 260 | ] 261 | }, 262 | "metadata": {}, 263 | "output_type": "display_data" 264 | }, 265 | { 266 | "data": { 267 | "image/png": "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", 268 | "text/plain": [ 269 | "
" 270 | ] 271 | }, 272 | "metadata": {}, 273 | "output_type": "display_data" 274 | } 275 | ], 276 | "source": [ 277 | "from filterpy.kalman import KalmanFilter\n", 278 | "filter = KalmanFilter(dim_x=9, dim_z=2)\n", 279 | "filter.x = np.array([ref_pos[0][0], ref_pos[0][1], ref_pos[0][2], 0, 0, 0, 0, 0, 0]).reshape(9,1)\n", 280 | "filter.F = F\n", 281 | "filter.B = B\n", 282 | "filter.H = C\n", 283 | "filter.P = np.eye(9)*1e+3\n", 284 | "filter.R = np.eye(2)*1e+2\n", 285 | "filter.Q = np.eye(9)*1e-6\n", 286 | "R_att = np.eye(3)\n", 287 | "\n", 288 | "rec_err = []\n", 289 | "rec_filter_pos = []\n", 290 | "rec_filter_angles = []\n", 291 | "for i,(acc,domega) in enumerate(zip(acc_data, data)):\n", 292 | " R_att = tf.euler.euler2mat(filter.x[6], filter.x[7], filter.x[8], axes='sxyz')\n", 293 | " phi = np.arctan2(acc[1], np.sqrt(acc[0]**2 + acc[2]**2))\n", 294 | " theta = np.arctan2(acc[0], np.sqrt(acc[1]**2 + acc[2]**2))\n", 295 | " z = np.array([phi, theta]).reshape(2,1)\n", 296 | " # filter.update(z)\n", 297 | " acc = (R_att @ acc) + g\n", 298 | " theta = filter.x[7][0]\n", 299 | " phi = filter.x[6][0]\n", 300 | " Rw = np.array([[np.cos(theta), 0, -np.cos(phi)*np.sin(theta)],\n", 301 | " [0 , 1, np.sin(phi)],\n", 302 | " [np.sin(theta), 0, np.cos(phi)*np.cos(theta)]])\n", 303 | " domega = domega * np.pi / 180\n", 304 | " u = np.concatenate((acc, Rw @ domega)).reshape(6,1)\n", 305 | " filter.predict(u=u)\n", 306 | " # data saving\n", 307 | " rec_err.append(abs(filter.x[:3] - ref_pos[i].reshape(3,1)).reshape(3,))\n", 308 | " rec_filter_pos.append(filter.x[:3].reshape(3,))\n", 309 | " rec_filter_angles.append(filter.x[6:].reshape(3,))\n", 310 | "\n", 311 | "time = np.arange(len(data)) * dt\n", 312 | "plt.plot(time, rec_err)\n", 313 | "plt.legend(['x', 'y', 'z'])\n", 314 | "plt.xlabel('time [s]')\n", 315 | "plt.ylabel('error [m]')\n", 316 | "plt.figure()\n", 317 | "rec_filter_pos = np.array(rec_filter_pos) - ref_pos[0]\n", 318 | "ref_pos = np.array(ref_pos) - ref_pos[0]\n", 319 | "plt.scatter(rec_filter_pos[::100,0], rec_filter_pos[::100,2], c='r')\n", 320 | "plt.scatter(ref_pos[::100,0], ref_pos[::100,2], c='b')\n", 321 | "plt.legend(['filter_xz', 'ref_xz'])\n", 322 | "plt.xlabel('x [m]')\n", 323 | "at = plt.ylabel('z [m]')\n", 324 | "# plot euler angles\n", 325 | "plt.figure()\n", 326 | "plt.plot(time, rec_filter_angles, '--')\n", 327 | "plt.plot(time, ref_euler * np.pi / 180)\n", 328 | "plt.legend(['roll', 'pitch', 'yaw', 'ref_yaw', 'ref_pitch', 'ref_roll'])\n", 329 | "plt.xlabel('time [s]')\n", 330 | "plt.ylabel('angle [rad]')" 331 | ] 332 | } 333 | ], 334 | "metadata": { 335 | "kernelspec": { 336 | "display_name": "Python 3 (ipykernel)", 337 | "language": "python", 338 | "name": "python3" 339 | }, 340 | "language_info": { 341 | "codemirror_mode": { 342 | "name": "ipython", 343 | "version": 3 344 | }, 345 | "file_extension": ".py", 346 | "mimetype": "text/x-python", 347 | "name": "python", 348 | "nbconvert_exporter": "python", 349 | "pygments_lexer": "ipython3", 350 | "version": "3.10.6" 351 | }, 352 | "orig_nbformat": 4, 353 | "vscode": { 354 | "interpreter": { 355 | "hash": "916dbcbb3f70747c44a77c7bcd40155683ae19c65e1c03b4aa3499c5328201f1" 356 | } 357 | } 358 | }, 359 | "nbformat": 4, 360 | "nbformat_minor": 2 361 | } 362 | --------------------------------------------------------------------------------