Skip to content

Commit cb0ed58

Browse files
committed
TUM rgbd dataset
1 parent 3286365 commit cb0ed58

File tree

2 files changed

+239
-0
lines changed

2 files changed

+239
-0
lines changed
Lines changed: 47 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,47 @@
1+
"""
2+
Computation of the camera matrix from world points and their projections.
3+
4+
References:
5+
> Terzakis--Lourakis, "A Consistently Fast and Globally Optimal Solution to the Perspective-n-Point Problem"
6+
> Hartley--Zisserman, "Multiple View Geometry in Computer Vision", 2nd ed.
7+
"""
8+
from typing import Tuple
9+
10+
import jax
11+
from jax import numpy as jnp
12+
13+
from b3d.pose import Pose
14+
from b3d.types import Array, Int, Matrix3x3, Matrix3x4, Point3D
15+
16+
17+
def solve_camera_projection_constraints(Xs: Point3D, ys: Point3D) -> Matrix3x4:
18+
"""
19+
Solve for the camera projection matrix given 3D points and their 2D projections,
20+
as described in Chapter 7 ("Computation of the Camera Matrix P") of
21+
> Hartley--Zisserman, "Multiple View Geometry in Computer Vision" (2nd ed).
22+
23+
Args:
24+
Xs: 3D points in world coordinates, shape (N, 3).
25+
ys: Normalized image coordinates, shape (N, 2).
26+
27+
Returns:
28+
Camera projection matrix, shape (3, 4).
29+
"""
30+
# We change notation from B3D notation
31+
# to Hartley--Zisserman, for easy of comparison
32+
X = Xs
33+
x = ys[:, 0]
34+
y = ys[:, 1]
35+
w = ys[:, 2]
36+
n = X.shape[0]
37+
38+
A = jnp.concatenate([
39+
jnp.block([
40+
[jnp.zeros(3), -w[i]*X[i], y[i]*X[i]],
41+
[ w[i]*X[i], jnp.zeros(3), -x[i]*X[i]],
42+
[ -y[i]*X[i], x[i]*X[i], jnp.zeros(3)]])
43+
for i in jnp.arange(n)], axis=0)
44+
45+
_, _, vt = jnp.linalg.svd(A)
46+
P = vt[-1].reshape(3, 4)
47+
return P

src/b3d/chisight/sfm/datasets.py

