Unverified Commit 8214a977 authored by encore-zhou's avatar encore-zhou Committed by GitHub
Browse files

[Feature] Support open3d visualization (#284)

* add h3d backbone

* add h3d backbone

* add h3dnet

* modify scannet config

* fix bugs for proposal refine

* fix bugs for test backbone

* add primitive head test

* modify h3dhead

* modify h3d head

* update loss weight config

* fix bugs for h3d head loss

* modify h3d head get targets function

* update h3dnet base config

* modify weighted loss

* Revert "Merge branch 'h3d_u2' into 'master'"

This reverts merge request !5

* add open3d visual

* modify docstring

* use bbox and coord convert

* modify docstring

* fix bugs for unittest

* fix bugs for unittest

* modify doc

* add visualize script and modify docs

* modify docs

* fix bugs
parent bdeacecd
......@@ -63,9 +63,16 @@ To see the points, detection results and ground truth of SUNRGBD, ScanNet or KIT
```bash
python tools/test.py ${CONFIG_FILE} ${CKPT_PATH} --eval 'mAP' --options 'show=True' 'out_dir=${SHOW_DIR}'
```
After running this command, you will obtain ***_points.ob, ***_pred.ply files and ***_gt.ply in `${SHOW_DIR}`.
After running this command, you will obtain ***_points.ob, ***_pred.ply files and ***_gt.ply in `${SHOW_DIR}`. When `show` is enabled, [Open3D](http://www.open3d.org/) will be used to visualize the results online. You need to set `show=False` while running test in remote server withou GUI.
You can use 3D visualization software such as the [MeshLab](http://www.meshlab.net/) to open the these files under `${SHOW_DIR}` to see the 3D detection output. Specifically, open `***_points.obj` to see the input point cloud and open `***_pred.ply` to see the predicted 3D bounding boxes. This allows the inference and results generation be done in remote server and the users can open them on their host with GUI.
As for offline visualization, you will have two options.
To visualize the results with `Open3D` backend, you can run the following command
```bash
python tools/visualize_results.py ${CONFIG_FILE} --result ${RESULTS_PATH} --show-dir ${SHOW_DIR}'
```
![Open3D_visualization](../resources/open3d_visual.gif)
Or you can use 3D visualization software such as the [MeshLab](http://www.meshlab.net/) to open the these files under `${SHOW_DIR}` to see the 3D detection output. Specifically, open `***_points.obj` to see the input point cloud and open `***_pred.ply` to see the predicted 3D bounding boxes. This allows the inference and results generation be done in remote server and the users can open them on their host with GUI.
**Notice**: The visualization API is a little unstable since we plan to refactor these parts together with MMDetection in the future.
......
import cv2
import numpy as np
import open3d as o3d
import torch
from matplotlib import pyplot as plt
from open3d import geometry
def _draw_points(points,
vis,
points_size=2,
point_color=(0.5, 0.5, 0.5),
mode='xyz'):
"""Draw points on visualizer.
Args:
points (numpy.array | torch.tensor, shape=[N, 3+C]):
points to visualize.
vis (:obj:`open3d.visualization.Visualizer`): open3d visualizer.
points_size (int): the size of points to show on visualizer.
Default: 2.
point_color (tuple[float]): the color of points.
Default: (0.5, 0.5, 0.5).
mode (str): indicate type of the input points, avaliable mode
['xyz', 'xyzrgb']. Default: 'xyz'.
Returns:
tuple: points, color of each point.
"""
vis.get_render_option().point_size = points_size # set points size
if isinstance(points, torch.Tensor):
points = points.cpu().numpy()
points = points.copy()
pcd = geometry.PointCloud()
if mode == 'xyz':
pcd.points = o3d.utility.Vector3dVector(points[:, :3])
points_colors = np.tile(np.array(point_color), (points.shape[0], 1))
elif mode == 'xyzrgb':
pcd.points = o3d.utility.Vector3dVector(points[:, :3])
points_colors = points[:, 3:6]
else:
raise NotImplementedError
pcd.colors = o3d.utility.Vector3dVector(points_colors)
vis.add_geometry(pcd)
return pcd, points_colors
def _draw_bboxes(bbox3d,
vis,
points_colors,
pcd=None,
bbox_color=(0, 1, 0),
points_in_box_color=(1, 0, 0),
rot_axis=2,
center_mode='lidar_bottom',
mode='xyz'):
"""Draw bbox on visualizer and change the color of points inside bbox3d.
Args:
bbox3d (numpy.array | torch.tensor, shape=[M, 7]):
3d bbox (x, y, z, dx, dy, dz, yaw) to visualize.
vis (:obj:`open3d.visualization.Visualizer`): open3d visualizer.
points_colors (numpy.array): color of each points.
pcd (:obj:`open3d.geometry.PointCloud`): point cloud. Default: None.
bbox_color (tuple[float]): the color of bbox. Default: (0, 1, 0).
points_in_box_color (tuple[float]):
the color of points inside bbox3d. Default: (1, 0, 0).
rot_axis (int): rotation axis of bbox. Default: 2.
center_mode (bool): indicate the center of bbox is bottom center
or gravity center. avaliable mode
['lidar_bottom', 'camera_bottom']. Default: 'lidar_bottom'.
mode (str): indicate type of the input points, avaliable mode
['xyz', 'xyzrgb']. Default: 'xyz'.
"""
if isinstance(bbox3d, torch.Tensor):
bbox3d = bbox3d.cpu().numpy()
bbox3d = bbox3d.copy()
in_box_color = np.array(points_in_box_color)
for i in range(len(bbox3d)):
center = bbox3d[i, 0:3]
dim = bbox3d[i, 3:6]
yaw = np.zeros(3)
yaw[rot_axis] = -bbox3d[i, 6]
rot_mat = geometry.get_rotation_matrix_from_xyz(yaw)
if center_mode == 'lidar_bottom':
center[rot_axis] += dim[
rot_axis] / 2 # bottom center to gravity center
elif center_mode == 'camera_bottom':
center[rot_axis] -= dim[
rot_axis] / 2 # bottom center to gravity center
box3d = geometry.OrientedBoundingBox(center, rot_mat, dim)
line_set = geometry.LineSet.create_from_oriented_bounding_box(box3d)
line_set.paint_uniform_color(bbox_color)
# draw bboxes on visualizer
vis.add_geometry(line_set)
# change the color of points which are in box
if pcd is not None and mode == 'xyz':
indices = box3d.get_point_indices_within_bounding_box(pcd.points)
points_colors[indices] = in_box_color
# update points colors
if pcd is not None:
pcd.colors = o3d.utility.Vector3dVector(points_colors)
vis.update_geometry(pcd)
def show_pts_boxes(points,
bbox3d=None,
show=True,
save_path=None,
points_size=2,
point_color=(0.5, 0.5, 0.5),
bbox_color=(0, 1, 0),
points_in_box_color=(1, 0, 0),
rot_axis=2,
center_mode='lidar_bottom',
mode='xyz'):
"""Draw bbox and points on visualizer.
Args:
points (numpy.array | torch.tensor, shape=[N, 3+C]):
points to visualize.
bbox3d (numpy.array | torch.tensor, shape=[M, 7]):
3d bbox (x, y, z, dx, dy, dz, yaw) to visualize. Default: None.
show (bool): whether to show the visualization results. Default: True.
save_path (str): path to save visualized results. Default: None.
points_size (int): the size of points to show on visualizer.
Default: 2.
point_color (tuple[float]): the color of points.
Default: (0.5, 0.5, 0.5).
bbox_color (tuple[float]): the color of bbox. Default: (0, 1, 0).
points_in_box_color (tuple[float]):
the color of points which are in bbox3d. Default: (1, 0, 0).
rot_axis (int): rotation axis of bbox. Default: 2.
center_mode (bool): indicate the center of bbox is bottom center
or gravity center. avaliable mode
['lidar_bottom', 'camera_bottom']. Default: 'lidar_bottom'.
mode (str): indicate type of the input points, avaliable mode
['xyz', 'xyzrgb']. Default: 'xyz'.
"""
# TODO: support score and class info
assert 0 <= rot_axis <= 2
# init visualizer
vis = o3d.visualization.Visualizer()
vis.create_window()
mesh_frame = geometry.TriangleMesh.create_coordinate_frame(
size=1, origin=[0, 0, 0]) # create coordinate frame
vis.add_geometry(mesh_frame)
# draw points
pcd, points_colors = _draw_points(points, vis, points_size, point_color,
mode)
# draw boxes
if bbox3d is not None:
_draw_bboxes(bbox3d, vis, points_colors, pcd, bbox_color,
points_in_box_color, rot_axis, center_mode, mode)
if show:
vis.run()
if save_path is not None:
vis.capture_screen_image(save_path)
vis.destroy_window()
def _draw_bboxes_ind(bbox3d,
vis,
indices,
points_colors,
pcd=None,
bbox_color=(0, 1, 0),
points_in_box_color=(1, 0, 0),
rot_axis=2,
center_mode='lidar_bottom',
mode='xyz'):
"""Draw bbox on visualizer and change the color or points inside bbox3d
with indices.
Args:
bbox3d (numpy.array | torch.tensor, shape=[M, 7]):
3d bbox (x, y, z, dx, dy, dz, yaw) to visualize.
vis (:obj:`open3d.visualization.Visualizer`): open3d visualizer.
indices (numpy.array | torch.tensor, shape=[N, M]):
indicate which bbox3d that each point lies in.
points_colors (numpy.array): color of each points.
pcd (:obj:`open3d.geometry.PointCloud`): point cloud. Default: None.
bbox_color (tuple[float]): the color of bbox. Default: (0, 1, 0).
points_in_box_color (tuple[float]):
the color of points which are in bbox3d. Default: (1, 0, 0).
rot_axis (int): rotation axis of bbox. Default: 2.
center_mode (bool): indicate the center of bbox is bottom center
or gravity center. avaliable mode
['lidar_bottom', 'camera_bottom']. Default: 'lidar_bottom'.
mode (str): indicate type of the input points, avaliable mode
['xyz', 'xyzrgb']. Default: 'xyz'.
"""
if isinstance(bbox3d, torch.Tensor):
bbox3d = bbox3d.cpu().numpy()
if isinstance(indices, torch.Tensor):
indices = indices.cpu().numpy()
bbox3d = bbox3d.copy()
in_box_color = np.array(points_in_box_color)
for i in range(len(bbox3d)):
center = bbox3d[i, 0:3]
dim = bbox3d[i, 3:6]
yaw = np.zeros(3)
# TODO: fix problem of current coordinate system
# dim[0], dim[1] = dim[1], dim[0] # for current coordinate
# yaw[rot_axis] = -(bbox3d[i, 6] - 0.5 * np.pi)
yaw[rot_axis] = -bbox3d[i, 6]
rot_mat = geometry.get_rotation_matrix_from_xyz(yaw)
if center_mode == 'lidar_bottom':
center[rot_axis] += dim[
rot_axis] / 2 # bottom center to gravity center
elif center_mode == 'camera_bottom':
center[rot_axis] -= dim[
rot_axis] / 2 # bottom center to gravity center
box3d = geometry.OrientedBoundingBox(center, rot_mat, dim)
line_set = geometry.LineSet.create_from_oriented_bounding_box(box3d)
line_set.paint_uniform_color(bbox_color)
# draw bboxes on visualizer
vis.add_geometry(line_set)
# change the color of points which are in box
if pcd is not None and mode == 'xyz':
points_colors[indices[:, i].astype(np.bool)] = in_box_color
# update points colors
if pcd is not None:
pcd.colors = o3d.utility.Vector3dVector(points_colors)
vis.update_geometry(pcd)
def show_pts_index_boxes(points,
bbox3d=None,
show=True,
indices=None,
save_path=None,
points_size=2,
point_color=(0.5, 0.5, 0.5),
bbox_color=(0, 1, 0),
points_in_box_color=(1, 0, 0),
rot_axis=2,
center_mode='lidar_bottom',
mode='xyz'):
"""Draw bbox and points on visualizer with indices that indicate which
bbox3d that each point lies in.
Args:
points (numpy.array | torch.tensor, shape=[N, 3+C]):
points to visualize.
bbox3d (numpy.array | torch.tensor, shape=[M, 7]):
3d bbox (x, y, z, dx, dy, dz, yaw) to visualize. Default: None.
show (bool): whether to show the visualization results. Default: True.
indices (numpy.array | torch.tensor, shape=[N, M]):
indicate which bbox3d that each point lies in. Default: None.
save_path (str): path to save visualized results. Default: None.
points_size (int): the size of points to show on visualizer.
Default: 2.
point_color (tuple[float]): the color of points.
Default: (0.5, 0.5, 0.5).
bbox_color (tuple[float]): the color of bbox. Default: (0, 1, 0).
points_in_box_color (tuple[float]):
the color of points which are in bbox3d. Default: (1, 0, 0).
rot_axis (int): rotation axis of bbox. Default: 2.
center_mode (bool): indicate the center of bbox is bottom center
or gravity center. avaliable mode
['lidar_bottom', 'camera_bottom']. Default: 'lidar_bottom'.
mode (str): indicate type of the input points, avaliable mode
['xyz', 'xyzrgb']. Default: 'xyz'.
"""
# TODO: support score and class info
assert 0 <= rot_axis <= 2
# init visualizer
vis = o3d.visualization.Visualizer()
vis.create_window()
mesh_frame = geometry.TriangleMesh.create_coordinate_frame(
size=1, origin=[0, 0, 0]) # create coordinate frame
vis.add_geometry(mesh_frame)
# draw points
pcd, points_colors = _draw_points(points, vis, points_size, point_color,
mode)
# draw boxes
if bbox3d is not None:
_draw_bboxes_ind(bbox3d, vis, indices, points_colors, pcd, bbox_color,
points_in_box_color, rot_axis, center_mode, mode)
if show:
vis.run()
if save_path is not None:
vis.capture_screen_image(save_path)
vis.destroy_window()
def project_pts_on_img(points,
raw_img,
lidar2img_rt,
max_distance=70,
thickness=-1):
"""Project the 3D points cloud on 2D image.
Args:
points (numpy.array): 3D points cloud (x, y, z) to visualize.
raw_img (numpy.array): The numpy array of image.
lidar2img_rt (numpy.array, shape=[4, 4]): The projection matrix
according to the camera intrinsic parameters.
max_distance (float): the max distance of the points cloud.
Default: 70.
thickness (int, optional): The thickness of 2D points. Default: -1.
"""
img = raw_img.copy()
num_points = points.shape[0]
pts_4d = np.concatenate([points[:, :3], np.ones((num_points, 1))], axis=-1)
pts_2d = pts_4d @ lidar2img_rt.T
# cam_points is Tensor of Nx4 whose last column is 1
# transform camera coordinate to image coordinate
pts_2d[:, 2] = np.clip(pts_2d[:, 2], a_min=1e-5, a_max=99999)
pts_2d[:, 0] /= pts_2d[:, 2]
pts_2d[:, 1] /= pts_2d[:, 2]
fov_inds = ((pts_2d[:, 0] < img.shape[1])
& (pts_2d[:, 0] >= 0)
& (pts_2d[:, 1] < img.shape[0])
& (pts_2d[:, 1] >= 0))
imgfov_pts_2d = pts_2d[fov_inds, :3] # u, v, d
cmap = plt.cm.get_cmap('hsv', 256)
cmap = np.array([cmap(i) for i in range(256)])[:, :3] * 255
for i in range(imgfov_pts_2d.shape[0]):
depth = imgfov_pts_2d[i, 2]
color = cmap[np.clip(int(max_distance * 10 / depth), 0, 255), :]
cv2.circle(
img,
center=(int(np.round(imgfov_pts_2d[i, 0])),
int(np.round(imgfov_pts_2d[i, 1]))),
radius=1,
color=tuple(color),
thickness=thickness,
)
cv2.imshow('project_pts_img', img)
cv2.waitKey(100)
def project_bbox3d_on_img(bboxes3d,
raw_img,
lidar2img_rt,
color=(0, 255, 0),
thickness=1):
"""Project the 3D bbox on 2D image.
Args:
bboxes3d (numpy.array, shape=[M, 7]):
3d bbox (x, y, z, dx, dy, dz, yaw) to visualize.
raw_img (numpy.array): The numpy array of image.
lidar2img_rt (numpy.array, shape=[4, 4]): The projection matrix
according to the camera intrinsic parameters.
color (tuple[int]): the color to draw bboxes. Default: (0, 255, 0).
thickness (int, optional): The thickness of bboxes. Default: 1.
"""
img = raw_img.copy()
corners_3d = bboxes3d.corners
num_bbox = corners_3d.shape[0]
pts_4d = np.concatenate(
[corners_3d.reshape(-1, 3),
np.ones((num_bbox * 8, 1))], axis=-1)
pts_2d = pts_4d @ lidar2img_rt.T
pts_2d[:, 2] = np.clip(pts_2d[:, 2], a_min=1e-5, a_max=1e5)
pts_2d[:, 0] /= pts_2d[:, 2]
pts_2d[:, 1] /= pts_2d[:, 2]
imgfov_pts_2d = pts_2d[..., :2].reshape(num_bbox, 8, 2)
line_indices = ((0, 1), (0, 3), (0, 4), (1, 2), (1, 5), (3, 2), (3, 7),
(4, 5), (4, 7), (2, 6), (5, 6), (6, 7))
for i in range(num_bbox):
corners = imgfov_pts_2d[i].astype(np.int)
for start, end in line_indices:
cv2.line(img, (corners[start, 0], corners[start, 1]),
(corners[end, 0], corners[end, 1]), color, thickness,
cv2.LINE_AA)
cv2.imshow('project_bbox3d_img', img)
cv2.waitKey(0)
class Visualizer(object):
r"""Online visualizer implemented with Open3d.
Args:
points (numpy.array, shape=[N, 3+C]): Points to visualize. The Points
cloud is in mode of Coord3DMode.DEPTH (please refer to
core.structures.coord_3d_mode).
bbox3d (numpy.array, shape=[M, 7]): 3d bbox (x, y, z, dx, dy, dz, yaw)
to visualize. The 3d bbox is in mode of Box3DMode.DEPTH with
gravity_center (please refer to core.structures.box_3d_mode).
Default: None.
save_path (str): path to save visualized results. Default: None.
points_size (int): the size of points to show on visualizer.
Default: 2.
point_color (tuple[float]): the color of points.
Default: (0.5, 0.5, 0.5).
bbox_color (tuple[float]): the color of bbox. Default: (0, 1, 0).
points_in_box_color (tuple[float]):
the color of points which are in bbox3d. Default: (1, 0, 0).
rot_axis (int): rotation axis of bbox. Default: 2.
center_mode (bool): indicate the center of bbox is bottom center
or gravity center. avaliable mode
['lidar_bottom', 'camera_bottom']. Default: 'lidar_bottom'.
mode (str): indicate type of the input points, avaliable mode
['xyz', 'xyzrgb']. Default: 'xyz'.
"""
def __init__(self,
points,
bbox3d=None,
save_path=None,
points_size=2,
point_color=(0.5, 0.5, 0.5),
bbox_color=(0, 1, 0),
points_in_box_color=(1, 0, 0),
rot_axis=2,
center_mode='lidar_bottom',
mode='xyz'):
super(Visualizer, self).__init__()
assert 0 <= rot_axis <= 2
# init visualizer
self.o3d_visualizer = o3d.visualization.Visualizer()
self.o3d_visualizer.create_window()
mesh_frame = geometry.TriangleMesh.create_coordinate_frame(
size=1, origin=[0, 0, 0]) # create coordinate frame
self.o3d_visualizer.add_geometry(mesh_frame)
self.points_size = points_size
self.point_color = point_color
self.bbox_color = bbox_color
self.points_in_box_color = points_in_box_color
self.rot_axis = rot_axis
self.center_mode = center_mode
self.mode = mode
# draw points
if points is not None:
self.pcd, self.points_colors = _draw_points(
points, self.o3d_visualizer, points_size, point_color, mode)
# draw boxes
if bbox3d is not None:
_draw_bboxes(bbox3d, self.o3d_visualizer, self.points_colors,
self.pcd, bbox_color, points_in_box_color, rot_axis,
center_mode, mode)
def add_bboxes(self, bbox3d, bbox_color=None, points_in_box_color=None):
"""Add bounding box to visualizer.
Args:
bbox3d (numpy.array, shape=[M, 7]):
3D bbox (x, y, z, dx, dy, dz, yaw) to be visualized.
The 3d bbox is in mode of Box3DMode.DEPTH with
gravity_center (please refer to core.structures.box_3d_mode).
bbox_color (tuple[float]): the color of bbox. Defaule: None.
points_in_box_color (tuple[float]): the color of points which
are in bbox3d. Defaule: None.
"""
if bbox_color is None:
bbox_color = self.bbox_color
if points_in_box_color is None:
points_in_box_color = self.points_in_box_color
_draw_bboxes(bbox3d, self.o3d_visualizer, self.points_colors, self.pcd,
bbox_color, points_in_box_color, self.rot_axis,
self.center_mode, self.mode)
def show(self, save_path=None):
"""Visualize the points cloud.
Args:
save_path (str): path to save image. Default: None.
"""
self.o3d_visualizer.run()
if save_path is not None:
self.o3d_visualizer.capture_screen_image(save_path)
self.o3d_visualizer.destroy_window()
return
......@@ -3,6 +3,8 @@ import numpy as np
import trimesh
from os import path as osp
from .open3d_vis import Visualizer
def _write_ply(points, out_filename):
"""Write points into ``ply`` format for meshlab visualization.
......@@ -68,7 +70,7 @@ def _write_oriented_bbox(scene_bbox, out_filename):
return
def show_result(points, gt_bboxes, pred_bboxes, out_dir, filename):
def show_result(points, gt_bboxes, pred_bboxes, out_dir, filename, show=True):
"""Convert results into format that is directly readable for meshlab.
Args:
......@@ -77,18 +79,34 @@ def show_result(points, gt_bboxes, pred_bboxes, out_dir, filename):
pred_bboxes (np.ndarray): Predicted boxes.
out_dir (str): Path of output directory
filename (str): Filename of the current frame.
show (bool): Visualize the results online.
"""
if show:
vis = Visualizer(points)
if pred_bboxes is not None:
vis.add_bboxes(bbox3d=pred_bboxes)
if gt_bboxes is not None:
vis.add_bboxes(bbox3d=gt_bboxes, bbox_color=(0, 0, 1))
vis.show()
result_path = osp.join(out_dir, filename)
mmcv.mkdir_or_exist(result_path)
if points is not None:
_write_ply(points, osp.join(result_path, f'{filename}_points.obj'))
if gt_bboxes is not None:
# bottom center to gravity center
gt_bboxes[..., 2] += gt_bboxes[..., 5] / 2
# the positive direction for yaw in meshlab is clockwise
gt_bboxes[:, 6] *= -1
_write_oriented_bbox(gt_bboxes,
osp.join(result_path, f'{filename}_gt.ply'))
if points is not None:
_write_ply(points, osp.join(result_path, f'{filename}_points.obj'))
if pred_bboxes is not None:
# bottom center to gravity center
pred_bboxes[..., 2] += pred_bboxes[..., 5] / 2
# the positive direction for yaw in meshlab is clockwise
pred_bboxes[:, 6] *= -1
_write_oriented_bbox(pred_bboxes,
osp.join(result_path, f'{filename}_pred.ply'))
......@@ -9,7 +9,8 @@ from os import path as osp
from mmdet.datasets import DATASETS
from ..core import show_result
from ..core.bbox import Box3DMode, CameraInstance3DBoxes, points_cam2img
from ..core.bbox import (Box3DMode, CameraInstance3DBoxes, Coord3DMode,
points_cam2img)
from .custom_3d import Custom3DDataset
......@@ -669,12 +670,13 @@ class KittiDataset(Custom3DDataset):
sample_idx=sample_idx,
)
def show(self, results, out_dir):
def show(self, results, out_dir, show=True):
"""Results visualization.
Args:
results (list[dict]): List of bounding boxes results.
out_dir (str): Output directory of visualization result.
show (bool): Visualize the results online.
"""
assert out_dir is not None, 'Expect out_dir, got none.'
for i, result in enumerate(results):
......@@ -684,14 +686,13 @@ class KittiDataset(Custom3DDataset):
file_name = osp.split(pts_path)[-1].split('.')[0]
# for now we convert points into depth mode
points = example['points'][0]._data.numpy()
points = points[..., [1, 0, 2]]
points[..., 0] *= -1
points = Coord3DMode.convert_point(points, Coord3DMode.LIDAR,
Coord3DMode.DEPTH)
gt_bboxes = self.get_ann_info(i)['gt_bboxes_3d'].tensor
gt_bboxes = Box3DMode.convert(gt_bboxes, Box3DMode.LIDAR,
Box3DMode.DEPTH)
gt_bboxes[..., 2] += gt_bboxes[..., 5] / 2
pred_bboxes = result['boxes_3d'].tensor.numpy()
pred_bboxes = Box3DMode.convert(pred_bboxes, Box3DMode.LIDAR,
Box3DMode.DEPTH)
pred_bboxes[..., 2] += pred_bboxes[..., 5] / 2
show_result(points, gt_bboxes, pred_bboxes, out_dir, file_name)
show_result(points, gt_bboxes, pred_bboxes, out_dir, file_name,
show)
......@@ -10,7 +10,7 @@ from pyquaternion import Quaternion
from mmdet3d.core.evaluation.lyft_eval import lyft_eval
from mmdet.datasets import DATASETS
from ..core import show_result
from ..core.bbox import Box3DMode, LiDARInstance3DBoxes
from ..core.bbox import Box3DMode, Coord3DMode, LiDARInstance3DBoxes
from .custom_3d import Custom3DDataset
......@@ -412,17 +412,15 @@ class LyftDataset(Custom3DDataset):
pts_path = data_info['lidar_path']
file_name = osp.split(pts_path)[-1].split('.')[0]
# for now we convert points into depth mode
points = points[..., [1, 0, 2]]
points[..., 0] *= -1
points = Coord3DMode.convert_point(points, Coord3DMode.LIDAR,
Coord3DMode.DEPTH)
inds = result['pts_bbox']['scores_3d'] > 0.1
gt_bboxes = self.get_ann_info(i)['gt_bboxes_3d'].tensor
gt_bboxes = Box3DMode.convert(gt_bboxes, Box3DMode.LIDAR,
Box3DMode.DEPTH)
gt_bboxes[..., 2] += gt_bboxes[..., 5] / 2
pred_bboxes = result['pts_bbox']['boxes_3d'][inds].tensor.numpy()
pred_bboxes = Box3DMode.convert(pred_bboxes, Box3DMode.LIDAR,
Box3DMode.DEPTH)
pred_bboxes[..., 2] += pred_bboxes[..., 5] / 2
show_result(points, gt_bboxes, pred_bboxes, out_dir, file_name)
def json2csv(self, json_path, csv_savepath):
......
......@@ -7,7 +7,7 @@ from os import path as osp
from mmdet.datasets import DATASETS
from ..core import show_result
from ..core.bbox import Box3DMode, LiDARInstance3DBoxes
from ..core.bbox import Box3DMode, Coord3DMode, LiDARInstance3DBoxes
from .custom_3d import Custom3DDataset
......@@ -504,17 +504,15 @@ class NuScenesDataset(Custom3DDataset):
pts_path = data_info['lidar_path']
file_name = osp.split(pts_path)[-1].split('.')[0]
# for now we convert points into depth mode
points = points[..., [1, 0, 2]]
points[..., 0] *= -1
points = Coord3DMode.convert_point(points, Coord3DMode.LIDAR,
Coord3DMode.DEPTH)
inds = result['pts_bbox']['scores_3d'] > 0.1
gt_bboxes = self.get_ann_info(i)['gt_bboxes_3d'].tensor
gt_bboxes = Box3DMode.convert(gt_bboxes, Box3DMode.LIDAR,
Box3DMode.DEPTH)
gt_bboxes[..., 2] += gt_bboxes[..., 5] / 2
pred_bboxes = result['pts_bbox']['boxes_3d'][inds].tensor.numpy()
pred_bboxes = Box3DMode.convert(pred_bboxes, Box3DMode.LIDAR,
Box3DMode.DEPTH)
pred_bboxes[..., 2] += pred_bboxes[..., 5] / 2
show_result(points, gt_bboxes, pred_bboxes, out_dir, file_name)
......
......@@ -106,12 +106,13 @@ class ScanNetDataset(Custom3DDataset):
pts_semantic_mask_path=pts_semantic_mask_path)
return anns_results
def show(self, results, out_dir):
def show(self, results, out_dir, show=True):
"""Results visualization.
Args:
results (list[dict]): List of bounding boxes results.
out_dir (str): Output directory of visualization result.
show (bool): Visualize the results online.
"""
assert out_dir is not None, 'Expect out_dir, got none.'
for i, result in enumerate(results):
......@@ -121,8 +122,7 @@ class ScanNetDataset(Custom3DDataset):
points = np.fromfile(
osp.join(self.data_root, pts_path),
dtype=np.float32).reshape(-1, 6)
gt_bboxes = np.pad(data_info['annos']['gt_boxes_upright_depth'],
((0, 0), (0, 1)), 'constant')
gt_bboxes = self.get_ann_info(i)['gt_bboxes_3d'].tensor
pred_bboxes = result['boxes_3d'].tensor.numpy()
pred_bboxes[..., 2] += pred_bboxes[..., 5] / 2
show_result(points, gt_bboxes, pred_bboxes, out_dir, file_name)
show_result(points, gt_bboxes, pred_bboxes, out_dir, file_name,
show)
......@@ -93,12 +93,13 @@ class SUNRGBDDataset(Custom3DDataset):
gt_bboxes_3d=gt_bboxes_3d, gt_labels_3d=gt_labels_3d)
return anns_results
def show(self, results, out_dir):
def show(self, results, out_dir, show=True):
"""Results visualization.
Args:
results (list[dict]): List of bounding boxes results.
out_dir (str): Output directory of visualization result.
show (bool): Visualize the results online.
"""
assert out_dir is not None, 'Expect out_dir, got none.'
for i, result in enumerate(results):
......@@ -109,10 +110,7 @@ class SUNRGBDDataset(Custom3DDataset):
osp.join(self.data_root, pts_path),
dtype=np.float32).reshape(-1, 6)
points[:, 3:] *= 255
if data_info['annos']['gt_num'] > 0:
gt_bboxes = data_info['annos']['gt_boxes_upright_depth']
else:
gt_bboxes = np.zeros((0, 7))
gt_bboxes = self.get_ann_info(i)['gt_bboxes_3d'].tensor
pred_bboxes = result['boxes_3d'].tensor.numpy()
pred_bboxes[..., 2] += pred_bboxes[..., 5] / 2
show_result(points, gt_bboxes, pred_bboxes, out_dir, file_name)
show_result(points, gt_bboxes, pred_bboxes, out_dir, file_name,
show)
import copy
import mmcv
import torch
from mmcv.parallel import DataContainer as DC
from mmcv.runner import auto_fp16
from os import path as osp
from mmdet3d.core import Box3DMode, show_result
from mmdet3d.core import Box3DMode, Coord3DMode, show_result
from mmdet.models.detectors import BaseDetector
......@@ -92,20 +91,17 @@ class Base3DDetector(BaseDetector):
assert out_dir is not None, 'Expect out_dir, got none.'
pred_bboxes = copy.deepcopy(
result[batch_id]['boxes_3d'].tensor.numpy())
# for now we convert points into depth mode
if box_mode_3d == Box3DMode.DEPTH:
pred_bboxes[..., 2] += pred_bboxes[..., 5] / 2
elif (box_mode_3d == Box3DMode.CAM) or (box_mode_3d
== Box3DMode.LIDAR):
points = points[..., [1, 0, 2]]
points[..., 0] *= -1
pred_bboxes = result[batch_id]['boxes_3d']
# for now we convert points and bbox into depth mode
if (box_mode_3d == Box3DMode.CAM) or (box_mode_3d
== Box3DMode.LIDAR):
points = Coord3DMode.convert_point(points, Coord3DMode.LIDAR,
Coord3DMode.DEPTH)
pred_bboxes = Box3DMode.convert(pred_bboxes, box_mode_3d,
Box3DMode.DEPTH)
pred_bboxes[..., 2] += pred_bboxes[..., 5] / 2
else:
elif box_mode_3d != Box3DMode.DEPTH:
ValueError(
f'Unsupported box_mode_3d {box_mode_3d} for convertion!')
pred_bboxes = pred_bboxes.tensor.cpu().numpy()
show_result(points, None, pred_bboxes, out_dir, file_name)
import copy
import mmcv
import torch
from mmcv.parallel import DataContainer as DC
......@@ -7,8 +6,8 @@ from os import path as osp
from torch import nn as nn
from torch.nn import functional as F
from mmdet3d.core import (Box3DMode, bbox3d2result, merge_aug_bboxes_3d,
show_result)
from mmdet3d.core import (Box3DMode, Coord3DMode, bbox3d2result,
merge_aug_bboxes_3d, show_result)
from mmdet3d.ops import Voxelization
from mmdet.core import multi_apply
from mmdet.models import DETECTORS
......@@ -486,19 +485,18 @@ class MVXTwoStageDetector(Base3DDetector):
assert out_dir is not None, 'Expect out_dir, got none.'
inds = result[batch_id]['pts_bbox']['scores_3d'] > 0.1
pred_bboxes = copy.deepcopy(
result[batch_id]['pts_bbox']['boxes_3d'][inds].tensor.numpy())
# for now we convert points into depth mode
if box_mode_3d == Box3DMode.DEPTH:
pred_bboxes[..., 2] += pred_bboxes[..., 5] / 2
elif (box_mode_3d == Box3DMode.CAM) or (box_mode_3d
== Box3DMode.LIDAR):
points = points[..., [1, 0, 2]]
points[..., 0] *= -1
pred_bboxes = result[batch_id]['pts_bbox']['boxes_3d'][inds]
# for now we convert points and bbox into depth mode
if (box_mode_3d == Box3DMode.CAM) or (box_mode_3d
== Box3DMode.LIDAR):
points = Coord3DMode.convert_point(points, Coord3DMode.LIDAR,
Coord3DMode.DEPTH)
pred_bboxes = Box3DMode.convert(pred_bboxes, box_mode_3d,
Box3DMode.DEPTH)
pred_bboxes[..., 2] += pred_bboxes[..., 5] / 2
else:
elif box_mode_3d != Box3DMode.DEPTH:
ValueError(
f'Unsupported box_mode_3d {box_mode_3d} for convertion!')
pred_bboxes = pred_bboxes.tensor.cpu().numpy()
show_result(points, None, pred_bboxes, out_dir, file_name)
......@@ -5,6 +5,7 @@ interrogate
isort
# Note: used for kwarray.group_items, this may be ported to mmcv in the future.
kwarray
open3d
pytest
pytest-cov
pytest-runner
......
......@@ -8,6 +8,6 @@ line_length = 79
multi_line_output = 0
known_standard_library = setuptools
known_first_party = mmdet,mmdet3d
known_third_party = load_scannet_data,lyft_dataset_sdk,m2r,matplotlib,mmcv,nuimages,numba,numpy,nuscenes,pandas,plyfile,pycocotools,pyquaternion,pytest,recommonmark,scannet_utils,scipy,seaborn,shapely,skimage,tensorflow,terminaltables,torch,trimesh,waymo_open_dataset
known_third_party = cv2,load_scannet_data,lyft_dataset_sdk,m2r,matplotlib,mmcv,nuimages,numba,numpy,nuscenes,open3d,pandas,plyfile,pycocotools,pyquaternion,pytest,recommonmark,scannet_utils,scipy,seaborn,shapely,skimage,tensorflow,terminaltables,torch,trimesh,waymo_open_dataset
no_lines_before = STDLIB,LOCALFOLDER
default_section = THIRDPARTY
......@@ -157,7 +157,7 @@ def test_show():
labels_3d = torch.tensor([0, 0, 1, 1, 2])
result = dict(boxes_3d=boxes_3d, scores_3d=scores_3d, labels_3d=labels_3d)
results = [result]
kitti_dataset.show(results, temp_dir)
kitti_dataset.show(results, temp_dir, show=False)
pts_file_path = osp.join(temp_dir, '000000', '000000_points.obj')
gt_file_path = osp.join(temp_dir, '000000', '000000_gt.ply')
pred_file_path = osp.join(temp_dir, '000000', '000000_pred.ply')
......
......@@ -201,7 +201,7 @@ def test_show():
labels_3d = torch.tensor([0, 0, 0, 0, 0])
result = dict(boxes_3d=boxes_3d, scores_3d=scores_3d, labels_3d=labels_3d)
results = [result]
scannet_dataset.show(results, temp_dir)
scannet_dataset.show(results, temp_dir, show=False)
pts_file_path = osp.join(temp_dir, 'scene0000_00',
'scene0000_00_points.obj')
gt_file_path = osp.join(temp_dir, 'scene0000_00', 'scene0000_00_gt.ply')
......
......@@ -145,7 +145,7 @@ def test_show():
labels_3d = torch.tensor([0, 0, 0, 0, 0])
result = dict(boxes_3d=boxes_3d, scores_3d=scores_3d, labels_3d=labels_3d)
results = [result]
sunrgbd_dataset.show(results, temp_dir)
sunrgbd_dataset.show(results, temp_dir, show=False)
pts_file_path = osp.join(temp_dir, '000001', '000001_points.obj')
gt_file_path = osp.join(temp_dir, '000001', '000001_gt.ply')
pred_file_path = osp.join(temp_dir, '000001', '000001_pred.ply')
......
import argparse
import mmcv
from mmcv import Config
from mmdet3d.datasets import build_dataset
def parse_args():
parser = argparse.ArgumentParser(
description='MMDet3D visualize the results')
parser.add_argument('config', help='test config file path')
parser.add_argument('--result', help='results file in pickle format')
parser.add_argument(
'--show-dir', help='directory where visualize results will be saved')
args = parser.parse_args()
return args
def main():
args = parse_args()
if args.result is not None and \
not args.result.endswith(('.pkl', '.pickle')):
raise ValueError('The results file must be a pkl file.')
cfg = Config.fromfile(args.config)
cfg.data.test.test_mode = True
# build the dataset
dataset = build_dataset(cfg.data.test)
results = mmcv.load(args.result)
if getattr(dataset, 'show', None) is not None:
dataset.show(results, args.show_dir)
else:
raise NotImplementedError(
'Show is not implemented for dataset {}!'.format(
type(dataset).__name__))
if __name__ == '__main__':
main()
Markdown is supported
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment