Skip to content

louhz/robogs

Folders and files

NameName
Last commit message
Last commit date

Latest commit

Β 

History

34 Commits
Β 
Β 
Β 
Β 
Β 
Β 
Β 
Β 
Β 
Β 
Β 
Β 

Repository files navigation

Robo-GS: A Physics Consistent Spatial-Temporal Model for Robotic Arm with Hybrid Representation

arXiv web license

Official Release
We currently support structure from motion toolsets: COLMAP and GLOMAP.
Follow the documentation for asset creation and 4D rendering.

πŸ“‹ Table of Contents

πŸš€ Installation

PyTorch (Recommended: PyTorch 2.1 + CUDA 11.8-12.6):

pip3 install torch torchvision torchaudio  # torch 2.7.1 with cuda 12.6
pip3 install torch torchvision torchaudio --index-url https://download.pytorch.org/whl/cu118  # torch 2.7.1 with cuda 11.8

⚠️ Note: CUDA 11.8 or later is recommended, but not CUDA 12.8 or newer. 50-series CUDA devices are untested.

Structure from Motion Tools

Project Setup

Follow the detailed installation instructions in robogs/installation.md.

🎯 Quick Start

We provide several pre-configured debug configurations in .vscode/launch.json for different pipeline stages. To use these configurations, replace the data paths with your own data location in the launch.json file.

πŸ“¦ Example Data

Tip: You can interactively view 4D render results, change camera views, time frames, and control signals to see editing effects.

Legacy Version

For results from the original paper (using GSplat 0.7 and old NeRFStudio), see the Old Version Repository.

πŸ”„ Complete Pipeline

Step 1: Capture Monocular 360Β° Video

Extract frames from video:

<data_path> = sample_data
python robogs/vis/video2image.py \
    -v <data_path>/<video_path> \
    -o <data_path>/<image_output_directory> \
    --num_frames <frame_count>

Step 2: Structure from Motion

Run COLMAP on the extracted images to obtain features and camera poses. See the COLMAP documentation for details.

Step 3: GSplat Training

Train the Gaussian Splatting model:

python robogs/vis/gsplat_trainer.py \
    default \
    --data_dir  <data_path> \
    --data_factor 1 \
    --result-dir  <data_path>/gs_result_sfm

or if you want to launch with debugger, please refer to the configuration Python Debugger: gsplat_trainer in .vscode/launch.json.

Step 4: Normal Map Generation

Use the StableNormal to generate normal maps from the extracted images. Save the normal images to the normals folder.

Step 5: Gaussian Splat & Mesh Processing

Gaussian Splat Extraction

Extract Gaussian Splat point clouds:

python robogs/vis/extract_ply.py \
    default \
    --ckpt \
    <data_path>/gs_result_sfm/ckpts/ckpt_29999_rank0.pt \
    --data_factor \
    1 \
    --export_ply_path \
    <data_path>/gs_result_sfm/scan30000.ply \
    --data_dir \
    <data_path> 

or if you want to launch with debugger, please refer to the configuration Python Debugger: export ply in .vscode/launch.json.

To view and edit Gaussian Splat, use the SuperSplat Viewer.

To edit the point clouds, refer to the demonstration videos for details. You can see how to select the links here: select links

and how to select fingers here: select fingers

Mesh Extraction

Train and render mesh:

python robogs/meshrecon/train.py \
    -s <data_path> \
    -r 2 \
    --lambda_normal_prior 1 \
    --lambda_dist 10 \
    --iteration 7000 \
    -m <mesh_result_path> \
    --w_normal_prior normals

python robogs/meshrecon/render.py \
    -s <data_path> \
    -m <mesh_result_path>

You can also use the VSCode debugger configurations trainmesh and extractmesh for these steps.

Step 6: Scene Alignment

Align the reconstructed scene. Refer to the demonstration video here for details.

Step 7: Segmentation & Labeling

Segment and label the scene. See the demonstration video here for details. (A SAM-based segmentation tool is coming soon.)

Step 8: ID Assignment

Assign custom IDs:

python robogs/assign.py

Step 9: Kinematics & Dynamics

Fine-tune MDH and physical properties using the Python Debugger: debug configuration in VSCode. See the demo video for more information.

Step 10: Coordinate & Scale Alignment

  • Recenter and reorient the Gaussian Splats and mesh.
  • Keep alignment vectors.
  • Perform automatic ICP-based scale registration.

Step 11: URDF/MJCF Generation

Clean the mesh bottom:

python robogs/mesh_util/fixbot.py \
    -i input_mesh.stl \
    -o output_mesh.stl

Generate URDF/MJCF:

python robogs/mesh_util/generate_mjcf.py \
    -o <output_mjcf_path.xml> \
    -s <path_to_seed.ply> \
    -m <path_to_original_scene.xml> \
    --raw_image <path_to_raw_rgb_image.png> \
    --seg_image <path_to_segmentation_image.png>

Sample MJCF files are stored in the franka_leap and franka_robotiq folders.

Step 12: Simulation & Rendering

⚠️ Important: After generating MJCF, carefully check joint angle limits between simulation and real-world.

The scene should be aligned with the real world and ready for rendering and simulation. See mjcf_asset/franka_robotiq/scene_cup_gripper.xml for an example, and refer to the Python Debugger: 4drender configuration in VSCode for visualization.

πŸ“š Citation

If you find this work helpful, please cite:

@misc{lou2024robogsphysicsconsistentspatialtemporal,
  title={Robo-GS: A Physics Consistent Spatial-Temporal Model for Robotic Arm with Hybrid Representation}, 
  author={Haozhe Lou and Yurong Liu and Yike Pan and Yiran Geng and Jianteng Chen and Wenlong Ma and Chenglong Li and Lin Wang and Hengzhen Feng and Lu Shi and Liyi Luo and Yongliang Shi},
  year={2024},
  eprint={2408.14873},
  archivePrefix={arXiv},
  primaryClass={cs.RO},
  url={https://arxiv.org/abs/2408.14873}, 
}

About

No description, website, or topics provided.

Resources

License

Stars

Watchers

Forks

Releases

No releases published

Packages

No packages published

Contributors 3

  •  
  •  
  •