Lines changed: 192 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,192 @@
1+
import subprocess
2+
import os
3+
from pathlib import Path
4+
import imageio.v3 as iio
5+
import re
6+
from b3d.camera import Intrinsics
7+
from b3d.pose import Pose
8+
import numpy as np
9+
import jax
10+
import jax.numpy as jnp
11+
12+
13+
_DOWNLOAD_BASH_SCRIPT = """#!/bin/bash
14+
15+
# Check if both sequence and target_folder arguments are provided
16+
if [ $# -ne 2 ]; then
17+
echo "Usage: $0 <sequence_url> <target_folder>"
18+
exit 1
19+
fi
20+
21+
# Assign arguments to variables
22+
sequence_url=$1
23+
target_folder=$2
24+
sequence=$(basename $sequence_url)
25+
26+
echo "Downloading $sequence to $target_folder..."
27+
28+
# Ensure the target folder exists
29+
mkdir -p "$target_folder"
30+
31+
# Download the file using wget
32+
wget "$sequence_url" -P "$target_folder"
33+
34+
# Extract the tar.gz file
35+
tar -xzf "$target_folder/$sequence" -C "$target_folder"
36+
37+
# Remove the tar.gz file
38+
rm "$target_folder/$sequence"
39+
"""
40+
41+
42+
class RgbdSlamSequenceData:
43+
""""
44+
Helper class to handle RGB-D Sequences from the TUM RGBD SLAM benchmark dataset.
45+
The dataset can be downloaded from the following link:
46+
> https://cvg.cit.tum.de/data/datasets/rgbd-dataset/download
47+
48+
Example Usage:
49+
```
50+
# Grab a sequence URL from set
51+
# a target folder to store the data
52+
# > https://cvg.cit.tum.de/data/datasets/rgbd-dataset/download
53+
sequence_url = "https://cvg.cit.tum.de/rgbd/dataset/freiburg1/rgbd_dataset_freiburg1_xyz.tgz"
54+
target_folder = "~/workspace/rgbd_slam_dataset_freiburg"
55+
56+
# Download and extract the sequence data into
57+
# a new folder under the target folder
58+
sequence_folder = RgbdSlamSequenceData._download_from_url(sequence_url, target_folder)
59+
data = RgbdSlamSequenceData(sequence_folder)
60+
61+
# Get the i'th RGB image
62+
# Note that rgb, depth, and pose sequences are not synchronized, so the i'th RGB image
63+
# and the i'th depth image and pose are not guaranteed to be from the same time.
64+
i = 100
65+
rgb = data.get_rgb(i)
66+
67+
# This returns i'th RGB image and the CLOSEST (in time) available depth image and pose
68+
rgb, depth, pose = data.get_synced(i)
69+
70+
# Plot the RGB and depth images side by side
71+
fig, axs = plt.subplots(1, 3, figsize=(10,5))
72+
axs[0].imshow(rgb)
73+
axs[1].imshow(np.where(depth>0, depth, np.nan))
74+
axs[2].imshow(rgb, alpha=1.)
75+
axs[2].imshow(np.where(depth>0, depth, np.nan), alpha=0.75)
76+
```
77+
"""
78+
def __init__(self, path):
79+
"""
80+
Args:
81+
path (str): Path to one ofthe the TUM RGB-D datasets, e.g.,
82+
.../data/rgbd_dataset_freiburg2_desk
83+
"""
84+
85+
self.path = path
86+
87+
self.gt_data = np.loadtxt(path/"groundtruth.txt", comments='#', dtype = [
88+
('timestamp', 'f8'),
89+
('tx', 'f8'), ('ty', 'f8'), ('tz', 'f8'),
90+
('qx', 'f8'), ('qy', 'f8'), ('qz', 'f8'), ('qw', 'f8')])
91+
92+
self.rgb_data = np.loadtxt(path/"rgb.txt", comments='#', dtype=[
93+
("timestamp", 'f8'), ("filename", 'U50')])
94+
95+
self.depth_data = np.loadtxt(path/"depth.txt", comments='#', dtype=[
96+
("timestamp", 'f8'), ("filename", 'U50')])
97+
98+
@staticmethod
99+
def _download_from_url(sequence_url, target_folder):
100+
101+
# Target folder for the sequence data
102+
sequence_folder = Path(target_folder)/Path(sequence_url).stem
103+
104+
# Check if the target folder exists
105+
if os.path.exists(sequence_folder):
106+
print(f"Sequence \n\t\"{Path(sequence_url).stem}\"\nalready exists here \n\t{sequence_folder}")
107+
return sequence_folder
108+
109+
try:
110+
# Execute the Bash script using subprocess and pass in the arguments
111+
print("Downloading and extracting...this might take a minute....")
112+
result = subprocess.run(
113+
['bash', '-c', _DOWNLOAD_BASH_SCRIPT, '_', sequence_url, target_folder],
114+
check=True,
115+
text=True,
116+
capture_output=True
117+
)
118+
119+
# Print the output of the script
120+
print("Script Output:...\n", result.stdout)
121+
print("Script executed successfully.")
122+
return sequence_folder
123+
124+
except subprocess.CalledProcessError as e:
125+
print(f"An error occurred while executing the script: {e}")
126+
print(f"Error output: {e.stderr}")
127+
128+
def len(self):
129+
"""Returns the number of (RGB) frames in the dataset."""
130+
return len(self.rgb_data)
131+
132+
def shape(self):
133+
"""Returns the shape of the RGB images."""
134+
return self.get_rgb(0).shape
135+
136+
def get_rgb(self, i):
137+
"""Returns the RGB image at index i."""
138+
return iio.imread(self.path/self.rgb_data[i][1])
139+
140+
def get_depth(self, i):
141+
"""Returns the depth image at index i."""
142+
return iio.imread(self.path/self.depth_data[i][1])/5_000
143+
144+
def get_pose(self, i):
145+
"""Returns the pose at index i."""
146+
_, tx, ty, tz, qx, qy, qz, qw = self.gt_data[i]
147+
return Pose(jnp.array([tx,ty,tz]), jnp.array([qx, qy, qz, qw]))
148+
149+
def get_synced(self, i):
150+
"""Returns the timestamp, RGB, depth image, and pose at index i."""
151+
t = self.rgb_data[i]["timestamp"]
152+
i_pose = np.argmin(np.abs(self.gt_data["timestamp"] - t))
153+
i_depth = np.argmin(np.abs(self.depth_data["timestamp"] - t))
154+
return self.get_rgb(i), self.get_depth(i_depth), self.get_pose(i_pose)
155+
156+
def get_timestamp(self, i):
157+
return self.rgb_data[i]["timestamp"]
158+
159+
def __getitem__(self, i):
160+
"""Returns the RGB, depth image, and pose at index i."""
161+
return self.get_synced(i)
162+
163+
def get_intrinsics(self, index=0):
164+
"""Returns the camera intrinsics."""
165+
# See
166+
# > https://cvg.cit.tum.de/data/datasets/rgbd-dataset/file_formats#intrinsic_camera_calibration_of_the_kinect
167+
intr0 = Intrinsics(640, 480, 525.0, 525.0, 319.5, 239.5, 1e-2, 1e-4)
168+
intr1 = Intrinsics(640, 480, 517.3, 516.5, 318.6, 255.3, 1e-2, 1e-4)
169+
intr2 = Intrinsics(640, 480, 520.9, 521.0, 325.1, 249.7, 1e-2, 1e-4)
170+
intr3 = Intrinsics(640, 480, 535.4, 539.2, 320.1, 247.6, 1e-2, 1e-4)
171+
172+
return [intr0, intr1, intr2, intr3][index]
173+
174+
175+
def val_from_im(uv, im):
176+
return im[int(uv[1]), int(uv[0])]
177+
178+
179+
vals_from_im = jax.vmap(val_from_im, in_axes=(0, None))
180+
181+
182+
def _extract_number_after_freiburg(input_string):
183+
match = re.search(r'freiburg(\d+)', input_string)
184+
if match:
185+
return int(match.group(1))
186+
else:
187+
return None
188+
189+
190+
def _sequence_url_from_sequence_stem(sequence_stem):
191+
n = _extract_number_after_freiburg(sequence_stem)
192+
return f"https://cvg.cit.tum.de/rgbd/dataset/freiburg{n}/{sequence_stem}.tgz"

0 commit comments

Comments
 (0)