Skip to content

Commit

Permalink
First commit
Browse files Browse the repository at this point in the history
Removing test data

Update Readme to add instructions for downloading test_data

Add gitattributes for test_data
  • Loading branch information
MartinSmeyer authored and arsalan-mousavian committed May 25, 2021
1 parent c9ca48e commit f28013a
Show file tree
Hide file tree
Showing 125 changed files with 56,191 additions and 1 deletion.
2 changes: 1 addition & 1 deletion .gitattributes
Original file line number Diff line number Diff line change
@@ -1,2 +1,2 @@

test_data/** filter= diff= merge= -text

6 changes: 6 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
results
checkpoints/*
*.npz
**/*.pyc
**/__pycache__
.vscode
Binary file added License.pdf
Binary file not shown.
134 changes: 134 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,134 @@
# Contact-GraspNet

### Contact-GraspNet: Efficient 6-DoF Grasp Generation in Cluttered Scenes
Martin Sundermeyer, Arsalan Mousavian, Rudolph Triebel, Dieter Fox
ICRA 2021

[paper](https://arxiv.org/abs/2103.14127), [project page](https://research.nvidia.com/publication/2021-03_Contact-GraspNet%3A--Efficient), [video](http://www.youtube.com/watch?v=qRLKYSLXElM)

<p align="center">
<img src="examples/2.gif" width="640" title="UOIS + Contact-GraspNet"/>
</p>

## Installation

This code has been tested with python 3.7, tensorflow 2.2, CUDA 10.1, and CUDNN 7.6.0

Create the conda env
```
conda env create -f contact_graspnet_env.yml
```

### Troubleshooting

- Recompile pointnet2 tf_ops, see [here](pointnet2/tf_ops/HowTO.md)

### Hardware
Training: 1x Nvidia GPU >= 24GB VRAM, >=64GB RAM
Inference: 1x Nvidia GPU >= 8GB VRAM (might work with less)

## Download Models and Data
### Model
Download trained models from [here](https://drive.google.com/drive/folders/1tBHKf60K8DLM5arm-Chyf7jxkzOr5zGl?usp=sharing) and copy them into the `checkpoints/` folder.
### Test data
Download the test data from [here](https://drive.google.com/drive/folders/1v0_QMTUIEOcu09Int5V6N2Nuq7UCtuAA?usp=sharing) and copy them them into the `test_data/` folder.

## Inference


Contact-GraspNet can directly predict a 6-DoF grasp distribution from a raw scene point cloud. However, to obtain object-wise grasps, remove background grasps and to achieve denser proposals it is highly recommended to use (unknown) object segmentation [e.g. [1](https://github.com/chrisdxie/uois), [2](https://arxiv.org/abs/2103.06796)] as preprocessing and then use the resulting segmentation map to crop local regions and filter grasp contacts.

Given a .npy/.npz file with a depth map (in meters), camera matrix K and (optionally) a 2D segmentation map, execute:

```shell
python contact_graspnet/inference.py \
--np_path=test_data/*.npy \
--local_regions --filter_grasps
```

<p align="center">
<img src="examples/7.png" width="640" title="UOIS + Contact-GraspNet"/>
</p>
--> close the window to go to next scene

Given a .npy/.npz file with just a 3D point cloud (in meters), execute [for example](examples/realsense_crop_sigma_001.png):
```shell
python contact_graspnet/inference.py --np_path=/path/to/your/pc.npy \
--forward_passes=5 \
--z_range=[0.2,1.1]
```

`--np_path`: input .npz/.npy file(s) with 'depth', 'K' and optionally 'segmap', 'rgb' keys. For processing a Nx3 point cloud instead use 'xzy' and optionally 'xyz_color' as keys.
`--ckpt_dir`: relative path to checkpooint directory. By default `checkpoint/scene_test_2048_bs3_hor_sigma_001` is used. For very clean / noisy depth data consider `scene_2048_bs3_rad2_32` / `scene_test_2048_bs3_hor_sigma_0025` trained with no / strong noise.
`--local_regions`: Crop 3D local regions around object segments for inference. (only works with segmap)
`--filter_grasps`: Filter grasp contacts such that they only lie on the surface of object segments. (only works with segmap)
`--skip_border_objects` Ignore segments touching the depth map boundary.
`--forward_passes` number of (batched) forward passes. Increase to sample more potential grasp contacts.
`--z_range` [min, max] z values in meter used to crop the input point cloud, e.g. to avoid grasps in the foreground/background(as above).
`--arg_configs TEST.second_thres:0.19 TEST.first_thres:0.23` Overwrite config confidence thresholds for successful grasp contacts to get more/less grasp proposals


## Training

### Download Data

Download the Acronym dataset, ShapeNet meshes and make them watertight, following these [steps](https://github.com/NVlabs/acronym#using-the-full-acronym-dataset).

Download the training data consisting of 10000 table top training scenes with contact grasp information from [here](https://drive.google.com/drive/folders/1eeEXAISPaStZyjMX8BHR08cdQY4HF4s0?usp=sharing) and extract it to the same folder:

```
acronym
├── grasps
├── meshes
├── scene_contacts
└── splits
```

### Train Contact-GraspNet

When training on a headless server set the environment variable
```shell
export PYOPENGL_PLATFORM='egl'
```

Start training with config `contact_graspnet/config.yaml`
```
python contact_graspnet/train.py --ckpt_dir checkpoints/your_model_name \
--data_path /path/to/acronym/data
```

### Generate Contact Grasps and Scenes yourself (optional)

The `scene_contacts` downloaded above are generated from the Acronym dataset. To generate/visualize table-top scenes yourself, also pip install the [acronym_tools]((https://github.com/NVlabs/acronym)) package in your conda environment as described in the acronym repository.

In the first step, object-wise 6-DoF grasps are mapped to their contact points saved in `mesh_contacts`

```
python tools/create_contact_infos.py /path/to/acronym
```

From the generated `mesh_contacts` you can create table-top scenes which are saved in `scene_contacts` with

```
python tools/create_table_top_scenes.py /path/to/acronym
```

Takes ~3 days in a single thread. Run the command several times to process on multiple cores in parallel.

You can also visualize existing table-top scenes and grasps

```
python tools/create_table_top_scenes.py /path/to/acronym \
--load_existing scene_contacts/000000.npz -vis
```

## Citation

```
@article{sundermeyer2021contact,
title={Contact-GraspNet: Efficient 6-DoF Grasp Generation in Cluttered Scenes},
author={Sundermeyer, Martin and Mousavian, Arsalan and Triebel, Rudolph and Fox, Dieter},
booktitle={2021 IEEE International Conference on Robotics and Automation (ICRA)},
year={2021}
}
```
Empty file added checkpoints/.gitkeep
Empty file.
Empty file added contact_graspnet/__init__.py
Empty file.
186 changes: 186 additions & 0 deletions contact_graspnet/config.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,186 @@
DATA:
scene_contacts_path: scene_contacts
gripper_width: 0.08
input_normals: false
use_uniform_quaternions: False
view_sphere:
elevation: [30,150]
distance_range: [0.9,1.3]
train_on_scenes: True
labels:
to_gpu: False
bin_weights:
- 0.16652107
- 0.21488856
- 0.37031708
- 0.55618503
- 0.75124664
- 0.93943357
- 1.07824539
- 1.19423112
- 1.55731375
- 3.17161779
filter_z: true
k: 1
max_radius: 0.005
num_neg_contacts: 0
num_pos_contacts: 8000
offset_bins:
- 0
- 0.00794435329
- 0.0158887021
- 0.0238330509
- 0.0317773996
- 0.0397217484
- 0.0476660972
- 0.055610446
- 0.0635547948
- 0.0714991435
- 0.08
z_val: -0.1
pc_augm:
occlusion_nclusters: 0
occlusion_dropout_rate: 0.0
sigma: 0.000
clip: 0.005
depth_augm:
sigma: 0.001
clip: 0.005
gaussian_kernel: 0
raw_num_points: 20000
ndataset_points: 20000
num_point: 2048
use_farthest_point: false
train_and_test: false
num_test_scenes: 1000
intrinsics: 'realsense'
LOSS:
min_geom_loss_divisor: 1.0
offset_loss_type: sigmoid_cross_entropy
too_small_offset_pred_bin_factor: 0
topk_confidence: 512
MODEL:
bin_offsets: true
dir_vec_length_offset: false
grasp_conf_head:
conv1d: 1
dropout_keep: 0.5
grasp_dir_head:
conv1d: 3
dropout_keep: 0.7
joint_head:
conv1d: 4
dropout_keep: 0.7
joint_heads: false
asymmetric_model: true
model: contact_graspnet
pointnet_fp_modules:
- mlp:
- 256
- 256
- mlp:
- 256
- 128
- mlp:
- 128
- 128
- 128
pointnet_sa_module:
group_all: true
mlp:
- 256
- 512
- 1024
pointnet_sa_modules_msg:
- mlp_list:
- - 32
- 32
- 64
- - 64
- 64
- 128
- - 64
- 96
- 128
npoint: 2048
nsample_list:
- 32
- 64
- 128
radius_list:
- 0.02
- 0.04
- 0.08
- mlp_list:
- - 64
- 64
- 128
- - 128
- 128
- 256
- - 128
- 128
- 256
npoint: 512
nsample_list:
- 64
- 64
- 128
radius_list:
- 0.04
- 0.08
- 0.16
- mlp_list:
- - 64
- 64
- 128
- - 128
- 128
- 256
- - 128
- 128
- 256
npoint: 128
nsample_list:
- 64
- 64
- 128
radius_list:
- 0.08
- 0.16
- 0.32
pred_contact_approach: false
pred_contact_base: false
pred_contact_offset: true
pred_contact_success: true
pred_grasps_adds: true
pred_grasps_adds_gt2pred: false
OPTIMIZER:
max_epoch: 16
batch_size: 3
learning_rate: 0.001
optimizer: adam
momentum: 0.9
adds_gt2pred_loss_weight: 1
adds_loss_weight: 10
approach_cosine_loss_weight: 1
dir_cosine_loss_weight: 1
offset_loss_weight: 1
score_ce_loss_weight: 1
bn_decay_clip: 0.99
bn_decay_decay_rate: 0.5
bn_decay_decay_step: 200000
bn_init_decay: 0.5
decay_rate: 0.7
decay_step: 200000
TEST:
first_thres: 0.23
second_thres: 0.19
allow_zero_margin: 0
bin_vals: max
center_to_tip: 0.0
extra_opening: 0.005
max_farthest_points: 150
num_samples: 200
with_replacement: false
filter_thres: 0.0001
66 changes: 66 additions & 0 deletions contact_graspnet/config_utils.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,66 @@
import os
import yaml

def recursive_key_value_assign(d,ks,v):
"""
Recursive value assignment to a nested dict
Arguments:
d {dict} -- dict
ks {list} -- list of hierarchical keys
v {value} -- value to assign
"""

if len(ks) > 1:
recursive_key_value_assign(d[ks[0]],ks[1:],v)
elif len(ks) == 1:
d[ks[0]] = v

def load_config(checkpoint_dir, batch_size=None, max_epoch=None, data_path=None, arg_configs=[], save=False):
"""
Loads yaml config file and overwrites parameters with function arguments and --arg_config parameters
Arguments:
checkpoint_dir {str} -- Checkpoint directory where config file was copied to
Keyword Arguments:
batch_size {int} -- [description] (default: {None})
max_epoch {int} -- "epochs" (number of scenes) to train (default: {None})
data_path {str} -- path to scenes with contact grasp data (default: {None})
arg_configs {list} -- Overwrite config parameters by hierarchical command line arguments (default: {[]})
save {bool} -- Save overwritten config file (default: {False})
Returns:
[dict] -- Config
"""

config_path = os.path.join(checkpoint_dir, 'config.yaml')
config_path = config_path if os.path.exists(config_path) else os.path.join(os.path.dirname(__file__),'config.yaml')
with open(config_path,'r') as f:
global_config = yaml.load(f)

for conf in arg_configs:
k_str, v = conf.split(':')
try:
v = eval(v)
except:
pass
ks = [int(k) if k.isdigit() else k for k in k_str.split('.')]

recursive_key_value_assign(global_config, ks, v)

if batch_size is not None:
global_config['OPTIMIZER']['batch_size'] = int(batch_size)
if max_epoch is not None:
global_config['OPTIMIZER']['max_epoch'] = int(max_epoch)
if data_path is not None:
global_config['DATA']['data_path'] = data_path

global_config['DATA']['classes'] = None

if save:
with open(os.path.join(checkpoint_dir, 'config.yaml'),'w') as f:
yaml.dump(global_config, f)

return global_config

Loading

0 comments on commit f28013a

Please sign in to comment.