Skip to content

Commit 838cfb4

Browse files
committed
fix hardcoded ycbv, some issues with panda batch and cosy eval doc
1 parent 10324d5 commit 838cfb4

File tree

4 files changed

+28
-15
lines changed

4 files changed

+28
-15
lines changed

docs/book/cosypose/evaluate.md

+10-4
Original file line numberDiff line numberDiff line change
@@ -1,11 +1,17 @@
1-
# Evaluating CosyPose
1+
# CosyPose single view evaluation
22

33
Please make sure you followed the steps relative to the evaluation in the main readme.
44

5-
Please run the following command to evaluate on YCBV dataset
5+
To evaluate on YCBV dataset:
66

77
```
8-
python -m happypose.pose_estimators.cosypose.cosypose.scripts.run_full_cosypose_eval_new detector_run_id=bop_pbr coarse_run_id=coarse-bop-ycbv-pbr--724183 refiner_run_id=refiner-bop-ycbv-pbr--604090 ds_names=["ycbv.bop19"] result_id=ycbv-debug detection_coarse_types=["detector"]
8+
python -m happypose.pose_estimators.cosypose.cosypose.scripts.run_full_cosypose_eval_new detector_run_id=bop_pbr coarse_run_id=coarse-bop-ycbv-pbr--724183 refiner_run_id=refiner-bop-ycbv-pbr--604090 ds_names=["ycbv.bop19"] result_id=ycbv-debug detection_coarse_types=["detector"] inference.renderer=bullet inference.n_workers=0
99
```
1010

11-
The other BOP datasets are supported as long as you download the correspond models.
11+
To change the renderer from bullet (originally used by cosypose) to panda3d:
12+
```
13+
python -m happypose.pose_estimators.cosypose.cosypose.scripts.run_full_cosypose_eval_new detector_run_id=bop_pbr coarse_run_id=coarse-bop-ycbv-pbr--724183 refiner_run_id=refiner-bop-ycbv-pbr--604090 ds_names=["ycbv.bop19"] result_id=ycbv-debug detection_coarse_types=["detector"] inference.renderer=panda3d inference.n_workers=1
14+
```
15+
16+
To evaluate on other datasets, change ["ycbv.bop19"] to e.g. ["tless.bop19"].
17+
To evaluate on a collection of datasets, change "ycbv.bop19" to e.g. ["ycbv.bop19", "lmo.bop19", "tless.bop19"].

happypose/pose_estimators/cosypose/cosypose/evaluation/evaluation.py

+9-8
Original file line numberDiff line numberDiff line change
@@ -34,7 +34,6 @@
3434

3535
# Pose estimator
3636
from happypose.toolbox.datasets.datasets_cfg import make_object_dataset, make_scene_dataset, get_obj_ds_info
37-
from happypose.toolbox.inference.utils import load_detector
3837
from happypose.toolbox.lib3d.rigid_mesh_database import MeshDataBase
3938
from happypose.toolbox.utils.distributed import get_rank, get_tmp_dir
4039
from happypose.toolbox.utils.logging import get_logger
@@ -69,7 +68,7 @@ def load_detector(run_id, ds_name):
6968
return model
7069

7170

72-
def load_pose_models(object_dataset, coarse_run_id, refiner_run_id, n_workers, renderer_type="panda3d"):
71+
def load_pose_models_cosypose(object_dataset, coarse_run_id, refiner_run_id, n_workers, renderer_type="panda3d"):
7372
run_dir = EXP_DIR / coarse_run_id
7473
cfg = yaml.load((run_dir / "config.yaml").read_text(), Loader=yaml.UnsafeLoader)
7574
cfg = check_update_config_pose(cfg)
@@ -161,6 +160,8 @@ def run_eval(
161160
cfg.save_dir = str(save_dir)
162161

163162
logger.info(f"Running eval on ds_name={cfg.ds_name} with setting={save_key}")
163+
# e.g. "ycbv.bop19" -> "ycbv"
164+
ds_name_short = cfg.ds_name.split('.')[0]
164165

165166
# Load the dataset
166167
ds_kwargs = {"load_depth": False}
@@ -181,8 +182,7 @@ def run_eval(
181182
# Load detector model
182183
if cfg.inference.detection_type == "detector":
183184
assert cfg.detector_run_id is not None
184-
detector_model = load_detector(cfg.detector_run_id, cfg.ds_name)
185-
# detector_model = load_detector(cfg.detector_run_id, device=device)
185+
detector_model = load_detector(cfg.detector_run_id, ds_name_short)
186186
elif cfg.inference.detection_type == "gt":
187187
detector_model = None
188188
else:
@@ -195,14 +195,15 @@ def run_eval(
195195
assert cfg.coarse_run_id is not None
196196
assert cfg.refiner_run_id is not None
197197

198-
object_ds = make_object_dataset('ycbv')
199198

200-
coarse_model, refiner_model, mesh_db = load_pose_models(
199+
object_ds = make_object_dataset(ds_name_short)
200+
201+
coarse_model, refiner_model, mesh_db = load_pose_models_cosypose(
201202
object_ds,
202203
coarse_run_id=cfg.coarse_run_id,
203204
refiner_run_id=cfg.refiner_run_id,
204-
n_workers=0,
205-
renderer_type="bullet"
205+
n_workers=cfg.inference.n_workers,
206+
renderer_type=cfg.inference.renderer
206207
)
207208

208209
renderer = refiner_model.renderer

happypose/pose_estimators/megapose/inference/types.py

+2
Original file line numberDiff line numberDiff line change
@@ -97,6 +97,8 @@ class InferenceConfig:
9797
depth_refiner: Optional[str] = None # ['icp', 'teaserpp']
9898
bsz_objects: int = 16 # How many parallel refiners to run
9999
bsz_images: int = 288 # How many images to push through coarse model
100+
renderer: str = "panda3d" # ['panda3d', 'pybullet']
101+
n_workers: int = 1 # How many workers to use in the batch renderer
100102

101103

102104
@dataclass

happypose/toolbox/renderer/panda3d_batch_renderer.py

+7-3
Original file line numberDiff line numberDiff line change
@@ -133,13 +133,16 @@ def __init__(
133133
preload_cache: bool = True,
134134
split_objects: bool = False,
135135
):
136-
assert n_workers >= 1
136+
self._is_closed = False
137137
self._object_dataset = asset_dataset
138138
self._n_workers = n_workers
139139
self._split_objects = split_objects
140+
self._renderers = []
141+
self._in_queues = []
142+
self._out_queue = None
143+
assert n_workers >= 1
140144

141145
self._init_renderers(preload_cache)
142-
self._is_closed = False
143146

144147
def make_scene_data(
145148
self,
@@ -340,7 +343,8 @@ def stop(self) -> None:
340343
renderer_process.terminate()
341344
for queue in self._in_queues:
342345
queue.close()
343-
self._out_queue.close()
346+
if self._out_queue is not None:
347+
self._out_queue.close()
344348
self._is_closed = True
345349
logger.debug("Batch renderer is closed.")
346350

0 commit comments

Comments
 (0)