Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add draft visualization for the voxels of the VoxelHashMap #383

Closed
wants to merge 5 commits into from
Closed
Show file tree
Hide file tree
Changes from 3 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
11 changes: 11 additions & 0 deletions cpp/kiss_icp/core/VoxelHashMap.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,6 +56,17 @@ std::vector<Eigen::Vector3d> VoxelHashMap::Pointcloud() const {
return points;
}

// Get the indices of the occupided voxels as points, mainly used for visualization
std::vector<Voxel> VoxelHashMap::GetVoxels() const {
std::vector<Voxel> voxels;
voxels.reserve(map_.size());
for (const auto &[voxel, voxel_block] : map_) {
(void)voxel_block;
voxels.emplace_back(voxel);
}
return voxels;
}

void VoxelHashMap::Update(const std::vector<Eigen::Vector3d> &points,
const Eigen::Vector3d &origin) {
AddPoints(points);
Expand Down
1 change: 1 addition & 0 deletions cpp/kiss_icp/core/VoxelHashMap.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,6 +49,7 @@ struct VoxelHashMap {
void RemovePointsFarFromLocation(const Eigen::Vector3d &origin);
std::vector<Eigen::Vector3d> Pointcloud() const;
std::vector<Eigen::Vector3d> GetPoints(const std::vector<Voxel> &query_voxels) const;
std::vector<Voxel> GetVoxels() const;

double voxel_size_;
double max_distance_;
Expand Down
4 changes: 4 additions & 0 deletions python/kiss_icp/mapping.py
Original file line number Diff line number Diff line change
Expand Up @@ -66,3 +66,7 @@ def remove_far_away_points(self, origin):
def point_cloud(self) -> np.ndarray:
"""Return the internal representaion as a np.array (pointcloud)."""
return np.asarray(self._internal_map._point_cloud())

def get_voxels(self) -> np.ndarray:
"""Return the occupied voxels, in indices (i,j,k( as a np.array."""
return np.asarray(self._internal_map._get_voxels())
1 change: 1 addition & 0 deletions python/kiss_icp/pipeline.py
Original file line number Diff line number Diff line change
Expand Up @@ -77,6 +77,7 @@ def __init__(

# Visualizer
self.visualizer = RegistrationVisualizer() if visualize else StubVisualizer()
self.visualizer.voxel_size = self.config.mapping.voxel_size
if hasattr(self._dataset, "use_global_visualizer"):
self.visualizer.global_view = self._dataset.use_global_visualizer

Expand Down
3 changes: 2 additions & 1 deletion python/kiss_icp/pybind/kiss_icp_pybind.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,8 @@ PYBIND11_MODULE(kiss_icp_pybind, m) {
"points"_a, "pose"_a)
.def("_add_points", &VoxelHashMap::AddPoints, "points"_a)
.def("_remove_far_away_points", &VoxelHashMap::RemovePointsFarFromLocation, "origin"_a)
.def("_point_cloud", &VoxelHashMap::Pointcloud);
.def("_point_cloud", &VoxelHashMap::Pointcloud)
.def("_get_voxels", &VoxelHashMap::GetVoxels);

// Point Cloud registration
py::class_<Registration> internal_registration(m, "_Registration", "Don't use this");
Expand Down
41 changes: 36 additions & 5 deletions python/kiss_icp/tools/visualizer.py
Original file line number Diff line number Diff line change
Expand Up @@ -34,11 +34,13 @@
BLACK = np.array([0, 0, 0]) / 255.0
BLUE = np.array([0.4, 0.5, 0.9])
GRAY = np.array([0.4, 0.4, 0.4])
LIGHT_GRAY = np.array([0.9, 0.9, 0.9])
SPHERE_SIZE = 0.20


class StubVisualizer(ABC):
def __init__(self):
self.voxel_size = 1.0
pass

def update(self, source, keypoints, target_map, pose):
Expand All @@ -63,6 +65,9 @@ def __init__(self):
self.source = self.o3d.geometry.PointCloud()
self.keypoints = self.o3d.geometry.PointCloud()
self.target = self.o3d.geometry.PointCloud()
self.voxel_map = self.o3d.geometry.VoxelGrid()
self.voxel_size = 1.0
self.voxel_map.voxel_size = self.voxel_size
self.frames = []

# Initialize visualizer
Expand All @@ -74,18 +79,19 @@ def __init__(self):
self.render_map = True
self.render_source = True
self.render_keypoints = False
self.render_voxel_grid = False
self.global_view = False
self.render_trajectory = True
# Cache the state of the visualizer
self.state = (
self.render_map,
self.render_keypoints,
self.render_source,
self.render_voxel_grid,
)

def update(self, source, keypoints, target_map, pose):
target = target_map.point_cloud()
self._update_geometries(source, keypoints, target, pose)
self._update_geometries(source, keypoints, target_map, pose)
while self.block_vis:
self.vis.poll_events()
self.vis.update_renderer()
Expand All @@ -100,8 +106,10 @@ def _initialize_visualizer(self):
self.vis.add_geometry(self.source)
self.vis.add_geometry(self.keypoints)
self.vis.add_geometry(self.target)
self.vis.add_geometry(self.voxel_map)
self._set_black_background(self.vis)
self.vis.get_render_option().point_size = 1
self.vis.get_render_option().mesh_show_wireframe = True
print(
f"{w_name} initialized. Press:\n"
"\t[SPACE] to pause/start\n"
Expand Down Expand Up @@ -130,6 +138,7 @@ def _register_key_callbacks(self):
self._register_key_callback(["F"], self._toggle_source)
self._register_key_callback(["K"], self._toggle_keypoints)
self._register_key_callback(["M"], self._toggle_map)
self._register_key_callback(["G"], self._toggle_voxel_grid)
self._register_key_callback(["T"], self._toggle_trajectory)
self._register_key_callback(["B"], self._set_black_background)
self._register_key_callback(["W"], self._set_white_background)
Expand Down Expand Up @@ -172,6 +181,16 @@ def _toggle_map(self, vis):
self.render_map = not self.render_map
return False

def _toggle_voxel_grid(self, vis):
if not self.global_view and not self.render_voxel_grid:
print(
"[WARNING] Can't render voxel grid in local view. "
"Open3D does not support VoxelGrid rotation"
)
return
self.render_voxel_grid = not self.render_voxel_grid
return False

def _toggle_view(self, vis):
self.global_view = not self.global_view
self._trajectory_handle()
Expand All @@ -194,7 +213,7 @@ def _trajectory_handle(self):
for frame in self.frames:
self.vis.remove_geometry(frame, reset_bounding_box=False)

def _update_geometries(self, source, keypoints, target, pose):
def _update_geometries(self, source, keypoints, target_map, pose):
# Source hot frame
if self.render_source:
self.source.points = self.o3d.utility.Vector3dVector(source)
Expand All @@ -215,15 +234,26 @@ def _update_geometries(self, source, keypoints, target, pose):

# Target Map
if self.render_map:
target = copy.deepcopy(target)
target = target_map.point_cloud()
self.target.points = self.o3d.utility.Vector3dVector(target)
if self.global_view:
self.target.paint_uniform_color(GRAY)
# self.target.paint_uniform_color(GRAY)
pass
else:
self.target.transform(np.linalg.inv(pose))
else:
self.target.points = self.o3d.utility.Vector3dVector()

# VoxelHashMap
if self.render_voxel_grid and self.global_view:
self.voxel_map.clear()
self.voxel_map.voxel_size = self.voxel_size
voxels = target_map.get_voxels()
for voxel in voxels:
self.voxel_map.add_voxel(self.o3d.geometry.Voxel(voxel, LIGHT_GRAY))
else:
self.voxel_map.clear()

# Update always a list with all the trajectories
new_frame = self.o3d.geometry.TriangleMesh.create_sphere(SPHERE_SIZE)
new_frame.paint_uniform_color(BLUE)
Expand All @@ -237,6 +267,7 @@ def _update_geometries(self, source, keypoints, target, pose):
self.vis.update_geometry(self.keypoints)
self.vis.update_geometry(self.source)
self.vis.update_geometry(self.target)
self.vis.update_geometry(self.voxel_map)
if self.reset_bounding_box:
self.vis.reset_view_point(True)
self.reset_bounding_box = False
Loading