Skip to content

Commit 02bbec0

Browse files
authored
Fix/improve rerun visualization, remove matplotlib as an undocumented dep, bump version (#10)
* remove unnecessary dependency on matplotlib. also prevents a break * use the rerun blueprint from the visualization we have now * move rerun config to the package folder, and then always log it on initialization so we get a well configured viz by default * improve docs a bit, and change the name for a workflow build * bump version because we fixed the visualization in this one
1 parent dba16df commit 02bbec0

File tree

8 files changed

+32
-11
lines changed

8 files changed

+32
-11
lines changed

.github/workflows/pypi.yaml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -34,6 +34,7 @@ jobs:
3434
name: artifact-${{ matrix.os }}
3535
path: ./wheelhouse/*.whl
3636
pypi:
37+
name: Publish wheels to PyPI
3738
if: github.event_name == 'release'
3839
needs: [cibuildwheel]
3940
runs-on: ubuntu-latest

README.md

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -128,9 +128,9 @@ You'll find further usage instructions [here](python#usage).
128128
For instructions on how to build from source, please check [here](/python/README.md#build-from-source).
129129

130130
<details>
131-
<summary>Please prefer the ROS version over the python version if you can</summary>
131+
<summary><b>Please prefer the ROS version over the python version if you can</b></summary>
132132

133-
**Please note:** the ROS version is the intended way to use our odometry system on a robot.
133+
The ROS version is the intended way to use our odometry system on a robot.
134134
The python version is slower than the ROS version, not on the odometry itself, but on how we read incoming data, i.e. dataloading.
135135
Without getting into details, if you can, you should prefer using the ROS version.
136136
We also provide a way to directly inspect and run our odometry on recorded rosbags (see offline mode in [ROS usage](ros#usage)) which has a performance benefit over the python version.

python/config/rko_lio.rbl

-25.4 KB
Binary file not shown.

python/pyproject.toml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -4,7 +4,7 @@ build-backend = "scikit_build_core.build"
44

55
[project]
66
name = "rko_lio"
7-
version = "0.0.2"
7+
version = "0.0.3"
88
description = "A Robust Approach for LiDAR-Inertial Odometry Without Sensor-Specific Modelling"
99
dependencies = ["numpy", "typer", "pyyaml", "scipy", "tqdm"]
1010
authors = [{ name = "Meher Malladi", email = "rm.meher97@gmail.com" }]

python/rko_lio/cli.py

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -144,6 +144,7 @@ def cli(
144144

145145
rr.init("rko_lio")
146146
rr.spawn(memory_limit="2GB")
147+
rr.log_file_from_path(Path(__file__).parent / "rko_lio.rbl")
147148

148149
except ImportError:
149150
raise ImportError(

python/rko_lio/lio_pipeline.py

Lines changed: 26 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -244,25 +244,44 @@ def dump_results_to_disk(self, results_dir: Path, run_name: str):
244244
self.lio.dump_results_to_disk(results_dir, run_name)
245245

246246

247+
viridis_ctrl = np.array(
248+
[
249+
[68, 1, 84],
250+
[71, 44, 122],
251+
[59, 81, 139],
252+
[44, 113, 142],
253+
[33, 144, 140],
254+
[39, 173, 129],
255+
[92, 200, 99],
256+
[170, 220, 50],
257+
[253, 231, 37],
258+
],
259+
dtype=np.uint8,
260+
)
261+
262+
247263
def height_colors_from_points(points: np.ndarray) -> np.ndarray:
248264
"""
249265
Given Nx3 array of points, return Nx3 array of RGB colors (dtype uint8)
250266
mapped from the z values using the viridis colormap.
251267
Colors are uint8 in range [0, 255].
252268
"""
253-
import matplotlib.pyplot as plt
254-
from matplotlib import cm
255-
256269
z = points[:, 2]
257270
z_min, z_max = np.percentile(z, 1), np.percentile(z, 99) # accounts for any noise
258271
z_clipped = np.clip(z, z_min, z_max)
272+
259273
if z_max == z_min:
260274
norm_z = np.zeros_like(z)
261275
else:
262276
norm_z = (z_clipped - z_min) / (z_max - z_min)
263277

264-
viridis = cm.get_cmap("viridis")
265-
colors_float = viridis(norm_z)[:, :3] # Nx3 floats in [0,1]
278+
idx = norm_z * (len(viridis_ctrl) - 1)
279+
idx_low = np.floor(idx).astype(int)
280+
idx_high = np.clip(idx_low + 1, 0, len(viridis_ctrl) - 1)
281+
alpha = idx - idx_low
282+
colors = (
283+
(1 - alpha)[:, None] * viridis_ctrl[idx_low]
284+
+ alpha[:, None] * viridis_ctrl[idx_high]
285+
).astype(np.uint8)
266286

267-
colors_uint8 = (colors_float * 255).astype(np.uint8)
268-
return colors_uint8
287+
return colors

python/rko_lio/rko_lio.rbl

44.3 KB
Binary file not shown.

ros/package.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
<?xml version="1.0" encoding="UTF-8"?>
22
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?><package format="3">
33
<name>rko_lio</name>
4-
<version>0.0.2</version>
4+
<version>0.0.3</version>
55
<description>A Robust Approach for LiDAR-Inertial Odometry Without Sensor-Specific Modelling</description>
66
<maintainer email="rm.meher97@gmail.com">Meher Malladi</maintainer>
77
<license>MIT</license>

0 commit comments

Comments
 (0)