Compare commits
8 Commits
4.1.0
...
pick-test-
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
3d6b73753a | ||
|
|
6314603676 | ||
|
|
b178aafe40 | ||
|
|
6032b12c59 | ||
|
|
1105a49e8f | ||
|
|
8d2fec09e0 | ||
|
|
6b78ba0d6f | ||
|
|
03d9a5b909 |
3
.gitignore
vendored
3
.gitignore
vendored
@@ -18,4 +18,5 @@ _isaac_sim_410
|
||||
InterDataEngine-docs
|
||||
debug.sh
|
||||
debug.yaml
|
||||
depre
|
||||
depre
|
||||
workflows/simbox/src/nvidia-curobo/
|
||||
133
README.md
133
README.md
@@ -1,6 +1,8 @@
|
||||
<div align="center">
|
||||
|
||||
# InternDataEngine: Pioneering High-Fidelity Synthetic Data Generator for Robotic Manipulation
|
||||
# InternDataEngine
|
||||
|
||||
**High-Fidelity Synthetic Data Generator for Robotic Manipulation**
|
||||
|
||||
</div>
|
||||
|
||||
@@ -15,30 +17,127 @@
|
||||
|
||||
</div>
|
||||
|
||||
## 💻 About
|
||||
## About
|
||||
|
||||
<div align="center">
|
||||
<img src="./docs/images/intern_data_engine.jpeg" alt="InternDataEngine Overview" width="80%">
|
||||
</div>
|
||||
|
||||
InternDataEngine is a synthetic data generation engine for embodied AI that powers large-scale model training and iteration. Built on NVIDIA Isaac Sim, it unifies high-fidelity physical interaction from InternData-A1, semantic task and scene generation from InternData-M1, and high-throughput scheduling from the Nimbus framework to deliver realistic, task-aligned, and massively scalable robotic manipulation data.
|
||||
InternDataEngine is a synthetic data generation engine for embodied AI, built on NVIDIA Isaac Sim. It unifies high-fidelity physical interaction (InternData-A1), semantic task and scene generation (InternData-M1), and high-throughput scheduling (Nimbus) to deliver realistic, task-aligned, and scalable robotic manipulation data.
|
||||
|
||||
- **More realistic physical interaction**: Unified simulation of rigid, articulated, deformable, and fluid objects across single-arm, dual-arm, and humanoid robots, enabling long-horizon, skill-composed manipulation that better supports sim-to-real transfer.
|
||||
- **More diverse data generation**: By leveraging the internal state of the simulation engine to extract high-quality ground truth, coupled with multi-dimensional domain randomization (e.g., layout, texture, structure, and lighting), the data distribution is significantly expanded. This approach produces precise and diverse operational data, while simultaneously exporting rich multimodal annotations such as bounding boxes, segmentation masks, and keypoints.
|
||||
- **More efficient large-scale production**: Nimbus-powered asynchronous pipelines that decouple planning, rendering, and storage, achieving 2–3× end-to-end throughput, cluster-level load balancing and fault tolerance for billion-scale data generation.
|
||||
**Key capabilities:**
|
||||
|
||||
## 🔥 Latest News
|
||||
- **Realistic physical interaction** -- Unified simulation of rigid, articulated, deformable, and fluid objects across single-arm, dual-arm, and humanoid robots. Supports long-horizon, skill-composed manipulation for sim-to-real transfer.
|
||||
- **Diverse data generation** -- Multi-dimensional domain randomization (layout, texture, structure, lighting) with rich multimodal annotations (bounding boxes, segmentation masks, keypoints).
|
||||
- **Efficient large-scale production** -- Nimbus-powered asynchronous pipelines that decouple planning, rendering, and storage, achieving 2-3x end-to-end throughput with cluster-level load balancing and fault tolerance.
|
||||
|
||||
- **[2026/03]** We release the InternDataEngine codebase v1.0, which includes the core modules: InternData-A1 and Nimbus.
|
||||
## Prerequisites
|
||||
|
||||
## 🚀 Quickstart
|
||||
| Dependency | Version |
|
||||
|------------|---------|
|
||||
| NVIDIA Isaac Sim | 5.0.0 (Kit 107.x) |
|
||||
| CUDA Toolkit | >= 12.8 |
|
||||
| Python | 3.10 |
|
||||
| GPU | NVIDIA RTX (tested on RTX PRO 6000 Blackwell) |
|
||||
|
||||
Please refer to the [Installation](https://internrobotics.github.io/InternDataEngine-Docs/guides/installation.html) and [Usage](https://internrobotics.github.io/InternDataEngine-Docs/guides/quickstart.html) to start the installation and run your first synthetic data generation task.
|
||||
> For detailed environment setup (conda, CUDA, PyTorch, curobo), see [install.md](install.md).
|
||||
>
|
||||
> If migrating from Isaac Sim 4.5.0, see [migrate/migrate.md](migrate/migrate.md) for known issues and fixes.
|
||||
|
||||
For more details, please check [Documentation](https://internrobotics.github.io/InternDataEngine-Docs/).
|
||||
## Quick Start
|
||||
|
||||
### 1. Install
|
||||
|
||||
```bash
|
||||
# Create conda environment
|
||||
conda create -n banana500 python=3.10
|
||||
conda activate banana500
|
||||
|
||||
# Install CUDA 12.8 and set up Isaac Sim 5.0.0
|
||||
conda install -y cuda-toolkit=12.8
|
||||
source ~/isaacsim500/setup_conda_env.sh
|
||||
export CUDA_HOME="$CONDA_PREFIX"
|
||||
|
||||
# Install PyTorch (CUDA 12.8)
|
||||
pip install torch==2.7.0 torchvision==0.22.0 torchaudio==2.7.0 --index-url https://download.pytorch.org/whl/cu128
|
||||
|
||||
# Install project dependencies
|
||||
pip install -r requirements.txt
|
||||
|
||||
# Install curobo (motion planning)
|
||||
cd workflows/simbox/curobo
|
||||
export TORCH_CUDA_ARCH_LIST="12.0+PTX" # Set to your GPU's compute capability
|
||||
pip install -e .[isaacsim] --no-build-isolation
|
||||
cd ../../..
|
||||
```
|
||||
|
||||
See [install.md](install.md) for the full step-by-step guide including troubleshooting.
|
||||
|
||||
### 2. Run Data Generation
|
||||
|
||||
```bash
|
||||
# Full pipeline: plan trajectories + render + save
|
||||
python launcher.py --config configs/simbox/de_plan_and_render_template.yaml
|
||||
```
|
||||
|
||||
Output is saved to `output/simbox_plan_and_render/` including:
|
||||
- `demo.mp4` -- rendered video from robot cameras
|
||||
- LMDB data files for model training
|
||||
|
||||
### 3. Available Pipeline Configs
|
||||
|
||||
| Config | Description |
|
||||
|--------|-------------|
|
||||
| `de_plan_and_render_template.yaml` | Full pipeline: plan + render + save |
|
||||
| `de_plan_template.yaml` | Plan trajectories only (no rendering) |
|
||||
| `de_render_template.yaml` | Render from existing plans |
|
||||
| `de_plan_with_render_template.yaml` | Plan with live rendering preview |
|
||||
| `de_pipe_template.yaml` | Pipelined mode for throughput |
|
||||
|
||||
### 4. Configuration
|
||||
|
||||
The main config file (`configs/simbox/de_plan_and_render_template.yaml`) controls:
|
||||
|
||||
```yaml
|
||||
simulator:
|
||||
headless: True # Set False for GUI debugging
|
||||
renderer: "RayTracedLighting" # Or "PathTracing" for higher quality
|
||||
physics_dt: 1/30
|
||||
rendering_dt: 1/30
|
||||
```
|
||||
|
||||
Task configs are in `workflows/simbox/core/configs/tasks/`. The example task (`sort_the_rubbish`) demonstrates a dual-arm pick-and-place scenario.
|
||||
|
||||
## Project Structure
|
||||
|
||||
```
|
||||
InternDataEngine/
|
||||
configs/simbox/ # Pipeline configuration files
|
||||
launcher.py # Main entry point
|
||||
nimbus_extension/ # Nimbus framework components
|
||||
workflows/simbox/
|
||||
core/
|
||||
configs/ # Task, robot, arena, camera configs
|
||||
controllers/ # Motion planning (curobo integration)
|
||||
skills/ # Manipulation skills (pick, place, etc.)
|
||||
tasks/ # Task definitions
|
||||
example_assets/ # Example USD assets (robots, objects, tables)
|
||||
curobo/ # GPU-accelerated motion planning library
|
||||
migrate/ # Migration tools and documentation
|
||||
output/ # Generated data output
|
||||
```
|
||||
|
||||
## Documentation
|
||||
|
||||
- [Installation Guide](install.md) -- Environment setup and dependency installation
|
||||
- [Migration Guide](migrate/migrate.md) -- Isaac Sim 4.5.0 to 5.0.0 migration notes and tools
|
||||
- [Online Documentation](https://internrobotics.github.io/InternDataEngine-Docs/) -- Full API docs, tutorials, and advanced usage
|
||||
|
||||
## License and Citation
|
||||
All the code within this repo are under [CC BY-NC-SA 4.0](https://creativecommons.org/licenses/by-nc-sa/4.0/). Please consider citing our papers if it helps your research.
|
||||
|
||||
This project is based on [InternDataEngine](https://github.com/InternRobotics/InternDataEngine) by InternRobotics, licensed under [CC BY-NC-SA 4.0](https://creativecommons.org/licenses/by-nc-sa/4.0/).
|
||||
|
||||
If this project helps your research, please cite the following papers:
|
||||
|
||||
```BibTeX
|
||||
@article{tian2025interndata,
|
||||
@@ -62,13 +161,3 @@ All the code within this repo are under [CC BY-NC-SA 4.0](https://creativecommon
|
||||
year={2025}
|
||||
}
|
||||
```
|
||||
|
||||
<!--
|
||||
```BibTeX
|
||||
@misc{interndataengine2026,
|
||||
title={InternDataEngine: A Synthetic Data Generation Engine for Robotic Learning},
|
||||
author={InternDataEngine Contributors},
|
||||
year={2026},
|
||||
}
|
||||
}
|
||||
``` -->
|
||||
|
||||
31
configs/simbox/de_pick_test_tube.yaml
Normal file
31
configs/simbox/de_pick_test_tube.yaml
Normal file
@@ -0,0 +1,31 @@
|
||||
name: simbox_pick_test_tube
|
||||
load_stage:
|
||||
scene_loader:
|
||||
type: env_loader
|
||||
args:
|
||||
workflow_type: SimBoxDualWorkFlow
|
||||
cfg_path: workflows/simbox/core/configs/tasks/example/pick_test_tube.yaml
|
||||
simulator:
|
||||
physics_dt: 1/30
|
||||
rendering_dt: 1/30
|
||||
stage_units_in_meters: 1.0
|
||||
headless: False # GUI mode for visual debugging first
|
||||
renderer: "RayTracedLighting"
|
||||
anti_aliasing: 0
|
||||
layout_random_generator:
|
||||
type: env_randomizer
|
||||
args:
|
||||
random_num: 1 # Start with 1 sample for testing
|
||||
strict_mode: true
|
||||
plan_stage:
|
||||
seq_planner:
|
||||
type: env_planner
|
||||
render_stage:
|
||||
renderer:
|
||||
type: env_renderer
|
||||
store_stage:
|
||||
writer:
|
||||
type: env_writer
|
||||
args:
|
||||
batch_async: true
|
||||
output_dir: output/${name}/
|
||||
@@ -10,7 +10,7 @@ load_stage:
|
||||
rendering_dt: 1/30 # Render update rate
|
||||
stage_units_in_meters: 1.0 # Stage unit scale
|
||||
headless: True # Headless mode (no GUI); set false for visual debugging
|
||||
renderer: "PathTracing" # PathTracing: higher quality, less noise on Blackwell
|
||||
renderer: "RayTracedLighting" # PathTracing: higher quality, less noise on Blackwell 改回快速渲染器就改成 "RayTracedLighting"
|
||||
anti_aliasing: 0 # Anti-aliasing level
|
||||
layout_random_generator: # Scene randomization
|
||||
type: env_randomizer
|
||||
|
||||
209
docs_crawled/api_controllers.md
Normal file
209
docs_crawled/api_controllers.md
Normal file
@@ -0,0 +1,209 @@
|
||||
# Source: https://internrobotics.github.io/InternDataEngine-Docs/api/controllers.html
|
||||
|
||||
# Controllers API Reference [](#controllers-api-reference)
|
||||
|
||||
This page provides API documentation for the controller module.
|
||||
|
||||
## TemplateController [](#templatecontroller)
|
||||
|
||||
Base class for all robot arm controllers.
|
||||
|
||||
### Constructor [](#constructor)
|
||||
python
|
||||
```
|
||||
TemplateController(cfg, task, robot_file: str, **kwargs)
|
||||
```
|
||||
1
|
||||
|
||||
**Parameters: **
|
||||
|
||||
| Parameter | Type | Description |
|
||||
| `cfg ` | DictConfig | Controller configuration |
|
||||
| `task ` | BananaBaseTask | Task instance |
|
||||
| `robot_file ` | str | Path to CuRobo robot config |
|
||||
|
||||
### Properties [](#properties)
|
||||
|
||||
| Property | Type | Description |
|
||||
| `raw_js_names ` | List[str] | Joint names in CuRobo order |
|
||||
| `cmd_js_names ` | List[str] | Joint names in simulation order |
|
||||
| `arm_indices ` | np.ndarray | Arm joint indices |
|
||||
| `gripper_indices ` | np.ndarray | Gripper joint indices |
|
||||
| `_gripper_state ` | float | Gripper state (1.0=open, -1.0=closed) |
|
||||
|
||||
### Methods [](#methods)
|
||||
|
||||
#### `_configure_joint_indices(robot_file: str) `[](#configure-joint-indices-robot-file-str)
|
||||
|
||||
Configure joint names and indices. **Must be implemented by subclass. **
|
||||
|
||||
#### `_get_default_ignore_substring() -> List[str] `[](#get-default-ignore-substring-list-str)
|
||||
|
||||
Return default collision filter substrings. **Must be implemented by subclass. **
|
||||
|
||||
#### `get_gripper_action() -> np.ndarray `[](#get-gripper-action-np-ndarray)
|
||||
|
||||
Map gripper state to joint targets. **Must be implemented by subclass. **
|
||||
|
||||
#### `_load_world(use_default: bool = True) `[](#load-world-use-default-bool-true)
|
||||
|
||||
Load world configuration for motion planning.
|
||||
|
||||
**Returns: **`WorldConfig `
|
||||
|
||||
#### `_get_motion_gen_collision_cache() -> dict `[](#get-motion-gen-collision-cache-dict)
|
||||
|
||||
Return collision cache sizes.
|
||||
|
||||
**Returns: **`{"obb": int, "mesh": int} `
|
||||
|
||||
#### `_get_grasp_approach_linear_axis() -> int `[](#get-grasp-approach-linear-axis-int)
|
||||
|
||||
Return grasp approach axis (0=x, 1=y, 2=z).
|
||||
|
||||
**Returns: **`int `(default: 2)
|
||||
|
||||
#### `_get_sort_path_weights() -> Optional[List[float]] `[](#get-sort-path-weights-optional-list-float)
|
||||
|
||||
Return weights for path selection.
|
||||
|
||||
**Returns: **`List[float] `or `None `
|
||||
|
||||
#### `plan_to_pose(target_pose) `[](#plan-to-pose-target-pose)
|
||||
|
||||
Plan motion to target pose.
|
||||
|
||||
**Parameters: **
|
||||
|
||||
- `target_pose `: Tuple of (position, orientation)
|
||||
|
||||
**Returns: **`bool `- Success status
|
||||
|
||||
#### `execute_plan() `[](#execute-plan)
|
||||
|
||||
Execute the planned trajectory.
|
||||
|
||||
#### `set_gripper_state(state: float) `[](#set-gripper-state-state-float)
|
||||
|
||||
Set gripper state.
|
||||
|
||||
**Parameters: **
|
||||
|
||||
- `state `: 1.0 for open, -1.0 for closed
|
||||
|
||||
#### `get_current_joint_state() -> np.ndarray `[](#get-current-joint-state-np-ndarray)
|
||||
|
||||
Get current joint positions.
|
||||
|
||||
**Returns: **`np.ndarray `of joint positions
|
||||
|
||||
## Lift2Controller [](#lift2controller)
|
||||
|
||||
Controller for ARX-Lift2 dual-arm robot.
|
||||
python
|
||||
```
|
||||
@register_controller
|
||||
class Lift2Controller(TemplateController):
|
||||
def _get_grasp_approach_linear_axis(self) -> int:
|
||||
return 0 # x-axis
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
|
||||
**Features: **
|
||||
|
||||
- Dual-arm support
|
||||
- Custom world configuration
|
||||
- X-axis grasp approach
|
||||
|
||||
## SplitAlohaController [](#splitalohacontroller)
|
||||
|
||||
Controller for Agilex Split Aloha dual-arm robot.
|
||||
python
|
||||
```
|
||||
@register_controller
|
||||
class SplitAlohaController(TemplateController):
|
||||
def _get_grasp_approach_linear_axis(self) -> int:
|
||||
return 2 # z-axis
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
|
||||
**Features: **
|
||||
|
||||
- Dual-arm support
|
||||
- Z-axis grasp approach
|
||||
- Optional joint control
|
||||
|
||||
## Genie1Controller [](#genie1controller)
|
||||
|
||||
Controller for Genie1 dual-arm robot.
|
||||
python
|
||||
```
|
||||
@register_controller
|
||||
class Genie1Controller(TemplateController):
|
||||
def _get_sort_path_weights(self) -> List[float]:
|
||||
return [1, 1, 1, 1, 3, 3, 1]
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
|
||||
**Features: **
|
||||
|
||||
- 7-DOF per arm
|
||||
- Path selection weights
|
||||
- Custom world configuration
|
||||
|
||||
## FR3Controller [](#fr3controller)
|
||||
|
||||
Controller for Franka FR3 single-arm robot.
|
||||
python
|
||||
```
|
||||
@register_controller
|
||||
class FR3Controller(TemplateController):
|
||||
def _get_motion_gen_collision_cache(self):
|
||||
return {"obb": 1000, "mesh": 1000}
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
|
||||
**Features: **
|
||||
|
||||
- Single-arm support
|
||||
- Panda gripper
|
||||
- Larger collision cache
|
||||
|
||||
## FrankaRobotiq85Controller [](#frankarobotiq85controller)
|
||||
|
||||
Controller for Franka with Robotiq 2F-85 gripper.
|
||||
python
|
||||
```
|
||||
@register_controller
|
||||
class FrankaRobotiq85Controller(TemplateController):
|
||||
def get_gripper_action(self):
|
||||
return np.clip(
|
||||
-self._gripper_state * self._gripper_joint_position,
|
||||
0.0, 5.0
|
||||
)
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
|
||||
**Features: **
|
||||
|
||||
- Single-arm support
|
||||
- Robotiq 2F-85 gripper
|
||||
- Inverted gripper mapping
|
||||
230
docs_crawled/api_skills.md
Normal file
230
docs_crawled/api_skills.md
Normal file
@@ -0,0 +1,230 @@
|
||||
# Source: https://internrobotics.github.io/InternDataEngine-Docs/api/skills.html
|
||||
|
||||
# Skills API Reference [](#skills-api-reference)
|
||||
|
||||
This page provides API documentation for the skills module.
|
||||
|
||||
## BaseSkill [](#baseskill)
|
||||
|
||||
Base class for all manipulation skills.
|
||||
|
||||
### Constructor [](#constructor)
|
||||
python
|
||||
```
|
||||
BaseSkill(cfg, task, controller, **kwargs)
|
||||
```
|
||||
1
|
||||
|
||||
**Parameters: **
|
||||
|
||||
| Parameter | Type | Description |
|
||||
| `cfg ` | DictConfig | Skill configuration |
|
||||
| `task ` | BananaBaseTask | Task instance |
|
||||
| `controller ` | TemplateController | Controller instance |
|
||||
|
||||
### Properties [](#properties)
|
||||
|
||||
| Property | Type | Description |
|
||||
| `skill_cfg ` | dict | Skill-specific configuration |
|
||||
| `task ` | BananaBaseTask | Reference to task |
|
||||
| `controller ` | TemplateController | Reference to controller |
|
||||
|
||||
### Methods [](#methods)
|
||||
|
||||
#### `run() -> bool `[](#run-bool)
|
||||
|
||||
Execute the skill. **Must be implemented by subclass. **
|
||||
|
||||
**Returns: **`bool `- Success status
|
||||
|
||||
## Dexpick [](#dexpick)
|
||||
|
||||
Dex-style picking skill with approach planning.
|
||||
python
|
||||
```
|
||||
class Dexpick(BaseSkill):
|
||||
def __init__(self, cfg, task, controller, **kwargs)
|
||||
def run(self) -> bool
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
|
||||
**Configuration: **
|
||||
|
||||
| Parameter | Type | Default | Description |
|
||||
| `objects ` | List[str] | required | Objects to pick |
|
||||
| `pick_pose_idx ` | int | 0 | Pick pose group index |
|
||||
| `pre_grasp_offset ` | float | 0.0 | Pre-grasp approach offset |
|
||||
| `post_grasp_offset ` | float | 0.1 | Post-grasp lift offset |
|
||||
|
||||
## Dexplace [](#dexplace)
|
||||
|
||||
Dex-style placing skill with constraints.
|
||||
python
|
||||
```
|
||||
class Dexplace(BaseSkill):
|
||||
def __init__(self, cfg, task, controller, **kwargs)
|
||||
def run(self) -> bool
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
|
||||
**Configuration: **
|
||||
|
||||
| Parameter | Type | Default | Description |
|
||||
| `objects ` | List[str] | required | [object, target] |
|
||||
| `camera_axis_filter ` | dict | None | Camera constraint |
|
||||
|
||||
## Pick [](#pick)
|
||||
|
||||
Standard pick skill.
|
||||
python
|
||||
```
|
||||
class Pick(BaseSkill):
|
||||
def run(self) -> bool
|
||||
```
|
||||
1
|
||||
2
|
||||
|
||||
**Configuration: **
|
||||
|
||||
| Parameter | Type | Default | Description |
|
||||
| `objects ` | List[str] | required | Objects to pick |
|
||||
|
||||
## Place [](#place)
|
||||
|
||||
Standard place skill.
|
||||
python
|
||||
```
|
||||
class Place(BaseSkill):
|
||||
def run(self) -> bool
|
||||
```
|
||||
1
|
||||
2
|
||||
|
||||
**Configuration: **
|
||||
|
||||
| Parameter | Type | Default | Description |
|
||||
| `objects ` | List[str] | required | [object, target] |
|
||||
|
||||
## GotoPose [](#gotopose)
|
||||
|
||||
Move to target pose skill.
|
||||
python
|
||||
```
|
||||
class GotoPose(BaseSkill):
|
||||
def run(self) -> bool
|
||||
```
|
||||
1
|
||||
2
|
||||
|
||||
**Configuration: **
|
||||
|
||||
| Parameter | Type | Default | Description |
|
||||
| `target_pose ` | tuple | required | (position, orientation) |
|
||||
|
||||
## Home [](#home)
|
||||
|
||||
Return to home configuration.
|
||||
python
|
||||
```
|
||||
class Home(BaseSkill):
|
||||
def run(self) -> bool
|
||||
```
|
||||
1
|
||||
2
|
||||
|
||||
**Configuration: **
|
||||
|
||||
| Parameter | Type | Default | Description |
|
||||
| `mode ` | str | "default" | Home configuration mode |
|
||||
|
||||
## Open / Close [](#open-close)
|
||||
|
||||
Gripper control skills.
|
||||
python
|
||||
```
|
||||
class Open(BaseSkill):
|
||||
def run(self) -> bool
|
||||
self.controller.set_gripper_state(1.0)
|
||||
|
||||
class Close(BaseSkill):
|
||||
def run(self) -> bool
|
||||
self.controller.set_gripper_state(-1.0)
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
|
||||
## PourWaterSucc [](#pourwatersucc)
|
||||
|
||||
Pouring skill for liquid simulation.
|
||||
python
|
||||
```
|
||||
class PourWaterSucc(BaseSkill):
|
||||
def run(self) -> bool
|
||||
```
|
||||
1
|
||||
2
|
||||
|
||||
**Configuration: **
|
||||
|
||||
| Parameter | Type | Default | Description |
|
||||
| `objects ` | List[str] | required | [container, target] |
|
||||
| `pour_angle ` | float | 90.0 | Pouring angle (degrees) |
|
||||
|
||||
## Rotate [](#rotate)
|
||||
|
||||
Rotation skill.
|
||||
python
|
||||
```
|
||||
class Rotate(BaseSkill):
|
||||
def run(self) -> bool
|
||||
```
|
||||
1
|
||||
2
|
||||
|
||||
**Configuration: **
|
||||
|
||||
| Parameter | Type | Default | Description |
|
||||
| `axis ` | str | "z" | Rotation axis |
|
||||
| `angle ` | float | 90.0 | Rotation angle (degrees) |
|
||||
|
||||
## Wait [](#wait)
|
||||
|
||||
Wait skill for timing control.
|
||||
python
|
||||
```
|
||||
class Wait(BaseSkill):
|
||||
def run(self) -> bool
|
||||
```
|
||||
1
|
||||
2
|
||||
|
||||
**Configuration: **
|
||||
|
||||
| Parameter | Type | Default | Description |
|
||||
| `duration ` | float | 1.0 | Wait duration (seconds) |
|
||||
|
||||
## HeuristicSkill [](#heuristicskill)
|
||||
|
||||
Configurable skill for simple actions.
|
||||
python
|
||||
```
|
||||
class HeuristicSkill(BaseSkill):
|
||||
def run(self) -> bool
|
||||
```
|
||||
1
|
||||
2
|
||||
|
||||
**Configuration: **
|
||||
|
||||
| Parameter | Type | Default | Description |
|
||||
| `mode ` | str | "home" | Action mode |
|
||||
| `gripper_state ` | float | None | Gripper state to set |
|
||||
188
docs_crawled/concepts_cameras.md
Normal file
188
docs_crawled/concepts_cameras.md
Normal file
@@ -0,0 +1,188 @@
|
||||
# Source: https://internrobotics.github.io/InternDataEngine-Docs/concepts/cameras.html
|
||||
|
||||
# Cameras [](#cameras)
|
||||
|
||||
Cameras capture visual data from the simulation. InternDataEngine uses a unified `CustomCamera `class that can be fully configured via YAML.
|
||||
|
||||
## Camera Architecture [](#camera-architecture)
|
||||
|
||||
```
|
||||
CustomCamera
|
||||
├── Pose Configuration
|
||||
│ ├── Translation
|
||||
│ └── Orientation
|
||||
├── Intrinsics
|
||||
│ ├── Focal length
|
||||
│ ├── Principal point
|
||||
│ └── Resolution
|
||||
├── Lens Settings
|
||||
│ ├── f-number
|
||||
│ ├── Focus distance
|
||||
│ └── Aperture
|
||||
└── Outputs
|
||||
├── RGB image
|
||||
└── Camera pose
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
10
|
||||
11
|
||||
12
|
||||
13
|
||||
14
|
||||
15
|
||||
|
||||
## Camera Configuration [](#camera-configuration)
|
||||
|
||||
Camera configuration is split into two parts: **pose configuration **(in task YAML) and **intrinsic parameters **(in separate camera YAML files).
|
||||
|
||||
### Part 1: Pose Configuration (Task YAML) [](#part-1-pose-configuration-task-yaml)
|
||||
|
||||
Configure camera pose and randomization in task YAML files:
|
||||
yaml
|
||||
```
|
||||
cameras:
|
||||
- name: lift2_hand_left # Unique camera name
|
||||
translation: [0.07, 0.01, 0.08] # Position offset [x, y, z] in meters
|
||||
orientation: [0.62, 0.33, -0.33, -0.62] # Quaternion [w, x, y, z]
|
||||
camera_axes: usd # Coordinate system (usd/ros/opencv)
|
||||
camera_file: workflows/simbox/core/configs/cameras/realsense_d405.yaml # Path to intrinsic config
|
||||
parent: "lift2/lift2/lift2/fl/link6" # Parent prim path (robot link or empty for world)
|
||||
apply_randomization: True # Enable pose randomization
|
||||
max_translation_noise: 0.02 # Max position noise (meters)
|
||||
max_orientation_noise: 2.5 # Max rotation noise (degrees)
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
10
|
||||
|
||||
### Part 2: Intrinsic Parameters (Camera YAML) [](#part-2-intrinsic-parameters-camera-yaml)
|
||||
|
||||
Define camera intrinsics in a separate YAML file (e.g., `workflows/simbox/core/configs/cameras/realsense_d405.yaml `):
|
||||
yaml
|
||||
```
|
||||
camera_type: "RealSense" # Camera model type
|
||||
camera_params: [433.89, 433.38, 322.79, 243.14] # [fx, fy, cx, cy] intrinsic parameters
|
||||
resolution_width: 640 # Image width in pixels
|
||||
resolution_height: 480 # Image height in pixels
|
||||
frequency: 30 # Capture frequency (Hz)
|
||||
pixel_size: 3 # Physical pixel size (μm)
|
||||
f_number: 2.0 # Lens aperture f-number
|
||||
focus_distance: 0.6 # Focus distance (meters)
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
|
||||
## Understanding Camera Parameters [](#understanding-camera-parameters)
|
||||
|
||||
### Intrinsic Matrix [](#intrinsic-matrix)
|
||||
|
||||
The camera intrinsic matrix K:
|
||||
|
||||
```
|
||||
K = | fx 0 cx |
|
||||
| 0 fy cy |
|
||||
| 0 0 1 |
|
||||
|
||||
fx, fy = focal lengths (pixels)
|
||||
cx, cy = principal point (pixels)
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
|
||||
### Sensor Settings [](#sensor-settings)
|
||||
|
||||
- **resolution_width **( int ): Image width in pixels. Typical value: 640 - 1920.
|
||||
- **resolution_height **( int ): Image height in pixels. Typical value: 480 - 1080.
|
||||
- **pixel_size **( float ): Physical pixel size (μm). Typical value: 1.4 - 3.0.
|
||||
- **f_number **( float ): Lens aperture. Typical value: 1.8 - 4.0.
|
||||
- **focus_distance **( float ): Focus distance (m). Typical value: 0.3 - 1.0.
|
||||
- **frequency **( int ): Capture frequency (Hz). Typical value: 15 - 60.
|
||||
|
||||
## Camera Mounting [](#camera-mounting)
|
||||
|
||||
### Robot-Mounted [](#robot-mounted)
|
||||
|
||||
Attach to robot link:
|
||||
yaml
|
||||
```
|
||||
parent: "lift2/lift2/lift2/fl/link6" # End-effector link
|
||||
translation: [0.07, 0.01, 0.08] # Offset from link
|
||||
```
|
||||
1
|
||||
2
|
||||
|
||||
### World-Fixed [](#world-fixed)
|
||||
|
||||
Fixed in world frame:
|
||||
yaml
|
||||
```
|
||||
parent: ""
|
||||
translation: [0.5, 0.5, 1.2]
|
||||
orientation: [0.707, 0.707, 0, 0] # Looking down
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
|
||||
## Domain Randomization [](#domain-randomization)
|
||||
|
||||
Enable camera pose randomization with the `_perturb_camera() `method defined in `workflows/simbox/core/tasks/banana.py `:
|
||||
yaml
|
||||
```
|
||||
cameras:
|
||||
- name: head_camera
|
||||
apply_randomization: true
|
||||
max_translation_noise: 0.03 # ±3 cm
|
||||
max_orientation_noise: 5.0 # ±5 degrees
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
|
||||
## Camera Outputs [](#camera-outputs)
|
||||
|
||||
`CustomCamera.get_observations() `returns:
|
||||
|
||||
- **color_image **( ndarray ): RGB image with shape H×W×3 (float32).
|
||||
- **camera2env_pose **( ndarray ): Camera to environment transform matrix with shape 4×4.
|
||||
- **camera_params **( ndarray ): Intrinsic matrix K with shape 3×3.
|
||||
|
||||
## Key Files [](#key-files)
|
||||
|
||||
| File | Purpose |
|
||||
| `cameras/custom_camera.py ` | CustomCamera implementation |
|
||||
| `cameras/__init__.py ` | Camera registry |
|
||||
|
||||
## References [](#references)
|
||||
|
||||
- [Isaac Sim Camera Sensors Documentation](https://docs.isaacsim.omniverse.nvidia.com/4.5.0/sensors/isaacsim_sensors_camera.html)
|
||||
- [Intel RealSense D415 Product Brief](https://simplecore.intel.com/realsensehub/wp-content/uploads/sites/63/D415_Series_ProductBrief_010718.pdf)
|
||||
- [Intel RealSense D435 Product Brief](https://simplecore.intel.com/realsensehub/wp-content/uploads/sites/63/D435_Series_ProductBrief_010718.pdf)
|
||||
- [Camera Frame Axes Reference](https://www.researchgate.net/figure/Axes-of-the-camera-frame-on-the-camera-CCD-and-lens_fig3_225025509)
|
||||
1241
docs_crawled/concepts_controllers.md
Normal file
1241
docs_crawled/concepts_controllers.md
Normal file
File diff suppressed because it is too large
Load Diff
372
docs_crawled/concepts_objects.md
Normal file
372
docs_crawled/concepts_objects.md
Normal file
@@ -0,0 +1,372 @@
|
||||
# Source: https://internrobotics.github.io/InternDataEngine-Docs/concepts/objects.html
|
||||
|
||||
# Objects [](#objects)
|
||||
|
||||
InternDataEngine supports various types of objects for simulation tasks. All object classes are located in `workflows/simbox/core/objects/ `.
|
||||
|
||||
## Supported Object Types [](#supported-object-types)
|
||||
|
||||
| Class | Description |
|
||||
| `RigidObject ` | Rigid body objects with physics properties (graspable objects) |
|
||||
| `GeometryObject ` | Static geometry objects without physics (tables, fixtures) |
|
||||
| `ArticulatedObject ` | Articulated objects with joints (microwaves, drawers) |
|
||||
| `PlaneObject ` | Simple planes with textures (floors, backgrounds) |
|
||||
| `XFormObject ` | Transform-only objects |
|
||||
| `ShapeObject ` | Basic geometric shapes |
|
||||
| `ConveyorObject ` | Conveyor belt objects |
|
||||
|
||||
## RigidObject [](#rigidobject)
|
||||
|
||||
`RigidObject `is used for objects that have physical properties and can be manipulated by robots. It inherits from Isaac Sim's `RigidPrim `and supports collision detection, mass properties, and texture randomization.
|
||||
|
||||
__init__(self, asset_root, root_prim_path, cfg, *args, **kwargs)
|
||||
|
||||
Initialize a rigid object in the simulation scene.
|
||||
|
||||
Parameters:
|
||||
|
||||
- **asset_root **( str ): Root path for asset files.
|
||||
- **root_prim_path **( str ): Root prim path in USD stage.
|
||||
- **cfg **( dict ): Configuration dictionary containing:
|
||||
- **name **( str ): Object name.
|
||||
- **path **( str ): USD file path relative to asset_root.
|
||||
- **prim_path_child **( str ): Child prim path for rigid body.
|
||||
- **translation **( list , optional): Initial translation [x, y, z].
|
||||
- **euler **( list , optional): Initial euler rotation [rx, ry, rz] in degrees.
|
||||
- **scale **( list , optional): Scale factor [sx, sy, sz].
|
||||
- **mass **( float , optional): Object mass.
|
||||
|
||||
- ** **kwargs **: Additional keyword arguments passed to `RigidPrim `.
|
||||
|
||||
### Config Example [](#config-example)
|
||||
yaml
|
||||
```
|
||||
objects:
|
||||
-
|
||||
name: pick_object_left
|
||||
path: pick_and_place/pre-train-pick/assets/omniobject3d-banana/omniobject3d-banana_001/Aligned_obj.usd
|
||||
target_class: RigidObject
|
||||
dataset: oo3d
|
||||
category: "omniobject3d-banana"
|
||||
prim_path_child: Aligned
|
||||
translation: [0.0, 0.0, 0.0]
|
||||
euler: [0.0, 0.0, 0.0]
|
||||
scale: [0.001, 0.001, 0.001]
|
||||
apply_randomization: True
|
||||
orientation_mode: "suggested"
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
10
|
||||
11
|
||||
12
|
||||
13
|
||||
|
||||
### Configuration Parameters [](#configuration-parameters)
|
||||
|
||||
- **name **( str ): Unique identifier for this object instance.
|
||||
- **path **( str ): Path to the USD file containing the object mesh.
|
||||
- **target_class **( str ): Must be `RigidObject `for rigid bodies.
|
||||
- **dataset **( str ): Dataset source identifier.
|
||||
- **category **( str ): Object category name.
|
||||
- **prim_path_child **( str ): Name of the child prim that contains the mesh.
|
||||
- **translation **( list ): Initial position [x, y, z] in world coordinates.
|
||||
- **euler **( list ): Initial rotation in degrees [roll, pitch, yaw].
|
||||
- **scale **( list ): Scale factors for each axis.
|
||||
- **apply_randomization **( bool ): Whether to apply domain randomization.
|
||||
- **orientation_mode **( str ): Orientation mode for randomization.
|
||||
|
||||
## GeometryObject [](#geometryobject)
|
||||
|
||||
`GeometryObject `is used for static objects without physics simulation. It's ideal for environmental objects like tables, shelves, or fixtures that don't need to interact physically with other objects.
|
||||
|
||||
__init__(self, asset_root, root_prim_path, cfg, *args, **kwargs)
|
||||
|
||||
Initialize a geometry object in the simulation scene.
|
||||
|
||||
Parameters:
|
||||
|
||||
- **asset_root **( str ): Root path for asset files.
|
||||
- **root_prim_path **( str ): Root prim path in USD stage.
|
||||
- **cfg **( dict ): Configuration dictionary containing:
|
||||
- **name **( str ): Object name.
|
||||
- **path **( str ): USD file path relative to asset_root.
|
||||
- **prim_path_child **( str , optional): Child prim path suffix.
|
||||
|
||||
- ** **kwargs **: Additional keyword arguments passed to `GeometryPrim `.
|
||||
|
||||
Difference from RigidObject:
|
||||
|
||||
- No physics simulation (no mass, no collision response)
|
||||
- Lighter weight for static environment objects
|
||||
- Cannot be grasped or moved by robots
|
||||
|
||||
### Config Example [](#config-example-1)
|
||||
yaml
|
||||
```
|
||||
objects:
|
||||
-
|
||||
name: table
|
||||
path: table0/instance.usd
|
||||
target_class: GeometryObject
|
||||
translation: [0.0, 0.0, 0.375]
|
||||
scale: [0.001, 0.001053, 0.001056]
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
|
||||
### Configuration Parameters [](#configuration-parameters-1)
|
||||
|
||||
- **name **( str ): Unique identifier for this object.
|
||||
- **path **( str ): Path to the USD file.
|
||||
- **target_class **( str ): Must be `GeometryObject `for static geometry.
|
||||
- **translation **( list ): Position in world coordinates.
|
||||
- **scale **( list ): Scale factors for each axis.
|
||||
|
||||
## PlaneObject [](#planeobject)
|
||||
|
||||
`PlaneObject `creates simple planes with optional texture mapping. It's commonly used for floors, backgrounds, and other flat surfaces.
|
||||
|
||||
__init__(self, asset_root, root_prim_path, cfg, *args, **kwargs)
|
||||
|
||||
Initialize a plane object in the simulation scene.
|
||||
|
||||
Parameters:
|
||||
|
||||
- **asset_root **( str ): Root path for asset files.
|
||||
- **root_prim_path **( str ): Root prim path in USD stage.
|
||||
- **cfg **( dict ): Configuration dictionary containing:
|
||||
- **name **( str ): Object name.
|
||||
- **size **( list ): Plane dimensions [width, height].
|
||||
- **translation **( list , optional): Position [x, y, z].
|
||||
- **euler **( list , optional): Rotation in degrees [roll, pitch, yaw].
|
||||
- **texture **( dict , optional): Texture configuration.
|
||||
|
||||
- ** **kwargs **: Additional keyword arguments.
|
||||
|
||||
### Config Example [](#config-example-2)
|
||||
yaml
|
||||
```
|
||||
objects:
|
||||
-
|
||||
name: floor
|
||||
target_class: PlaneObject
|
||||
size: [5.0, 5.0]
|
||||
translation: [0, 0, 0]
|
||||
texture:
|
||||
texture_lib: "floor_textures"
|
||||
apply_randomization: True
|
||||
texture_id: 1
|
||||
texture_scale: [1.0, 1.0]
|
||||
-
|
||||
name: background0
|
||||
target_class: PlaneObject
|
||||
size: [3.0, 5.0]
|
||||
translation: [-2, 0, 1]
|
||||
euler: [0.0, 90.0, 0.0]
|
||||
texture:
|
||||
texture_lib: "background_textures"
|
||||
apply_randomization: True
|
||||
texture_id: 1
|
||||
texture_scale: [1.0, 1.0]
|
||||
-
|
||||
name: background1
|
||||
target_class: PlaneObject
|
||||
size: [3.0, 5.0]
|
||||
translation: [2, 0, 1]
|
||||
euler: [0.0, 90.0, 0.0]
|
||||
texture:
|
||||
texture_lib: "background_textures"
|
||||
apply_randomization: True
|
||||
texture_id: 1
|
||||
texture_scale: [1.0, 1.0]
|
||||
-
|
||||
name: background2
|
||||
target_class: PlaneObject
|
||||
size: [5.0, 3.0]
|
||||
translation: [0, -2, 1]
|
||||
euler: [90.0, 0.0, 0.0]
|
||||
texture:
|
||||
texture_lib: "background_textures"
|
||||
apply_randomization: True
|
||||
texture_id: 1
|
||||
texture_scale: [1.0, 1.0]
|
||||
-
|
||||
name: background3
|
||||
target_class: PlaneObject
|
||||
size: [5.0, 3.0]
|
||||
translation: [0, 2, 1]
|
||||
euler: [90.0, 0.0, 0.0]
|
||||
texture:
|
||||
texture_lib: "background_textures"
|
||||
apply_randomization: True
|
||||
texture_id: 1
|
||||
texture_scale: [1.0, 1.0]
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
10
|
||||
11
|
||||
12
|
||||
13
|
||||
14
|
||||
15
|
||||
16
|
||||
17
|
||||
18
|
||||
19
|
||||
20
|
||||
21
|
||||
22
|
||||
23
|
||||
24
|
||||
25
|
||||
26
|
||||
27
|
||||
28
|
||||
29
|
||||
30
|
||||
31
|
||||
32
|
||||
33
|
||||
34
|
||||
35
|
||||
36
|
||||
37
|
||||
38
|
||||
39
|
||||
40
|
||||
41
|
||||
42
|
||||
43
|
||||
44
|
||||
45
|
||||
46
|
||||
47
|
||||
48
|
||||
49
|
||||
50
|
||||
51
|
||||
52
|
||||
53
|
||||
54
|
||||
55
|
||||
|
||||
### Configuration Parameters [](#configuration-parameters-2)
|
||||
|
||||
- **name **( str ): Unique identifier for the plane.
|
||||
- **target_class **( str ): Must be `PlaneObject `.
|
||||
- **size **( list ): Plane dimensions [width, height].
|
||||
- **translation **( list ): Position [x, y, z].
|
||||
- **euler **( list ): Rotation angles [roll, pitch, yaw] in degrees.
|
||||
- **texture.texture_lib **( str ): Name of texture library folder.
|
||||
- **texture.apply_randomization **( bool ): Whether to randomize texture selection.
|
||||
- **texture.texture_id **( int ): Specific texture ID (used when randomization is False).
|
||||
- **texture.texture_scale **( list ): Scale factors for texture UV mapping.
|
||||
|
||||
## ArticulatedObject [](#articulatedobject)
|
||||
|
||||
`ArticulatedObject `handles objects with movable joints, such as microwaves, drawers, and cabinets. It inherits from Isaac Sim's `Articulation `class and provides methods for joint control and state retrieval.
|
||||
|
||||
__init__(self, asset_root, root_prim_path, cfg, *args, **kwargs)
|
||||
|
||||
Initialize an articulated object in the simulation scene. Loads articulation info from the specified `info.json `file.
|
||||
|
||||
Parameters:
|
||||
|
||||
- **asset_root **( str ): Root path for asset files.
|
||||
- **root_prim_path **( str ): Root prim path in USD stage.
|
||||
- **cfg **( dict ): Configuration dictionary containing:
|
||||
- **name **( str ): Object name.
|
||||
- **path **( str ): USD file path relative to asset_root.
|
||||
- **info_name **( str ): Name of the skill folder containing `info.json `.
|
||||
- **category **( str ): Object category identifier.
|
||||
- **euler **( list , optional): Initial rotation [roll, pitch, yaw].
|
||||
- **joint_position_range **( list , optional): Random range for initial joint position [min, max].
|
||||
- **apply_randomization **( bool , optional): Whether to apply domain randomization.
|
||||
|
||||
- ** **kwargs **: Additional keyword arguments passed to `Articulation `.
|
||||
|
||||
get_articulated_info(self, object_info)
|
||||
|
||||
Parse and store articulation information from the object's info.json file. This method extracts keypoints, joint paths, scale information, and axis orientations.
|
||||
|
||||
Parameters:
|
||||
|
||||
- **object_info **( dict ): Dictionary loaded from `Kps/{skill}/info.json `containing:
|
||||
- **object_keypoints **( dict ): Keypoint positions in link_0 frame.
|
||||
- **object_scale **( list ): Object scale factors.
|
||||
- **object_prim_path **( str ): Prim path for the object.
|
||||
- **object_link_path **( str ): Prim path for the articulated link.
|
||||
- **object_base_path **( str ): Prim path for the base link.
|
||||
- **object_joint_path **( str ): Prim path for the joint.
|
||||
- **joint_index **( int ): Index of the main joint.
|
||||
- **object_link0_rot_axis **( str ): Rotation axis of the link.
|
||||
- **object_base_front_axis **( str ): Front axis of the base.
|
||||
|
||||
get_joint_position(self, stage)
|
||||
|
||||
Count and configure joints in the articulated object. This method identifies prismatic and revolute joints, and optionally fixes the base of the articulated object.
|
||||
|
||||
Parameters:
|
||||
|
||||
- **stage **( UsdStage ): The USD stage containing the articulation.
|
||||
|
||||
Sets the following attributes:
|
||||
|
||||
- **object_joint_number **( int ): Total number of joints found.
|
||||
|
||||
### Config Example [](#config-example-3)
|
||||
yaml
|
||||
```
|
||||
objects:
|
||||
-
|
||||
name: close_v_left
|
||||
target_class: ArticulatedObject
|
||||
info_name: "close_v"
|
||||
euler: [0.0, 0.0, 90.0]
|
||||
joint_position_range: [0.6, 0.8]
|
||||
apply_randomization: False
|
||||
path: "art/microwave_gr/microwave7119/instance.usd"
|
||||
category: "microwave_gr"
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
10
|
||||
|
||||
### Configuration Parameters [](#configuration-parameters-3)
|
||||
|
||||
- **name **( str ): Unique identifier for the articulated object.
|
||||
- **target_class **( str ): Must be `ArticulatedObject `.
|
||||
- **info_name **( str ): Name of the skill folder containing `info.json `.
|
||||
- **euler **( list ): Initial rotation [roll, pitch, yaw] in degrees.
|
||||
- **joint_position_range **( list ): Random range for initial joint position [min, max].
|
||||
- **apply_randomization **( bool ): Whether to apply domain randomization.
|
||||
- **path **( str ): Path to the USD file (relative to asset_root).
|
||||
- **category **( str ): Object category identifier.
|
||||
736
docs_crawled/concepts_robots.md
Normal file
736
docs_crawled/concepts_robots.md
Normal file
@@ -0,0 +1,736 @@
|
||||
# Source: https://internrobotics.github.io/InternDataEngine-Docs/concepts/robots.html
|
||||
|
||||
# Robots [](#robots)
|
||||
|
||||
InternDataEngine supports multiple robot platforms for manipulation tasks. Each robot has a dedicated wrapper class for articulation control and state management.
|
||||
|
||||
## Supported Robots [](#supported-robots)
|
||||
|
||||
| Robot | Type | DOF | Gripper (DOF) | Arm Model |
|
||||
| **ARX Lift-2 ** | Dual-arm | 6+6 | Parallel (2) | R5a |
|
||||
| **Agilex Split Aloha ** | Dual-arm | 6+6 | Parallel (2) | Piper-100 |
|
||||
| **Genie-1 ** | Dual-arm | 7+7 | Parallel (2) | G1-120s |
|
||||
| **Franka FR3 ** | Single-arm | 7 | Panda (1) | Franka |
|
||||
| **Franka Robotiq85 ** | Single-arm | 7 | Robotiq 2F-85 (2) | Franka |
|
||||
|
||||
### Robot End Effector and TCP Frame Visualizations [](#robot-end-effector-and-tcp-frame-visualizations)
|
||||
FR3 (Single-arm, Franka Panda Gripper)
|
||||
|
||||

|
||||
|
||||
*FR3 end-effector head frame visualization *
|
||||
|
||||

|
||||
|
||||
*FR3 TCP (Tool Center Point) head frame visualization *
|
||||
|
||||

|
||||
|
||||
*FR3 TCP hand frame visualization *
|
||||
Franka Robotiq85 (Single-arm, Robotiq 2F-85 Gripper)
|
||||
|
||||

|
||||
|
||||
*Franka Robotiq85 end-effector head frame visualization *
|
||||
|
||||

|
||||
|
||||
*Franka Robotiq85 TCP (Tool Center Point) head frame visualization *
|
||||
|
||||

|
||||
|
||||
*Franka Robotiq85 TCP hand frame visualization *
|
||||
Genie-1 (Dual-arm, G1-120s)
|
||||
|
||||

|
||||
|
||||
*Genie-1 left arm end-effector head frame visualization *
|
||||
|
||||

|
||||
|
||||
*Genie-1 left arm TCP head frame visualization *
|
||||
|
||||

|
||||
|
||||
*Genie-1 left arm TCP hand frame visualization *
|
||||
|
||||

|
||||
|
||||
*Genie-1 right arm end-effector head frame visualization *
|
||||
|
||||

|
||||
|
||||
*Genie-1 right arm TCP head frame visualization *
|
||||
|
||||

|
||||
|
||||
*Genie-1 right arm TCP hand frame visualization *
|
||||
ARX Lift-2 (Dual-arm, R5a)
|
||||
|
||||

|
||||
|
||||
*Lift-2 left arm end-effector head frame visualization *
|
||||
|
||||

|
||||
|
||||
*Lift-2 left arm TCP head frame visualization *
|
||||
|
||||

|
||||
|
||||
*Lift-2 left arm TCP hand frame visualization *
|
||||
|
||||

|
||||
|
||||
*Lift-2 right arm end-effector head frame visualization *
|
||||
|
||||

|
||||
|
||||
*Lift-2 right arm TCP head frame visualization *
|
||||
|
||||

|
||||
|
||||
*Lift-2 right arm TCP hand frame visualization *
|
||||
Agilex Split Aloha (Dual-arm, Piper-100)
|
||||
|
||||

|
||||
|
||||
*Split Aloha right arm end-effector head frame visualization *
|
||||
|
||||

|
||||
|
||||
*Split Aloha right arm TCP head frame visualization *
|
||||
|
||||

|
||||
|
||||
*Split Aloha right arm TCP hand frame visualization *
|
||||
|
||||
## Robot Configuration [](#robot-configuration)
|
||||
|
||||
Robot configuration is split into two parts: **task-level configuration **(in task YAML) and **robot-specific parameters **(in separate robot YAML files).
|
||||
|
||||
### Part 1: Task-Level Configuration (Task YAML) [](#part-1-task-level-configuration-task-yaml)
|
||||
|
||||
Configure robot instance in task YAML files:
|
||||
yaml
|
||||
```
|
||||
robots:
|
||||
- name: "lift2" # Robot identifier
|
||||
robot_config_file: workflows/simbox/core/configs/robots/lift2.yaml # Path to robot-specific config
|
||||
euler: [0.0, 0.0, 90.0] # Initial orientation [roll, pitch, yaw] in degrees
|
||||
ignore_substring: ["material", "table", "gso_box"] # Collision filter substrings
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
|
||||
### Part 2: Robot-Specific Parameters (Robot YAML) [](#part-2-robot-specific-parameters-robot-yaml)
|
||||
|
||||
Define robot hardware parameters in a separate YAML file (e.g., `workflows/simbox/core/configs/robots/lift2.yaml `):
|
||||
yaml
|
||||
```
|
||||
# Robot info
|
||||
target_class: Lift2 # Python class for robot wrapper
|
||||
path: "lift2/robot_invisible.usd" # USD file path relative to asset root
|
||||
|
||||
# CuRobo kinematics config files (one per arm for dual-arm robots)
|
||||
robot_file:
|
||||
- workflows/simbox/curobo/src/curobo/content/configs/robot/r5a_left_arm.yml
|
||||
- workflows/simbox/curobo/src/curobo/content/configs/robot/r5a_right_arm.yml
|
||||
|
||||
# Gripper parameters
|
||||
gripper_max_width: 0.088 # Maximum gripper opening width (meters)
|
||||
gripper_min_width: 0.0 # Minimum gripper closing width (meters)
|
||||
tcp_offset: 0.125 # Tool center point offset from end-effector (meters)
|
||||
|
||||
# Solver parameters for physics simulation
|
||||
solver_position_iteration_count: 128 # Position solver iterations
|
||||
solver_velocity_iteration_count: 4 # Velocity solver iterations
|
||||
stabilization_threshold: 0.005 # Stabilization threshold
|
||||
|
||||
# Joint indices in articulation
|
||||
left_joint_indices: [10, 12, 14, 16, 18, 20] # Left arm joint indices
|
||||
right_joint_indices: [9, 11, 13, 15, 17, 19] # Right arm joint indices
|
||||
left_gripper_indices: [23] # Left end-effector (gripper) joint index
|
||||
right_gripper_indices: [21] # Right end-effector (gripper) joint index
|
||||
lift_indices: [6] # Lift joint index
|
||||
|
||||
# End-effector paths
|
||||
fl_ee_path: "lift2/lift2/fl/link6" # Front-left end-effector prim path
|
||||
fr_ee_path: "lift2/lift2/fr/link6" # Front-right end-effector prim path
|
||||
fl_base_path: "lift2/lift2/fl/base_link" # Front-left base prim path
|
||||
fr_base_path: "lift2/lift2/fr/base_link" # Front-right base prim path
|
||||
|
||||
# Gripper keypoints for visualization
|
||||
fl_gripper_keypoints:
|
||||
tool_head: [0.135, 0.0, 0.0, 1]
|
||||
tool_tail: [0.085, 0.0, 0.0, 1]
|
||||
tool_side: [0.135, -0.044, 0.0, 1]
|
||||
fr_gripper_keypoints:
|
||||
tool_head: [0.135, 0.0, 0.0, 1]
|
||||
tool_tail: [0.085, 0.0, 0.0, 1]
|
||||
tool_side: [0.135, -0.044, 0.0, 1]
|
||||
|
||||
# Collision filter paths
|
||||
fl_filter_paths: # Paths to filter from collision (gripper fingers)
|
||||
- "lift2/lift2/fl/link7"
|
||||
- "lift2/lift2/fl/link8"
|
||||
fr_filter_paths:
|
||||
- "lift2/lift2/fr/link7"
|
||||
- "lift2/lift2/fr/link8"
|
||||
fl_forbid_collision_paths: # Paths forbidden for self-collision
|
||||
- "lift2/lift2/fl/link2"
|
||||
- "lift2/lift2/fl/link3"
|
||||
- "lift2/lift2/fl/link4"
|
||||
- "lift2/lift2/fl/link5"
|
||||
fr_forbid_collision_paths:
|
||||
- "lift2/lift2/fr/link2"
|
||||
- "lift2/lift2/fr/link3"
|
||||
- "lift2/lift2/fr/link4"
|
||||
- "lift2/lift2/fr/link5"
|
||||
|
||||
# Pose processing parameters
|
||||
R_ee_graspnet: [[1.0, 0.0, 0.0], [0.0, -1.0, 0.0], [0.0, 0.0, -1.0]] # Grasp rotation correction
|
||||
ee_axis: "x" # End-effector approach axis (x/y/z)
|
||||
|
||||
# Default joint home positions (radians)
|
||||
left_joint_home: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
|
||||
right_joint_home: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
|
||||
left_joint_home_std: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0] # Randomization std for left arm
|
||||
right_joint_home_std: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0] # Randomization std for right arm
|
||||
left_gripper_home: [0.044] # Left gripper default width (meters)
|
||||
right_gripper_home: [0.044] # Right gripper default width (meters)
|
||||
lift_home: [0.46] # Lift joint default position (meters)
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
10
|
||||
11
|
||||
12
|
||||
13
|
||||
14
|
||||
15
|
||||
16
|
||||
17
|
||||
18
|
||||
19
|
||||
20
|
||||
21
|
||||
22
|
||||
23
|
||||
24
|
||||
25
|
||||
26
|
||||
27
|
||||
28
|
||||
29
|
||||
30
|
||||
31
|
||||
32
|
||||
33
|
||||
34
|
||||
35
|
||||
36
|
||||
37
|
||||
38
|
||||
39
|
||||
40
|
||||
41
|
||||
42
|
||||
43
|
||||
44
|
||||
45
|
||||
46
|
||||
47
|
||||
48
|
||||
49
|
||||
50
|
||||
51
|
||||
52
|
||||
53
|
||||
54
|
||||
55
|
||||
56
|
||||
57
|
||||
58
|
||||
59
|
||||
60
|
||||
61
|
||||
62
|
||||
63
|
||||
64
|
||||
65
|
||||
66
|
||||
67
|
||||
68
|
||||
69
|
||||
70
|
||||
71
|
||||
72
|
||||
|
||||
## Understanding Robot Parameters [](#understanding-robot-parameters)
|
||||
|
||||
### Task-Level Fields [](#task-level-fields)
|
||||
|
||||
- **name **( str ): Robot identifier used in skills and cameras.
|
||||
- **robot_config_file **( str ): Path to robot-specific YAML configuration file.
|
||||
- **euler **( list ): Initial robot orientation in degrees [roll, pitch, yaw].
|
||||
- **ignore_substring **( list ): Collision filter substrings to ignore during simulation.
|
||||
|
||||
### Robot-Specific Fields [](#robot-specific-fields)
|
||||
|
||||
Some fields require detailed explanation due to their importance in grasp pose processing and robot kinematics:
|
||||
|
||||
R_ee_graspnet
|
||||
|
||||
A 3×3 rotation matrix that transforms the grasp pose orientation from the pre-defined graspnet frame to the robot's end-effector frame. Our generated grasp pose follows the frame definition from GraspNet.
|
||||
|
||||

|
||||
|
||||
*GraspNet gripper frame definition (source: graspnetAPI) *
|
||||
|
||||
*Source: [graspnet/graspnetAPI](https://github.com/graspnet/graspnetAPI?tab=readme-ov-file)*
|
||||
|
||||
The following examples illustrate how `R_ee_graspnet `is configured for different robots. You can verify these values by comparing the GraspNet frame definition with each robot's end-effector orientation shown in the visualizations above.
|
||||
|
||||
Config Example:
|
||||
yaml
|
||||
```
|
||||
# FR3
|
||||
R_ee_graspnet: [[0.0, 0.0, -1.0], [0.0, 1.0, 0.0], [1.0, 0.0, 0.0]]
|
||||
|
||||
# Genie-1
|
||||
R_ee_graspnet: [[0.0, 1.0, 0.0], [0.0, 0.0, 1.0], [1.0, 0.0, 0.0]]
|
||||
|
||||
# ARX Lift-2
|
||||
R_ee_graspnet: [[1.0, 0.0, 0.0], [0.0, -1.0, 0.0], [0.0, 0.0, -1.0]]
|
||||
|
||||
# Agilex Split Aloha
|
||||
R_ee_graspnet: [[0.0, -1.0, 0.0], [0.0, 0.0, -1.0], [1.0, 0.0, 0.0]]
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
10
|
||||
11
|
||||
|
||||
fl_ee_path / fr_ee_path
|
||||
|
||||
The USD prim path to the end-effector link (typically the last link of the arm **before **the TCP).
|
||||
|
||||
Warning
|
||||
|
||||
This link frame has a fixed transformation to the TCP frame. This path should be **aligned with the `ee_link `in the CuRobo config file **.
|
||||
|
||||
Usage:
|
||||
|
||||
- Compute the end-effector pose relative to the robot base via `get_relative_transform `
|
||||
- Define where gripper keypoints are attached
|
||||
- Serve as the reference frame for TCP (Tool Center Point) calculations
|
||||
|
||||
Config Example:
|
||||
yaml
|
||||
```
|
||||
# FR3
|
||||
fl_ee_path: "fr3/panda_hand" # relative to root robot prim path
|
||||
|
||||
# Franka Robotiq
|
||||
fl_ee_path: "arm/panda_link8"
|
||||
|
||||
# Agilex Split Aloha
|
||||
fl_ee_path: "split_aloha_mid_360_with_piper/split_aloha_mid_360_with_piper/fl/link6"
|
||||
fr_ee_path: "split_aloha_mid_360_with_piper/split_aloha_mid_360_with_piper/fr/link6"
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
|
||||
ee_axis
|
||||
|
||||
The axis along from end-effector origin to gripper TCP. Valid values are `"x" `, `"y" `, or `"z" `.
|
||||
|
||||
Usage:
|
||||
|
||||
- Used in `pose_post_process_fn `to calculate the actual EE position from TCP
|
||||
- Affects the 180° rotation variant generation for grasp pose diversity
|
||||
|
||||
Config Example:
|
||||
yaml
|
||||
```
|
||||
# FR3
|
||||
ee_axis: "z"
|
||||
|
||||
# ARX Lift-2
|
||||
ee_axis: "x"
|
||||
|
||||
# Agilex Split Aloha
|
||||
ee_axis: "z"
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
|
||||
tcp_offset
|
||||
|
||||
The distance from the end-effector frame origin to the Tool Center Point (TCP). The TCP is the point where the gripper fingertips meet when closed, which is the actual grasping point.
|
||||
|
||||
Usage:
|
||||
|
||||
- During grasp pose processing, the EE position is calculated as: `ee_center = tcp_center + approach_axis * (depth - tcp_offset) `
|
||||
- This offset accounts for the physical distance between the robot's end-effector frame and the actual grasping point
|
||||
|
||||
fl_gripper_keypoints / fr_gripper_keypoints
|
||||
|
||||
3D keypoints defined in the end-effector frame for articulated object manipulation planning.
|
||||
|
||||
Assume the gripper is oriented upright facing the user. The keypoints are defined as follows:
|
||||
|
||||
- **`tool_head `**: The point at the midpoint of the gripper fingertips, along the approach direction.
|
||||
- **`tool_tail `**: The point at the midpoint of the gripper finger bases, along the same approach direction.
|
||||
- **`tool_side `**: A point on the side of the right fingertip, used to indicate the gripper width.
|
||||
|
||||

|
||||
|
||||
*Gripper keypoints visualization showing tool_head, tool_tail, and tool_side *
|
||||
|
||||
Config Example:
|
||||
yaml
|
||||
```
|
||||
# ARX Lift-2
|
||||
fl_gripper_keypoints:
|
||||
tool_head: [0.135, 0.0, 0.0, 1] # Gripper fingertip (approach direction)
|
||||
tool_tail: [0.085, 0.0, 0.0, 1] # Gripper base
|
||||
tool_side: [0.135, -0.044, 0.0, 1] # Side point for width visualization
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
|
||||
### Other Fields [](#other-fields)
|
||||
|
||||
- **target_class **( str ): Python class for robot wrapper (e.g., `Lift2 `, `FR3 `).
|
||||
- **path **( str ): USD file path relative to asset root.
|
||||
- **robot_file **( list ): CuRobo kinematics config file(s) - one per arm.
|
||||
- **gripper_max_width **( float ): Maximum gripper opening width (meters).
|
||||
- **gripper_min_width **( float ): Minimum gripper closing width (meters).
|
||||
- **solver_position_iteration_count **( int ): Physics solver position iterations.
|
||||
- **solver_velocity_iteration_count **( int ): Physics solver velocity iterations.
|
||||
- **stabilization_threshold **( float ): Physics stabilization threshold.
|
||||
- **left_joint_indices **( list ): Joint indices for left arm in articulation.
|
||||
- **right_joint_indices **( list ): Joint indices for right arm in articulation.
|
||||
- **left_gripper_indices **( list ): Gripper joint index for left arm.
|
||||
- **right_gripper_indices **( list ): Gripper joint index for right arm.
|
||||
- **lift_indices **( list ): Lift joint indices (for robots with lift mechanism).
|
||||
- **fl_base_path **( str ): Left arm base prim path.
|
||||
- **fr_base_path **( str ): Right arm base prim path.
|
||||
- **fl_filter_paths **( list ): Collision filter prims' paths for left arm.
|
||||
- **fr_filter_paths **( list ): Collision filter prims' paths for right arm.
|
||||
- **fl_forbid_collision_paths **( list ): Forbidden collision prims' paths for left arm.
|
||||
- **fr_forbid_collision_paths **( list ): Forbidden collision prims' paths for right arm.
|
||||
- **left_joint_home **( list ): Default joint positions for left arm (radians).
|
||||
- **right_joint_home **( list ): Default joint positions for right arm (radians).
|
||||
- **left_joint_home_std **( list ): Standard deviation for randomizing left arm home position.
|
||||
- **right_joint_home_std **( list ): Standard deviation for randomizing right arm home position.
|
||||
- **left_gripper_home **( list ): Default gripper joint value for left gripper (Isaac).
|
||||
- **right_gripper_home **( list ): Default gripper joint value for right gripper (Isaac).
|
||||
- **lift_home **( list ): Default lift joint position (meters).
|
||||
|
||||
## Robot Wrappers [](#robot-wrappers)
|
||||
|
||||
Robot wrappers ( `workflows/simbox/core/robots/ `) provide a unified interface for:
|
||||
|
||||
- Articulation control
|
||||
- Gripper interface
|
||||
- State / observation management
|
||||
- Grasp pose post-processing
|
||||
|
||||
All concrete robots (e.g., `FR3 `, `FrankaRobotiq `, `Genie1 `, `Lift2 `, `SplitAloha `) share the same `TemplateRobot `implementation, with differences configured through YAML files and minimal subclass code.
|
||||
|
||||
Template Code Example:
|
||||
python
|
||||
```
|
||||
from copy import deepcopy
|
||||
|
||||
import numpy as np
|
||||
from core.robots.base_robot import register_robot
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
from omni.isaac.core.utils.prims import create_prim, get_prim_at_path
|
||||
from omni.isaac.core.utils.transformations import (
|
||||
get_relative_transform,
|
||||
tf_matrix_from_pose,
|
||||
)
|
||||
from scipy.interpolate import interp1d
|
||||
|
||||
@register_robot
|
||||
class TemplateRobot(Robot):
|
||||
"""
|
||||
Template class for manipulator robots.
|
||||
|
||||
All important parameters should be prepared in cfg before instantiation.
|
||||
The cfg is merged from: robot_config_file -> task_config_robots
|
||||
"""
|
||||
|
||||
def __init__(self, asset_root: str, root_prim_path: str, cfg: dict, *args, **kwargs):
|
||||
self.asset_root = asset_root
|
||||
self.cfg = cfg
|
||||
|
||||
# Create prim from USD
|
||||
usd_path = f"{asset_root}/{cfg['path']}"
|
||||
prim_path = f"{root_prim_path}/{cfg['name']}"
|
||||
create_prim(usd_path=usd_path, prim_path=prim_path)
|
||||
super().__init__(prim_path, cfg["name"], *args, **kwargs)
|
||||
|
||||
self.robot_prim_path = prim_path
|
||||
|
||||
# Gripper parameters (from cfg)
|
||||
self.gripper_max_width = cfg["gripper_max_width"]
|
||||
self.gripper_min_width = cfg["gripper_min_width"]
|
||||
|
||||
# Solver parameters
|
||||
self.set_solver_position_iteration_count(cfg["solver_position_iteration_count"])
|
||||
self.set_stabilization_threshold(cfg["stabilization_threshold"])
|
||||
self.set_solver_velocity_iteration_count(cfg["solver_velocity_iteration_count"])
|
||||
|
||||
# Setup from config
|
||||
self._setup_joint_indices()
|
||||
self._setup_paths()
|
||||
self._setup_gripper_keypoints()
|
||||
self._setup_collision_paths()
|
||||
self._load_extra_depth(usd_path)
|
||||
|
||||
def initialize(self, *args, **kwargs):
|
||||
super().initialize()
|
||||
self._articulation_view.initialize()
|
||||
self._setup_joint_velocities()
|
||||
self._setup_joint_homes()
|
||||
self._set_initial_positions()
|
||||
|
||||
def apply_action(self, joint_positions, joint_indices, *args, **kwargs):
|
||||
self._articulation_view.set_joint_position_targets(joint_positions, joint_indices=joint_indices)
|
||||
|
||||
def get_observations(self) -> dict:
|
||||
joint_state = self.get_joints_state()
|
||||
qpos, qvel = joint_state.positions, joint_state.velocities
|
||||
|
||||
T_base_ee_fl = get_relative_transform(
|
||||
get_prim_at_path(self.fl_ee_path), get_prim_at_path(self.fl_base_path)
|
||||
)
|
||||
T_world_base = tf_matrix_from_pose(*self.get_local_pose())
|
||||
|
||||
obs = self._build_observations(qpos, qvel, T_base_ee_fl, T_world_base)
|
||||
return obs
|
||||
|
||||
def pose_post_process_fn(
|
||||
self, poses, *args, lr_arm="left", grasp_scale=1, tcp_offset=None, constraints=None, **kwargs
|
||||
):
|
||||
if poses.shape[-2:] == (4, 4):
|
||||
return poses
|
||||
|
||||
R_ee_graspnet = self._get_R_ee_graspnet()
|
||||
n_grasps = poses.shape[0]
|
||||
T_obj_tcp = np.repeat(np.eye(4)[np.newaxis, :, :], n_grasps, axis=0)
|
||||
R_ee_graspnet = np.array(R_ee_graspnet)
|
||||
T_obj_tcp[:, :3, :3] = np.matmul(poses[:, 4:13].reshape(-1, 3, 3), R_ee_graspnet.T)
|
||||
T_obj_tcp[:, :3, 3] = poses[:, 13:16] * grasp_scale
|
||||
scores = poses[:, 0]
|
||||
widths = np.clip(poses[:, 1:2], self.gripper_min_width, self.gripper_max_width)
|
||||
depths = poses[:, 3:4]
|
||||
|
||||
if tcp_offset is None:
|
||||
tcp_offset = self.tcp_offset
|
||||
|
||||
if self._gripper_ed_func is not None:
|
||||
depths = depths + self._gripper_ed_func(widths)
|
||||
|
||||
# ... see full implementation in workflows/simbox/core/robots/template_robot.py
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
10
|
||||
11
|
||||
12
|
||||
13
|
||||
14
|
||||
15
|
||||
16
|
||||
17
|
||||
18
|
||||
19
|
||||
20
|
||||
21
|
||||
22
|
||||
23
|
||||
24
|
||||
25
|
||||
26
|
||||
27
|
||||
28
|
||||
29
|
||||
30
|
||||
31
|
||||
32
|
||||
33
|
||||
34
|
||||
35
|
||||
36
|
||||
37
|
||||
38
|
||||
39
|
||||
40
|
||||
41
|
||||
42
|
||||
43
|
||||
44
|
||||
45
|
||||
46
|
||||
47
|
||||
48
|
||||
49
|
||||
50
|
||||
51
|
||||
52
|
||||
53
|
||||
54
|
||||
55
|
||||
56
|
||||
57
|
||||
58
|
||||
59
|
||||
60
|
||||
61
|
||||
62
|
||||
63
|
||||
64
|
||||
65
|
||||
66
|
||||
67
|
||||
68
|
||||
69
|
||||
70
|
||||
71
|
||||
72
|
||||
73
|
||||
74
|
||||
75
|
||||
76
|
||||
77
|
||||
78
|
||||
79
|
||||
80
|
||||
81
|
||||
82
|
||||
83
|
||||
84
|
||||
85
|
||||
86
|
||||
87
|
||||
88
|
||||
89
|
||||
90
|
||||
91
|
||||
92
|
||||
93
|
||||
94
|
||||
95
|
||||
|
||||
__init__(self, asset_root: str , root_prim_path: str , cfg: dict , *args, **kwargs)
|
||||
|
||||
Create a robot instance from USD and initialize all geometry and dynamics-related paths/parameters based on configuration.
|
||||
|
||||
Parameters:
|
||||
|
||||
- **asset_root **( str ): Root directory for robot assets.
|
||||
- **root_prim_path **( str ): Root prim path where the robot is mounted in the USD stage.
|
||||
- **cfg **( dict ): Merged robot configuration (from robot YAML + task YAML).
|
||||
- ***args, **kwargs **: Passed to the `Robot `base class.
|
||||
|
||||
initialize(self, *args, **kwargs)
|
||||
|
||||
Perform one-time initialization after the physics engine is ready, including joint velocity limits, home poses, and initial joint positions.
|
||||
|
||||
apply_action(self, joint_positions, joint_indices, *args, **kwargs)
|
||||
|
||||
Send joint position targets to the Isaac articulation. This is one of the main interfaces between upper-level controllers/policies and the robot.
|
||||
|
||||
Parameters:
|
||||
|
||||
- **joint_positions **( np.ndarray ): Target joint positions.
|
||||
- **joint_indices **( np.ndarray ): Joint indices to control.
|
||||
- ***args, **kwargs **: Reserved for future extensions (e.g., velocity, torque control).
|
||||
|
||||
get_observations(self)
|
||||
|
||||
Collect the robot's current state for use as observation input by upper-level policies/planning modules.
|
||||
|
||||
Returns:
|
||||
|
||||
- **dict **: Observation dictionary for policy/planning.
|
||||
|
||||
pose_post_process_fn(self, poses, *args, lr_arm="left", grasp_scale=1, tcp_offset=None, constraints=None, **kwargs)
|
||||
|
||||
Convert grasp poses from a graspnet-style annotations (e.g., `(score, width, depth, R, t) `) to robot-specific end-effector pose sets, including TCP offset, grasp width clipping, and optional spatial constraints.
|
||||
|
||||
Core Logic:
|
||||
|
||||
- If `poses `is already a transformation matrix of shape `(N, 4, 4) `, return directly.
|
||||
- Use `R_ee_graspnet = self._get_R_ee_graspnet() `to correct the grasp rotation and construct `T_obj_tcp `:
|
||||
- Rotation: `R_tcp = poses_rot @ R_ee_graspnet^T `.
|
||||
- Translation: `t_tcp = poses[:, 13:16] * grasp_scale `.
|
||||
|
||||
- Clip grasp widths `widths `to `[gripper_min_width, gripper_max_width] `, and optionally correct insertion depth `depths `using `_gripper_ed_func `.
|
||||
- Use `tcp_offset `and the end-effector axis (determined by `ee_axis `) to transform TCP to actual EE transform `T_obj_ee `.
|
||||
- If `constraints = [axis, min_ratio, max_ratio] `is provided, filter grasps along the specified axis, keeping only those within the given range.
|
||||
- Call `_apply_rotation_variant `to generate a 180° rotation variant around the grasp axis, returning two sets of candidate grasp poses and their scores.
|
||||
|
||||
Parameters:
|
||||
|
||||
- **poses **( np.ndarray ): Raw grasp annotations, typically shape `(N, 16) `.
|
||||
- **lr_arm **( str ): Left/right arm marker ("left" or "right", currently mainly used by upper layers).
|
||||
- **grasp_scale **( float ): Grasp position scale factor.
|
||||
- **tcp_offset **( float , optional): TCP offset relative to EE; defaults to `self.tcp_offset `from config.
|
||||
- **constraints **( list , optional): Spatial filtering constraint of the form `[axis, min_ratio, max_ratio] `.
|
||||
- ***args, **kwargs **: Reserved for extensions.
|
||||
|
||||
Returns:
|
||||
|
||||
- **tuple **:
|
||||
- First item: `np.ndarray `of EE poses, shape approximately `(2N_filtered, 4, 4) `.
|
||||
- Second item: `np.ndarray `of corresponding scores, shape approximately `(2N_filtered,) `.
|
||||
|
||||
## References [](#references)
|
||||
|
||||
- [Isaac Sim Robot Manipulators Documentation](https://docs.isaacsim.omniverse.nvidia.com/5.1.0/py/source/extensions/isaacsim.robot.manipulators/docs/index.html)
|
||||
61
docs_crawled/concepts_skills.md
Normal file
61
docs_crawled/concepts_skills.md
Normal file
@@ -0,0 +1,61 @@
|
||||
# Source: https://internrobotics.github.io/InternDataEngine-Docs/concepts/skills.html
|
||||
|
||||
# Skills [](#skills)
|
||||
|
||||
Skills are the fundamental building blocks of robotic manipulation in InternDataEngine. Each skill defines an atomic action that a robot can perform, from simple gripper operations to complex manipulation sequences.
|
||||
|
||||
## Quick Navigation [](#quick-navigation)
|
||||
|
||||
| Category | Description |
|
||||
| [Overview](/InternDataEngine-Docs/concepts/skills/overview.html) | Skill architecture and available skills |
|
||||
| [Pick Skill](/InternDataEngine-Docs/concepts/skills/pick.html) | Grasping and lifting objects |
|
||||
| [Place Skill](/InternDataEngine-Docs/concepts/skills/place.html) | Placing objects at target locations |
|
||||
| [Articulation Skill](/InternDataEngine-Docs/concepts/skills/articulation.html) | Operating articulated objects (doors, drawers) |
|
||||
|
||||
## What is a Skill? [](#what-is-a-skill)
|
||||
|
||||
A skill encapsulates:
|
||||
|
||||
- **Motion Planning **: Trajectory generation using CuRobo
|
||||
- **Execution Control **: Step-by-step command execution
|
||||
- **State Monitoring **: Success/failure evaluation
|
||||
- **Gripper Actions **: Open/close operations
|
||||
|
||||
## Skill Categories [](#skill-categories)
|
||||
|
||||
### Manipulation Skills [](#manipulation-skills)
|
||||
|
||||
Skills for interacting with objects in the environment:
|
||||
|
||||
- **Pick **: Grasp and lift objects using sampled grasp poses
|
||||
- **Place **: Position objects at target locations
|
||||
- **Articulation **: Operate doors, drawers, and other articulated objects
|
||||
|
||||
### Motion Skills [](#motion-skills)
|
||||
|
||||
Skills for robot movement:
|
||||
|
||||
- `goto_pose `- Move to a target end-effector pose
|
||||
- `move `- Cartesian motion in a direction
|
||||
- `rotate `- Rotate the end-effector
|
||||
|
||||
### Utility Skills [](#utility-skills)
|
||||
|
||||
Helper skills for common operations:
|
||||
|
||||
- `home `- Return to home configuration
|
||||
- `open `/ `close `- Gripper control
|
||||
- `wait `- Pause execution
|
||||
|
||||
## Getting Started [](#getting-started)
|
||||
|
||||
- Read the [Skills Overview](/InternDataEngine-Docs/concepts/skills/overview.html)to understand the architecture
|
||||
- Learn about [Pick Skill](/InternDataEngine-Docs/concepts/skills/pick.html)for grasping objects
|
||||
- Explore [Place Skill](/InternDataEngine-Docs/concepts/skills/place.html)for placing operations
|
||||
- Check [Articulation Skill](/InternDataEngine-Docs/concepts/skills/articulation.html)for operating doors and drawers
|
||||
|
||||
## Related Topics [](#related-topics)
|
||||
|
||||
- [Tasks](/InternDataEngine-Docs/concepts/tasks/)- Combine skills into complete workflows
|
||||
- [Controllers](/InternDataEngine-Docs/concepts/controllers/)- Understand motion control
|
||||
- [Custom Skill](/InternDataEngine-Docs/custom/skill/)- Create your own skills
|
||||
577
docs_crawled/concepts_skills_articulation.md
Normal file
577
docs_crawled/concepts_skills_articulation.md
Normal file
@@ -0,0 +1,577 @@
|
||||
# Source: https://internrobotics.github.io/InternDataEngine-Docs/concepts/skills/articulation.html
|
||||
|
||||
# Articulation Skills [](#articulation-skills)
|
||||
|
||||
Articulation skills operate objects with joints, such as doors, drawers, microwaves, laptops, and knobs. They are all built on top of a keypoint-based planner ( **KPAMPlanner **) that solves geometric constraints online to generate keyframe trajectories.
|
||||
|
||||
## Available Articulation Skills [](#available-articulation-skills)
|
||||
text
|
||||
```
|
||||
workflows/simbox/core/skills/
|
||||
├── artpreplan.py # Pre-plan for long-horizon tasks
|
||||
├── open.py # Open or pull articulated objects
|
||||
├── close.py # Close or push articulated objects
|
||||
└── rotate.py # Rotate knobs / handles
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
|
||||
| Skill | Description | Use Cases |
|
||||
| `artpreplan ` | Pre-plan / fake-plan for long-horizon tasks | Search for reasonable layouts before actual execution |
|
||||
| `open ` | Open or pull articulated objects | Microwave doors, cabinet doors, laptop screens, drawers |
|
||||
| `close ` | Close or push articulated objects | Push microwaves closed, fold laptops, push drawers |
|
||||
| `rotate ` | Rotate knobs or handles | Twist oven knobs, turn handles |
|
||||
|
||||
### Skill Roles [](#skill-roles)
|
||||
|
||||
-
|
||||
|
||||
**`artpreplan.py `**: Performs a **fake plan **in long-horizon tasks. It uses KPAM to search for reasonable keyframes and layouts (e.g., door open angle, drawer position) without actually executing them. The results inform subsequent skills about feasible configurations.
|
||||
|
||||
-
|
||||
|
||||
**`open.py `**: Opens articulated objects:
|
||||
|
||||
- Horizontal opening: microwave doors, cabinet doors
|
||||
- Vertical opening: laptop screens
|
||||
- Pulling: drawers with handles
|
||||
|
||||
-
|
||||
|
||||
**`close.py `**: Closes articulated objects:
|
||||
|
||||
- Horizontal closing: push microwave doors closed
|
||||
- Vertical closing: fold laptop screens down
|
||||
- Push closing: push drawers back in
|
||||
|
||||
-
|
||||
|
||||
**`rotate.py `**: Grabs and rotates knobs or rotary handles around a specified axis.
|
||||
|
||||
All skills share the same planner core ( `KPAMPlanner `in `workflows/simbox/solver/planner.py `), inspired by **[GenSim2](https://gensim2.github.io/)**.
|
||||
|
||||
## Core API [](#core-api)
|
||||
|
||||
Below we use `Close `as the main example.
|
||||
|
||||
Code Example:
|
||||
python
|
||||
```
|
||||
# Source: workflows/simbox/core/skills/close.py
|
||||
from copy import deepcopy
|
||||
|
||||
import numpy as np
|
||||
from core.skills.base_skill import BaseSkill, register_skill
|
||||
from omegaconf import DictConfig
|
||||
from omni.isaac.core.controllers import BaseController
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
from omni.isaac.core.utils.prims import get_prim_at_path
|
||||
from omni.isaac.core.utils.transformations import get_relative_transform
|
||||
from scipy.spatial.transform import Rotation as R
|
||||
from solver.planner import KPAMPlanner
|
||||
|
||||
@register_skill
|
||||
class Close(BaseSkill):
|
||||
def __init__(self, robot: Robot, controller: BaseController, task: BaseTask, cfg: DictConfig, *args, **kwargs):
|
||||
super().__init__()
|
||||
self.robot = robot
|
||||
self.controller = controller
|
||||
self.task = task
|
||||
self.stage = task.stage
|
||||
self.name = cfg["name"]
|
||||
art_obj_name = cfg["objects"][0]
|
||||
self.skill_cfg = cfg
|
||||
self.art_obj = task.objects[art_obj_name]
|
||||
self.planner_setting = cfg["planner_setting"]
|
||||
self.contact_pose_index = self.planner_setting["contact_pose_index"]
|
||||
self.success_threshold = self.planner_setting["success_threshold"]
|
||||
self.update_art_joint = self.planner_setting.get("update_art_joint", False)
|
||||
if kwargs:
|
||||
self.world = kwargs["world"]
|
||||
self.draw = kwargs["draw"]
|
||||
self.manip_list = []
|
||||
|
||||
if self.skill_cfg.get("obj_info_path", None):
|
||||
self.art_obj.update_articulated_info(self.skill_cfg["obj_info_path"])
|
||||
|
||||
lr_arm = "left" if "left" in self.controller.robot_file else "right"
|
||||
self.fingers_link_contact_view = task.artcontact_views[robot.name][lr_arm][art_obj_name + "_fingers_link"]
|
||||
self.fingers_base_contact_view = task.artcontact_views[robot.name][lr_arm][art_obj_name + "_fingers_base"]
|
||||
self.forbid_collision_contact_view = task.artcontact_views[robot.name][lr_arm][
|
||||
art_obj_name + "_forbid_collision"
|
||||
]
|
||||
self.collision_valid = True
|
||||
self.process_valid = True
|
||||
|
||||
def setup_kpam(self):
|
||||
self.planner = KPAMPlanner(
|
||||
env=self.world,
|
||||
robot=self.robot,
|
||||
object=self.art_obj,
|
||||
cfg_path=self.planner_setting,
|
||||
controller=self.controller,
|
||||
draw_points=self.draw,
|
||||
stage=self.stage,
|
||||
)
|
||||
|
||||
def simple_generate_manip_cmds(self):
|
||||
if self.skill_cfg.get("obj_info_path", None):
|
||||
self.art_obj.update_articulated_info(self.skill_cfg["obj_info_path"])
|
||||
|
||||
self.setup_kpam()
|
||||
traj_keyframes, sample_times = self.planner.get_keypose()
|
||||
if len(traj_keyframes) == 0 and len(sample_times) == 0:
|
||||
print("No keyframes found, return empty manip_list")
|
||||
self.manip_list = []
|
||||
return
|
||||
|
||||
T_world_base = get_relative_transform(
|
||||
get_prim_at_path(self.robot.base_path), get_prim_at_path(self.task.root_prim_path)
|
||||
)
|
||||
self.traj_keyframes = traj_keyframes
|
||||
self.sample_times = sample_times
|
||||
manip_list = []
|
||||
|
||||
p_base_ee_cur, q_base_ee_cur = self.controller.get_ee_pose()
|
||||
ignore_substring = deepcopy(self.controller.ignore_substring + self.skill_cfg.get("ignore_substring", []))
|
||||
cmd = (
|
||||
p_base_ee_cur,
|
||||
q_base_ee_cur,
|
||||
"update_specific",
|
||||
{"ignore_substring": ignore_substring, "reference_prim_path": self.controller.reference_prim_path},
|
||||
)
|
||||
manip_list.append(cmd)
|
||||
|
||||
for i in range(len(self.traj_keyframes)):
|
||||
p_base_ee_tgt = self.traj_keyframes[i][:3, 3]
|
||||
q_base_ee_tgt = R.from_matrix(self.traj_keyframes[i][:3, :3]).as_quat(scalar_first=True)
|
||||
cmd = (p_base_ee_tgt, q_base_ee_tgt, "close_gripper", {})
|
||||
manip_list.append(cmd)
|
||||
|
||||
if i == self.contact_pose_index - 1:
|
||||
p_base_ee = self.traj_keyframes[i][:3, 3]
|
||||
q_base_ee = R.from_matrix(self.traj_keyframes[i][:3, :3]).as_quat(scalar_first=True)
|
||||
ignore_substring = deepcopy(
|
||||
self.controller.ignore_substring + self.skill_cfg.get("ignore_substring", [])
|
||||
)
|
||||
parent_name = self.art_obj.prim_path.split("/")[-2]
|
||||
ignore_substring.append(parent_name)
|
||||
cmd = (
|
||||
p_base_ee,
|
||||
q_base_ee,
|
||||
"update_specific",
|
||||
{"ignore_substring": ignore_substring, "reference_prim_path": self.controller.reference_prim_path},
|
||||
)
|
||||
manip_list.append(cmd)
|
||||
self.manip_list = manip_list
|
||||
|
||||
def update(self):
|
||||
curr_joint_p = self.art_obj._articulation_view.get_joint_positions()[:, self.art_obj.object_joint_index]
|
||||
if self.update_art_joint and self.is_success():
|
||||
self.art_obj._articulation_view.set_joint_position_targets(
|
||||
positions=curr_joint_p, joint_indices=self.art_obj.object_joint_index
|
||||
)
|
||||
|
||||
def is_success(self):
|
||||
contact = self.get_contact()
|
||||
|
||||
if self.skill_cfg.get("collision_valid", True):
|
||||
self.collision_valid = (
|
||||
self.collision_valid
|
||||
and len(contact["forbid_collision"]["forbid_collision_contact_indices"]) == 0
|
||||
and len(contact["fingers_base"]["fingers_base_contact_indices"]) == 0
|
||||
)
|
||||
if self.skill_cfg.get("process_valid", True):
|
||||
self.process_valid = np.max(np.abs(self.robot.get_joints_state().velocities)) < 5 and (
|
||||
np.max(np.abs(self.art_obj.get_linear_velocity())) < 5
|
||||
)
|
||||
|
||||
curr_joint_p = self.art_obj._articulation_view.get_joint_positions()[:, self.art_obj.object_joint_index]
|
||||
return np.abs(curr_joint_p) <= self.success_threshold and self.collision_valid and self.process_valid
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
10
|
||||
11
|
||||
12
|
||||
13
|
||||
14
|
||||
15
|
||||
16
|
||||
17
|
||||
18
|
||||
19
|
||||
20
|
||||
21
|
||||
22
|
||||
23
|
||||
24
|
||||
25
|
||||
26
|
||||
27
|
||||
28
|
||||
29
|
||||
30
|
||||
31
|
||||
32
|
||||
33
|
||||
34
|
||||
35
|
||||
36
|
||||
37
|
||||
38
|
||||
39
|
||||
40
|
||||
41
|
||||
42
|
||||
43
|
||||
44
|
||||
45
|
||||
46
|
||||
47
|
||||
48
|
||||
49
|
||||
50
|
||||
51
|
||||
52
|
||||
53
|
||||
54
|
||||
55
|
||||
56
|
||||
57
|
||||
58
|
||||
59
|
||||
60
|
||||
61
|
||||
62
|
||||
63
|
||||
64
|
||||
65
|
||||
66
|
||||
67
|
||||
68
|
||||
69
|
||||
70
|
||||
71
|
||||
72
|
||||
73
|
||||
74
|
||||
75
|
||||
76
|
||||
77
|
||||
78
|
||||
79
|
||||
80
|
||||
81
|
||||
82
|
||||
83
|
||||
84
|
||||
85
|
||||
86
|
||||
87
|
||||
88
|
||||
89
|
||||
90
|
||||
91
|
||||
92
|
||||
93
|
||||
94
|
||||
95
|
||||
96
|
||||
97
|
||||
98
|
||||
99
|
||||
100
|
||||
101
|
||||
102
|
||||
103
|
||||
104
|
||||
105
|
||||
106
|
||||
107
|
||||
108
|
||||
109
|
||||
110
|
||||
111
|
||||
112
|
||||
113
|
||||
114
|
||||
115
|
||||
116
|
||||
117
|
||||
118
|
||||
119
|
||||
120
|
||||
121
|
||||
122
|
||||
123
|
||||
124
|
||||
125
|
||||
126
|
||||
127
|
||||
128
|
||||
129
|
||||
130
|
||||
131
|
||||
132
|
||||
133
|
||||
|
||||
__init__(self, robot, controller, task, cfg, *args, **kwargs)
|
||||
|
||||
Initialize the close skill and bind it to a specific articulated object.
|
||||
|
||||
Parameters:
|
||||
|
||||
- **robot **( Robot ): Robot instance.
|
||||
- **controller **( BaseController ): Motion controller.
|
||||
- **task **( BaseTask ): Task containing scene objects.
|
||||
- **cfg **( DictConfig ): Skill configuration from YAML.
|
||||
|
||||
Key Operations:
|
||||
|
||||
- Extract articulated object from `cfg["objects"][0] `
|
||||
- Load planner settings ( `contact_pose_index `, `success_threshold `)
|
||||
- Initialize contact views for collision monitoring
|
||||
- Load articulation info from `obj_info_path `if provided
|
||||
|
||||
setup_kpam(self)
|
||||
|
||||
Initialize the KPAM planner with world, robot, object, and configuration.
|
||||
|
||||
KPAM Planner Components:
|
||||
|
||||
- **env **: Simulation world
|
||||
- **robot **: Robot instance
|
||||
- **object **: Articulated object
|
||||
- **cfg_path **: Planner configuration (constraints, solver options)
|
||||
- **controller **: Motion controller
|
||||
- **stage **: USD stage
|
||||
|
||||
simple_generate_manip_cmds(self)
|
||||
|
||||
Generate manipulation commands by solving constraints.
|
||||
|
||||
Steps:
|
||||
|
||||
- **Setup KPAM **: Initialize planner with current world state
|
||||
- **Get keyframes **: `traj_keyframes, sample_times = self.planner.get_keypose() `
|
||||
- **Build manip_list **:
|
||||
- Update collision settings
|
||||
- For each keyframe, add `close_gripper `command
|
||||
- Before contact pose, update collision filters to ignore parent link
|
||||
|
||||
Gripper Behavior:
|
||||
|
||||
- **Close skill **: Gripper remains **closed **throughout trajectory (pushing motion)
|
||||
- **Open skill **: Gripper is open before contact, closes at contact point, then pulls
|
||||
|
||||
update(self)
|
||||
|
||||
Update articulation joint targets during execution.
|
||||
|
||||
When Enabled:
|
||||
|
||||
If `update_art_joint `is `True `and skill succeeds, the current joint position is written back as the target. This "locks in" the closed state for subsequent skills.
|
||||
|
||||
is_success(self)
|
||||
|
||||
Check if the close operation succeeded.
|
||||
|
||||
Success Conditions:
|
||||
|
||||
- **Collision validity **: No forbidden collisions, no palm contacts
|
||||
- **Process validity **: Velocities within limits (< 5)
|
||||
- **Joint position **: `|curr_joint_p| <= success_threshold `(near closed state)
|
||||
|
||||
Returns:
|
||||
|
||||
- bool : `True `if all conditions satisfied
|
||||
|
||||
## KPAM Planner: Constraint-Based Trajectory Generation [](#kpam-planner-constraint-based-trajectory-generation)
|
||||
|
||||
The `KPAMPlanner `solves geometric constraints defined in the task YAML to generate keyframe trajectories. The solver code is in:
|
||||
|
||||
- `workflows/simbox/solver/planner.py `
|
||||
- `workflows/simbox/solver/planner_utils.py `
|
||||
|
||||
### Keypoint Annotation [](#keypoint-annotation)
|
||||
|
||||
Before defining constraints, keypoints must be annotated on both the robot gripper and the articulated object.
|
||||
|
||||
#### Robot Gripper Keypoints [](#robot-gripper-keypoints)
|
||||
|
||||
Defined in robot YAML under `fl_gripper_keypoints `/ `fr_gripper_keypoints `(see [Robots](/InternDataEngine-Docs/concepts/robots/)):
|
||||
|
||||
- **tool_head **( list ): TCP position (fingertip center).
|
||||
- **tool_tail **( list ): Gripper base position.
|
||||
- **tool_side **( list ): Side fingertip position.
|
||||
|
||||

|
||||
|
||||
#### Articulated Object Keypoints [](#articulated-object-keypoints)
|
||||
|
||||
Annotated in the object's articulation info file. See [Assets - Articulated Objects](/InternDataEngine-Docs/custom/assets/#articulated-objects)for details.
|
||||
|
||||
Common keypoints:
|
||||
|
||||
- `articulated_object_head `— One end of the movable part
|
||||
- `articulated_object_tail `— Other end of the movable part
|
||||
- `link0_contact_axis `— Axis direction for contact
|
||||
|
||||
### Constraint Types [](#constraint-types)
|
||||
|
||||
Users define constraints in the task YAML under `planner_setting.constraint_list `. The planner solves these constraints to find valid keyframe poses.
|
||||
|
||||
#### Point-to-Point Constraint [](#point-to-point-constraint)
|
||||
yaml
|
||||
```
|
||||
- keypoint_name: tool_head
|
||||
target_keypoint_name: articulated_object_head
|
||||
tolerance: 0.0001
|
||||
name: fingers_contact_with_link0
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
|
||||
- keypoint_name: tool_head **Effect **: Enforces that `keypoint_name `(tool_head on gripper) and `target_keypoint_name `(articulated_object_head on object) are within `tolerance `distance. Used to ensure gripper contacts the object.
|
||||
|
||||
#### Keypoints Vector Parallelism [](#keypoints-vector-parallelism)
|
||||
yaml
|
||||
```
|
||||
- axis_from_keypoint_name: tool_head
|
||||
axis_to_keypoint_name: tool_side
|
||||
cross_target_axis1_from_keypoint_name: articulated_object_head
|
||||
cross_target_axis1_to_keypoint_name: articulated_object_tail
|
||||
target_axis: link0_contact_axis
|
||||
target_axis_frame: object
|
||||
tolerance: 0.005
|
||||
target_inner_product: -1
|
||||
type: frame_axis_parallel
|
||||
name: hand_parallel_to_link0_edge_door
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
10
|
||||
|
||||
**Effect **: Enforces parallelism between two vectors:
|
||||
|
||||
- **Gripper vector **: `axis_from_keypoint_name → axis_to_keypoint_name `(here `tool_head → tool_side `)
|
||||
- **Object vector **: `cross_target_axis1_from_keypoint_name → cross_target_axis1_to_keypoint_name `(here `articulated_object_head → articulated_object_tail `)
|
||||
|
||||
The `target_inner_product `specifies the desired alignment with `tolerance `:
|
||||
|
||||
- `-1 `: Vectors should be anti-parallel (opposite direction)
|
||||
- `1 `: Vectors should be parallel (same direction)
|
||||
|
||||
#### Parallelism with Cross Product [](#parallelism-with-cross-product)
|
||||
yaml
|
||||
```
|
||||
- axis_from_keypoint_name: tool_head
|
||||
axis_to_keypoint_name: tool_tail
|
||||
cross_target_axis1_from_keypoint_name: articulated_object_head
|
||||
cross_target_axis1_to_keypoint_name: articulated_object_tail
|
||||
target_axis: link0_contact_axis
|
||||
target_axis_frame: object
|
||||
tolerance: 0.005
|
||||
target_inner_product: 0.7
|
||||
type: frame_axis_parallel
|
||||
name: fingers_orthogonal_to_link0
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
10
|
||||
|
||||
**Effect **: Enforces parallelism between two vectors:
|
||||
|
||||
-
|
||||
|
||||
**Gripper vector **: `axis_from_keypoint_name → axis_to_keypoint_name `(here `tool_head → tool_tail `, the approach direction)
|
||||
|
||||
-
|
||||
|
||||
**Computed object vector **: Cross product of:
|
||||
|
||||
- `(cross_target_axis1_from_keypoint_name → cross_target_axis1_to_keypoint_name) `(here `articulated_object_head → articulated_object_tail `)
|
||||
- `target_axis `(here `link0_contact_axis `)
|
||||
|
||||
The `target_inner_product `specifies the desired dot product between these two vectors:
|
||||
|
||||
- `1.0 `: Parallel (same direction)
|
||||
- `-1.0 `: Anti-parallel (opposite direction)
|
||||
- `0.0 `: Perpendicular
|
||||
- `0.7 `: At an angle (approximately 45°)
|
||||
|
||||
In this example, `target_inner_product: 0.7 `enforces that the gripper's approach direction is at an angle to the door surface, which is often needed for stable grasping during manipulation.
|
||||
|
||||
#### Vector Alignment Constraint (simple) [](#vector-alignment-constraint-simple)
|
||||
yaml
|
||||
```
|
||||
- axis_from_keypoint_name: tool_head
|
||||
axis_to_keypoint_name: tool_side
|
||||
target_axis: object_link0_move_axis
|
||||
target_axis_frame: object
|
||||
tolerance: 0.0005
|
||||
target_inner_product: -1
|
||||
type: frame_axis_parallel
|
||||
name: hand_parallel_to_link0_edge
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
|
||||
**Effect **: Enforces that the gripper vector `tool_head → tool_side `aligns directly with `target_axis `(here `object_link0_move_axis `), without any cross product calculation.
|
||||
|
||||
This is used when the target axis is already known (e.g., the pulling direction of a drawer) and you want the gripper to align with it.
|
||||
|
||||
### How Constraints Are Solved [](#how-constraints-are-solved)
|
||||
|
||||
- **Keypoint lookup **: Planner reads all keypoint positions from robot and object
|
||||
- **Constraint evaluation **: Each constraint computes a cost based on current EE pose
|
||||
- **Optimization **: Solver minimizes total cost to find valid keyframe poses
|
||||
- **Trajectory generation **: Valid poses become waypoints in `manip_list `
|
||||
|
||||
## Configuration Reference [](#configuration-reference)
|
||||
|
||||
- **objects **( list , default: required): `[articulated_object_name] `.
|
||||
- **obj_info_path **( string , default: `None `): Path to articulation info YAML.
|
||||
- **planner_setting.contact_pose_index **( int , default: required): Keyframe index where gripper contacts object.
|
||||
- **planner_setting.success_threshold **( float , default: required): Joint displacement threshold for success.
|
||||
- **planner_setting.update_art_joint **( bool , default: `False `): Update articulation joint targets on success.
|
||||
- **planner_setting.constraint_list **( list , default: required): List of constraint definitions.
|
||||
- **ignore_substring **( list , default: `[] `): Collision filter substrings.
|
||||
|
||||
## References [](#references)
|
||||
|
||||
- [GenSim2](https://gensim2.github.io/)— Scaling Robot Data Generation with Multi-modal and Reasoning LLMs. The KPAM planner design is inspired by the keypoint-based manipulation approach in GenSim2.
|
||||
216
docs_crawled/concepts_skills_overview.md
Normal file
216
docs_crawled/concepts_skills_overview.md
Normal file
@@ -0,0 +1,216 @@
|
||||
# Source: https://internrobotics.github.io/InternDataEngine-Docs/concepts/skills/overview.html
|
||||
|
||||
# Skills Overview [](#skills-overview)
|
||||
|
||||
Skills define **atomic manipulation actions **that robots can perform, such as picking, placing, or moving objects. Each skill encapsulates a specific behavior and generates a sequence of manipulation commands for the controller to execute.
|
||||
|
||||
## Architecture [](#architecture)
|
||||
|
||||
All skills inherit from `BaseSkill `defined in `workflows/simbox/core/skills/base_skill.py `.
|
||||
|
||||
```
|
||||
workflows/simbox/core/skills/
|
||||
├── base_skill.py # Abstract base class
|
||||
├── __init__.py # Skill registry
|
||||
│
|
||||
├── Pick-and-Place Skills
|
||||
│ ├── pick.py # Standard pick operation
|
||||
│ ├── place.py # Standard place operation
|
||||
│ ├── dexpick.py # Dex-style pick with constraints
|
||||
│ ├── dexplace.py # Dex-style place with constraints
|
||||
│ ├── manualpick.py # Manual grasp pose specification
|
||||
│ ├── dynamicpick.py # Dynamic grasp selection
|
||||
│ └── failpick.py # Failure case pick
|
||||
│
|
||||
├── Articulation-Related Skills
|
||||
│ ├── open.py # Open or pull articulation
|
||||
│ ├── close.py # Close or push articulation
|
||||
│ ├── rotate.py # Rotate articulation joint
|
||||
│ └── artpreplan.py # Articulation pre-planning
|
||||
│
|
||||
├── Heuristic Skills
|
||||
│ ├── goto_pose.py # Move to target pose
|
||||
│ ├── gripper_action.py # Generic gripper action (Open, Close)
|
||||
│ ├── heuristic_skill.py # Configurable heuristic actions
|
||||
│ ├── joint_ctrl.py # Joint-level control
|
||||
│ └── wait.py # Wait for duration
|
||||
│
|
||||
└── Task-Specific Skills
|
||||
├── move.py # Cartesian motion
|
||||
├── track.py # Trajectory tracking
|
||||
├── approach_rotate.py # Approach with rotation
|
||||
├── flip.py # Flip object
|
||||
├── scan.py # Scan motion
|
||||
└── pour_water_succ.py # Pouring metric
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
10
|
||||
11
|
||||
12
|
||||
13
|
||||
14
|
||||
15
|
||||
16
|
||||
17
|
||||
18
|
||||
19
|
||||
20
|
||||
21
|
||||
22
|
||||
23
|
||||
24
|
||||
25
|
||||
26
|
||||
27
|
||||
28
|
||||
29
|
||||
30
|
||||
31
|
||||
32
|
||||
33
|
||||
|
||||
## Skill Template [](#skill-template)
|
||||
|
||||
All skills inherit from `BaseSkill `and implement a standard interface:
|
||||
python
|
||||
```
|
||||
from core.skills.base_skill import BaseSkill, register_skill
|
||||
|
||||
@register_skill
|
||||
class MySkill(BaseSkill):
|
||||
"""Custom manipulation skill."""
|
||||
|
||||
def __init__(self, robot, controller, task, cfg, *args, **kwargs):
|
||||
super().__init__()
|
||||
self.robot = robot
|
||||
self.controller = controller
|
||||
self.task = task
|
||||
self.skill_cfg = cfg
|
||||
self.manip_list = []
|
||||
|
||||
def simple_generate_manip_cmds(self):
|
||||
"""Generate the manipulation command list (REQUIRED)."""
|
||||
# Build manip_list with (position, quaternion, function, params) tuples
|
||||
pass
|
||||
|
||||
def is_feasible(self, th=5):
|
||||
"""Check if skill can continue based on planning failures."""
|
||||
return self.controller.num_plan_failed <= th
|
||||
|
||||
def is_subtask_done(self, t_eps=1e-3, o_eps=5e-3):
|
||||
"""Check if current waypoint is reached."""
|
||||
pass
|
||||
|
||||
def is_done(self):
|
||||
"""Check if all commands are executed."""
|
||||
return len(self.manip_list) == 0
|
||||
|
||||
def is_success(self):
|
||||
"""Check if skill succeeded."""
|
||||
pass
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
10
|
||||
11
|
||||
12
|
||||
13
|
||||
14
|
||||
15
|
||||
16
|
||||
17
|
||||
18
|
||||
19
|
||||
20
|
||||
21
|
||||
22
|
||||
23
|
||||
24
|
||||
25
|
||||
26
|
||||
27
|
||||
28
|
||||
29
|
||||
30
|
||||
31
|
||||
32
|
||||
33
|
||||
34
|
||||
|
||||
For detailed implementation instructions, see the [Custom Skill Guide](/InternDataEngine-Docs/custom/skill/).
|
||||
|
||||
## Core Concepts [](#core-concepts)
|
||||
|
||||
### Manipulation Command List [](#manipulation-command-list)
|
||||
|
||||
Each skill generates a `manip_list `— a sequence of command tuples defining waypoint poses and actions:
|
||||
python
|
||||
```
|
||||
manip_list = [
|
||||
(p_base_ee_tgt, q_base_ee_tgt, function_name, params),
|
||||
# ... more commands
|
||||
]
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
|
||||
**Command tuple structure: **
|
||||
|
||||
- **p_base_ee_tgt **( np.ndarray ): Target end-effector position in arm base frame, shape `(3,) `.
|
||||
- **q_base_ee_tgt **( np.ndarray ): Target end-effector quaternion `(w, x, y, z) `in arm base frame, shape `(4,) `.
|
||||
- **function_name **( str ): Action function to execute.
|
||||
- **params **( dict ): Parameters for the action function.
|
||||
|
||||
**Common action functions: **
|
||||
|
||||
- `open_gripper `/ `close_gripper `— Gripper control
|
||||
- `attach_obj `/ `detach_obj `— Physics attachment
|
||||
- `update_pose_cost_metric `— Planning weight adjustment
|
||||
- `update_specific `— Collision avoidance settings
|
||||
- `dummy_forward `— Direct action without planning
|
||||
|
||||
### Execution Flow [](#execution-flow)
|
||||
|
||||
```
|
||||
┌──────────────────────────────────────────────────────────────┐
|
||||
│ Skill Execution Pipeline │
|
||||
├──────────────────────────────────────────────────────────────┤
|
||||
│ 1. Initialize skill with YAML config │
|
||||
│ 2. Generate manip_list via simple_generate_manip_cmds() │
|
||||
│ 3. Pop next command from manip_list │
|
||||
│ 4. Plan motion trajectory with CuRobo controller │
|
||||
│ 5. Execute motion and apply action function │
|
||||
│ 6. Check is_subtask_done() → if True, pop next command │
|
||||
│ 7. Repeat until is_done() returns True │
|
||||
│ 8. Evaluate is_success() for final task status │
|
||||
└──────────────────────────────────────────────────────────────┘
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
10
|
||||
11
|
||||
12
|
||||
975
docs_crawled/concepts_skills_pick.md
Normal file
975
docs_crawled/concepts_skills_pick.md
Normal file
@@ -0,0 +1,975 @@
|
||||
# Source: https://internrobotics.github.io/InternDataEngine-Docs/concepts/skills/pick.html
|
||||
|
||||
# Pick Skill [](#pick-skill)
|
||||
|
||||
The `Pick `skill performs a standard pick operation with grasp pose selection. It loads pre-annotated grasp poses from `.npy `files, filters them based on orientation constraints, and executes the pick motion.
|
||||
|
||||
Code Example:
|
||||
python
|
||||
```
|
||||
# Source workflows/simbox/core/skills/pick.py
|
||||
import os
|
||||
import random
|
||||
from copy import deepcopy
|
||||
|
||||
import numpy as np
|
||||
from core.skills.base_skill import BaseSkill, register_skill
|
||||
from core.utils.constants import CUROBO_BATCH_SIZE
|
||||
from core.utils.plan_utils import (
|
||||
select_index_by_priority_dual,
|
||||
select_index_by_priority_single,
|
||||
)
|
||||
from core.utils.transformation_utils import poses_from_tf_matrices
|
||||
from omegaconf import DictConfig
|
||||
from omni.isaac.core.controllers import BaseController
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
from omni.isaac.core.utils.prims import get_prim_at_path
|
||||
from omni.isaac.core.utils.transformations import (
|
||||
get_relative_transform,
|
||||
tf_matrix_from_pose,
|
||||
)
|
||||
|
||||
@register_skill
|
||||
class Pick(BaseSkill):
|
||||
def __init__(self, robot: Robot, controller: BaseController, task: BaseTask, cfg: DictConfig, *args, **kwargs):
|
||||
super().__init__()
|
||||
self.robot = robot
|
||||
self.controller = controller
|
||||
self.task = task
|
||||
self.skill_cfg = cfg
|
||||
object_name = self.skill_cfg["objects"][0]
|
||||
self.pick_obj = task.objects[object_name]
|
||||
|
||||
# Get grasp annotation
|
||||
usd_path = [obj["path"] for obj in task.cfg["objects"] if obj["name"] == object_name][0]
|
||||
usd_path = os.path.join(self.task.asset_root, usd_path)
|
||||
grasp_pose_path = usd_path.replace(
|
||||
"Aligned_obj.usd", self.skill_cfg.get("npy_name", "Aligned_grasp_sparse.npy")
|
||||
)
|
||||
sparse_grasp_poses = np.load(grasp_pose_path)
|
||||
lr_arm = "right" if "right" in self.controller.robot_file else "left"
|
||||
self.T_obj_ee, self.scores = self.robot.pose_post_process_fn(
|
||||
sparse_grasp_poses,
|
||||
lr_arm=lr_arm,
|
||||
grasp_scale=self.skill_cfg.get("grasp_scale", 1),
|
||||
tcp_offset=self.skill_cfg.get("tcp_offset", self.robot.tcp_offset),
|
||||
constraints=self.skill_cfg.get("constraints", None),
|
||||
)
|
||||
|
||||
# Keyposes should be generated after previous skill is done
|
||||
self.manip_list = []
|
||||
self.pickcontact_view = task.pickcontact_views[robot.name][lr_arm][object_name]
|
||||
self.process_valid = True
|
||||
self.obj_init_trans = deepcopy(self.pick_obj.get_local_pose()[0])
|
||||
final_gripper_state = self.skill_cfg.get("final_gripper_state", -1)
|
||||
if final_gripper_state == 1:
|
||||
self.gripper_cmd = "open_gripper"
|
||||
elif final_gripper_state == -1:
|
||||
self.gripper_cmd = "close_gripper"
|
||||
else:
|
||||
raise ValueError(f"final_gripper_state must be 1 or -1, got {final_gripper_state}")
|
||||
self.fixed_orientation = self.skill_cfg.get("fixed_orientation", None)
|
||||
if self.fixed_orientation is not None:
|
||||
self.fixed_orientation = np.array(self.fixed_orientation)
|
||||
|
||||
def simple_generate_manip_cmds(self):
|
||||
manip_list = []
|
||||
|
||||
# Update
|
||||
p_base_ee_cur, q_base_ee_cur = self.controller.get_ee_pose()
|
||||
cmd = (p_base_ee_cur, q_base_ee_cur, "update_pose_cost_metric", {"hold_vec_weight": None})
|
||||
manip_list.append(cmd)
|
||||
|
||||
ignore_substring = deepcopy(self.controller.ignore_substring + self.skill_cfg.get("ignore_substring", []))
|
||||
ignore_substring.append(self.pick_obj.name)
|
||||
cmd = (
|
||||
p_base_ee_cur,
|
||||
q_base_ee_cur,
|
||||
"update_specific",
|
||||
{"ignore_substring": ignore_substring, "reference_prim_path": self.controller.reference_prim_path},
|
||||
)
|
||||
manip_list.append(cmd)
|
||||
|
||||
# Pre grasp
|
||||
T_base_ee_grasps = self.sample_ee_pose() # (N, 4, 4)
|
||||
T_base_ee_pregrasps = deepcopy(T_base_ee_grasps)
|
||||
self.controller.update_specific(
|
||||
ignore_substring=ignore_substring, reference_prim_path=self.controller.reference_prim_path
|
||||
)
|
||||
|
||||
if "r5a" in self.controller.robot_file:
|
||||
T_base_ee_pregrasps[:, :3, 3] -= T_base_ee_pregrasps[:, :3, 0] * self.skill_cfg.get("pre_grasp_offset", 0.1)
|
||||
else:
|
||||
T_base_ee_pregrasps[:, :3, 3] -= T_base_ee_pregrasps[:, :3, 2] * self.skill_cfg.get("pre_grasp_offset", 0.1)
|
||||
|
||||
p_base_ee_pregrasps, q_base_ee_pregrasps = poses_from_tf_matrices(T_base_ee_pregrasps)
|
||||
p_base_ee_grasps, q_base_ee_grasps = poses_from_tf_matrices(T_base_ee_grasps)
|
||||
|
||||
if self.controller.use_batch:
|
||||
# Check if the input arrays are exactly the same
|
||||
if np.array_equal(p_base_ee_pregrasps, p_base_ee_grasps) and np.array_equal(
|
||||
q_base_ee_pregrasps, q_base_ee_grasps
|
||||
):
|
||||
# Inputs are identical, compute only once to avoid redundant computation
|
||||
result = self.controller.test_batch_forward(p_base_ee_grasps, q_base_ee_grasps)
|
||||
index = select_index_by_priority_single(result)
|
||||
else:
|
||||
# Inputs are different, compute separately
|
||||
pre_result = self.controller.test_batch_forward(p_base_ee_pregrasps, q_base_ee_pregrasps)
|
||||
result = self.controller.test_batch_forward(p_base_ee_grasps, q_base_ee_grasps)
|
||||
index = select_index_by_priority_dual(pre_result, result)
|
||||
else:
|
||||
for index in range(T_base_ee_grasps.shape[0]):
|
||||
p_base_ee_pregrasp, q_base_ee_pregrasp = p_base_ee_pregrasps[index], q_base_ee_pregrasps[index]
|
||||
p_base_ee_grasp, q_base_ee_grasp = p_base_ee_grasps[index], q_base_ee_grasps[index]
|
||||
test_mode = self.skill_cfg.get("test_mode", "forward")
|
||||
if test_mode == "forward":
|
||||
result_pre = self.controller.test_single_forward(p_base_ee_pregrasp, q_base_ee_pregrasp)
|
||||
elif test_mode == "ik":
|
||||
result_pre = self.controller.test_single_ik(p_base_ee_pregrasp, q_base_ee_pregrasp)
|
||||
else:
|
||||
raise NotImplementedError
|
||||
if self.skill_cfg.get("pre_grasp_offset", 0.1) > 0:
|
||||
if test_mode == "forward":
|
||||
result = self.controller.test_single_forward(p_base_ee_grasp, q_base_ee_grasp)
|
||||
elif test_mode == "ik":
|
||||
result = self.controller.test_single_ik(p_base_ee_grasp, q_base_ee_grasp)
|
||||
else:
|
||||
raise NotImplementedError
|
||||
if result == 1 and result_pre == 1:
|
||||
print("pick plan success")
|
||||
break
|
||||
else:
|
||||
if result_pre == 1:
|
||||
print("pick plan success")
|
||||
break
|
||||
|
||||
if self.fixed_orientation is not None:
|
||||
q_base_ee_pregrasps[index] = self.fixed_orientation
|
||||
q_base_ee_grasps[index] = self.fixed_orientation
|
||||
|
||||
# Pre-grasp
|
||||
cmd = (p_base_ee_pregrasps[index], q_base_ee_pregrasps[index], "open_gripper", {})
|
||||
manip_list.append(cmd)
|
||||
if self.skill_cfg.get("pre_grasp_hold_vec_weight", None) is not None:
|
||||
cmd = (
|
||||
p_base_ee_pregrasps[index],
|
||||
q_base_ee_pregrasps[index],
|
||||
"update_pose_cost_metric",
|
||||
{"hold_vec_weight": self.skill_cfg.get("pre_grasp_hold_vec_weight", None)},
|
||||
)
|
||||
manip_list.append(cmd)
|
||||
|
||||
# Grasp
|
||||
cmd = (p_base_ee_grasps[index], q_base_ee_grasps[index], "open_gripper", {})
|
||||
manip_list.append(cmd)
|
||||
cmd = (p_base_ee_grasps[index], q_base_ee_grasps[index], self.gripper_cmd, {})
|
||||
manip_list.extend(
|
||||
[cmd] * self.skill_cfg.get("gripper_change_steps", 40)
|
||||
) # Default we use 40 steps to make sure the gripper is fully closed
|
||||
ignore_substring = deepcopy(self.controller.ignore_substring + self.skill_cfg.get("ignore_substring", []))
|
||||
cmd = (
|
||||
p_base_ee_grasps[index],
|
||||
q_base_ee_grasps[index],
|
||||
"update_specific",
|
||||
{"ignore_substring": ignore_substring, "reference_prim_path": self.controller.reference_prim_path},
|
||||
)
|
||||
manip_list.append(cmd)
|
||||
cmd = (
|
||||
p_base_ee_grasps[index],
|
||||
q_base_ee_grasps[index],
|
||||
"attach_obj",
|
||||
{"obj_prim_path": self.pick_obj.mesh_prim_path},
|
||||
)
|
||||
manip_list.append(cmd)
|
||||
|
||||
# Post-grasp
|
||||
post_grasp_offset = np.random.uniform(
|
||||
self.skill_cfg.get("post_grasp_offset_min", 0.05), self.skill_cfg.get("post_grasp_offset_max", 0.05)
|
||||
)
|
||||
if post_grasp_offset:
|
||||
p_base_ee_postgrasps = deepcopy(p_base_ee_grasps)
|
||||
p_base_ee_postgrasps[index][2] += post_grasp_offset
|
||||
cmd = (p_base_ee_postgrasps[index], q_base_ee_grasps[index], self.gripper_cmd, {})
|
||||
manip_list.append(cmd)
|
||||
|
||||
# Whether return to pre-grasp
|
||||
if self.skill_cfg.get("return_to_pregrasp", False):
|
||||
cmd = (p_base_ee_pregrasps[index], q_base_ee_pregrasps[index], self.gripper_cmd, {})
|
||||
manip_list.append(cmd)
|
||||
|
||||
self.manip_list = manip_list
|
||||
|
||||
def sample_ee_pose(self, max_length=CUROBO_BATCH_SIZE):
|
||||
T_base_ee = self.get_ee_poses("armbase")
|
||||
|
||||
num_pose = T_base_ee.shape[0]
|
||||
flags = {
|
||||
"x": np.ones(num_pose, dtype=bool),
|
||||
"y": np.ones(num_pose, dtype=bool),
|
||||
"z": np.ones(num_pose, dtype=bool),
|
||||
"direction_to_obj": np.ones(num_pose, dtype=bool),
|
||||
}
|
||||
filter_conditions = {
|
||||
"x": {
|
||||
"forward": (0, 0, 1), # (row, col, direction)
|
||||
"backward": (0, 0, -1),
|
||||
"upward": (2, 0, 1),
|
||||
"downward": (2, 0, -1),
|
||||
},
|
||||
"y": {"forward": (0, 1, 1), "backward": (0, 1, -1), "downward": (2, 1, -1), "upward": (2, 1, 1)},
|
||||
"z": {"forward": (0, 2, 1), "backward": (0, 2, -1), "downward": (2, 2, -1), "upward": (2, 2, 1)},
|
||||
}
|
||||
for axis in ["x", "y", "z"]:
|
||||
filter_list = self.skill_cfg.get(f"filter_{axis}_dir", None)
|
||||
if filter_list is not None:
|
||||
# direction, value = filter_list
|
||||
direction = filter_list[0]
|
||||
row, col, sign = filter_conditions[axis][direction]
|
||||
if len(filter_list) == 2:
|
||||
value = filter_list[1]
|
||||
cos_val = np.cos(np.deg2rad(value))
|
||||
flags[axis] = T_base_ee[:, row, col] >= cos_val if sign > 0 else T_base_ee[:, row, col] <= cos_val
|
||||
elif len(filter_list) == 3:
|
||||
value1, value2 = filter_list[1:]
|
||||
cos_val1 = np.cos(np.deg2rad(value1))
|
||||
cos_val2 = np.cos(np.deg2rad(value2))
|
||||
if sign > 0:
|
||||
flags[axis] = np.logical_and(
|
||||
T_base_ee[:, row, col] >= cos_val1, T_base_ee[:, row, col] <= cos_val2
|
||||
)
|
||||
else:
|
||||
flags[axis] = np.logical_and(
|
||||
T_base_ee[:, row, col] <= cos_val1, T_base_ee[:, row, col] >= cos_val2
|
||||
)
|
||||
if self.skill_cfg.get("direction_to_obj", None) is not None:
|
||||
direction_to_obj = self.skill_cfg["direction_to_obj"]
|
||||
T_world_obj = tf_matrix_from_pose(*self.pick_obj.get_local_pose())
|
||||
T_base_world = get_relative_transform(
|
||||
get_prim_at_path(self.task.root_prim_path), get_prim_at_path(self.controller.reference_prim_path)
|
||||
)
|
||||
T_base_obj = T_base_world @ T_world_obj
|
||||
if direction_to_obj == "right":
|
||||
flags["direction_to_obj"] = T_base_ee[:, 1, 3] <= T_base_obj[1, 3]
|
||||
elif direction_to_obj == "left":
|
||||
flags["direction_to_obj"] = T_base_ee[:, 1, 3] > T_base_obj[1, 3]
|
||||
else:
|
||||
raise NotImplementedError
|
||||
|
||||
combined_flag = np.logical_and.reduce(list(flags.values()))
|
||||
if sum(combined_flag) == 0:
|
||||
# idx_list = [i for i in range(max_length)]
|
||||
idx_list = list(range(max_length))
|
||||
else:
|
||||
tmp_scores = self.scores[combined_flag]
|
||||
tmp_idxs = np.arange(num_pose)[combined_flag]
|
||||
combined = list(zip(tmp_scores, tmp_idxs))
|
||||
combined.sort()
|
||||
idx_list = [idx for (score, idx) in combined[:max_length]]
|
||||
score_list = self.scores[idx_list]
|
||||
weights = 1.0 / (score_list + 1e-8)
|
||||
weights = weights / weights.sum()
|
||||
|
||||
sampled_idx = random.choices(idx_list, weights=weights, k=max_length)
|
||||
sampled_scores = self.scores[sampled_idx]
|
||||
|
||||
# Sort indices by their scores (ascending)
|
||||
sorted_pairs = sorted(zip(sampled_scores, sampled_idx))
|
||||
idx_list = [idx for _, idx in sorted_pairs]
|
||||
|
||||
print(self.scores[idx_list])
|
||||
# print((T_base_ee[idx_list])[:, 0, 1])
|
||||
return T_base_ee[idx_list]
|
||||
|
||||
def get_ee_poses(self, frame: str = "world"):
|
||||
# get grasp poses at specific frame
|
||||
if frame not in ["world", "body", "armbase"]:
|
||||
raise ValueError(
|
||||
f"poses in {frame} frame is not supported: accepted values are [world, body, armbase] only"
|
||||
)
|
||||
|
||||
if frame == "body":
|
||||
return self.T_obj_ee
|
||||
|
||||
T_world_obj = tf_matrix_from_pose(*self.pick_obj.get_local_pose())
|
||||
T_world_ee = T_world_obj[None] @ self.T_obj_ee
|
||||
|
||||
if frame == "world":
|
||||
return T_world_ee
|
||||
|
||||
if frame == "armbase": # arm base frame
|
||||
T_world_base = get_relative_transform(
|
||||
get_prim_at_path(self.controller.reference_prim_path), get_prim_at_path(self.task.root_prim_path)
|
||||
)
|
||||
T_base_world = np.linalg.inv(T_world_base)
|
||||
T_base_ee = T_base_world[None] @ T_world_ee
|
||||
return T_base_ee
|
||||
|
||||
def get_contact(self, contact_threshold=0.0):
|
||||
contact = np.abs(self.pickcontact_view.get_contact_force_matrix()).squeeze()
|
||||
contact = np.sum(contact, axis=-1)
|
||||
indices = np.where(contact > contact_threshold)[0]
|
||||
return contact, indices
|
||||
|
||||
def is_feasible(self, th=5):
|
||||
return self.controller.num_plan_failed <= th
|
||||
|
||||
def is_subtask_done(self, t_eps=1e-3, o_eps=5e-3):
|
||||
assert len(self.manip_list) != 0
|
||||
p_base_ee_cur, q_base_ee_cur = self.controller.get_ee_pose()
|
||||
p_base_ee, q_base_ee, *_ = self.manip_list[0]
|
||||
diff_trans = np.linalg.norm(p_base_ee_cur - p_base_ee)
|
||||
diff_ori = 2 * np.arccos(min(abs(np.dot(q_base_ee_cur, q_base_ee)), 1.0))
|
||||
pose_flag = np.logical_and(
|
||||
diff_trans < t_eps,
|
||||
diff_ori < o_eps,
|
||||
)
|
||||
self.plan_flag = self.controller.num_last_cmd > 10
|
||||
return np.logical_or(pose_flag, self.plan_flag)
|
||||
|
||||
def is_done(self):
|
||||
if len(self.manip_list) == 0:
|
||||
return True
|
||||
if self.is_subtask_done(t_eps=self.skill_cfg.get("t_eps", 1e-3), o_eps=self.skill_cfg.get("o_eps", 5e-3)):
|
||||
self.manip_list.pop(0)
|
||||
return len(self.manip_list) == 0
|
||||
|
||||
def is_success(self):
|
||||
flag = True
|
||||
|
||||
_, indices = self.get_contact()
|
||||
if self.gripper_cmd == "close_gripper":
|
||||
flag = len(indices) >= 1
|
||||
|
||||
if self.skill_cfg.get("process_valid", True):
|
||||
self.process_valid = np.max(np.abs(self.robot.get_joints_state().velocities)) < 5 and (
|
||||
np.max(np.abs(self.pick_obj.get_linear_velocity())) < 5
|
||||
)
|
||||
flag = flag and self.process_valid
|
||||
|
||||
if self.skill_cfg.get("lift_th", 0.0) > 0.0:
|
||||
p_world_obj = deepcopy(self.pick_obj.get_local_pose()[0])
|
||||
flag = flag and ((p_world_obj[2] - self.obj_init_trans[2]) > self.skill_cfg.get("lift_th", 0.0))
|
||||
|
||||
return flag
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
10
|
||||
11
|
||||
12
|
||||
13
|
||||
14
|
||||
15
|
||||
16
|
||||
17
|
||||
18
|
||||
19
|
||||
20
|
||||
21
|
||||
22
|
||||
23
|
||||
24
|
||||
25
|
||||
26
|
||||
27
|
||||
28
|
||||
29
|
||||
30
|
||||
31
|
||||
32
|
||||
33
|
||||
34
|
||||
35
|
||||
36
|
||||
37
|
||||
38
|
||||
39
|
||||
40
|
||||
41
|
||||
42
|
||||
43
|
||||
44
|
||||
45
|
||||
46
|
||||
47
|
||||
48
|
||||
49
|
||||
50
|
||||
51
|
||||
52
|
||||
53
|
||||
54
|
||||
55
|
||||
56
|
||||
57
|
||||
58
|
||||
59
|
||||
60
|
||||
61
|
||||
62
|
||||
63
|
||||
64
|
||||
65
|
||||
66
|
||||
67
|
||||
68
|
||||
69
|
||||
70
|
||||
71
|
||||
72
|
||||
73
|
||||
74
|
||||
75
|
||||
76
|
||||
77
|
||||
78
|
||||
79
|
||||
80
|
||||
81
|
||||
82
|
||||
83
|
||||
84
|
||||
85
|
||||
86
|
||||
87
|
||||
88
|
||||
89
|
||||
90
|
||||
91
|
||||
92
|
||||
93
|
||||
94
|
||||
95
|
||||
96
|
||||
97
|
||||
98
|
||||
99
|
||||
100
|
||||
101
|
||||
102
|
||||
103
|
||||
104
|
||||
105
|
||||
106
|
||||
107
|
||||
108
|
||||
109
|
||||
110
|
||||
111
|
||||
112
|
||||
113
|
||||
114
|
||||
115
|
||||
116
|
||||
117
|
||||
118
|
||||
119
|
||||
120
|
||||
121
|
||||
122
|
||||
123
|
||||
124
|
||||
125
|
||||
126
|
||||
127
|
||||
128
|
||||
129
|
||||
130
|
||||
131
|
||||
132
|
||||
133
|
||||
134
|
||||
135
|
||||
136
|
||||
137
|
||||
138
|
||||
139
|
||||
140
|
||||
141
|
||||
142
|
||||
143
|
||||
144
|
||||
145
|
||||
146
|
||||
147
|
||||
148
|
||||
149
|
||||
150
|
||||
151
|
||||
152
|
||||
153
|
||||
154
|
||||
155
|
||||
156
|
||||
157
|
||||
158
|
||||
159
|
||||
160
|
||||
161
|
||||
162
|
||||
163
|
||||
164
|
||||
165
|
||||
166
|
||||
167
|
||||
168
|
||||
169
|
||||
170
|
||||
171
|
||||
172
|
||||
173
|
||||
174
|
||||
175
|
||||
176
|
||||
177
|
||||
178
|
||||
179
|
||||
180
|
||||
181
|
||||
182
|
||||
183
|
||||
184
|
||||
185
|
||||
186
|
||||
187
|
||||
188
|
||||
189
|
||||
190
|
||||
191
|
||||
192
|
||||
193
|
||||
194
|
||||
195
|
||||
196
|
||||
197
|
||||
198
|
||||
199
|
||||
200
|
||||
201
|
||||
202
|
||||
203
|
||||
204
|
||||
205
|
||||
206
|
||||
207
|
||||
208
|
||||
209
|
||||
210
|
||||
211
|
||||
212
|
||||
213
|
||||
214
|
||||
215
|
||||
216
|
||||
217
|
||||
218
|
||||
219
|
||||
220
|
||||
221
|
||||
222
|
||||
223
|
||||
224
|
||||
225
|
||||
226
|
||||
227
|
||||
228
|
||||
229
|
||||
230
|
||||
231
|
||||
232
|
||||
233
|
||||
234
|
||||
235
|
||||
236
|
||||
237
|
||||
238
|
||||
239
|
||||
240
|
||||
241
|
||||
242
|
||||
243
|
||||
244
|
||||
245
|
||||
246
|
||||
247
|
||||
248
|
||||
249
|
||||
250
|
||||
251
|
||||
252
|
||||
253
|
||||
254
|
||||
255
|
||||
256
|
||||
257
|
||||
258
|
||||
259
|
||||
260
|
||||
261
|
||||
262
|
||||
263
|
||||
264
|
||||
265
|
||||
266
|
||||
267
|
||||
268
|
||||
269
|
||||
270
|
||||
271
|
||||
272
|
||||
273
|
||||
274
|
||||
275
|
||||
276
|
||||
277
|
||||
278
|
||||
279
|
||||
280
|
||||
281
|
||||
282
|
||||
283
|
||||
284
|
||||
285
|
||||
286
|
||||
287
|
||||
288
|
||||
289
|
||||
290
|
||||
291
|
||||
292
|
||||
293
|
||||
294
|
||||
295
|
||||
296
|
||||
297
|
||||
298
|
||||
299
|
||||
300
|
||||
301
|
||||
302
|
||||
303
|
||||
304
|
||||
305
|
||||
306
|
||||
307
|
||||
308
|
||||
309
|
||||
310
|
||||
311
|
||||
312
|
||||
313
|
||||
314
|
||||
315
|
||||
316
|
||||
317
|
||||
318
|
||||
319
|
||||
320
|
||||
321
|
||||
322
|
||||
323
|
||||
324
|
||||
325
|
||||
326
|
||||
327
|
||||
328
|
||||
329
|
||||
330
|
||||
331
|
||||
332
|
||||
333
|
||||
334
|
||||
335
|
||||
336
|
||||
337
|
||||
338
|
||||
339
|
||||
340
|
||||
341
|
||||
342
|
||||
343
|
||||
344
|
||||
345
|
||||
346
|
||||
|
||||
__init__(self, robot, controller, task, cfg, *args, **kwargs)
|
||||
|
||||
Initialize the pick skill and load grasp annotations.
|
||||
|
||||
Parameters:
|
||||
|
||||
- **robot **( Robot ): Robot instance for state queries and actions.
|
||||
- **controller **( BaseController ): Controller for motion planning.
|
||||
- **task **( BaseTask ): Task instance containing scene objects.
|
||||
- **cfg **( DictConfig ): Skill configuration from task YAML.
|
||||
|
||||
Key Operations:
|
||||
|
||||
- Extract target object name from `cfg["objects"][0] `
|
||||
- Load sparse grasp poses from `Aligned_grasp_sparse.npy `
|
||||
- Transform grasp poses to EE frame via `robot.pose_post_process_fn() `
|
||||
- Initialize `manip_list `for command sequence
|
||||
|
||||
simple_generate_manip_cmds(self)
|
||||
|
||||
Generate the full pick motion sequence. This is the core method that defines the pick behavior.
|
||||
|
||||
Steps:
|
||||
|
||||
- **Update planning settings **— Reset cost metrics and collision settings
|
||||
- **Sample EE poses **— Call `sample_ee_pose() `to filter valid grasp candidates
|
||||
- **Generate pre-grasp poses **— Offset grasp poses along approach direction
|
||||
- **Test motion feasibility **— Use CuRobo to check which candidates are reachable
|
||||
- **Build manip_list **— Construct command sequence:
|
||||
- Move to pre-grasp pose with open gripper
|
||||
- Move to grasp pose
|
||||
- Close gripper
|
||||
- Attach object to gripper (physics)
|
||||
- Lift object (post-grasp offset)
|
||||
|
||||
sample_ee_pose(self, max_length=CUROBO_BATCH_SIZE)
|
||||
|
||||
Filter grasp poses based on end-effector orientation constraints.
|
||||
|
||||
Parameters:
|
||||
|
||||
- **max_length **( int ): Maximum number of poses to return.
|
||||
|
||||
Returns:
|
||||
|
||||
- np.ndarray : Filtered grasp poses as transformation matrices `(N, 4, 4) `.
|
||||
|
||||
Filtering Logic:
|
||||
|
||||
- Transform all candidate grasp poses to arm base frame
|
||||
- Apply `filter_x_dir `, `filter_y_dir `, `filter_z_dir `constraints
|
||||
- Sort remaining poses by grasp quality score
|
||||
- Sample top candidates weighted by inverse score
|
||||
|
||||
is_success(self)
|
||||
|
||||
Check if the pick operation succeeded.
|
||||
|
||||
Success Conditions:
|
||||
|
||||
- **Contact check **: Gripper is in contact with at least one object (when closing gripper)
|
||||
- **Motion validity **: Joint velocities < 5 rad/s, object velocity < 5 m/s
|
||||
- **Lift check **(optional): Object lifted above initial height by `lift_th `threshold
|
||||
|
||||
Returns:
|
||||
|
||||
- bool : `True `if all conditions are satisfied.
|
||||
|
||||
## Grasp Orientation Filtering [](#grasp-orientation-filtering)
|
||||
|
||||
The pick skill uses a **direction-based filtering strategy **to select valid grasp poses. Instead of constructing specific poses, we filter pre-annotated grasp candidates based on the desired end-effector orientation.
|
||||
|
||||
### Coordinate System [](#coordinate-system)
|
||||
|
||||
All arm base frames follow this convention:
|
||||
|
||||
- **X-axis **: Forward (toward the table/workspace)
|
||||
- **Y-axis **: Right (when facing the table)
|
||||
- **Z-axis **: Upward
|
||||
|
||||
**Arm Base Frame Examples: **
|
||||
|
||||
| Franka | ARX Lift-2 | Agilex Split Aloha |
|
||||
|  |  |  |
|
||||
|
||||
The end-effector frame has its own local X, Y, Z axes. The filter constraints control how these EE axes align with the arm base frame.
|
||||
|
||||
### Filter Parameters [](#filter-parameters)
|
||||
|
||||
- **filter_x_dir **( list ): Filter based on EE's X-axis direction in arm base frame.
|
||||
- **filter_y_dir **( list ): Filter based on EE's Y-axis direction in arm base frame.
|
||||
- **filter_z_dir **( list ): Filter based on EE's Z-axis direction in arm base frame.
|
||||
|
||||
**Format **: `[direction, angle] `or `[direction, angle_min, angle_max] `
|
||||
|
||||
### Direction Mapping [](#direction-mapping)
|
||||
|
||||
- **forward **: EE axis dot arm_base_X ≥ cos(angle)
|
||||
- **backward **: EE axis dot arm_base_X ≤ cos(angle)
|
||||
- **upward **: EE axis dot arm_base_Z ≥ cos(angle)
|
||||
- **downward **: EE axis dot arm_base_Z ≤ cos(angle)
|
||||
|
||||
**Positive sign **: Use `≥ cos(angle) `when direction is positive (forward/upward)
|
||||
|
||||
**Negative sign **: Use `≤ cos(angle) `when direction is negative (backward/downward)
|
||||
|
||||
## Examples [](#examples)
|
||||
|
||||
### Example 1: Franka Research 3 [](#example-1-franka-research-3)
|
||||
|
||||
Config Example:
|
||||
yaml
|
||||
```
|
||||
# Source: workflows/simbox/core/configs/tasks/pick_and_place/franka/single_pick/omniobject3d-banana.yaml
|
||||
skills:
|
||||
- franka:
|
||||
- left:
|
||||
- name: pick
|
||||
objects: [pick_object_left]
|
||||
filter_x_dir: ["forward", 90]
|
||||
filter_z_dir: ["downward", 140]
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
|
||||
Figure Example: 
|
||||
|
||||
**Analysis **:
|
||||
|
||||
For Franka, the gripper's approach direction (toward fingers) is the **Z-axis **of the end-effector frame.
|
||||
|
||||
-
|
||||
|
||||
**`filter_z_dir: ["downward", 140] `**: We want the gripper to approach **vertically downward **. The EE's Z-axis should form an angle ≥ 140° with the arm base's Z-axis (upward). Since 140° > 90°, the EE's Z-axis points downward.
|
||||
|
||||
-
|
||||
|
||||
**`filter_x_dir: ["forward", 90] `**: We want the gripper to face **forward **(no reverse grasping). The EE's X-axis should form an angle ≤ 90° with the arm base's X-axis (forward), ensuring the gripper doesn't rotate backward.
|
||||
|
||||
Result: Gripper approaches from above with fingers pointing down, facing forward.
|
||||
|
||||
### Example 2: Agilex Split Aloha with Piper-100 arm [](#example-2-agilex-split-aloha-with-piper-100-arm)
|
||||
|
||||
Config Example:
|
||||
yaml
|
||||
```
|
||||
# Source: workflows/simbox/core/configs/tasks/pick_and_place/split_aloha/single_pick/left/omniobject3d-banana.yaml
|
||||
skills:
|
||||
- split_aloha:
|
||||
- left:
|
||||
- name: pick
|
||||
objects: [pick_object_left]
|
||||
filter_y_dir: ["forward", 90]
|
||||
filter_z_dir: ["downward", 140]
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
|
||||
Figure Example: 
|
||||
|
||||
**Analysis **:
|
||||
|
||||
For Agilex Split Aloha's left arm, the gripper approach direction is still the **Z-axis **, but the forward-facing direction is the **Y-axis **.
|
||||
|
||||
-
|
||||
|
||||
**`filter_z_dir: ["downward", 140] `**: Same as Franka — gripper approaches vertically **downward **.
|
||||
|
||||
-
|
||||
|
||||
**`filter_y_dir: ["forward", 90] `**: The EE's Y-axis should form an angle ≤ 90° with the arm base's X-axis (forward). This ensures the gripper faces **forward **.
|
||||
|
||||
Result: Same grasp orientation as Franka, but using Y-axis for forward direction control.
|
||||
|
||||
### Example 3: ARX Lift-2 with R5a arm [](#example-3-arx-lift-2-with-r5a-arm)
|
||||
|
||||
Config Example:
|
||||
yaml
|
||||
```
|
||||
# Source: workflows/simbox/core/configs/tasks/pick_and_place/lift2/single_pick/left/omniobject3d-banana.yaml
|
||||
skills:
|
||||
- lift2:
|
||||
- left:
|
||||
- name: pick
|
||||
objects: [pick_object_left]
|
||||
filter_z_dir: ["forward", 90]
|
||||
filter_x_dir: ["downward", 140]
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
|
||||
Figure Example: 
|
||||
|
||||
**Analysis **:
|
||||
|
||||
For Lift2 with R5A gripper, the approach direction (toward fingers) is the **X-axis **of the end-effector frame.
|
||||
|
||||
-
|
||||
|
||||
**`filter_x_dir: ["downward", 140] `**: The EE's X-axis (approach direction) should form an angle ≥ 140° with the arm base's Z-axis, meaning the gripper approaches **downward **.
|
||||
|
||||
-
|
||||
|
||||
**`filter_z_dir: ["forward", 90] `**: The EE's Z-axis (gripper facing direction) should form an angle ≤ 90° with the arm base's X-axis (forward), ensuring the gripper faces **forward **.
|
||||
|
||||
Result: Gripper approaches from above, facing forward — same physical outcome as Franka, but using different axes.
|
||||
|
||||
## Design Philosophy [](#design-philosophy)
|
||||
|
||||
Note
|
||||
|
||||
**Filtering vs. Construction **: We use a filtering strategy rather than constructing specific grasp poses. This approach:
|
||||
|
||||
-
|
||||
|
||||
**Leverages existing annotations **: Pre-computed grasp poses from `Aligned_grasp_sparse.npy `already contain valid grasp configurations.
|
||||
|
||||
-
|
||||
|
||||
**Aligns with human intuition **: Specifying "gripper should approach downward and face forward" is more intuitive than computing exact rotation matrices.
|
||||
|
||||
-
|
||||
|
||||
**Provides flexibility **: Different robots with different EE frame conventions can achieve the same physical grasp by filtering different axes.
|
||||
|
||||
-
|
||||
|
||||
**Maintains diversity **: Multiple valid grasp poses remain after filtering, allowing the planner to select based on reachability and collision constraints.
|
||||
|
||||
## Configuration Reference [](#configuration-reference)
|
||||
|
||||
- **objects **( list , default: required): Target object names.
|
||||
- **npy_name **( string , default: `"Aligned_grasp_sparse.npy" `): Grasp annotation file name.
|
||||
- **grasp_scale **( float , default: `1 `): Scale factor for grasp poses.
|
||||
- **tcp_offset **( float , default: `robot.tcp_offset `): TCP offset override.
|
||||
- **constraints **( dict , default: `None `): Additional grasp constraints.
|
||||
- **final_gripper_state **( int , default: `-1 `): Gripper state after pick: `1 `(open) or `-1 `(close).
|
||||
- **fixed_orientation **( list , default: `None `): Fixed quaternion `[w, x, y, z] `if specified.
|
||||
- **filter_x_dir **( list , default: `None `): EE X-axis filter: `[direction, angle] `.
|
||||
- **filter_y_dir **( list , default: `None `): EE Y-axis filter: `[direction, angle] `.
|
||||
- **filter_z_dir **( list , default: `None `): EE Z-axis filter: `[direction, angle] `.
|
||||
- **direction_to_obj **( string , default: `None `): Filter by object position: `"left" `or `"right" `.
|
||||
- **pre_grasp_offset **( float , default: `0.1 `): Distance to offset before grasp (meters).
|
||||
- **pre_grasp_hold_vec_weight **( list , default: `None `): Hold vector weight at pre-grasp.
|
||||
- **gripper_change_steps **( int , default: `40 `): Steps to close gripper.
|
||||
- **post_grasp_offset_min **( float , default: `0.05 `): Minimum lift distance (meters).
|
||||
- **post_grasp_offset_max **( float , default: `0.05 `): Maximum lift distance (meters).
|
||||
- **return_to_pregrasp **( bool , default: `False `): Return to pre-grasp pose after lift.
|
||||
- **lift_th **( float , default: `0.0 `): Lift threshold for success check (meters).
|
||||
- **ignore_substring **( list , default: `[] `): Collision filter substrings.
|
||||
- **test_mode **( string , default: `"forward" `): Motion test mode: `"forward" `or `"ik" `.
|
||||
- **t_eps **( float , default: `1e-3 `): Translation tolerance (meters).
|
||||
- **o_eps **( float , default: `5e-3 `): Orientation tolerance (radians).
|
||||
- **process_valid **( bool , default: `True `): Check motion validity for success.
|
||||
711
docs_crawled/concepts_skills_place.md
Normal file
711
docs_crawled/concepts_skills_place.md
Normal file
@@ -0,0 +1,711 @@
|
||||
# Source: https://internrobotics.github.io/InternDataEngine-Docs/concepts/skills/place.html
|
||||
|
||||
# Place Skill [](#place-skill)
|
||||
|
||||
The `Place `skill performs placement operations with constrained end-effector orientations. It generates valid place poses through random sampling and filtering, then executes the placement motion.
|
||||
|
||||
Code Example:
|
||||
python
|
||||
```
|
||||
# Source workflows/simbox/core/skills/place.py
|
||||
from copy import deepcopy
|
||||
|
||||
import numpy as np
|
||||
from core.skills.base_skill import BaseSkill, register_skill
|
||||
from core.utils.box import Box, get_bbox_center_and_corners
|
||||
from core.utils.constants import CUROBO_BATCH_SIZE
|
||||
from core.utils.iou import IoU
|
||||
from core.utils.plan_utils import (
|
||||
select_index_by_priority_dual,
|
||||
select_index_by_priority_single,
|
||||
)
|
||||
from core.utils.transformation_utils import create_pose_matrices, poses_from_tf_matrices
|
||||
from core.utils.usd_geom_utils import compute_bbox
|
||||
from omegaconf import DictConfig
|
||||
from omni.isaac.core.controllers import BaseController
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
from omni.isaac.core.utils.prims import get_prim_at_path
|
||||
from omni.isaac.core.utils.transformations import (
|
||||
get_relative_transform,
|
||||
pose_from_tf_matrix,
|
||||
tf_matrix_from_pose,
|
||||
)
|
||||
from scipy.spatial.transform import Rotation as R
|
||||
|
||||
@register_skill
|
||||
class Place(BaseSkill):
|
||||
def __init__(self, robot: Robot, controller: BaseController, task: BaseTask, cfg: DictConfig, *args, **kwargs):
|
||||
super().__init__()
|
||||
self.robot = robot
|
||||
self.controller = controller
|
||||
self.task = task
|
||||
|
||||
self.name = cfg["name"]
|
||||
self.pick_obj = task._task_objects[cfg["objects"][0]]
|
||||
self.place_obj = task._task_objects[cfg["objects"][1]]
|
||||
self.place_align_axis = cfg.get("place_align_axis", None)
|
||||
self.pick_align_axis = cfg.get("pick_align_axis", None)
|
||||
self.constraint_gripper_x = cfg.get("constraint_gripper_x", False)
|
||||
self.place_part_prim_path = cfg.get("place_part_prim_path", None)
|
||||
if self.place_part_prim_path:
|
||||
self.place_prim_path = f"{self.place_obj.prim_path}/{self.place_part_prim_path}"
|
||||
else:
|
||||
self.place_prim_path = self.place_obj.prim_path
|
||||
self.manip_list = []
|
||||
self.robot_ee_path = self.controller.robot_ee_path
|
||||
self.robot_base_path = self.controller.robot_base_path
|
||||
|
||||
self.skill_cfg = cfg
|
||||
self.align_pick_obj_axis = self.skill_cfg.get("align_pick_obj_axis", None)
|
||||
self.align_place_obj_axis = self.skill_cfg.get("align_place_obj_axis", None)
|
||||
self.align_plane_x_axis = self.skill_cfg.get("align_plane_x_axis", None)
|
||||
self.align_plane_y_axis = self.skill_cfg.get("align_plane_y_axis", None)
|
||||
self.align_obj_tol = self.skill_cfg.get("align_obj_tol", None)
|
||||
|
||||
def simple_generate_manip_cmds(self):
|
||||
manip_list = []
|
||||
|
||||
p_base_ee_cur, q_base_ee_cur = self.controller.get_ee_pose()
|
||||
cmd = (p_base_ee_cur, q_base_ee_cur, "update_pose_cost_metric", {"hold_vec_weight": None})
|
||||
manip_list.append(cmd)
|
||||
|
||||
if self.skill_cfg.get("ignore_substring", []):
|
||||
ignore_substring = deepcopy(self.controller.ignore_substring + self.skill_cfg.get("ignore_substring", []))
|
||||
cmd = (
|
||||
p_base_ee_cur,
|
||||
q_base_ee_cur,
|
||||
"update_specific",
|
||||
{"ignore_substring": ignore_substring, "reference_prim_path": self.controller.reference_prim_path},
|
||||
)
|
||||
manip_list.append(cmd)
|
||||
|
||||
result = self.sample_gripper_place_traj()
|
||||
|
||||
cmd = (result[0][0], result[0][1], "close_gripper", {})
|
||||
manip_list.append(cmd)
|
||||
|
||||
p_base_ee_place, q_base_ee_place = result[1][0], result[1][1]
|
||||
cmd = (p_base_ee_place, q_base_ee_place, "close_gripper", {})
|
||||
manip_list.append(cmd)
|
||||
|
||||
cmd = (p_base_ee_place, q_base_ee_place, "open_gripper", {})
|
||||
manip_list.extend([cmd] * self.skill_cfg.get("gripper_change_steps", 10))
|
||||
|
||||
cmd = (p_base_ee_place, q_base_ee_place, "detach_obj", {})
|
||||
manip_list.append(cmd)
|
||||
|
||||
self.manip_list = manip_list
|
||||
self.place_ee_trans = p_base_ee_place
|
||||
|
||||
def sample_gripper_place_traj(self):
|
||||
# ... sampling logic ...
|
||||
pass
|
||||
|
||||
def generate_constrained_rotation_batch(self, batch_size=3000):
|
||||
filter_conditions = {
|
||||
"x": {
|
||||
"forward": (0, 0, 1),
|
||||
"backward": (0, 0, -1),
|
||||
"leftward": (1, 0, 1),
|
||||
"rightward": (1, 0, -1),
|
||||
"upward": (2, 0, 1),
|
||||
"downward": (2, 0, -1),
|
||||
},
|
||||
"y": {
|
||||
"forward": (0, 1, 1),
|
||||
"backward": (0, 1, -1),
|
||||
"leftward": (1, 1, 1),
|
||||
"rightward": (1, 1, -1),
|
||||
"upward": (2, 1, 1),
|
||||
"downward": (2, 1, -1),
|
||||
},
|
||||
"z": {
|
||||
"forward": (0, 2, 1),
|
||||
"backward": (0, 2, -1),
|
||||
"leftward": (1, 2, 1),
|
||||
"rightward": (1, 2, -1),
|
||||
"upward": (2, 2, 1),
|
||||
"downward": (2, 2, -1),
|
||||
},
|
||||
}
|
||||
rot_mats = R.random(batch_size).as_matrix()
|
||||
valid_mask = np.ones(batch_size, dtype=bool)
|
||||
|
||||
for axis in ["x", "y", "z"]:
|
||||
filter_list = self.skill_cfg.get(f"filter_{axis}_dir", None)
|
||||
if filter_list is not None:
|
||||
direction = filter_list[0]
|
||||
row, col, sign = filter_conditions[axis][direction]
|
||||
elements = rot_mats[:, row, col]
|
||||
if len(filter_list) == 2:
|
||||
value = filter_list[1]
|
||||
cos_val = np.cos(np.deg2rad(value))
|
||||
if sign > 0:
|
||||
valid_mask &= elements >= cos_val
|
||||
else:
|
||||
valid_mask &= elements <= cos_val
|
||||
|
||||
valid_rot_mats = rot_mats[valid_mask]
|
||||
if len(valid_rot_mats) == 0:
|
||||
return rot_mats[:CUROBO_BATCH_SIZE]
|
||||
else:
|
||||
indices = np.random.choice(len(valid_rot_mats), CUROBO_BATCH_SIZE)
|
||||
return valid_rot_mats[indices]
|
||||
|
||||
def is_feasible(self, th=5):
|
||||
return self.controller.num_plan_failed <= th
|
||||
|
||||
def is_subtask_done(self, t_eps=1e-3, o_eps=5e-3):
|
||||
assert len(self.manip_list) != 0
|
||||
p_base_ee_cur, q_base_ee_cur = self.controller.get_ee_pose()
|
||||
p_base_ee, q_base_ee, *_ = self.manip_list[0]
|
||||
diff_trans = np.linalg.norm(p_base_ee_cur - p_base_ee)
|
||||
diff_ori = 2 * np.arccos(min(abs(np.dot(q_base_ee_cur, q_base_ee)), 1.0))
|
||||
pose_flag = np.logical_and(diff_trans < t_eps, diff_ori < o_eps)
|
||||
self.plan_flag = self.controller.num_last_cmd > 10
|
||||
return np.logical_or(pose_flag, self.plan_flag)
|
||||
|
||||
def is_done(self):
|
||||
if len(self.manip_list) == 0:
|
||||
return True
|
||||
if self.is_subtask_done(t_eps=self.skill_cfg.get("t_eps", 1e-3), o_eps=self.skill_cfg.get("o_eps", 5e-3)):
|
||||
self.manip_list.pop(0)
|
||||
return len(self.manip_list) == 0
|
||||
|
||||
def is_success(self, th=0.0):
|
||||
if self.skill_cfg.get("success_mode", "3diou") == "3diou":
|
||||
bbox_pick_obj = compute_bbox(self.pick_obj.prim)
|
||||
bbox_place_obj = compute_bbox(get_prim_at_path(self.place_prim_path))
|
||||
iou = IoU(
|
||||
Box(get_bbox_center_and_corners(bbox_pick_obj)), Box(get_bbox_center_and_corners(bbox_place_obj))
|
||||
).iou()
|
||||
return iou > th
|
||||
elif self.skill_cfg.get("success_mode", "3diou") == "xybbox":
|
||||
bbox_place_obj = compute_bbox(get_prim_at_path(self.place_prim_path))
|
||||
pick_x, pick_y = self.pick_obj.get_local_pose()[0][:2]
|
||||
place_xy_min = bbox_place_obj.min[:2]
|
||||
place_xy_max = bbox_place_obj.max[:2]
|
||||
return ((place_xy_min[0] + 0.015) < pick_x < (place_xy_max[0] - 0.015)) and (
|
||||
(place_xy_min[1] + 0.015) < pick_y < (place_xy_max[1] - 0.015)
|
||||
)
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
10
|
||||
11
|
||||
12
|
||||
13
|
||||
14
|
||||
15
|
||||
16
|
||||
17
|
||||
18
|
||||
19
|
||||
20
|
||||
21
|
||||
22
|
||||
23
|
||||
24
|
||||
25
|
||||
26
|
||||
27
|
||||
28
|
||||
29
|
||||
30
|
||||
31
|
||||
32
|
||||
33
|
||||
34
|
||||
35
|
||||
36
|
||||
37
|
||||
38
|
||||
39
|
||||
40
|
||||
41
|
||||
42
|
||||
43
|
||||
44
|
||||
45
|
||||
46
|
||||
47
|
||||
48
|
||||
49
|
||||
50
|
||||
51
|
||||
52
|
||||
53
|
||||
54
|
||||
55
|
||||
56
|
||||
57
|
||||
58
|
||||
59
|
||||
60
|
||||
61
|
||||
62
|
||||
63
|
||||
64
|
||||
65
|
||||
66
|
||||
67
|
||||
68
|
||||
69
|
||||
70
|
||||
71
|
||||
72
|
||||
73
|
||||
74
|
||||
75
|
||||
76
|
||||
77
|
||||
78
|
||||
79
|
||||
80
|
||||
81
|
||||
82
|
||||
83
|
||||
84
|
||||
85
|
||||
86
|
||||
87
|
||||
88
|
||||
89
|
||||
90
|
||||
91
|
||||
92
|
||||
93
|
||||
94
|
||||
95
|
||||
96
|
||||
97
|
||||
98
|
||||
99
|
||||
100
|
||||
101
|
||||
102
|
||||
103
|
||||
104
|
||||
105
|
||||
106
|
||||
107
|
||||
108
|
||||
109
|
||||
110
|
||||
111
|
||||
112
|
||||
113
|
||||
114
|
||||
115
|
||||
116
|
||||
117
|
||||
118
|
||||
119
|
||||
120
|
||||
121
|
||||
122
|
||||
123
|
||||
124
|
||||
125
|
||||
126
|
||||
127
|
||||
128
|
||||
129
|
||||
130
|
||||
131
|
||||
132
|
||||
133
|
||||
134
|
||||
135
|
||||
136
|
||||
137
|
||||
138
|
||||
139
|
||||
140
|
||||
141
|
||||
142
|
||||
143
|
||||
144
|
||||
145
|
||||
146
|
||||
147
|
||||
148
|
||||
149
|
||||
150
|
||||
151
|
||||
152
|
||||
153
|
||||
154
|
||||
155
|
||||
156
|
||||
157
|
||||
158
|
||||
159
|
||||
160
|
||||
161
|
||||
162
|
||||
163
|
||||
164
|
||||
165
|
||||
166
|
||||
167
|
||||
168
|
||||
169
|
||||
170
|
||||
171
|
||||
172
|
||||
173
|
||||
174
|
||||
175
|
||||
176
|
||||
177
|
||||
178
|
||||
179
|
||||
180
|
||||
181
|
||||
182
|
||||
183
|
||||
|
||||
__init__(self, robot, controller, task, cfg, *args, **kwargs)
|
||||
|
||||
Initialize the place skill with target objects and constraints.
|
||||
|
||||
Parameters:
|
||||
|
||||
- **robot **( Robot ): Robot instance for state queries and actions.
|
||||
- **controller **( BaseController ): Controller for motion planning.
|
||||
- **task **( BaseTask ): Task instance containing scene objects.
|
||||
- **cfg **( DictConfig ): Skill configuration from task YAML.
|
||||
|
||||
Key Operations:
|
||||
|
||||
- Extract pick object from `cfg["objects"][0] `
|
||||
- Extract place container from `cfg["objects"][1] `
|
||||
- Initialize alignment constraints ( `align_pick_obj_axis `, `align_place_obj_axis `)
|
||||
- Set up collision filtering paths
|
||||
|
||||
simple_generate_manip_cmds(self)
|
||||
|
||||
Generate the full placement motion sequence.
|
||||
|
||||
Steps:
|
||||
|
||||
- **Update planning settings **— Reset cost metrics and collision settings
|
||||
- **Generate place trajectory **— Call `sample_gripper_place_traj() `to get pre-place and place poses
|
||||
- **Build manip_list **— Construct command sequence:
|
||||
- Move to pre-place pose (gripper closed)
|
||||
- Move to place pose
|
||||
- Open gripper to release object
|
||||
- Detach object from gripper (physics)
|
||||
- Retreat motion (if `post_place_vector `configured)
|
||||
|
||||
sample_gripper_place_traj(self)
|
||||
|
||||
Generate pre-place and place poses based on placement direction mode.
|
||||
|
||||
Returns:
|
||||
|
||||
- list : `[T_base_ee_preplace, T_base_ee_place] `or `[T_base_ee_preplace, T_base_ee_place, T_base_ee_postplace] `
|
||||
|
||||
Position Constraint Modes:
|
||||
|
||||
- **`"gripper" `**: Target pose controls gripper position directly
|
||||
- **`"object" `**: Target pose controls pick object position (accounts for object offset from EE)
|
||||
|
||||
Direction Modes:
|
||||
|
||||
See [Placement Direction Modes](#placement-direction-modes)section below.
|
||||
|
||||
generate_constrained_rotation_batch(self, batch_size=3000)
|
||||
|
||||
Generate valid end-effector orientations through random sampling and filtering.
|
||||
|
||||
Parameters:
|
||||
|
||||
- **batch_size **( int ): Number of random rotations to sample.
|
||||
|
||||
Returns:
|
||||
|
||||
- np.ndarray : Filtered rotation matrices `(N, 3, 3) `.
|
||||
|
||||
Filtering Logic:
|
||||
|
||||
- Sample random rotation matrices using `scipy.spatial.transform.Rotation `
|
||||
- Apply direction filters ( `filter_x_dir `, `filter_y_dir `, `filter_z_dir `)
|
||||
- Apply object alignment constraints (if configured)
|
||||
- Return filtered rotations
|
||||
|
||||
For detailed filtering explanation, see [Orientation Filtering](#orientation-filtering).
|
||||
|
||||
is_success(self, th=0.0)
|
||||
|
||||
Check if the placement succeeded based on configured mode.
|
||||
|
||||
Parameters:
|
||||
|
||||
- **th **( float ): Threshold for IoU-based success.
|
||||
|
||||
Returns:
|
||||
|
||||
- bool : `True `if success conditions are satisfied.
|
||||
|
||||
Success Modes:
|
||||
|
||||
| Mode | Condition |
|
||||
| `3diou ` | 3D IoU between pick object and container > threshold |
|
||||
| `xybbox ` | Pick object center within container XY bounds |
|
||||
| `height ` | Pick object below height threshold |
|
||||
| `left `/ `right ` | Object positioned left/right of container |
|
||||
| `flower ` | IoU + object center within container bounds |
|
||||
| `cup ` | IoU + object above container base |
|
||||
|
||||
## Placement Direction Modes [](#placement-direction-modes)
|
||||
|
||||
### Vertical Placement [](#vertical-placement)
|
||||
|
||||
Default mode for placing objects on top of containers (e.g., placing items in boxes, on plates).
|
||||
yaml
|
||||
```
|
||||
place_direction: "vertical"
|
||||
```
|
||||
1
|
||||
|
||||
**Algorithm **:
|
||||
|
||||
- Sample (x, y) position within container top surface using ratio ranges
|
||||
- Set z-height to `b_max[2] + pre_place_z_offset `(above container)
|
||||
- Lower to `b_max[2] + place_z_offset `(final placement height)
|
||||
yaml
|
||||
```
|
||||
x_ratio_range: [0.4, 0.6] # X position ratio within container bbox
|
||||
y_ratio_range: [0.4, 0.6] # Y position ratio within container bbox
|
||||
pre_place_z_offset: 0.2 # Height above container for approach
|
||||
place_z_offset: 0.1 # Final placement height offset
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
|
||||
### Horizontal Placement [](#horizontal-placement)
|
||||
|
||||
For inserting objects into slots, shelves, or openings from the side.
|
||||
yaml
|
||||
```
|
||||
place_direction: "horizontal"
|
||||
align_place_obj_axis: [1, 0, 0] # Insertion direction
|
||||
offset_place_obj_axis: [0, 0, 1] # Offset direction
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
|
||||
**Algorithm **:
|
||||
|
||||
- Sample position within container bounding box
|
||||
- Compute approach position offset along alignment axis
|
||||
- Move forward along alignment axis to place position
|
||||
yaml
|
||||
```
|
||||
# Position constraint: "object" or "gripper"
|
||||
position_constraint: "object"
|
||||
|
||||
# Approach distances
|
||||
pre_place_align: 0.2 # Pre-place offset along alignment axis
|
||||
pre_place_offset: 0.2 # Pre-place offset along offset axis
|
||||
place_align: 0.1 # Place offset along alignment axis
|
||||
place_offset: 0.1 # Place offset along offset axis
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
|
||||
## Orientation Filtering [](#orientation-filtering)
|
||||
|
||||
The place skill uses the same **direction-based filtering strategy **as the pick skill. See [Pick Skill - Grasp Orientation Filtering](/InternDataEngine-Docs/concepts/skills/pick/#grasp-orientation-filtering)for detailed explanation.
|
||||
|
||||
### Filter Parameters [](#filter-parameters)
|
||||
|
||||
- **filter_x_dir **( list ): Filter based on EE's X-axis direction in arm base frame.
|
||||
- **filter_y_dir **( list ): Filter based on EE's Y-axis direction in arm base frame.
|
||||
- **filter_z_dir **( list ): Filter based on EE's Z-axis direction in arm base frame.
|
||||
|
||||
**Format **: `[direction, angle] `or `[direction, angle_min, angle_max] `
|
||||
|
||||
### Direction Mapping [](#direction-mapping)
|
||||
|
||||
- **forward **: EE axis dot arm_base_X ≥ cos(angle)
|
||||
- **backward **: EE axis dot arm_base_X ≤ cos(angle)
|
||||
- **leftward **: EE axis dot arm_base_Y ≥ cos(angle)
|
||||
- **rightward **: EE axis dot arm_base_Y ≤ cos(angle)
|
||||
- **upward **: EE axis dot arm_base_Z ≥ cos(angle)
|
||||
- **downward **: EE axis dot arm_base_Z ≤ cos(angle)
|
||||
|
||||
### Object Alignment Constraint [](#object-alignment-constraint)
|
||||
|
||||
Additional constraint to align pick object axis with place container axis:
|
||||
yaml
|
||||
```
|
||||
align_pick_obj_axis: [0, 0, 1] # Axis on pick object (e.g., height axis)
|
||||
align_place_obj_axis: [0, 0, 1] # Target axis on place container
|
||||
align_obj_tol: 15 # Alignment tolerance (degrees)
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
|
||||
This ensures that a specific axis on the held object (e.g., bottle height) aligns with a target axis on the container (e.g., cup opening direction).
|
||||
|
||||
## Design Philosophy [](#design-philosophy)
|
||||
|
||||
Note
|
||||
|
||||
**Random Generation + Filter **: The place skill uses a random generation and filtering strategy rather than delicate construction. This approach is chosen for three key reasons:
|
||||
|
||||
-
|
||||
|
||||
**Intuitive Position Control **: Specifying place position based on target EE activity direction and object bounding box range is intuitive and easy to configure.
|
||||
|
||||
-
|
||||
|
||||
**Simple Rotation Sampling **: Randomly generating 3x3 rotation matrices and filtering them is computationally simple. With sufficient samples, valid orientations that pass planning constraints are always found.
|
||||
|
||||
-
|
||||
|
||||
**Container Diversity **: Different place containers have varying volumes, shapes, and opening directions. Delicate construction of place poses for each container type is difficult. The filtering approach is general and adaptable.
|
||||
|
||||
## Configuration Reference [](#configuration-reference)
|
||||
|
||||
- **objects **( list , default: required): `[pick_object, place_container] `.
|
||||
- **place_part_prim_path **( string , default: `None `): Sub-path within place container prim.
|
||||
- **place_direction **( string , default: `"vertical" `): `"vertical" `or `"horizontal" `.
|
||||
- **position_constraint **( string , default: `"gripper" `): `"gripper" `or `"object" `.
|
||||
- **pre_place_z_offset **( float , default: `0.2 `): Approach height above container.
|
||||
- **place_z_offset **( float , default: `0.1 `): Final placement height.
|
||||
- **x_ratio_range **( [float, float] , default: `[0.4, 0.6] `): X-position sampling range.
|
||||
- **y_ratio_range **( [float, float] , default: `[0.4, 0.6] `): Y-position sampling range.
|
||||
- **z_ratio_range **( [float, float] , default: `[0.4, 0.6] `): Z-position sampling range (horizontal).
|
||||
- **align_place_obj_axis **( [float, float, float] , default: `None `): Insertion axis on place container (horizontal).
|
||||
- **offset_place_obj_axis **( [float, float, float] , default: `None `): Offset axis on place container (horizontal).
|
||||
- **pre_place_align **( float , default: `0.2 `): Pre-place offset along alignment axis.
|
||||
- **pre_place_offset **( float , default: `0.2 `): Pre-place offset along offset axis.
|
||||
- **place_align **( float , default: `0.1 `): Place offset along alignment axis.
|
||||
- **place_offset **( float , default: `0.1 `): Place offset along offset axis.
|
||||
- **filter_x_dir **( list , default: `None `): EE X-axis direction filter.
|
||||
- **filter_y_dir **( list , default: `None `): EE Y-axis direction filter.
|
||||
- **filter_z_dir **( list , default: `None `): EE Z-axis direction filter.
|
||||
- **align_pick_obj_axis **( [float, float, float] , default: `None `): Axis on pick object to align.
|
||||
- **align_place_obj_axis **( [float, float, float] , default: `None `): Target axis on place container.
|
||||
- **align_obj_tol **( float , default: `None `): Alignment tolerance (degrees).
|
||||
- **align_plane_x_axis **( [float, float, float] , default: `None `): X-axis alignment plane.
|
||||
- **align_plane_y_axis **( [float, float, float] , default: `None `): Y-axis alignment plane.
|
||||
- **pre_place_hold_vec_weight **( list , default: `None `): Hold vector weight at pre-place.
|
||||
- **post_place_hold_vec_weight **( list , default: `None `): Hold vector weight at place.
|
||||
- **gripper_change_steps **( int , default: `10 `): Steps for gripper open action.
|
||||
- **hesitate_steps **( int , default: `0 `): Pause steps before release.
|
||||
- **post_place_vector **( [float, float, float] , default: `None `): Retreat direction after placement.
|
||||
- **ignore_substring **( list , default: `[] `): Collision filter substrings.
|
||||
- **test_mode **( string , default: `"forward" `): Motion test mode: `"forward" `or `"ik" `.
|
||||
- **t_eps **( float , default: `1e-3 `): Translation tolerance (meters).
|
||||
- **o_eps **( float , default: `5e-3 `): Orientation tolerance (radians).
|
||||
- **success_mode **( string , default: `"3diou" `): Success evaluation mode.
|
||||
- **success_th **( float , default: `0.0 `): IoU threshold for success.
|
||||
- **threshold **( float , default: `0.03 `): Distance threshold for left/right modes.
|
||||
|
||||
## Example Configuration [](#example-configuration)
|
||||
|
||||
### Vertical Place on Container [](#vertical-place-on-container)
|
||||
yaml
|
||||
```
|
||||
skills:
|
||||
- lift2:
|
||||
- left:
|
||||
- name: place
|
||||
objects: [pick_object, container]
|
||||
place_direction: "vertical"
|
||||
x_ratio_range: [0.4, 0.6]
|
||||
y_ratio_range: [0.4, 0.6]
|
||||
pre_place_z_offset: 0.15
|
||||
place_z_offset: 0.05
|
||||
filter_z_dir: ["downward", 140]
|
||||
gripper_change_steps: 10
|
||||
success_mode: "xybbox"
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
10
|
||||
11
|
||||
12
|
||||
13
|
||||
|
||||
### Horizontal Insertion [](#horizontal-insertion)
|
||||
yaml
|
||||
```
|
||||
skills:
|
||||
- franka:
|
||||
- left:
|
||||
- name: place
|
||||
objects: [peg, hole]
|
||||
place_direction: "horizontal"
|
||||
position_constraint: "object"
|
||||
align_place_obj_axis: [1, 0, 0]
|
||||
offset_place_obj_axis: [0, 0, 1]
|
||||
pre_place_align: 0.15
|
||||
place_align: 0.02
|
||||
filter_x_dir: ["forward", 30]
|
||||
success_mode: "3diou"
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
10
|
||||
11
|
||||
12
|
||||
13
|
||||
|
||||
### Place with Retreat [](#place-with-retreat)
|
||||
yaml
|
||||
```
|
||||
skills:
|
||||
- split_aloha:
|
||||
- left:
|
||||
- name: place
|
||||
objects: [item, shelf]
|
||||
place_direction: "vertical"
|
||||
post_place_vector: [-0.05, 0.0, 0.1]
|
||||
gripper_change_steps: 15
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
253
docs_crawled/concepts_workflows.md
Normal file
253
docs_crawled/concepts_workflows.md
Normal file
@@ -0,0 +1,253 @@
|
||||
# Source: https://internrobotics.github.io/InternDataEngine-Docs/concepts/workflows.html
|
||||
|
||||
# Workflows [](#workflows)
|
||||
|
||||
Workflows are the interfaces designed by the engine to manipulate the synthetic data pipeline. To understand workflows, you first need a basic understanding of the engine's overall architecture.
|
||||
|
||||
## Overall Architecture [](#overall-architecture)
|
||||
|
||||
The framework of the engine is shown in the figure:
|
||||
|
||||

|
||||
|
||||
Above the optimization layer, the engine provides designs related to the Stage Runner Layer and the Components Layer.
|
||||
|
||||
In the Stage Runner Layer, the standardized lifecycle of data production is defined, namely Load → Plan → Render → Store.
|
||||
|
||||
Based on iterator execution flow, a strict set of abstract base class interfaces is designed, unifying the workflow control of all tasks to ensure that different components extended based on the same interface can collaborate seamlessly.
|
||||
|
||||
For manipulating the data generation pipeline, they are integrated through Env series components combined with workflows. Its core extension principle is based on standardized component interfaces and lifecycle design:
|
||||
|
||||
| Abstract Class | Derived Class | Core Interface | Functional Duty |
|
||||
| `BaseLoader ` | `EnvLoader ` | `load_asset() ` | Resource loading and validation |
|
||||
| `BaseRandomizer ` | `EnvRandomizer ` | `randomize_scene() ` | Domain randomization of the scene |
|
||||
| `BasePlanner ` | `EnvPlanner ` | `generate_sequence() ` | Generate trajectory or action sequence |
|
||||
| `BaseRenderer ` | `EnvRenderer ` | `generate_obs() ` | Synthesize multimodal visual data |
|
||||
| `BaseWriter ` | `EnvWriter ` | `flush_to_disk() ` | Serialized storage |
|
||||
|
||||
## Workflow Base Class and Interfaces [](#workflow-base-class-and-interfaces)
|
||||
|
||||
Based on the Env component architecture, a workflow base class `NimbusWorkFlow `is defined in [workflows/base.py](https://github.com/InternRobotics/InternDataEngine/blob/master/workflows/base.py), with its core API as follows:
|
||||
|
||||
### Workflow Interface List [](#workflow-interface-list)
|
||||
|
||||
The workflow base class `NimbusWorkFlow `provides a complete set of interfaces. The table below lists all interfaces and their types:
|
||||
|
||||
| Method | Return | Calling Component | Type | Description |
|
||||
| `parse_task_cfgs(task_cfg_path) ` | `list ` | EnvLoader | ✓ Core | Parse task configuration files, return task list |
|
||||
| `get_task_name() ` | `str ` | EnvLoader | ✓ Core | Get the name of the currently executing task |
|
||||
| `reset(need_preload) ` | - | EnvLoader | ✓ Core | Reset environment to initial task state |
|
||||
| `randomization(layout_path=None) ` | `bool ` | EnvRandomizer | ✓ Core | Execute domain randomization |
|
||||
| `generate_seq() ` | `list ` | EnvPlanner | ✓ Core | Generate action sequence/trajectory |
|
||||
| `seq_replay(sequence) ` | `int ` | EnvRenderer | ✓ Core | Replay sequence and generate visual data |
|
||||
| `save(save_path) ` | `int ` | EnvWriter | ✓ Core | Save all data (trajectory + visual data) |
|
||||
| `save_seq(save_path) ` | `int ` | EnvWriter | Optional | Only save trajectory, do not save visual data |
|
||||
| `recover_seq(seq_path) ` | `list ` | EnvReader | Optional | Recover trajectory from disk |
|
||||
| `generate_seq_with_obs() ` | `int ` | EnvPlanWithRender | Optional | Generate sequence with visual data |
|
||||
| `dump_plan_info() ` | `bytes ` | EnvDumper | Optional | Serialize planning information |
|
||||
| `dedump_plan_info(ser_obj) ` | `object ` | Dedumper | Optional | Deserialize planning information |
|
||||
| `randomization_from_mem(data) ` | `bool ` | EnvRandomizer | Optional | Randomize from in-memory data |
|
||||
| `recover_seq_from_mem(data) ` | `list ` | EnvReader | Optional | Recover sequence from in-memory data |
|
||||
|
||||
**Interface Type Description: **
|
||||
|
||||
| Type | Description |
|
||||
| ✓ Core Interface | Abstract methods that must be overridden in all workflow implementations |
|
||||
| Optional | Implemented on-demand based on execution mode |
|
||||
|
||||
### Execution Modes [](#execution-modes)
|
||||
|
||||
#### Plan with Render Mode [](#plan-with-render-mode)
|
||||
|
||||
Execute planning and rendering at the same time within a single stage to generate complete trajectories and visual data. Corresponding configuration template: [de_plan_and_render_template.yaml](https://github.com/InternRobotics/InternDataEngine/tree/master/configs/simbox/de_plan_and_render_template.yaml)
|
||||
|
||||
**Lifecycle Flow: **Involved components and corresponding workflow interfaces:
|
||||
|
||||
```
|
||||
EnvLoader <-> get_task_name() → init_task() → reset()
|
||||
EnvRandomizer <-> randomization()
|
||||
EnvPlanWithRender <-> generate_seq_with_obs()
|
||||
EnvWriter <-> save()
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
|
||||
**Application Scenario: **Fluid simulation tasks
|
||||
|
||||
#### Plan and Render Mode [](#plan-and-render-mode)
|
||||
|
||||
Execute the planning and rendering stages sequentially. Corresponding configuration template: [de_plan_and_render_template.yaml](https://github.com/InternRobotics/InternDataEngine/tree/master/configs/simbox/de_plan_and_render_template.yaml)
|
||||
|
||||
**Lifecycle Flow: **Involved components and corresponding workflow interfaces:
|
||||
|
||||
```
|
||||
EnvLoader <-> get_task_name() → init_task() → reset()
|
||||
EnvRandomizer <-> randomization()
|
||||
EnvPlanner <-> generate_seq()
|
||||
EnvRenderer <-> seq_replay(sequence)
|
||||
EnvWriter <-> save()
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
|
||||
**Application Scenario: **Algorithm debugging, prototype validation
|
||||
|
||||
#### Pipeline Mode (Distributed Pipeline) [](#pipeline-mode-distributed-pipeline)
|
||||
|
||||
Decouple planning and rendering stages, supporting custom dynamic pipeline scheduling. Corresponding configuration template: [de_pipe_template.yaml](https://github.com/InternRobotics/InternDataEngine/tree/master/configs/simbox/de_pipe_template.yaml)
|
||||
|
||||
**Plan Process Lifecycle: **Involved components and corresponding workflow interfaces:
|
||||
|
||||
```
|
||||
EnvLoader <-> get_task_name() → init_task() → reset()
|
||||
EnvRandomizer <-> randomization()
|
||||
EnvPlanner <-> generate_seq()
|
||||
EnvDumper <-> dump_plan_info()
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
|
||||
**Render Process Lifecycle: **Involved components and corresponding workflow interfaces:
|
||||
|
||||
```
|
||||
Dedumper
|
||||
EnvLoader <-> get_task_name() → init_task() → reset() → dedump_plan_info(ser_obj)
|
||||
EnvRandomizer <-> randomization_from_mem(data)
|
||||
EnvReader <-> recover_seq_from_mem(data)
|
||||
EnvRenderer <-> seq_replay(sequence)
|
||||
EnvWriter <-> save()
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
|
||||
**Application Scenario: **Large-scale distributed data generation
|
||||
|
||||
#### Plan Only Mode [](#plan-only-mode)
|
||||
|
||||
Generate only trajectory data, do not perform rendering operations; can reduce computational resource occupation.
|
||||
|
||||
**Lifecycle Flow: **Involved components and corresponding workflow interfaces:
|
||||
|
||||
```
|
||||
EnvLoader <-> get_task_name() → init_task() → reset()
|
||||
EnvRandomizer <-> randomization()
|
||||
EnvPlanner <-> generate_seq()
|
||||
EnvWriter <-> save()
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
|
||||
**Application Scenario: **Trajectory pre-generation, cooperate with Render Only mode to generate diversified background and material videos
|
||||
|
||||
#### Render Only Mode [](#render-only-mode)
|
||||
|
||||
Perform visual rendering on previously generated trajectory data.
|
||||
|
||||
**Lifecycle Flow: **Involved components and corresponding workflow interfaces:
|
||||
|
||||
```
|
||||
EnvLoader <-> get_task_name() → init_task() → reset()
|
||||
EnvRandomizer <-> randomization(layout_path)
|
||||
EnvReader <-> recover_seq()
|
||||
EnvRenderer <-> seq_replay(sequence)
|
||||
EnvWriter <-> save()
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
|
||||
**Application Scenario: **Cooperate with Plan Only mode to generate diversified background and material videos, CI correctness validation
|
||||
|
||||
## SimBox Workflow Implementation [](#simbox-workflow-implementation)
|
||||
|
||||
### Workflow Registration [](#workflow-registration)
|
||||
|
||||
In ****[workflows/init.py](https://github.com/InternRobotics/InternDataEngine/blob/master/workflows/__init__.py), register workflow extensions:
|
||||
python
|
||||
```
|
||||
def import_extensions(workflow_type):
|
||||
if workflow_type == "SimBoxDualWorkFlow":
|
||||
import workflows.simbox_dual_workflow
|
||||
else:
|
||||
raise ValueError(f"Unsupported workflow type: {workflow_type}")
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
|
||||
### Workflow Definition [](#workflow-definition)
|
||||
|
||||
In [workflows/simbox_dual_workflow.py](https://github.com/InternRobotics/InternDataEngine/blob/master/workflows/simbox_dual_workflow.py), define the specific implementation:
|
||||
python
|
||||
```
|
||||
@NimbusWorkFlow.register("SimBoxDualWorkFlow")
|
||||
class SimBoxDualWorkFlow(NimbusWorkFlow):
|
||||
def __init__(
|
||||
self,
|
||||
world,
|
||||
task_cfg_path: str,
|
||||
scene_info: str = "dining_room_scene_info",
|
||||
random_seed: int = None,
|
||||
):
|
||||
...
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
10
|
||||
|
||||
### Workflow Architecture Design [](#workflow-architecture-design)
|
||||
|
||||
The core component structure of the SimBox workflow is as follows:
|
||||
|
||||
```
|
||||
SimBoxDualWorkFlow
|
||||
Task Module (task/banana.py)
|
||||
├── SceneObject Object Management
|
||||
├── Camera Configuration
|
||||
└── Region Definition
|
||||
Controller Module (controller/template_controller.py)
|
||||
├── CuRobo Motion Planner
|
||||
└── Gripper Controller
|
||||
Skill Module (skill/pick.py, place.py, ...)
|
||||
└── Atomic Operation Units
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
10
|
||||
|
||||
## Related Documentation [](#related-documentation)
|
||||
|
||||
- [Controller Design](/InternDataEngine-Docs/concepts/controllers.html)- Robot motion planning and control
|
||||
- [Skill Development](/InternDataEngine-Docs/concepts/skills.html)- Implementation and extension of manipulation skills
|
||||
- [Task Definition](/InternDataEngine-Docs/concepts/tasks.html)- Construction and configuration of simulation environments
|
||||
259
docs_crawled/config_assets.md
Normal file
259
docs_crawled/config_assets.md
Normal file
@@ -0,0 +1,259 @@
|
||||
# Source: https://internrobotics.github.io/InternDataEngine-Docs/config/assets.html
|
||||
|
||||
# Assets [](#assets)
|
||||
|
||||
All simulation assets are organized under `workflows/simbox/assets `. This document describes the asset structure, required assets, and organization conventions.
|
||||
|
||||
## Asset Structure [](#asset-structure)
|
||||
|
||||
```
|
||||
workflows/simbox/assets/
|
||||
├── envmap_lib/ # HDR environment maps for scene lighting
|
||||
├── background_textures/ # Background textures for domain randomization
|
||||
├── floor_textures/ # Floor textures for domain randomization
|
||||
├── table_textures/ # Table surface textures
|
||||
├── table0/ # Default table USD model
|
||||
├── lift2/ # ARX Lift-2 robot assets
|
||||
├── G1_120s/ # Genie-1 robot assets
|
||||
├── franka/ # Franka robot assets
|
||||
├── frankarobotiq/ # Franka with Robotiq 2F-85 gripper assets
|
||||
├── split_aloha_mid_360/ # Agilex Split ALOHA robot assets
|
||||
├── basic/ # Basic task-specific assets
|
||||
│ ├── arrange_the_tableware/
|
||||
│ ├── hang_the_cup_on_rack/
|
||||
│ ├── pour/
|
||||
│ ├── store_the_eggs/
|
||||
│ └── ... # Other task folders
|
||||
├── art/ # Articulated object assets
|
||||
│ ├── electriccooker/
|
||||
│ ├── microwave_gr/
|
||||
│ ├── laptop/
|
||||
│ └── ...
|
||||
├── long_horizon/ # Long-horizon task assets
|
||||
└── pick_and_place/ # Pick-and-place task assets
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
10
|
||||
11
|
||||
12
|
||||
13
|
||||
14
|
||||
15
|
||||
16
|
||||
17
|
||||
18
|
||||
19
|
||||
20
|
||||
21
|
||||
22
|
||||
23
|
||||
24
|
||||
|
||||
## Required Assets [](#required-assets)
|
||||
|
||||
To run a simulation task, the following assets are required:
|
||||
|
||||
- **Environment Maps **( `envmap_lib/ `): HDR lighting for scene illumination.
|
||||
- **Background Textures **( `background_textures/ `): Domain randomization backgrounds.
|
||||
- **Floor Textures **( `floor_textures/ `): Floor appearance variation.
|
||||
- **Table Model **( `table0/ `): Default table fixture.
|
||||
- **Robot Assets **(e.g., `lift2/ `): Robot USD and kinematics configs.
|
||||
- **Task Assets **(e.g., `basic/<task_name>/ `): Objects specific to each task.
|
||||
|
||||
## Rigid Object Assets [](#rigid-object-assets)
|
||||
|
||||
This section describes the asset structure for rigid objects, using `workflows/simbox/example_assets/task/sort_the_rubbish `as an example.
|
||||
|
||||
### Directory Organization [](#directory-organization)
|
||||
|
||||
Different object categories are placed in separate folders at the same level. Objects of the same category are grouped together in a single folder to facilitate **category-level randomization **.
|
||||
|
||||
```
|
||||
workflows/simbox/example_assets/task/sort_the_rubbish/
|
||||
├── garbage_can/ # Container category
|
||||
│ ├── recyclable_can/
|
||||
│ └── nonrecyclable_can/
|
||||
├── non_recyclable_garbage/ # Non-recyclable items category
|
||||
│ ├── obj_1/
|
||||
│ ├── obj_2/
|
||||
│ └── ...
|
||||
└── recyclable_garbage/ # Recyclable items category
|
||||
├── bottle_0/
|
||||
├── bottle_1/
|
||||
└── ...
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
10
|
||||
11
|
||||
12
|
||||
|
||||
### Object Instance Structure [](#object-instance-structure)
|
||||
|
||||
Each object instance folder contains the USD model, textures, and annotations:
|
||||
|
||||
```
|
||||
workflows/simbox/example_assets/task/sort_the_rubbish/non_recyclable_garbage/obj_2/
|
||||
├── Aligned_obj.usd # Object USD with physics properties (mass, collision, etc.)
|
||||
├── Aligned_grasp_sparse.npy # Grasp pose annotations (for pickable objects)
|
||||
└── textures/ # Texture files
|
||||
└── baked_mesh_*.png
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
|
||||
**File Naming Conventions: **
|
||||
|
||||
- **Aligned_obj.usd **( file ): USD file containing the 3D model with complete physics properties (mass, collision mesh, etc.).
|
||||
- **Aligned_grasp_sparse.npy **( file ): Grasp pose annotations for manipulation tasks.
|
||||
- **textures/ **( directory ): Directory containing texture maps for the object.
|
||||
|
||||
## Articulated Object Assets [](#articulated-object-assets)
|
||||
|
||||
Articulated objects (e.g., doors, drawers, appliances) follow a similar organization pattern. This section uses `workflows/simbox/assets/art/electriccooker `as an example.
|
||||
|
||||
### Directory Organization [](#directory-organization-1)
|
||||
|
||||
Different articulated object categories are placed in separate folders. Objects within the same category share consistent orientation, category classification, and functionality after preprocessing.
|
||||
|
||||
```
|
||||
workflows/simbox/assets/art/electriccooker/
|
||||
├── electriccooker_0002/
|
||||
├── electriccooker_0008/
|
||||
├── electriccooker_0011/
|
||||
├── electriccooker_0017/
|
||||
├── electriccooker_0031/
|
||||
└── ...
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
|
||||
### Articulated Object Instance Structure [](#articulated-object-instance-structure)
|
||||
|
||||
Each articulated object instance contains the USD model, materials, and keypoint annotations:
|
||||
|
||||
```
|
||||
workflows/simbox/assets/art/electriccooker/electriccooker_0031/
|
||||
├── instance.usd # Articulated object USD
|
||||
├── instance.png # Preview image
|
||||
├── Materials/ # Material definitions
|
||||
└── Kps/ # Keypoint annotations
|
||||
└── close_h/ # Keypoints for "close horizontally" action
|
||||
├── keypoints.json
|
||||
├── keypoints_final.json
|
||||
└── info.json
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
|
||||
**File Naming Conventions: **
|
||||
|
||||
- **instance.usd **( file ): USD file for articulated objects (unlike rigid objects which use `Aligned_obj.usd `).
|
||||
- **instance.png **( file ): Preview/thumbnail image.
|
||||
- **Materials/ **( directory ): Material and texture definitions.
|
||||
- **Kps/ **( directory ): Keypoint annotations for interaction points.
|
||||
- **Kps/<action_type>/ **( directory ): Action-specific keypoints (e.g., `close_h `for closing horizontally).
|
||||
|
||||
### Keypoint Annotations [](#keypoint-annotations)
|
||||
|
||||
Keypoint annotations define interaction points for articulated objects:
|
||||
|
||||
```
|
||||
Kps/
|
||||
├── close_h/ # Close horizontally (e.g., laptop, pot, electric cooker)
|
||||
├── close_v/ # Close vertically (e.g., microwave)
|
||||
├── open_h/ # Open horizontally
|
||||
├── open_v/ # Open vertically
|
||||
├── pull/ # Pull (e.g., drawer)
|
||||
├── push/ # Push
|
||||
└── ...
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
|
||||
Each action folder contains:
|
||||
|
||||
- **keypoints.json **( file ): Initial keypoint positions.
|
||||
- **keypoints_final.json **( file ): Final/processed keypoint positions.
|
||||
- **info.json **( file ): Metadata about the keypoints.
|
||||
|
||||
## Asset Configuration [](#asset-configuration)
|
||||
|
||||
Assets are referenced in task YAML configurations:
|
||||
yaml
|
||||
```
|
||||
objects:
|
||||
- name: bottle_1
|
||||
path: task/sort_the_rubbish/recyclable_garbage/bottle_1/Aligned_obj.usd
|
||||
target_class: RigidObject
|
||||
category: bottle
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
|
||||
For more details on object configuration, see [Objects](/InternDataEngine-Docs/concepts/objects.html).
|
||||
|
||||
## Best Practices [](#best-practices)
|
||||
|
||||
-
|
||||
|
||||
**Category Organization **: Group objects of the same category in a single folder for efficient domain randomization.
|
||||
|
||||
-
|
||||
|
||||
**Consistent Naming **: Use standardized naming conventions:
|
||||
|
||||
- `Aligned_obj.usd `for rigid objects
|
||||
- `instance.usd `for articulated objects
|
||||
- `Aligned_grasp_sparse.npy `for grasp annotations
|
||||
|
||||
-
|
||||
|
||||
**Complete Physics Properties **: Ensure USD files include:
|
||||
|
||||
- Accurate mass properties
|
||||
- Collision meshes
|
||||
- Appropriate friction coefficients
|
||||
|
||||
-
|
||||
|
||||
**Preprocessing **: For all objects, ensure consistent frame and alignment across instances in the same category.
|
||||
433
docs_crawled/config_dr.md
Normal file
433
docs_crawled/config_dr.md
Normal file
@@ -0,0 +1,433 @@
|
||||
# Source: https://internrobotics.github.io/InternDataEngine-Docs/config/dr.html
|
||||
|
||||
# Domain Randomization [](#domain-randomization)
|
||||
|
||||
Domain randomization generates diverse training data by varying simulation parameters. This helps bridge the sim-to-real gap and improves model generalization.
|
||||
|
||||
## Randomization Types [](#randomization-types)
|
||||
|
||||
### 1. Environment Map Randomization [](#_1-environment-map-randomization)
|
||||
|
||||
Config Example:
|
||||
yaml
|
||||
```
|
||||
# Source: configs/manip/simbox/pick_and_place/lift2/single_pick/left/omniobject3d-banana.yaml
|
||||
env_map:
|
||||
envmap_lib: envmap_lib
|
||||
apply_randomization: True
|
||||
intensity_range: [4000, 7000]
|
||||
rotation_range: [0, 180]
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
|
||||
Code Example:
|
||||
python
|
||||
```
|
||||
# Source: workflows/simbox/core/tasks/banana.py
|
||||
def _set_envmap(self):
|
||||
"""Randomize or reset the environment map (HDR dome light)."""
|
||||
cfg = self.cfg["env_map"]
|
||||
if cfg.get("light_type", "DomeLight") == "DomeLight":
|
||||
envmap_hdr_path_list = glob.glob(os.path.join(self.asset_root, cfg["envmap_lib"], "*.hdr"))
|
||||
envmap_hdr_path_list.sort()
|
||||
if cfg.get("apply_randomization", False):
|
||||
envmap_id = random.randint(0, len(envmap_hdr_path_list) - 1)
|
||||
intensity = random.uniform(cfg["intensity_range"][0], cfg["intensity_range"][1])
|
||||
rotation = [random.uniform(cfg["rotation_range"][0], cfg["rotation_range"][1]) for _ in range(3)]
|
||||
else:
|
||||
envmap_id = 0
|
||||
intensity = 1000.0
|
||||
rotation = [0.0, 0.0, 0.0]
|
||||
dome_prim_path = f"{self.root_prim_path}/DomeLight"
|
||||
envmap_hdr_path = envmap_hdr_path_list[envmap_id]
|
||||
|
||||
if not is_prim_path_valid(dome_prim_path):
|
||||
self.dome_light_prim = UsdLux.DomeLight.Define(self.stage, dome_prim_path)
|
||||
UsdGeom.Xformable(self.dome_light_prim).AddRotateXYZOp().Set((rotation[0], rotation[1], rotation[2]))
|
||||
else:
|
||||
self.dome_light_prim.GetOrderedXformOps()[0].Set((rotation[0], rotation[1], rotation[2]))
|
||||
self.dome_light_prim.GetIntensityAttr().Set(intensity)
|
||||
self.dome_light_prim.GetTextureFileAttr().Set(envmap_hdr_path)
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
10
|
||||
11
|
||||
12
|
||||
13
|
||||
14
|
||||
15
|
||||
16
|
||||
17
|
||||
18
|
||||
19
|
||||
20
|
||||
21
|
||||
22
|
||||
23
|
||||
24
|
||||
25
|
||||
|
||||
### 2. Texture Randomization [](#_2-texture-randomization)
|
||||
|
||||
Config Example:
|
||||
yaml
|
||||
```
|
||||
# Source: workflows/simbox/core/configs/arenas/pick_randomized_arena.yaml
|
||||
fixtures:
|
||||
-
|
||||
name: table
|
||||
path: table0/instance.usd
|
||||
target_class: GeometryObject
|
||||
translation: [0.0, 0.0, 0.375]
|
||||
scale: [0.001, 0.001053, 0.001056]
|
||||
texture:
|
||||
texture_lib: "table_textures"
|
||||
apply_randomization: True
|
||||
texture_id: 0
|
||||
texture_scale: [0.001, 0.001]
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
10
|
||||
11
|
||||
12
|
||||
13
|
||||
|
||||
Code Example:
|
||||
python
|
||||
```
|
||||
# Source: workflows/simbox/core/objects/plane_object.py
|
||||
def apply_texture(self, asset_root, cfg):
|
||||
texture_name = cfg["texture_lib"]
|
||||
texture_path_list = glob.glob(os.path.join(asset_root, texture_name, "*"))
|
||||
texture_path_list.sort()
|
||||
if cfg.get("apply_randomization", False):
|
||||
texture_id = random.randint(0, len(texture_path_list) - 1)
|
||||
else:
|
||||
texture_id = cfg["texture_id"]
|
||||
texture_path = texture_path_list[texture_id]
|
||||
mat_prim_path = f"{self.prim_path}/Looks/Material"
|
||||
if not is_prim_path_valid(mat_prim_path):
|
||||
self.mat = OmniPBR(
|
||||
prim_path=mat_prim_path,
|
||||
name="Material",
|
||||
texture_path=texture_path,
|
||||
texture_scale=cfg.get("texture_scale"),
|
||||
)
|
||||
self.apply_visual_material(self.mat)
|
||||
else:
|
||||
self.mat.set_texture(
|
||||
texture_path,
|
||||
)
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
10
|
||||
11
|
||||
12
|
||||
13
|
||||
14
|
||||
15
|
||||
16
|
||||
17
|
||||
18
|
||||
19
|
||||
20
|
||||
21
|
||||
22
|
||||
23
|
||||
|
||||
### 3. Camera Pose Randomization [](#_3-camera-pose-randomization)
|
||||
|
||||
Config Example:
|
||||
yaml
|
||||
```
|
||||
# Source: configs/manip/simbox/pick_and_place/lift2/single_pick/left/omniobject3d-banana.yaml
|
||||
cameras:
|
||||
-
|
||||
name: lift2_hand_left
|
||||
translation: [0.07, 0.01, 0.08]
|
||||
orientation: [0.62, 0.33, -0.33, -0.62]
|
||||
camera_axes: usd
|
||||
camera_file: workflows/simbox/core/configs/cameras/realsense_d405.yaml
|
||||
parent: "lift2/lift2/lift2/fl/link6" # todo
|
||||
apply_randomization: True
|
||||
max_translation_noise: 0.02
|
||||
max_orientation_noise: 2.5
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
10
|
||||
11
|
||||
12
|
||||
|
||||
Code Example:
|
||||
python
|
||||
```
|
||||
# Source: workflows/simbox/core/tasks/banana.py
|
||||
def _perturb_camera(self, camera, cfg, max_translation_noise=0.05, max_orientation_noise=10.0):
|
||||
translation = np.array(cfg["translation"])
|
||||
orientation = np.array(cfg["orientation"])
|
||||
|
||||
random_direction = np.random.randn(3)
|
||||
random_direction /= np.linalg.norm(random_direction)
|
||||
random_distance = np.random.uniform(0, max_translation_noise)
|
||||
perturbed_translation = translation + random_direction * random_distance
|
||||
|
||||
original_rot = R.from_quat(orientation, scalar_first=True)
|
||||
random_axis = np.random.randn(3)
|
||||
random_axis /= np.linalg.norm(random_axis)
|
||||
random_angle_deg = np.random.uniform(-max_orientation_noise, max_orientation_noise)
|
||||
random_angle_rad = np.radians(random_angle_deg)
|
||||
perturbation_rot = R.from_rotvec(random_axis * random_angle_rad)
|
||||
perturbed_rot = perturbation_rot * original_rot
|
||||
perturbed_orientation = perturbed_rot.as_quat(scalar_first=True)
|
||||
|
||||
camera.set_local_pose(
|
||||
translation=perturbed_translation,
|
||||
orientation=perturbed_orientation,
|
||||
camera_axes=cfg["camera_axes"],
|
||||
)
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
10
|
||||
11
|
||||
12
|
||||
13
|
||||
14
|
||||
15
|
||||
16
|
||||
17
|
||||
18
|
||||
19
|
||||
20
|
||||
21
|
||||
22
|
||||
23
|
||||
24
|
||||
|
||||
### 4. Region Randomization [](#_4-region-randomization)
|
||||
|
||||
Config Example:
|
||||
yaml
|
||||
```
|
||||
# Source: configs/manip/simbox/pick_and_place/lift2/single_pick/left/omniobject3d-banana.yaml
|
||||
regions:
|
||||
-
|
||||
object: pick_object_left
|
||||
target: table
|
||||
random_type: A_on_B_region_sampler
|
||||
random_config:
|
||||
pos_range: [
|
||||
[-0.35, -0.25, 0.0],
|
||||
[0.05, 0.05, 0.0]
|
||||
]
|
||||
yaw_rotation: [-180.0, 180.0]
|
||||
-
|
||||
object: lift2
|
||||
target: table
|
||||
random_type: A_on_B_region_sampler
|
||||
random_config:
|
||||
pos_range: [
|
||||
[-0.025, -0.80, -0.775],
|
||||
[0.025, -0.80, -0.67]
|
||||
]
|
||||
yaw_rotation: [-0.0, 0.0]
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
10
|
||||
11
|
||||
12
|
||||
13
|
||||
14
|
||||
15
|
||||
16
|
||||
17
|
||||
18
|
||||
19
|
||||
20
|
||||
21
|
||||
22
|
||||
|
||||
Code Example:
|
||||
python
|
||||
```
|
||||
# Source: workflows/simbox/core/tasks/banana.py
|
||||
def _set_regions(self):
|
||||
"""Randomize object poses according to region configs."""
|
||||
random_region_list = deepcopy(self.random_region_list)
|
||||
for cfg in self.cfg["regions"]:
|
||||
obj = self._task_objects[cfg["object"]]
|
||||
tgt = self._task_objects[cfg["target"]]
|
||||
if "sub_tgt_prim" in cfg:
|
||||
tgt = XFormPrim(prim_path=tgt.prim_path + cfg["sub_tgt_prim"])
|
||||
if "priority" in cfg:
|
||||
if cfg["priority"]:
|
||||
idx = random.choice(cfg["priority"])
|
||||
else:
|
||||
idx = random.randint(0, len(random_region_list) - 1)
|
||||
random_config = (random_region_list.pop(idx))["random_config"]
|
||||
sampler_fn = getattr(RandomRegionSampler, cfg["random_type"])
|
||||
pose = sampler_fn(obj, tgt, **random_config)
|
||||
obj.set_local_pose(*pose)
|
||||
elif "container" in cfg:
|
||||
container = self._task_objects[cfg["container"]]
|
||||
obj_trans = container.get_local_pose()[0]
|
||||
x_bias = random.choice(container.gap) if container.gap else 0
|
||||
obj_trans[0] += x_bias
|
||||
obj_trans[2] += cfg["z_init"]
|
||||
obj_ori = obj.get_local_pose()[1]
|
||||
obj.set_local_pose(obj_trans, obj_ori)
|
||||
elif "target2" in cfg:
|
||||
tgt2 = self._task_objects[cfg["target2"]]
|
||||
sampler_fn = getattr(RandomRegionSampler, cfg["random_type"])
|
||||
pose = sampler_fn(obj, tgt, tgt2, **cfg["random_config"])
|
||||
obj.set_local_pose(*pose)
|
||||
else:
|
||||
sampler_fn = getattr(RandomRegionSampler, cfg["random_type"])
|
||||
pose = sampler_fn(obj, tgt, **cfg["random_config"])
|
||||
obj.set_local_pose(*pose)
|
||||
|
||||
# Source: workflows/simbox/core/utils/region_sampler.py
|
||||
@staticmethod
|
||||
def A_on_B_region_sampler(obj, tgt, pos_range, yaw_rotation):
|
||||
# Translation
|
||||
shift = np.random.uniform(*pos_range)
|
||||
bbox_obj = compute_bbox(obj.prim)
|
||||
obj_z_min = bbox_obj.min[2]
|
||||
bbox_tgt = compute_bbox(tgt.prim)
|
||||
tgt_center = (np.asarray(bbox_tgt.min) + np.asarray(bbox_tgt.max)) / 2
|
||||
tgt_z_max = bbox_tgt.max[2]
|
||||
place_pos = np.zeros(3)
|
||||
place_pos[0] = tgt_center[0]
|
||||
place_pos[1] = tgt_center[1]
|
||||
place_pos[2] = (
|
||||
tgt_z_max + (obj.get_local_pose()[0][2] - obj_z_min) + 0.001
|
||||
) # add a small value to avoid penetration
|
||||
place_pos += shift
|
||||
# Orientation
|
||||
yaw = np.random.uniform(*yaw_rotation)
|
||||
dr = R.from_euler("xyz", [0.0, 0.0, yaw], degrees=True)
|
||||
r = R.from_quat(obj.get_local_pose()[1], scalar_first=True)
|
||||
orientation = (dr * r).as_quat(scalar_first=True)
|
||||
return place_pos, orientation
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
10
|
||||
11
|
||||
12
|
||||
13
|
||||
14
|
||||
15
|
||||
16
|
||||
17
|
||||
18
|
||||
19
|
||||
20
|
||||
21
|
||||
22
|
||||
23
|
||||
24
|
||||
25
|
||||
26
|
||||
27
|
||||
28
|
||||
29
|
||||
30
|
||||
31
|
||||
32
|
||||
33
|
||||
34
|
||||
35
|
||||
36
|
||||
37
|
||||
38
|
||||
39
|
||||
40
|
||||
41
|
||||
42
|
||||
43
|
||||
44
|
||||
45
|
||||
46
|
||||
47
|
||||
48
|
||||
49
|
||||
50
|
||||
51
|
||||
52
|
||||
53
|
||||
54
|
||||
55
|
||||
56
|
||||
57
|
||||
58
|
||||
59
|
||||
|
||||
## Key Files [](#key-files)
|
||||
|
||||
- **utils/dr.py **( file ): Randomization utilities.
|
||||
- **utils/constants.py **( file ): Category parameters.
|
||||
- **tasks/banana.py **( file ): Randomization implementation.
|
||||
|
||||
## References [](#references)
|
||||
|
||||
- [Omni6DPose: A Benchmark and Model for Universal 6D Object Pose Estimation and Tracking (ECCV 2024)](https://jiyao06.github.io/Omni6DPose/)
|
||||
523
docs_crawled/config_yaml.md
Normal file
523
docs_crawled/config_yaml.md
Normal file
@@ -0,0 +1,523 @@
|
||||
# Source: https://internrobotics.github.io/InternDataEngine-Docs/config/yaml.html
|
||||
|
||||
# YAML Configuration [](#yaml-configuration)
|
||||
|
||||
Task configurations in InternDataEngine are defined using YAML files. This page explains the structure and available options.
|
||||
|
||||
## Overview [](#overview)
|
||||
|
||||
A task YAML file defines all components needed for a simulation episode: environment, robots, objects, cameras, and skills. The workflow loads this configuration to set up the simulation.
|
||||
|
||||
## World Settings [](#world-settings)
|
||||
|
||||
Global simulation settings are defined in the YAML files under `configs/simbox `:
|
||||
yaml
|
||||
```
|
||||
simulator:
|
||||
physics_dt: 1/30 # Physics update rate
|
||||
rendering_dt: 1/30 # Render update rate
|
||||
stage_units_in_meters: 1.0 # Stage unit scale
|
||||
headless: True # Run without GUI; set to False for visual debugging
|
||||
anti_aliasing: 0 # Anti-aliasing level
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
|
||||
### World Settings [](#world-settings-1)
|
||||
|
||||
- **physics_dt **( float ): Physics simulation time step (in seconds).
|
||||
- **rendering_dt **( float ): Rendering time step (in seconds).
|
||||
- **stage_units_in_meters **( float ): Unit scale used for the USD stage.
|
||||
- **headless **( bool ): Run without GUI; set to `False `for visual debugging.
|
||||
- **anti_aliasing **( int ): Anti-aliasing level (0 = disabled).
|
||||
|
||||
## Task Basic Configuration [](#task-basic-configuration)
|
||||
|
||||
Each task begins with basic metadata and settings:
|
||||
yaml
|
||||
```
|
||||
tasks:
|
||||
-
|
||||
name: banana_base_task # Task identifier
|
||||
asset_root: workflows/simbox/example_assets # Root path for all assets
|
||||
task: BananaBaseTask # Task class name
|
||||
task_id: 0 # Task instance ID
|
||||
|
||||
offset: null # Optional position offset
|
||||
render: True # Enable rendering
|
||||
|
||||
neglect_collision_names: ["table"] # Collision filter names
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
10
|
||||
11
|
||||
|
||||
### Task Basic Configuration [](#task-basic-configuration-1)
|
||||
|
||||
- **name **( str ): Unique task identifier.
|
||||
- **asset_root **( str ): Root directory for all USD assets.
|
||||
- **task **( str ): Python class that implements task logic.
|
||||
- **task_id **( int ): Instance ID for multi-task scenarios.
|
||||
- **offset **( list ): Optional world offset [x, y, z].
|
||||
- **render **( bool ): Enable/disable visual rendering.
|
||||
- **neglect_collision_names **( list ): Object names to exclude from gripper collision checking.
|
||||
|
||||
## Arena [](#arena)
|
||||
|
||||
Arena configuration defines static fixtures in the environment, such as tables, floors, and backgrounds. Each fixture specifies its USD asset path, position, orientation, scale, and optionally texture randomization settings.
|
||||
|
||||
Arena configs are stored in `workflows/simbox/core/configs/arenas/ `and referenced via the `arena_file `field.
|
||||
yaml
|
||||
```
|
||||
name: example
|
||||
fixtures:
|
||||
-
|
||||
name: table
|
||||
path: table0/instance.usd
|
||||
target_class: GeometryObject
|
||||
translation: [0.0, 0.0, 0.375]
|
||||
scale: [0.000525, 0.001053, 0.001056]
|
||||
-
|
||||
name: floor
|
||||
target_class: PlaneObject
|
||||
size: [5.0, 5.0]
|
||||
translation: [0, 0, 0]
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
10
|
||||
11
|
||||
12
|
||||
13
|
||||
|
||||
## Environment Map [](#environment-map)
|
||||
|
||||
Environment map controls scene lighting and HDR backgrounds. It supports randomization of lighting intensity and rotation:
|
||||
yaml
|
||||
```
|
||||
env_map:
|
||||
envmap_lib: envmap_lib # Path to HDR environment maps
|
||||
apply_randomization: True # Enable random lighting
|
||||
intensity_range: [4000, 7000] # Light intensity range
|
||||
rotation_range: [0, 180] # Environment rotation range (degrees)
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
|
||||
## Robots [](#robots)
|
||||
|
||||
Robot configuration specifies the robot name, its configuration file path, initial orientation, and collision filter substrings:
|
||||
yaml
|
||||
```
|
||||
robots:
|
||||
-
|
||||
name: "split_aloha"
|
||||
robot_config_file: workflows/simbox/core/configs/robots/split_aloha.yaml
|
||||
euler: [0.0, 0.0, 90.0]
|
||||
ignore_substring: ["material", "table", "gso_box"]
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
|
||||
### Robots [](#robots-1)
|
||||
|
||||
- **name **( str ): Robot identifier (must match skill definitions).
|
||||
- **robot_config_file **( str ): Path to robot config file, relative to asset_root.
|
||||
- **euler **( list ): Initial rotation [roll, pitch, yaw] in degrees, in world frame.
|
||||
- **ignore_substring **( list ): Substrings for collision filtering; objects with matching name prefixes are excluded from CuRobo collision checking.
|
||||
|
||||
For detailed robot configuration, see [Robots](/InternDataEngine-Docs/concepts/robots.html).
|
||||
|
||||
## Objects [](#objects)
|
||||
|
||||
Objects define items in the scene that can be manipulated, along with their metadata and placement properties:
|
||||
yaml
|
||||
```
|
||||
objects:
|
||||
-
|
||||
name: pick_object_left
|
||||
path: task/sort_the_rubbish/non_recyclable_garbage/obj_0/Aligned_obj.usd
|
||||
target_class: RigidObject
|
||||
dataset: oo3d
|
||||
category: bottle
|
||||
prim_path_child: Aligned
|
||||
translation: [0.0, 0.0, 0.0]
|
||||
euler: [0.0, 0.0, 0.0]
|
||||
scale: [1, 1, 1]
|
||||
apply_randomization: True
|
||||
orientation_mode: random
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
10
|
||||
11
|
||||
12
|
||||
13
|
||||
|
||||
### Objects [](#objects-1)
|
||||
|
||||
- **name **( str ): Unique object identifier (must match skill definitions).
|
||||
- **path **( str ): USD file path relative to asset_root.
|
||||
- **target_class **( str ): Object type: `RigidObject `, `GeometryObject `, `ArticulatedObject `, `XFormObject `, `ConveyorObject `.
|
||||
- **dataset **( str ): Source dataset (e.g., `oo3d `, `gso `).
|
||||
- **category **( str ): Object category for grasp detection.
|
||||
- **prim_path_child **( str ): USD sub-prim name (default: `Aligned `). This prim contains the target mesh for collision and grasping.
|
||||
- **translation **( list ): Initial position [x, y, z] in world frame.
|
||||
- **euler **( list ): Initial rotation [roll, pitch, yaw] in degrees, in world frame.
|
||||
- **scale **( list ): Scale factors [sx, sy, sz].
|
||||
- **apply_randomization **( bool ): Enable pose randomization within the category.
|
||||
- **orientation_mode **( str ): Orientation constraint: `random `(pure random), `suggested `(follows category defaults), or `keep `(use `euler `values).
|
||||
|
||||
For detailed object configuration, see [Objects](/InternDataEngine-Docs/concepts/objects.html).
|
||||
|
||||
## Regions [](#regions)
|
||||
|
||||
Regions define spatial constraints for object placement, specifying which object to place, the target surface, and the allowed position/orientation ranges:
|
||||
yaml
|
||||
```
|
||||
regions:
|
||||
-
|
||||
object: pick_object_left
|
||||
target: table
|
||||
random_type: A_on_B_region_sampler
|
||||
random_config:
|
||||
pos_range: [
|
||||
[-0.3, -0.20, 0.0],
|
||||
[-0.025, 0.10, 0.0]
|
||||
]
|
||||
yaw_rotation: [-45.0, 15.0]
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
10
|
||||
11
|
||||
|
||||
### Regions [](#regions-1)
|
||||
|
||||
- **object **( str ): Name of the object to place.
|
||||
- **target **( str ): Target surface name from arena fixtures (default: `table `).
|
||||
- **random_type **( str ): Sampler type for placement.
|
||||
- **pos_range **( list ): Position range [[x_min, y_min, z_min], [x_max, y_max, z_max]] in world frame.
|
||||
- **yaw_rotation **( list ): Yaw angle range [min, max] in degrees in world frame.
|
||||
|
||||
## Cameras [](#cameras)
|
||||
|
||||
Camera configuration defines viewpoint, intrinsic parameters, and extrinsic randomization:
|
||||
yaml
|
||||
```
|
||||
cameras:
|
||||
-
|
||||
name: split_aloha_hand_left
|
||||
translation: [0.0, 0.08, 0.05]
|
||||
orientation: [0.0, 0.0, 0.965, 0.259]
|
||||
camera_axes: usd
|
||||
camera_file: workflows/simbox/core/configs/cameras/astra.yaml
|
||||
parent: "split_aloha/split_aloha_mid_360_with_piper/split_aloha_mid_360_with_piper/fl/link6"
|
||||
apply_randomization: False
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
|
||||
### Cameras [](#cameras-1)
|
||||
|
||||
- **name **( str ): Camera identifier.
|
||||
- **translation **( list ): Position offset [x, y, z] from parent link.
|
||||
- **orientation **( list ): Rotation offset as quaternion [qx, qy, qz, qw] from parent link.
|
||||
- **camera_axes **( str ): Coordinate convention: `usd `or `ros `.
|
||||
- **camera_file **( str ): Path to camera parameter file.
|
||||
- **parent **( str ): USD prim path to attach the camera to.
|
||||
- **apply_randomization **( bool ): Enable extrinsics randomization.
|
||||
|
||||
For detailed camera configuration, see [Cameras](/InternDataEngine-Docs/concepts/cameras.html).
|
||||
|
||||
## Data [](#data)
|
||||
|
||||
The data section stores metadata for dataset generation:
|
||||
yaml
|
||||
```
|
||||
data:
|
||||
task_dir: "sort_the_rubbish_part0"
|
||||
language_instruction: "Sort the garbage on the desktop into recyclable and non-recyclable."
|
||||
detailed_language_instruction: "Pick the bottles and place them into the recyclable trashbin with right arm, and pick the other garbage and place it into the non-recyclable trashbin with left arm."
|
||||
collect_info: ""
|
||||
version: "v2.0, head camera 1280x720, wrist 640x480"
|
||||
update: True
|
||||
max_episode_length: 4000
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
|
||||
### Data [](#data-1)
|
||||
|
||||
- **task_dir **( str ): Output directory name.
|
||||
- **language_instruction **( str ): Short task description.
|
||||
- **detailed_language_instruction **( str ): Detailed instruction for training.
|
||||
- **collect_info **( str ): Additional collection metadata.
|
||||
- **version **( str ): Dataset version string.
|
||||
- **update **( bool ): Whether to overwrite existing data.
|
||||
- **max_episode_length **( int ): Maximum steps per episode.
|
||||
|
||||
## Skills [](#skills)
|
||||
|
||||
Skills define the action sequence for the robot:
|
||||
yaml
|
||||
```
|
||||
skills:
|
||||
-
|
||||
split_aloha:
|
||||
-
|
||||
right:
|
||||
-
|
||||
name: pick
|
||||
objects: [pick_object_right]
|
||||
filter_y_dir: ["forward", 60]
|
||||
filter_z_dir: ["downward", 150]
|
||||
pre_grasp_offset: 0.05
|
||||
gripper_change_steps: 10
|
||||
t_eps: 0.025
|
||||
o_eps: 1
|
||||
process_valid: True
|
||||
lift_th: 0.02
|
||||
post_grasp_offset_min: 0.10
|
||||
post_grasp_offset_max: 0.15
|
||||
-
|
||||
name: place
|
||||
objects: [pick_object_right, gso_box_right]
|
||||
place_direction: vertical
|
||||
x_ratio_range: [0.3, 0.4]
|
||||
y_ratio_range: [0.3, 0.4]
|
||||
pre_place_z_offset: 0.3
|
||||
place_z_offset: 0.3
|
||||
success_mode: height
|
||||
-
|
||||
name: heuristic__skill
|
||||
mode: home
|
||||
gripper_state: 1.0
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
10
|
||||
11
|
||||
12
|
||||
13
|
||||
14
|
||||
15
|
||||
16
|
||||
17
|
||||
18
|
||||
19
|
||||
20
|
||||
21
|
||||
22
|
||||
23
|
||||
24
|
||||
25
|
||||
26
|
||||
27
|
||||
28
|
||||
29
|
||||
30
|
||||
31
|
||||
|
||||
For detailed skill configuration, see [Skills](/InternDataEngine-Docs/concepts/skills/overview.html).
|
||||
|
||||
## Complete Example [](#complete-example)
|
||||
|
||||
Here is a minimal task configuration:
|
||||
yaml
|
||||
```
|
||||
tasks:
|
||||
-
|
||||
name: banana_base_task
|
||||
asset_root: workflows/simbox/assets
|
||||
task: BananaBaseTask
|
||||
task_id: 0
|
||||
offset: null
|
||||
render: True
|
||||
|
||||
arena_file: workflows/simbox/core/configs/arenas/example.yaml
|
||||
|
||||
env_map:
|
||||
envmap_lib: envmap_lib
|
||||
apply_randomization: False
|
||||
|
||||
robots:
|
||||
-
|
||||
name: "fr3"
|
||||
robot_config_file: workflows/simbox/core/configs/robots/fr3.yaml
|
||||
euler: [0.0, 0.0, 0.0]
|
||||
|
||||
objects:
|
||||
-
|
||||
name: bottle
|
||||
path: objects/bottle.usd
|
||||
target_class: RigidObject
|
||||
dataset: oo3d
|
||||
category: bottle
|
||||
prim_path_child: Aligned
|
||||
translation: [0.3, 0.0, 0.0]
|
||||
euler: [0.0, 0.0, 0.0]
|
||||
scale: [1, 1, 1]
|
||||
apply_randomization: False
|
||||
|
||||
regions:
|
||||
-
|
||||
object: bottle
|
||||
target: table
|
||||
random_type: A_on_B_region_sampler
|
||||
random_config:
|
||||
pos_range: [[0.2, -0.1, 0.0], [0.4, 0.1, 0.0]]
|
||||
yaw_rotation: [-30.0, 30.0]
|
||||
|
||||
cameras:
|
||||
-
|
||||
name: head_camera
|
||||
translation: [0.0, 0.0, 0.5]
|
||||
orientation: [0.707, 0.0, 0.0, 0.707]
|
||||
camera_file: workflows/simbox/core/configs/cameras/realsense_d455.yaml
|
||||
parent: ""
|
||||
|
||||
data:
|
||||
task_dir: "pick_bottle"
|
||||
language_instruction: "Pick the bottle."
|
||||
detailed_language_instruction: "Pick the bottle."
|
||||
collect_info: ""
|
||||
version: "v1.0"
|
||||
update: True
|
||||
max_episode_length: 500
|
||||
|
||||
skills:
|
||||
-
|
||||
fr3:
|
||||
-
|
||||
name: pick
|
||||
objects: [bottle]
|
||||
pre_grasp_offset: 0.05
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
10
|
||||
11
|
||||
12
|
||||
13
|
||||
14
|
||||
15
|
||||
16
|
||||
17
|
||||
18
|
||||
19
|
||||
20
|
||||
21
|
||||
22
|
||||
23
|
||||
24
|
||||
25
|
||||
26
|
||||
27
|
||||
28
|
||||
29
|
||||
30
|
||||
31
|
||||
32
|
||||
33
|
||||
34
|
||||
35
|
||||
36
|
||||
37
|
||||
38
|
||||
39
|
||||
40
|
||||
41
|
||||
42
|
||||
43
|
||||
44
|
||||
45
|
||||
46
|
||||
47
|
||||
48
|
||||
49
|
||||
50
|
||||
51
|
||||
52
|
||||
53
|
||||
54
|
||||
55
|
||||
56
|
||||
57
|
||||
58
|
||||
59
|
||||
60
|
||||
61
|
||||
62
|
||||
63
|
||||
64
|
||||
65
|
||||
66
|
||||
67
|
||||
373
docs_crawled/custom_assets.md
Normal file
373
docs_crawled/custom_assets.md
Normal file
@@ -0,0 +1,373 @@
|
||||
# Source: https://internrobotics.github.io/InternDataEngine-Docs/custom/assets.html
|
||||
|
||||
# New Assets [](#new-assets)
|
||||
|
||||
This guide explains how to add new assets to InternDataEngine for simulation tasks.
|
||||
|
||||
## Part 1: Rigid Objects [](#part-1-rigid-objects)
|
||||
|
||||
This section describes how to introduce new rigid objects for manipulation tasks.
|
||||
|
||||
### Step 1: Obtain Geometry and Textures [](#step-1-obtain-geometry-and-textures)
|
||||
|
||||
We recommend starting with an OBJ file that includes:
|
||||
|
||||
- An `.mtl `file storing material properties
|
||||
- With texture images
|
||||
|
||||
**Sources for OBJ Files: **
|
||||
|
||||
- **Open-source datasets **( source ): Various public 3D model repositories.
|
||||
- **ARCode **( source ): 3D reconstruction software for high-fidelity surface textures.
|
||||
- **LiDAR-based apps **( source ): Reconstruction apps with depth sensors for mesh generation.
|
||||
- **Tencent Hunyuan3D **( source ): Multi-view reconstruction for fine, non-convex, or transparent/specular objects.
|
||||
|
||||
Hint
|
||||
|
||||
For objects that are difficult to reconstruct (fine details, non-convex shapes, transparent or highly reflective surfaces), we recommend [Tencent Hunyuan3D](https://3d.hunyuan.tencent.com/)for high-quality multi-view reconstruction.
|
||||
|
||||
### Step 2: Preprocess the OBJ File [](#step-2-preprocess-the-obj-file)
|
||||
|
||||
Before conversion, preprocess the OBJ file to ensure it meets the following requirements:
|
||||
|
||||
- **Correct units **: Use real-world scale (meters recommended)
|
||||
- **Centered origin **: Place origin at the object's center
|
||||
- **Canonical pose **: Align with a reasonable axis (e.g., along a symmetry axis)
|
||||
|
||||
You can perform these adjustments in **MeshLab **:
|
||||
|
||||

|
||||
|
||||
*Setting the origin point at the object center in MeshLab *
|
||||
|
||||

|
||||
|
||||
*Setting the correct scale (units) for the object *
|
||||
|
||||

|
||||
|
||||
*Rotating the object to align with canonical pose *
|
||||
|
||||
After adjustment, export and rename to `Aligned_obj.obj `.
|
||||
|
||||
### Step 3: Convert OBJ to USD [](#step-3-convert-obj-to-usd)
|
||||
|
||||
Navigate to the tools directory and run the converter:
|
||||
bash
|
||||
```
|
||||
cd workflows/simbox/tools/rigid_obj
|
||||
python asset_usd_converter.py --folders /path/to/obj/folder
|
||||
```
|
||||
1
|
||||
2
|
||||
|
||||
This converts the OBJ to USD format and saves it as `Aligned_obj.usd `in the same directory.
|
||||
|
||||

|
||||
|
||||
*Converting OBJ to USD format *
|
||||
|
||||
### Step 4: Add Rigid Body Properties [](#step-4-add-rigid-body-properties)
|
||||
|
||||
Add rigid body physics properties (mass, etc.) to the USD file:
|
||||
bash
|
||||
```
|
||||
python make_rigid.py --usd_path /path/to/Aligned_obj.usd
|
||||
```
|
||||
1
|
||||
|
||||

|
||||
|
||||
*Adding rigid body physics properties (mass) to the USD *
|
||||
|
||||
### Step 5: Add Collision and Friction [](#step-5-add-collision-and-friction)
|
||||
|
||||
Add collider properties and physics materials with friction:
|
||||
bash
|
||||
```
|
||||
# NOTE: This requires Isaac Sim Python
|
||||
isaacsim.python.sh make_collider.py --usd_path /path/to/Aligned_obj.usd
|
||||
```
|
||||
1
|
||||
2
|
||||
|
||||
The collider uses convex decomposition to tightly wrap the object for accurate collision detection.
|
||||
|
||||

|
||||
|
||||
*Adding collision mesh and friction properties *
|
||||
|
||||
### Step 6: Verify Properties [](#step-6-verify-properties)
|
||||
|
||||
After processing, confirm the USD file has the following physics properties:
|
||||
|
||||
- Rigid body dynamics
|
||||
- Collision mesh
|
||||
- Friction coefficients
|
||||
|
||||
The USD file structure will be:
|
||||
|
||||
```
|
||||
World (defaultprim)
|
||||
├── Looks
|
||||
│ └── materials
|
||||
└── Aligned
|
||||
└── mesh
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
|
||||
This hierarchical design ensures consistency. The `Aligned `prim (commonly set as `prim_path_child `) contains the mesh, which is used to detect force contact with the gripper.
|
||||
|
||||
### Step 7 (Optional but Common): Generate Grasp Poses [](#step-7-optional-but-common-generate-grasp-poses)
|
||||
|
||||
If the object will be used for grasping, generate grasp pose annotations:
|
||||
bash
|
||||
```
|
||||
cd workflows/simbox/tools/grasp
|
||||
# See README.md for detailed usage
|
||||
python gen_sparse_label.py --obj_path /path/to/Aligned_obj.obj --unit m
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
|
||||
For detailed instructions, refer to the [README.md](https://github.com/InternRobotics/InternDataEngine/blob/master/workflows/simbox/tools/grasp/README.md)in the grasp tools directory.
|
||||
|
||||

|
||||
|
||||
*Visualization of generated grasp poses on a banana object *
|
||||
|
||||
Warning
|
||||
|
||||
The OBJ file must maintain consistent canonical frame and scale with the USD file. If you modify the OBJ file (scale, orientation) after USD conversion and then regenerate grasp poses, the grasp poses will be incorrect because they are generated from the OBJ mesh.
|
||||
|
||||
### Step 8: Final Directory Structure [](#step-8-final-directory-structure)
|
||||
|
||||
After completing all the steps above, your task's asset directory should have the following structure:
|
||||
|
||||
```
|
||||
new_task/
|
||||
└── new_objs/ # Directory containing all rigid objects
|
||||
├── new_obj0/ # Example object instance
|
||||
│ ├── Aligned_obj.obj # Preprocessed OBJ mesh (source)
|
||||
│ ├── Aligned.mtl # Material file for OBJ
|
||||
│ ├── Aligned_obj.usd # Final USD with physics properties
|
||||
│ ├── Aligned_grasp_sparse.npy # Sparse grasp poses (N × 17)
|
||||
│ ├── Aligned_grasp_dense.npz # Dense grasp poses (optional)
|
||||
│ └── textures/ # Texture files
|
||||
│ └── Scan.jpg # Object texture image
|
||||
├── new_obj1/ # Another object instance
|
||||
├── new_obj2/
|
||||
├── new_obj3/
|
||||
└── new_obj4/
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
10
|
||||
11
|
||||
12
|
||||
13
|
||||
14
|
||||
|
||||
## Part 2: Articulated Objects [](#part-2-articulated-objects)
|
||||
|
||||
This section describes how to add new articulated objects (e.g., microwave, drawer, cabinet) for manipulation tasks.
|
||||
|
||||
### Step 1: Prepare a Stable USD Asset [](#step-1-prepare-a-stable-usd-asset)
|
||||
|
||||
First, you need to prepare a stable USD asset for the articulated object. This USD can be:
|
||||
|
||||
- Built from scratch
|
||||
- Converted from URDF format
|
||||
|
||||
The asset should have stable physical properties:
|
||||
|
||||
- **Mass **: Properly defined for each link
|
||||
- **Joint properties **: Appropriate stiffness and damping values
|
||||
- **Collision **: Properly configured colliders for realistic interaction
|
||||
|
||||
The initial hierarchy structure should look like this:
|
||||
|
||||

|
||||
|
||||
*Initial USD hierarchy structure - root positioned at articulation root *
|
||||
|
||||
### Step 2: Understand the Skills Directory Structure [](#step-2-understand-the-skills-directory-structure)
|
||||
|
||||
We provide tools for different articulated object manipulation skills in `workflows/simbox/tools/art/ `. Currently available:
|
||||
|
||||
- `close_v `: Close vertical articulated objects (e.g., microwave, oven)
|
||||
- `open_v `: Open vertical articulated objects
|
||||
|
||||
More skills will be added gradually.
|
||||
|
||||
Take `close_v `as an example - this skill handles horizontal closing motions like closing a microwave from the side. A sample asset is provided at `workflows/simbox/tools/art/close_v/7265/usd/ `.
|
||||
|
||||
### Step 3: Create keypoints_config.json (close_v example) [](#step-3-create-keypoints-config-json-close-v-example)
|
||||
|
||||
After obtaining the original asset (e.g., `microwave_0.usd `), create a `keypoints_config.json `file with the following structure:
|
||||
json
|
||||
```
|
||||
{
|
||||
"DIR": "/path/to/your/usd/directory",
|
||||
"USD_NAME": "microwave_0.usd",
|
||||
"INSTANCE_NAME": "microwave7265",
|
||||
"link0_initial_prim_path": "/root/group_18",
|
||||
"base_initial_prim_path": "/root/group_0",
|
||||
"revolute_joint_initial_prim_path": "/root/group_18/RevoluteJoint",
|
||||
"joint_index": 0,
|
||||
"LINK0_ROT_AXIS": "y",
|
||||
"BASE_FRONT_AXIS": "z",
|
||||
"LINK0_CONTACT_AXIS": "-y",
|
||||
"SCALED_VOLUME": 0.02
|
||||
}
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
10
|
||||
11
|
||||
12
|
||||
13
|
||||
|
||||
- **DIR **( str ): Directory where USD files are stored.
|
||||
- **USD_NAME **( str ): Original USD file name.
|
||||
- **INSTANCE_NAME **( str ): Model identifier (name it yourself, preferably matching the asset).
|
||||
- **link0_initial_prim_path **( str ): Absolute path in Isaac Sim for the "door" that interacts with the gripper.
|
||||
- **base_initial_prim_path **( str ): Absolute path in Isaac Sim for the object base.
|
||||
- **revolute_joint_initial_prim_path **( str ): Absolute path for the revolute joint.
|
||||
- **joint_index **( int ): Joint number (default: 0).
|
||||
- **LINK0_ROT_AXIS **( str ): Axis pointing vertically upward in the rotating joint's local coordinate system.
|
||||
- **BASE_FRONT_AXIS **( str ): Axis facing the door in the base link's local coordinate system.
|
||||
- **LINK0_CONTACT_AXIS **( str ): Axis pointing vertically downward in the contact link's local coordinate system.
|
||||
- **SCALED_VOLUME **( float ): Default value 0.02 for microwave-like objects.
|
||||
|
||||
For detailed axis configuration with visual examples, refer to the [readme.md](https://github.com/InternRobotics/InternDataEngine/blob/master/workflows/simbox/tools/art/close_v/readme.md).
|
||||
|
||||
### Step 4: Run the Keypoint Annotation Pipeline (close_v example) [](#step-4-run-the-keypoint-annotation-pipeline-close-v-example)
|
||||
|
||||
Navigate to the tools directory and follow the pipeline in `keypoints_pipeline.sh `:
|
||||
bash
|
||||
```
|
||||
cd workflows/simbox/tools/art/close_v/tool
|
||||
```
|
||||
1
|
||||
|
||||
**Step 4.1: Rehier - Restructure Asset Hierarchy **
|
||||
bash
|
||||
```
|
||||
python rehier.py --config $CONFIG_PATH
|
||||
```
|
||||
1
|
||||
|
||||
This step reorganizes the asset hierarchy to a unified standard. After rehier, the structure should look like:
|
||||
|
||||

|
||||
|
||||
*Restructured USD hierarchy - instance prim inserted between original asset and root as articulation root *
|
||||
|
||||
An `instance.usd `file will be generated, indicating success. All joints except the specified one will be locked.
|
||||
|
||||
**Step 4.2: Select Keypoints **
|
||||
bash
|
||||
```
|
||||
python select_keypoint.py --config $CONFIG_PATH
|
||||
```
|
||||
1
|
||||
|
||||
This opens an Open3D visualization window for interactive point selection:
|
||||
|
||||
- **Ctrl + Left Click **: Add a point
|
||||
- **Ctrl + Right Click **: Remove a point
|
||||
|
||||
You need to annotate two contact points:
|
||||
|
||||
| Point | Description |
|
||||
| **First point (articulated_object_head) ** | Desired base position where the gripper contacts the door |
|
||||
| **Second point (articulated_object_tail) ** | The line from the first point should be perpendicular to the rotation axis |
|
||||
|
||||
For visual guidance, refer to the [readme.md](https://github.com/InternRobotics/InternDataEngine/blob/master/workflows/simbox/tools/art/close_v/readme.md).
|
||||
|
||||
**Step 4.3: Transfer Keypoints **
|
||||
bash
|
||||
```
|
||||
python transfer_keypoints.py --config $CONFIG_PATH
|
||||
```
|
||||
1
|
||||
|
||||
**Step 4.4: Overwrite Keypoints **
|
||||
bash
|
||||
```
|
||||
python overwrite_keypoints.py --config $CONFIG_PATH
|
||||
```
|
||||
1
|
||||
|
||||
### Step 5: Final Directory Structure (close_v example) [](#step-5-final-directory-structure-close-v-example)
|
||||
|
||||
After completing all steps, your asset directory should have the following structure:
|
||||
|
||||
```
|
||||
7265/ # Asset ID
|
||||
└── usd/
|
||||
├── microwave_0.usd # Original USD asset
|
||||
├── instance.usd # Processed USD with rehiered structure
|
||||
├── keypoints_config.json # Configuration file
|
||||
├── textures/ # Texture files
|
||||
│ ├── door_mesh_0_texture_0.jpg
|
||||
│ └── door_mesh_1_texture_0.jpg
|
||||
└── Kps/ # Keypoint annotations
|
||||
└── close_v/ # Skill directory
|
||||
├── info.json # Complete metadata
|
||||
├── keypoints.json # Raw keypoints
|
||||
└── keypoints_final.json # Final processed keypoints
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
10
|
||||
11
|
||||
12
|
||||
13
|
||||
|
||||
You can have multiple USD files for similar objects. Each USD directory must contain:
|
||||
|
||||
- `instance.usd `: The processed USD asset
|
||||
- `Kps/ `: Keypoint annotations organized by skill
|
||||
|
||||
Each skill directory under `Kps/ `must contain:
|
||||
|
||||
- `info.json `: Complete object metadata including paths, axes, and keypoint positions
|
||||
- `keypoints.json `: Raw keypoint coordinates
|
||||
- `keypoints_final.json `: Processed keypoint data
|
||||
|
||||
### Step 6: Test with Task Configuration [](#step-6-test-with-task-configuration)
|
||||
|
||||
With the annotated asset, you can now write a task configuration file to test the manipulation task. Refer to existing task configs in `workflows/simbox/core/configs/tasks/art/ `for examples.
|
||||
|
||||
## References [](#references)
|
||||
|
||||
- [GraspNet API](https://github.com/graspnet/graspnetAPI)
|
||||
- [Tencent Hunyuan3D](https://3d.hunyuan.tencent.com/)
|
||||
385
docs_crawled/custom_controller.md
Normal file
385
docs_crawled/custom_controller.md
Normal file
@@ -0,0 +1,385 @@
|
||||
# Source: https://internrobotics.github.io/InternDataEngine-Docs/custom/controller.html
|
||||
|
||||
# New Controller [](#new-controller)
|
||||
|
||||
This guide explains how to create a new robot controller for motion planning with CuRobo.
|
||||
|
||||
## Part 1: Create CuRobo Configuration Files [](#part-1-create-curobo-configuration-files)
|
||||
|
||||
Our controller uses a separate CuRobo config file for each arm. You need to:
|
||||
|
||||
- **Prepare URDF files for each arm **- Extract single-arm URDF from your robot's full URDF
|
||||
- **Create CuRobo config files **- Follow the official CuRobo tutorial
|
||||
|
||||
### Step 1.1: Prepare URDF Files [](#step-1-1-prepare-urdf-files)
|
||||
|
||||
For dual-arm robots, create separate URDF files for left and right arms. Save them in:
|
||||
|
||||
```
|
||||
workflows/simbox/curobo/src/curobo/content/assets/robot/
|
||||
├── your_robot_left_arm.urdf
|
||||
├── your_robot_right_arm.urdf
|
||||
└── meshes/
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
|
||||
Hint
|
||||
|
||||
Each arm URDF should be a standalone file containing only that arm's links and joints. Make sure mesh paths in the URDF are correct relative to the assets folder.
|
||||
|
||||
### Step 1.2: Create CuRobo Config Files [](#step-1-2-create-curobo-config-files)
|
||||
|
||||
Follow the official CuRobo tutorial: [Configuring a New Robot](https://curobo.org/tutorials/1_robot_configuration.html)
|
||||
|
||||
Key steps:
|
||||
|
||||
- Convert URDF to USD using Isaac Sim
|
||||
- Use Lula Robot Description Editor to generate collision spheres
|
||||
- Configure self-collision parameters
|
||||
|
||||
Save config files in:
|
||||
|
||||
```
|
||||
workflows/simbox/curobo/src/curobo/content/configs/robot/
|
||||
├── your_robot_left_arm.yml
|
||||
└── your_robot_right_arm.yml
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
|
||||
Warning
|
||||
|
||||
Isaac Sim's Lula Robot Description Editor is only available in **Isaac Sim 4.0.0 **. Later versions have removed this feature. If you're using a newer version, you may need to manually create the collision sphere configuration or use Isaac Sim 4.0.0 for this step.
|
||||
|
||||
### Example CuRobo Config Structure [](#example-curobo-config-structure)
|
||||
yaml
|
||||
```
|
||||
# your_robot_left_arm.yml
|
||||
robot_cfg:
|
||||
kinematics:
|
||||
usd_path: "robot/your_robot_left_arm.usd"
|
||||
usd_robot_root: "/robot"
|
||||
urdf_path: "robot/your_robot_left_arm.urdf"
|
||||
asset_root_path: "robot"
|
||||
base_link: "base_link"
|
||||
ee_link: "link6" # End-effector link (must match fl_ee_path in robot.yaml)
|
||||
|
||||
collision_link_names:
|
||||
- link1
|
||||
- link2
|
||||
# ...
|
||||
|
||||
collision_spheres:
|
||||
link1:
|
||||
- center: [0.0, 0.0, 0.0]
|
||||
radius: 0.05
|
||||
# ...
|
||||
|
||||
self_collision_ignore:
|
||||
link1: ["link2", "link3"]
|
||||
# ...
|
||||
|
||||
cspace:
|
||||
joint_names: ["joint1", "joint2", "joint3", "joint4", "joint5", "joint6"]
|
||||
retract_config: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
|
||||
null_space_weight: [1.0, 1.0, 1.0, 1.0, 1.0, 1.0]
|
||||
cspace_distance_weight: [1.0, 1.0, 1.0, 1.0, 1.0, 1.0]
|
||||
max_jerk: 500.0
|
||||
max_acceleration: 15.0
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
10
|
||||
11
|
||||
12
|
||||
13
|
||||
14
|
||||
15
|
||||
16
|
||||
17
|
||||
18
|
||||
19
|
||||
20
|
||||
21
|
||||
22
|
||||
23
|
||||
24
|
||||
25
|
||||
26
|
||||
27
|
||||
28
|
||||
29
|
||||
30
|
||||
31
|
||||
32
|
||||
|
||||
## Part 2: Update Robot YAML Configuration [](#part-2-update-robot-yaml-configuration)
|
||||
|
||||
In your `new_robot.yaml `(see [New Robot](/InternDataEngine-Docs/custom/robot.html)), fill in the `robot_file `field:
|
||||
|
||||
### For Dual-Arm Robots [](#for-dual-arm-robots)
|
||||
yaml
|
||||
```
|
||||
# CuRobo kinematics config files (one per arm)
|
||||
robot_file:
|
||||
- workflows/simbox/curobo/src/curobo/content/configs/robot/your_robot_left_arm.yml
|
||||
- workflows/simbox/curobo/src/curobo/content/configs/robot/your_robot_right_arm.yml
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
|
||||
### For Single-Arm Robots [](#for-single-arm-robots)
|
||||
|
||||
For single-arm robots, we conventionally name it as the "left" arm:
|
||||
yaml
|
||||
```
|
||||
# CuRobo kinematics config file
|
||||
robot_file:
|
||||
- workflows/simbox/curobo/src/curobo/content/configs/robot/your_robot_left_arm.yml
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
|
||||
## Part 3: Create Controller Python Class [](#part-3-create-controller-python-class)
|
||||
|
||||
Create a new controller file in `workflows/simbox/core/controllers/ `. Here's a new controller template:
|
||||
python
|
||||
```
|
||||
"""NewRobot controller implementation."""
|
||||
|
||||
import numpy as np
|
||||
from core.controllers.base_controller import register_controller
|
||||
from core.controllers.template_controller import TemplateController
|
||||
|
||||
@register_controller
|
||||
class NewRobotController(TemplateController):
|
||||
"""Controller for NewRobot."""
|
||||
|
||||
def _get_default_ignore_substring(self):
|
||||
"""Return default collision ignore substrings."""
|
||||
return ["material", "table", "floor", "scene"]
|
||||
|
||||
def _configure_joint_indices(self, robot_file: str) -> None:
|
||||
"""
|
||||
Configure joint names and indices for motion planning.
|
||||
|
||||
This method maps between CuRobo's joint names and the robot USD's joint names.
|
||||
"""
|
||||
# Raw joint names from CuRobo config (must match cspace.joint_names in yaml)
|
||||
self.raw_js_names = ["joint1", "joint2", "joint3", "joint4", "joint5", "joint6"]
|
||||
|
||||
if "left" in robot_file:
|
||||
# Command joint names in robot USD (with prefix)
|
||||
self.cmd_js_names = ["fl_joint1", "fl_joint2", "fl_joint3",
|
||||
"fl_joint4", "fl_joint5", "fl_joint6"]
|
||||
# Joint indices from robot config
|
||||
self.arm_indices = np.array(self.robot.cfg["left_joint_indices"])
|
||||
self.gripper_indices = np.array(self.robot.cfg["left_gripper_indices"])
|
||||
self.reference_prim_path = self.task.robots[self.name].fl_base_path
|
||||
self.lr_name = "left"
|
||||
self._gripper_state = 1.0 if self.robot.left_gripper_state == 1.0 else -1.0
|
||||
|
||||
elif "right" in robot_file:
|
||||
# Command joint names in robot USD (with prefix)
|
||||
self.cmd_js_names = ["fr_joint1", "fr_joint2", "fr_joint3",
|
||||
"fr_joint4", "fr_joint5", "fr_joint6"]
|
||||
self.arm_indices = np.array(self.robot.cfg["right_joint_indices"])
|
||||
self.gripper_indices = np.array(self.robot.cfg["right_gripper_indices"])
|
||||
self.reference_prim_path = self.task.robots[self.name].fr_base_path
|
||||
self.lr_name = "right"
|
||||
self._gripper_state = 1.0 if self.robot.right_gripper_state == 1.0 else -1.0
|
||||
|
||||
else:
|
||||
raise ValueError("robot_file must contain 'left' or 'right'")
|
||||
|
||||
# Gripper joint position for open/close
|
||||
# Adjust based on your gripper's joint values
|
||||
self._gripper_joint_position = np.array([0.044]) # Example: 44mm for open
|
||||
|
||||
def get_gripper_action(self):
|
||||
"""
|
||||
Map gripper state to joint positions.
|
||||
|
||||
Returns:
|
||||
np.ndarray: Joint positions for gripper.
|
||||
|
||||
State mapping:
|
||||
- _gripper_state = 1.0 -> Gripper OPEN
|
||||
- _gripper_state = -1.0 -> Gripper CLOSED
|
||||
"""
|
||||
# When _gripper_state is 1.0, gripper opens (joint value = positive)
|
||||
# When _gripper_state is -1.0, gripper closes (joint value = 0 or negative)
|
||||
return np.clip(self._gripper_state * self._gripper_joint_position, 0.0, 0.1)
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
10
|
||||
11
|
||||
12
|
||||
13
|
||||
14
|
||||
15
|
||||
16
|
||||
17
|
||||
18
|
||||
19
|
||||
20
|
||||
21
|
||||
22
|
||||
23
|
||||
24
|
||||
25
|
||||
26
|
||||
27
|
||||
28
|
||||
29
|
||||
30
|
||||
31
|
||||
32
|
||||
33
|
||||
34
|
||||
35
|
||||
36
|
||||
37
|
||||
38
|
||||
39
|
||||
40
|
||||
41
|
||||
42
|
||||
43
|
||||
44
|
||||
45
|
||||
46
|
||||
47
|
||||
48
|
||||
49
|
||||
50
|
||||
51
|
||||
52
|
||||
53
|
||||
54
|
||||
55
|
||||
56
|
||||
57
|
||||
58
|
||||
59
|
||||
60
|
||||
61
|
||||
62
|
||||
63
|
||||
64
|
||||
65
|
||||
66
|
||||
|
||||
_configure_joint_indices(self, robot_file: str )
|
||||
|
||||
Configure joint names and indices for motion planning. This method maps between CuRobo's joint names and the robot USD's joint names.
|
||||
|
||||
Parameters:
|
||||
|
||||
- **robot_file **( str ): Path to the CuRobo config file, used to determine left/right arm.
|
||||
|
||||
Key Variables:
|
||||
|
||||
- **raw_js_names **( list ): Joint names in CuRobo config (from `cspace.joint_names `in yaml).
|
||||
- **cmd_js_names **( list ): Joint names in robot USD (must match actual USD joint names).
|
||||
- **arm_indices **( np.ndarray ): Joint indices for arm in articulation.
|
||||
- **gripper_indices **( np.ndarray ): Joint indices for gripper in articulation.
|
||||
|
||||
Warning
|
||||
|
||||
The order of `raw_js_names `and `cmd_js_names `must correspond! The i-th element in `raw_js_names `maps to the i-th element in `cmd_js_names `.
|
||||
|
||||
get_gripper_action(self)
|
||||
|
||||
Convert `_gripper_state `to actual gripper joint positions.
|
||||
|
||||
Returns:
|
||||
|
||||
- **np.ndarray **: Joint positions for gripper.
|
||||
|
||||
State Mapping:
|
||||
|
||||
- **_gripper_state = 1.0 **: Gripper OPEN (joint value that fingers open)
|
||||
- **_gripper_state = -1.0 **: Gripper CLOSED (joint value that fingers close)
|
||||
|
||||
Code Example:
|
||||
python
|
||||
```
|
||||
# Parallel gripper (single joint)
|
||||
def get_gripper_action(self):
|
||||
return np.clip(self._gripper_state * self._gripper_joint_position, 0.0, 0.1)
|
||||
|
||||
# Two-finger gripper (two joints, e.g., Franka Panda)
|
||||
def get_gripper_action(self):
|
||||
finger1 = np.clip(self._gripper_state * 0.04, 0.0, 0.04)
|
||||
finger2 = np.clip(-self._gripper_state * 0.04, -0.04, 0.0)
|
||||
return np.array([finger1, finger2])
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
|
||||
### Register the Controller [](#register-the-controller)
|
||||
|
||||
Add your controller to `workflows/simbox/core/controllers/__init__.py `:
|
||||
python
|
||||
```
|
||||
from core.controllers.newrobot_controller import NewRobotController
|
||||
|
||||
__all__ = [
|
||||
# ... existing controllers
|
||||
"NewRobotController",
|
||||
]
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
|
||||
## Checklist [](#checklist)
|
||||
|
||||
- [ ] Prepare single-arm URDF files for each arm
|
||||
- [ ] Create CuRobo config YAML files using Isaac Sim 4.0.0 (Lula)
|
||||
- [ ] Update `robot_file `in robot YAML configuration
|
||||
- [ ] Create controller Python class
|
||||
- [ ] Implement `_get_default_ignore_substring() `
|
||||
- [ ] Implement `_configure_joint_indices() `with correct joint name mapping
|
||||
- [ ] Implement `get_gripper_action() `with correct open/close mapping
|
||||
- [ ] Register controller in `__init__.py `
|
||||
- [ ] Test with task configuration
|
||||
|
||||
## References [](#references)
|
||||
|
||||
- [CuRobo Robot Configuration Tutorial](https://curobo.org/tutorials/1_robot_configuration.html)
|
||||
- [Controllers API Reference](/InternDataEngine-Docs/api/controllers.html)
|
||||
- [Template Controller Source](https://github.com/your-org/DataEngine/blob/main/workflows/simbox/core/controllers/template_controller.py)
|
||||
561
docs_crawled/custom_robot.md
Normal file
561
docs_crawled/custom_robot.md
Normal file
@@ -0,0 +1,561 @@
|
||||
# Source: https://internrobotics.github.io/InternDataEngine-Docs/custom/robot.html
|
||||
|
||||
# New Robot [](#new-robot)
|
||||
|
||||
This guide explains how to add a new robot platform to InternDataEngine.
|
||||
|
||||
## Part 1: Obtain Robot USD [](#part-1-obtain-robot-usd)
|
||||
|
||||
We recommend converting **URDF to USD **for robot assets. Isaac Sim provides a URDF Importer that converts URDF files to USD format.
|
||||
|
||||
### Requirements for the USD File [](#requirements-for-the-usd-file)
|
||||
|
||||
-
|
||||
|
||||
**Physics Properties **: Ensure the USD has proper physics attributes - joint angles should move correctly when set, and dynamics parameters (damping, stiffness) should be configured appropriately.
|
||||
|
||||
-
|
||||
|
||||
**Collision Mesh **: Use **convex hull **collision meshes rather than convex decomposition. Convex decomposition creates many collision shapes, which significantly slows down motion planning and interaction physics.
|
||||
|
||||
-
|
||||
|
||||
**Joint Locking (Dual-arm Robots) **: For dual-arm robots, we recommend locking all joints except the two arm joints and gripper joints to simplify experiments and planning.
|
||||
|
||||
Hint
|
||||
|
||||
Isaac Sim's default URDF Importer typically produces stable USD files. However, URDF files themselves may have issues, and some damping/stiffness parameters might need adjustment after conversion.
|
||||
|
||||
Warning
|
||||
|
||||
Some grippers have underactuated joints (passive/follower joints) with a forward extension offset. These may exhibit undesirable physical interactions with objects. Test thoroughly before proceeding.
|
||||
|
||||
Good luck obtaining a physically stable robot USD!
|
||||
|
||||
## Part 2: Create Robot YAML Configuration [](#part-2-create-robot-yaml-configuration)
|
||||
|
||||
Create a robot configuration file in `workflows/simbox/core/configs/robots/ `. Here's a template `new_robot.yaml `:
|
||||
yaml
|
||||
```
|
||||
# =============================================================================
|
||||
# New Robot Configuration Template
|
||||
# =============================================================================
|
||||
# Description: [e.g., Dual-arm 6-DOF robot with lift joint]
|
||||
|
||||
# -----------------------------------------------------------------------------
|
||||
# Robot Info
|
||||
# -----------------------------------------------------------------------------
|
||||
target_class: NewRobot # Python class name for robot wrapper
|
||||
path: "YOUR_PATH_TO_ROBOT_USD_PATH (relative to asset root)" # USD file path relative to asset root
|
||||
|
||||
# -----------------------------------------------------------------------------
|
||||
# CuRobo Kinematics Config (one per arm for dual-arm robots)
|
||||
# -----------------------------------------------------------------------------
|
||||
robot_file:
|
||||
- "" # Left arm CuRobo config path
|
||||
- "" # Right arm CuRobo config path (dual-arm only)
|
||||
|
||||
# -----------------------------------------------------------------------------
|
||||
# Gripper Parameters
|
||||
# -----------------------------------------------------------------------------
|
||||
gripper_max_width: 0.0 # Maximum gripper opening (meters)
|
||||
gripper_min_width: 0.0 # Minimum gripper closing (meters)
|
||||
tcp_offset: 0.0 # Distance from EE origin to TCP (meters, MUST be positive)
|
||||
|
||||
# -----------------------------------------------------------------------------
|
||||
# Physics Solver Parameters
|
||||
# -----------------------------------------------------------------------------
|
||||
solver_position_iteration_count: 128 # Position solver iterations
|
||||
solver_velocity_iteration_count: 4 # Velocity solver iterations
|
||||
stabilization_threshold: 0.005 # Stabilization threshold
|
||||
|
||||
# -----------------------------------------------------------------------------
|
||||
# Joint Indices (find in Isaac Sim's articulation inspector)
|
||||
# -----------------------------------------------------------------------------
|
||||
left_joint_indices: [] # Left arm joint indices, e.g., [0, 1, 2, 3, 4, 5]
|
||||
right_joint_indices: [] # Right arm joint indices (dual-arm only)
|
||||
left_gripper_indices: [] # Left gripper joint index, e.g., [6]
|
||||
right_gripper_indices: [] # Right gripper joint index (dual-arm only)
|
||||
lift_indices: [] # Lift joint indices (if applicable)
|
||||
|
||||
# -----------------------------------------------------------------------------
|
||||
# End-Effector Paths (relative to robot prim path)
|
||||
# IMPORTANT: Transformation from EE to TCP must be FIXED!
|
||||
# -----------------------------------------------------------------------------
|
||||
fl_ee_path: "" # Front-left end-effector prim path
|
||||
fr_ee_path: "" # Front-right end-effector prim path (dual-arm only)
|
||||
fl_base_path: "" # Front-left base prim path
|
||||
fr_base_path: "" # Front-right base prim path (dual-arm only)
|
||||
|
||||
# -----------------------------------------------------------------------------
|
||||
# Gripper Keypoints (in EE frame, for visualization)
|
||||
# -----------------------------------------------------------------------------
|
||||
fl_gripper_keypoints:
|
||||
tool_head: [0.0, 0.0, 0.0, 1] # Gripper fingertip (approach direction)
|
||||
tool_tail: [0.0, 0.0, 0.0, 1] # Gripper base
|
||||
tool_side: [0.0, 0.0, 0.0, 1] # Side point for width visualization
|
||||
fr_gripper_keypoints:
|
||||
tool_head: [0.0, 0.0, 0.0, 1]
|
||||
tool_tail: [0.0, 0.0, 0.0, 1]
|
||||
tool_side: [0.0, 0.0, 0.0, 1]
|
||||
|
||||
# -----------------------------------------------------------------------------
|
||||
# Collision Filter Paths (relative to robot prim path)
|
||||
# -----------------------------------------------------------------------------
|
||||
fl_filter_paths: # Gripper fingers to filter from collision
|
||||
- ""
|
||||
fr_filter_paths:
|
||||
- ""
|
||||
fl_forbid_collision_paths: # Arm links forbidden for self-collision
|
||||
- ""
|
||||
fr_forbid_collision_paths:
|
||||
- ""
|
||||
|
||||
# -----------------------------------------------------------------------------
|
||||
# Pose Processing Parameters
|
||||
# -----------------------------------------------------------------------------
|
||||
# Rotation matrix from GraspNet gripper frame to robot EE frame
|
||||
# See: doc/InterDataEngine-docs/concepts/robots.md#r-ee-graspnet
|
||||
R_ee_graspnet: [[0.0, 0.0, 0.0], [0.0, 0.0, 0.0], [0.0, 0.0, 0.0]]
|
||||
ee_axis: "" # Approach axis from EE to TCP: "x", "y", or "z"
|
||||
|
||||
# -----------------------------------------------------------------------------
|
||||
# Default Joint Home Positions (radians)
|
||||
# -----------------------------------------------------------------------------
|
||||
left_joint_home: [] # Default left arm joint positions
|
||||
right_joint_home: [] # Default right arm joint positions (dual-arm only)
|
||||
left_joint_home_std: [] # Randomization std for left arm
|
||||
right_joint_home_std: [] # Randomization std for right arm (dual-arm only)
|
||||
left_gripper_home: [] # Default left gripper width (meters)
|
||||
right_gripper_home: [] # Default right gripper width (meters, dual-arm only)
|
||||
lift_home: [] # Default lift position (if applicable)
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
10
|
||||
11
|
||||
12
|
||||
13
|
||||
14
|
||||
15
|
||||
16
|
||||
17
|
||||
18
|
||||
19
|
||||
20
|
||||
21
|
||||
22
|
||||
23
|
||||
24
|
||||
25
|
||||
26
|
||||
27
|
||||
28
|
||||
29
|
||||
30
|
||||
31
|
||||
32
|
||||
33
|
||||
34
|
||||
35
|
||||
36
|
||||
37
|
||||
38
|
||||
39
|
||||
40
|
||||
41
|
||||
42
|
||||
43
|
||||
44
|
||||
45
|
||||
46
|
||||
47
|
||||
48
|
||||
49
|
||||
50
|
||||
51
|
||||
52
|
||||
53
|
||||
54
|
||||
55
|
||||
56
|
||||
57
|
||||
58
|
||||
59
|
||||
60
|
||||
61
|
||||
62
|
||||
63
|
||||
64
|
||||
65
|
||||
66
|
||||
67
|
||||
68
|
||||
69
|
||||
70
|
||||
71
|
||||
72
|
||||
73
|
||||
74
|
||||
75
|
||||
76
|
||||
77
|
||||
78
|
||||
79
|
||||
80
|
||||
81
|
||||
82
|
||||
83
|
||||
84
|
||||
85
|
||||
86
|
||||
87
|
||||
88
|
||||
89
|
||||
90
|
||||
91
|
||||
92
|
||||
|
||||
Refer to [Robots](/InternDataEngine-Docs/concepts/robots.html)for detailed explanations of each parameter. Here we highlight several critical parameters that require special attention:
|
||||
|
||||
### Critical Parameters [](#critical-parameters)
|
||||
|
||||
fl_ee_path / fr_ee_path
|
||||
|
||||
Specify the relative path (under the robot's local prim path) to the end-effector link.
|
||||
|
||||
Why It Matters:
|
||||
|
||||
- CuRobo plans target poses for this link
|
||||
- Grasp poses are transformed based on this link's EE pose
|
||||
- The `ee_axis `(approach direction from EE origin to TCP) depends on this link
|
||||
|
||||
Selection Rule:
|
||||
|
||||
Common choices:
|
||||
|
||||
- The last link of the gripper (e.g., Robotiq, Genie-1)
|
||||
- A link on the gripper (e.g., Lift-2, Panda)
|
||||
|
||||
Warning
|
||||
|
||||
The transformation from EE to TCP must be **FIXED **(fixed rotation + fixed translation = tcp_offset).
|
||||
|
||||
Figure Examples:
|
||||
|
||||

|
||||
|
||||
*Genie-1: EE link is the last gripper link (fixed EE-to-TCP transform) *
|
||||
|
||||

|
||||
|
||||
*Lift-2: EE link is a gripper link (fixed EE-to-TCP transform) *
|
||||
|
||||

|
||||
|
||||
*Robotiq: EE link is the last gripper link (fixed EE-to-TCP transform) *
|
||||
|
||||

|
||||
|
||||
*Panda: EE link is a gripper link (fixed EE-to-TCP transform) *
|
||||
|
||||
tcp_offset
|
||||
|
||||
Once `fl_ee_path `is determined, calculate the distance from EE origin to TCP. This should be a **positive value **.
|
||||
|
||||
Config Example:
|
||||
yaml
|
||||
```
|
||||
# Example: ARX Lift-2
|
||||
tcp_offset: 0.125 # Distance in meters from EE frame origin to TCP
|
||||
```
|
||||
1
|
||||
2
|
||||
|
||||
ee_axis
|
||||
|
||||
The axis direction from EE origin pointing toward TCP, expressed in the EE frame. Valid values are `"x" `, `"y" `, or `"z" `.
|
||||
|
||||
Config Example:
|
||||
yaml
|
||||
```
|
||||
# Example: ARX Lift-2
|
||||
ee_axis: "x" # Approach direction in EE frame
|
||||
```
|
||||
1
|
||||
2
|
||||
|
||||
R_ee_graspnet
|
||||
|
||||
The rotation matrix that transforms from the GraspNet API's canonical gripper frame to the robot's end-effector frame.
|
||||
|
||||
Warning
|
||||
|
||||
This parameter is important but can be tricky! For calculation details, refer to [Robots - R_ee_graspnet](/concepts/robots.html#r-ee-graspnet).
|
||||
|
||||
Config Example:
|
||||
yaml
|
||||
```
|
||||
# Example: ARX Lift-2
|
||||
R_ee_graspnet: [[1.0, 0.0, 0.0], [0.0, -1.0, 0.0], [0.0, 0.0, -1.0]]
|
||||
```
|
||||
1
|
||||
2
|
||||
|
||||
## Part 3: Create Robot Python Class [](#part-3-create-robot-python-class)
|
||||
|
||||
Create a Python file in `workflows/simbox/core/robots/ `. Here's a template based on `lift2.py `:
|
||||
python
|
||||
```
|
||||
"""New robot implementation."""
|
||||
import numpy as np
|
||||
from core.robots.base_robot import register_robot
|
||||
from core.robots.template_robot import TemplateRobot
|
||||
|
||||
@register_robot
|
||||
class NewRobot(TemplateRobot):
|
||||
"""New robot implementation."""
|
||||
|
||||
def _setup_joint_indices(self):
|
||||
"""Configure joint indices from config."""
|
||||
self.left_joint_indices = self.cfg["left_joint_indices"]
|
||||
self.right_joint_indices = self.cfg["right_joint_indices"]
|
||||
self.left_gripper_indices = self.cfg["left_gripper_indices"]
|
||||
self.right_gripper_indices = self.cfg["right_gripper_indices"]
|
||||
# Optional: lift, body, head indices for special robots
|
||||
self.lift_indices = self.cfg.get("lift_indices", [])
|
||||
|
||||
def _setup_paths(self):
|
||||
"""Configure USD prim paths from config."""
|
||||
fl_ee_path = self.cfg["fl_ee_path"]
|
||||
fr_ee_path = self.cfg["fr_ee_path"]
|
||||
self.fl_ee_path = f"{self.robot_prim_path}/{fl_ee_path}"
|
||||
self.fr_ee_path = f"{self.robot_prim_path}/{fr_ee_path}"
|
||||
self.fl_base_path = f"{self.robot_prim_path}/{self.cfg['fl_base_path']}"
|
||||
self.fr_base_path = f"{self.robot_prim_path}/{self.cfg['fr_base_path']}"
|
||||
self.fl_hand_path = self.fl_ee_path
|
||||
self.fr_hand_path = self.fr_ee_path
|
||||
|
||||
def _setup_gripper_keypoints(self):
|
||||
"""Configure gripper keypoints from config."""
|
||||
self.fl_gripper_keypoints = self.cfg["fl_gripper_keypoints"]
|
||||
self.fr_gripper_keypoints = self.cfg["fr_gripper_keypoints"]
|
||||
|
||||
def _setup_collision_paths(self):
|
||||
"""Configure collision filter paths from config."""
|
||||
self.fl_filter_paths_expr = [
|
||||
f"{self.robot_prim_path}/{p}" for p in self.cfg["fl_filter_paths"]
|
||||
]
|
||||
self.fr_filter_paths_expr = [
|
||||
f"{self.robot_prim_path}/{p}" for p in self.cfg["fr_filter_paths"]
|
||||
]
|
||||
self.fl_forbid_collision_paths = [
|
||||
f"{self.robot_prim_path}/{p}" for p in self.cfg["fl_forbid_collision_paths"]
|
||||
]
|
||||
self.fr_forbid_collision_paths = [
|
||||
f"{self.robot_prim_path}/{p}" for p in self.cfg["fr_forbid_collision_paths"]
|
||||
]
|
||||
|
||||
def _get_gripper_state(self, gripper_home):
|
||||
"""
|
||||
Determine gripper open/close state.
|
||||
|
||||
Returns:
|
||||
1.0 if gripper is open, -1.0 if closed.
|
||||
"""
|
||||
# Adjust threshold based on your gripper's joint values
|
||||
# return 1.0 if gripper_home and gripper_home[0] >= value else -1.0
|
||||
pass
|
||||
|
||||
def _setup_joint_velocities(self):
|
||||
"""Configure joint velocity limits (optional)."""
|
||||
# Override if needed for custom velocity limits
|
||||
pass
|
||||
|
||||
def apply_action(self, joint_positions, joint_indices, *args, **kwargs):
|
||||
"""Override for custom action application (optional)."""
|
||||
super().apply_action(joint_positions, joint_indices, *args, **kwargs)
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
10
|
||||
11
|
||||
12
|
||||
13
|
||||
14
|
||||
15
|
||||
16
|
||||
17
|
||||
18
|
||||
19
|
||||
20
|
||||
21
|
||||
22
|
||||
23
|
||||
24
|
||||
25
|
||||
26
|
||||
27
|
||||
28
|
||||
29
|
||||
30
|
||||
31
|
||||
32
|
||||
33
|
||||
34
|
||||
35
|
||||
36
|
||||
37
|
||||
38
|
||||
39
|
||||
40
|
||||
41
|
||||
42
|
||||
43
|
||||
44
|
||||
45
|
||||
46
|
||||
47
|
||||
48
|
||||
49
|
||||
50
|
||||
51
|
||||
52
|
||||
53
|
||||
54
|
||||
55
|
||||
56
|
||||
57
|
||||
58
|
||||
59
|
||||
60
|
||||
61
|
||||
62
|
||||
63
|
||||
64
|
||||
65
|
||||
66
|
||||
67
|
||||
68
|
||||
69
|
||||
|
||||
### Key Methods [](#key-methods)
|
||||
|
||||
_get_gripper_state(self, gripper_home)
|
||||
|
||||
Determine whether the gripper is open or closed based on the current joint positions.
|
||||
|
||||
Parameters:
|
||||
|
||||
- **gripper_home **( list ): Current gripper joint positions.
|
||||
|
||||
Returns:
|
||||
|
||||
- **float **: `1.0 `if gripper is open, `-1.0 `if closed.
|
||||
|
||||
Hint
|
||||
|
||||
Adjust the threshold value based on your gripper's specific joint values. Different grippers have different open/close positions.
|
||||
|
||||
Code Example:
|
||||
python
|
||||
```
|
||||
# Example 1: ARX Lift-2 (single-joint parallel gripper)
|
||||
# Gripper is open when joint value >= 0.044 (44mm)
|
||||
def _get_gripper_state(self, gripper_home):
|
||||
return 1.0 if gripper_home and gripper_home[0] >= 0.044 else -1.0
|
||||
|
||||
# Example 2: Franka with Robotiq 2F-85 (two-joint gripper)
|
||||
# Gripper is open when both joints are 0.0
|
||||
def _get_gripper_state(self, gripper_home):
|
||||
if not gripper_home or len(gripper_home) < 2:
|
||||
return 1.0
|
||||
return 1.0 if (gripper_home[0] == 0.0 and gripper_home[1] == 0.0) else -1.0
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
10
|
||||
11
|
||||
|
||||
### Register the Robot [](#register-the-robot)
|
||||
|
||||
Add your robot to `workflows/simbox/core/robots/__init__.py `:
|
||||
python
|
||||
```
|
||||
from core.robots.new_robot import NewRobot
|
||||
|
||||
__all__ = [
|
||||
# ... existing robots
|
||||
"NewRobot",
|
||||
]
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
|
||||
## Part 4: Create Task Robot Configuration [](#part-4-create-task-robot-configuration)
|
||||
|
||||
Add the robot configuration to your task YAML file:
|
||||
yaml
|
||||
```
|
||||
robots:
|
||||
- name: "new_robot"
|
||||
robot_config_file: workflows/simbox/core/configs/robots/new_robot.yaml
|
||||
euler: [0.0, 0.0, 0.0] # Initial orientation [roll, pitch, yaw] in degrees
|
||||
ignore_substring: ["material", "table"] # Collision filter substrings
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
|
||||
See [YAML Configuration](/InternDataEngine-Docs/config/yaml.html)for more details on task configuration.
|
||||
|
||||
## Checklist [](#checklist)
|
||||
|
||||
- [ ] Obtain or create robot USD file (URDF → USD via Isaac Sim)
|
||||
- [ ] Verify physics properties (joint movement, damping, stiffness)
|
||||
- [ ] Set up collision meshes (use convex hull, not convex decomposition)
|
||||
- [ ] Lock unnecessary joints for dual-arm robots
|
||||
- [ ] Create robot YAML config file in `workflows/simbox/core/configs/robots/ `
|
||||
- [ ] Configure `fl_ee_path `/ `fr_ee_path `(EE link with fixed EE-to-TCP transform)
|
||||
- [ ] Calculate and set `tcp_offset `(distance from EE origin to TCP)
|
||||
- [ ] Determine `ee_axis `(approach direction: "x", "y", or "z")
|
||||
- [ ] Calculate `R_ee_graspnet `(rotation from GraspNet frame to EE frame)
|
||||
- [ ] Configure joint indices ( `left_joint_indices `, `right_joint_indices `, etc.)
|
||||
- [ ] Set up gripper keypoints for visualization
|
||||
- [ ] Configure collision filter paths
|
||||
- [ ] Create robot Python class in `workflows/simbox/core/robots/ `
|
||||
- [ ] Implement `_setup_joint_indices() `
|
||||
- [ ] Implement `_setup_paths() `
|
||||
- [ ] Implement `_setup_gripper_keypoints() `
|
||||
- [ ] Implement `_setup_collision_paths() `
|
||||
- [ ] Implement `_get_gripper_state() `(1.0 = open, -1.0 = closed)
|
||||
- [ ] Register robot in `__init__.py `
|
||||
- [ ] Add robot to task YAML configuration
|
||||
- [ ] Test robot in simulation
|
||||
509
docs_crawled/custom_skill.md
Normal file
509
docs_crawled/custom_skill.md
Normal file
@@ -0,0 +1,509 @@
|
||||
# Source: https://internrobotics.github.io/InternDataEngine-Docs/custom/skill.html
|
||||
|
||||
# New Skill [](#new-skill)
|
||||
|
||||
This guide explains how to create a new manipulation skill for robot task execution.
|
||||
|
||||
## Overview [](#overview)
|
||||
|
||||
Skills define atomic manipulation actions (e.g., pick, place, articulation). Each skill generates a sequence of manipulation commands ( `manip_list `) that the controller executes sequentially.
|
||||
|
||||
## Skill Template [](#skill-template)
|
||||
|
||||
Create a new file in `workflows/simbox/core/skills/ `:
|
||||
python
|
||||
```
|
||||
"""NewSkill implementation."""
|
||||
|
||||
from copy import deepcopy
|
||||
import numpy as np
|
||||
from core.skills.base_skill import BaseSkill, register_skill
|
||||
from omegaconf import DictConfig
|
||||
from omni.isaac.core.controllers import BaseController
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
|
||||
@register_skill
|
||||
class NewSkill(BaseSkill):
|
||||
"""New manipulation skill."""
|
||||
|
||||
def __init__(
|
||||
self,
|
||||
robot: Robot,
|
||||
controller: BaseController,
|
||||
task: BaseTask,
|
||||
cfg: DictConfig,
|
||||
*args,
|
||||
**kwargs
|
||||
):
|
||||
"""Initialize the skill.
|
||||
|
||||
Args:
|
||||
robot: Robot instance for getting state and applying actions
|
||||
controller: Controller instance for motion planning
|
||||
task: Task instance containing scene information
|
||||
cfg: Skill configuration from task YAML
|
||||
"""
|
||||
super().__init__()
|
||||
self.robot = robot
|
||||
self.controller = controller
|
||||
self.task = task
|
||||
self.skill_cfg = cfg
|
||||
|
||||
# Get target object from config
|
||||
object_name = self.skill_cfg["objects"][0]
|
||||
self.target_obj = task.objects[object_name]
|
||||
|
||||
# Initialize manip_list (will be filled in simple_generate_manip_cmds)
|
||||
self.manip_list = []
|
||||
|
||||
# Initialize other skill-specific variables
|
||||
self.process_valid = True
|
||||
|
||||
def simple_generate_manip_cmds(self):
|
||||
"""
|
||||
Generate the manipulation command list.
|
||||
|
||||
This is the MOST IMPORTANT method! It generates a list of manipulation
|
||||
commands (manip_list) that define the sequence of waypoint poses and
|
||||
intermediate states for the skill execution.
|
||||
"""
|
||||
manip_list = []
|
||||
|
||||
# ... generate commands ...
|
||||
|
||||
self.manip_list = manip_list
|
||||
|
||||
def is_feasible(self, th=5):
|
||||
"""Check if the skill is still feasible to execute."""
|
||||
return self.controller.num_plan_failed <= th
|
||||
|
||||
def is_subtask_done(self, t_eps=1e-3, o_eps=5e-3):
|
||||
"""Check if the current waypoint is reached."""
|
||||
pass
|
||||
|
||||
def is_done(self):
|
||||
"""Check if the entire skill is completed."""
|
||||
pass
|
||||
|
||||
def is_success(self):
|
||||
"""Check if the skill executed successfully."""
|
||||
pass
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
10
|
||||
11
|
||||
12
|
||||
13
|
||||
14
|
||||
15
|
||||
16
|
||||
17
|
||||
18
|
||||
19
|
||||
20
|
||||
21
|
||||
22
|
||||
23
|
||||
24
|
||||
25
|
||||
26
|
||||
27
|
||||
28
|
||||
29
|
||||
30
|
||||
31
|
||||
32
|
||||
33
|
||||
34
|
||||
35
|
||||
36
|
||||
37
|
||||
38
|
||||
39
|
||||
40
|
||||
41
|
||||
42
|
||||
43
|
||||
44
|
||||
45
|
||||
46
|
||||
47
|
||||
48
|
||||
49
|
||||
50
|
||||
51
|
||||
52
|
||||
53
|
||||
54
|
||||
55
|
||||
56
|
||||
57
|
||||
58
|
||||
59
|
||||
60
|
||||
61
|
||||
62
|
||||
63
|
||||
64
|
||||
65
|
||||
66
|
||||
67
|
||||
68
|
||||
69
|
||||
70
|
||||
71
|
||||
72
|
||||
73
|
||||
74
|
||||
75
|
||||
76
|
||||
77
|
||||
|
||||
__init__(self, robot, controller, task, cfg, *args, **kwargs)
|
||||
|
||||
Initialize the skill and store all required references and configuration.
|
||||
|
||||
Parameters:
|
||||
|
||||
- **robot **( Robot ): Robot instance used to query state and apply actions.
|
||||
- **controller **( BaseController ): Controller instance that handles motion planning and execution.
|
||||
- **task **( BaseTask ): Task instance that owns scene objects and environment information.
|
||||
- **cfg **( DictConfig ): Skill configuration loaded from the task YAML file.
|
||||
|
||||
simple_generate_manip_cmds(self)
|
||||
|
||||
This is the MOST IMPORTANT method of the skill. It constructs the full sequence of manipulation commands that defines how the robot executes this skill.
|
||||
|
||||
**Command tuple format: **
|
||||
python
|
||||
```
|
||||
(p_base_ee_tgt, q_base_ee_tgt, function_name, params)
|
||||
```
|
||||
1
|
||||
|
||||
**Components: **
|
||||
|
||||
- **p_base_ee_tgt **( np.ndarray , shape `(3,) `): Target end-effector position in the arm base frame.
|
||||
- **q_base_ee_tgt **( np.ndarray , shape `(4,) `): Target end-effector quaternion `(w, x, y, z) `in the arm base frame.
|
||||
- **function_name **( str ): Name of the action function to execute.
|
||||
- **params **( dict ): Keyword arguments passed to the action function.
|
||||
|
||||
**Execution flow: **
|
||||
|
||||
- Controller pops commands from `manip_list `one by one.
|
||||
- For each command, the target pose is passed to CuRobo for motion planning.
|
||||
- The specified action function is applied using `params `during or after the motion.
|
||||
- When the waypoint is reached (see `is_subtask_done `), the next command is processed.
|
||||
|
||||
**Common function names: **
|
||||
|
||||
- **update_pose_cost_metric **– update planning cost and constraint weights:
|
||||
python
|
||||
```
|
||||
cmd = (
|
||||
p_base_ee_cur,
|
||||
q_base_ee_cur,
|
||||
"update_pose_cost_metric",
|
||||
{"hold_vec_weight": [1, 1, 1, 0, 0, 0]}, # Hold orientation, free translation
|
||||
)
|
||||
manip_list.append(cmd)
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
|
||||
`hold_vec_weight `format: `[angular-x, angular-y, angular-z, linear-x, linear-y, linear-z] `.
|
||||
|
||||
- **update_specific **– update collision-avoidance settings:
|
||||
python
|
||||
```
|
||||
cmd = (
|
||||
p_base_ee_cur,
|
||||
q_base_ee_cur,
|
||||
"update_specific",
|
||||
{
|
||||
"ignore_substring": ignore_substring,
|
||||
"reference_prim_path": self.controller.reference_prim_path,
|
||||
},
|
||||
)
|
||||
manip_list.append(cmd)
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
10
|
||||
|
||||
- **open_gripper **/ **close_gripper **– control gripper state:
|
||||
python
|
||||
```
|
||||
cmd = (p_base_ee_pregrasp, q_base_ee_pregrasp, "open_gripper", {})
|
||||
manip_list.append(cmd)
|
||||
|
||||
cmd = (p_base_ee_grasp, q_base_ee_grasp, "close_gripper", {})
|
||||
manip_list.extend([cmd] * 40) # Repeat for duration
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
|
||||
- **attach_obj **/ **detach_obj **– attach or detach objects in the physics scene:
|
||||
python
|
||||
```
|
||||
cmd = (
|
||||
p_base_ee_grasp,
|
||||
q_base_ee_grasp,
|
||||
"attach_obj",
|
||||
{"obj_prim_path": self.target_obj.mesh_prim_path},
|
||||
)
|
||||
manip_list.append(cmd)
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
|
||||
- **dummy_forward **– apply actions directly without calling the planner:
|
||||
python
|
||||
```
|
||||
cmd = (
|
||||
p_base_ee_cur,
|
||||
q_base_ee_cur,
|
||||
"dummy_forward",
|
||||
{"arm_action": arm_action, "gripper_state": gripper_state},
|
||||
)
|
||||
manip_list.append(cmd)
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
|
||||
is_feasible(self, th=5)
|
||||
|
||||
Check whether the skill should continue execution based on recent motion-planning failures.
|
||||
|
||||
Parameters:
|
||||
|
||||
- **th **( int , optional): Maximum number of allowed planning failures before the skill is considered infeasible. Default is `5 `.
|
||||
|
||||
Returns:
|
||||
|
||||
- **bool **: `True `if the skill is still feasible; `False `if too many failures occurred and the episode should terminate.
|
||||
|
||||
Code Example:
|
||||
python
|
||||
```
|
||||
def is_feasible(self, th=5):
|
||||
return self.controller.num_plan_failed <= th
|
||||
```
|
||||
1
|
||||
2
|
||||
|
||||
Warning
|
||||
|
||||
Typical reasons to return False: too many planning failures, unrecoverable robot state, or clearly unreachable target.
|
||||
|
||||
is_subtask_done(self, t_eps=1e-3, o_eps=5e-3)
|
||||
|
||||
Check whether the robot has reached the current waypoint defined by the first command in `manip_list `.
|
||||
|
||||
Parameters:
|
||||
|
||||
- **t_eps **( float , optional): Translation tolerance in meters (default: `1e-3 `, about 1 mm).
|
||||
- **o_eps **( float , optional): Orientation tolerance in radians (default: `5e-3 `, about 0.3°).
|
||||
|
||||
Returns:
|
||||
|
||||
- **bool **: `True `if the current waypoint is considered reached; `False `otherwise.
|
||||
|
||||
Code Example:
|
||||
python
|
||||
```
|
||||
def is_subtask_done(self, t_eps=1e-3, o_eps=5e-3):
|
||||
assert len(self.manip_list) != 0
|
||||
|
||||
p_base_ee_cur, q_base_ee_cur = self.controller.get_ee_pose()
|
||||
p_base_ee, q_base_ee, *_ = self.manip_list[0]
|
||||
|
||||
diff_trans = np.linalg.norm(p_base_ee_cur - p_base_ee)
|
||||
diff_ori = 2 * np.arccos(min(abs(np.dot(q_base_ee_cur, q_base_ee)), 1.0))
|
||||
|
||||
pose_flag = np.logical_and(diff_trans < t_eps, diff_ori < o_eps)
|
||||
self.plan_flag = self.controller.num_last_cmd > 10
|
||||
|
||||
return np.logical_or(pose_flag, self.plan_flag)
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
10
|
||||
11
|
||||
12
|
||||
13
|
||||
|
||||
is_done(self)
|
||||
|
||||
Determine whether the entire skill has finished executing all planned commands.
|
||||
|
||||
Returns:
|
||||
|
||||
- **bool **: `True `if all commands have been executed and `manip_list `is empty; `False `otherwise.
|
||||
|
||||
Code Example:
|
||||
python
|
||||
```
|
||||
def is_done(self):
|
||||
if len(self.manip_list) == 0:
|
||||
return True
|
||||
|
||||
t_eps = self.skill_cfg.get("t_eps", 1e-3)
|
||||
o_eps = self.skill_cfg.get("o_eps", 5e-3)
|
||||
|
||||
if self.is_subtask_done(t_eps=t_eps, o_eps=o_eps):
|
||||
self.manip_list.pop(0)
|
||||
|
||||
return len(self.manip_list) == 0
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
10
|
||||
11
|
||||
|
||||
**Logic **: if the list is empty, the skill is done; otherwise, when the current waypoint is done, pop it and check again.
|
||||
|
||||
is_success(self)
|
||||
|
||||
Evaluate task-specific success conditions at the end of the skill. This method defines what "success" means for the given manipulation skill.
|
||||
|
||||
Returns:
|
||||
|
||||
- **bool **: `True `if all success conditions are satisfied; `False `otherwise.
|
||||
|
||||
Code Example:
|
||||
python
|
||||
```
|
||||
def is_success(self):
|
||||
flag = True
|
||||
|
||||
# Check object contact
|
||||
_, indices = self.get_contact()
|
||||
if self.gripper_cmd == "close_gripper":
|
||||
flag = len(indices) >= 1
|
||||
|
||||
# Check motion validity
|
||||
self.process_valid = (
|
||||
np.max(np.abs(self.robot.get_joints_state().velocities)) < 5
|
||||
and np.max(np.abs(self.target_obj.get_linear_velocity())) < 5
|
||||
)
|
||||
flag = flag and self.process_valid
|
||||
|
||||
return flag
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
10
|
||||
11
|
||||
12
|
||||
13
|
||||
14
|
||||
15
|
||||
16
|
||||
|
||||
Warning
|
||||
|
||||
For pick skills, the object is in stable contact and lifted; for place skills, the object is near the target pose and released; for articulation skills, the articulated joints reach the desired configuration.
|
||||
|
||||
## Registration [](#registration)
|
||||
|
||||
Add to `workflows/simbox/core/skills/__init__.py `:
|
||||
python
|
||||
```
|
||||
from core.skills.new_skill import NewSkill
|
||||
|
||||
__all__ = [
|
||||
# ... existing skills
|
||||
"NewSkill",
|
||||
]
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
|
||||
## Usage [](#usage)
|
||||
yaml
|
||||
```
|
||||
skills:
|
||||
- lift2:
|
||||
- left:
|
||||
- name: new_skill
|
||||
objects: [target_object]
|
||||
custom_param: 0.1
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
|
||||
## Checklist [](#checklist)
|
||||
|
||||
- [ ] Create skill file in `workflows/simbox/core/skills/ `
|
||||
- [ ] Implement `__init__ `
|
||||
- [ ] Implement `simple_generate_manip_cmds() `
|
||||
- [ ] Implement `is_feasible() `
|
||||
- [ ] Implement `is_subtask_done() `
|
||||
- [ ] Implement `is_done() `
|
||||
- [ ] Implement `is_success() `
|
||||
- [ ] Register in `__init__.py `
|
||||
- [ ] Test with task config
|
||||
673
docs_crawled/custom_task.md
Normal file
673
docs_crawled/custom_task.md
Normal file
@@ -0,0 +1,673 @@
|
||||
# Source: https://internrobotics.github.io/InternDataEngine-Docs/custom/task.html
|
||||
|
||||
# Creating a Custom Task [](#creating-a-custom-task)
|
||||
|
||||
This guide explains how to create a new task by combining your custom assets, robots, controllers, and skills into a complete task configuration.
|
||||
|
||||
## Overview [](#overview)
|
||||
|
||||
After creating custom components (assets, robots, controllers, skills), you can combine them into a task YAML configuration. The workflow will load this configuration to set up the simulation environment.
|
||||
|
||||
## Prerequisites [](#prerequisites)
|
||||
|
||||
Before creating a custom task, ensure you have:
|
||||
|
||||
- **Custom Assets **- See [Assets Guide](/InternDataEngine-Docs/custom/assets.html)
|
||||
- **Custom Robot **- See [Robot Guide](/InternDataEngine-Docs/custom/robot.html)
|
||||
- **Custom Controller **- See [Controller Guide](/InternDataEngine-Docs/custom/controller.html)
|
||||
- **Custom Skill **- See [Skill Guide](/InternDataEngine-Docs/custom/skill.html)
|
||||
|
||||
## Prepare Asset Directory [](#prepare-asset-directory)
|
||||
|
||||
Organize your task assets following the structure:
|
||||
|
||||
```
|
||||
new_task/
|
||||
└── new_objs/ # Rigid objects directory
|
||||
├── new_obj0/ # Object instance 0
|
||||
│ ├── Aligned_obj.obj # Preprocessed mesh
|
||||
│ ├── Aligned.mtl # Material file
|
||||
│ ├── Aligned_obj.usd # USD with physics properties
|
||||
│ ├── Aligned_grasp_sparse.npy # Grasp poses (optional)
|
||||
│ └── textures/ # Texture files
|
||||
├── new_obj1/ # Object instance 1
|
||||
└── new_obj2/ # Object instance 2
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
10
|
||||
|
||||
Place this directory under your asset root (e.g., `workflows/simbox/assets/ `or `workflows/simbox/example_assets/ `).
|
||||
|
||||
Note
|
||||
|
||||
For rigid manipulation objects, objects of the **same category **should be placed in the **same parent folder **(e.g., `new_obj0 `, `new_obj1 `, `new_obj2 `all under `new_objs/ `). This organization enables **category-level domain randomization **. Inside each object subfolder, use consistent naming conventions: `Aligned_obj.obj `, `Aligned_obj.usd `, `Aligned_grasp_sparse.npy `, etc.
|
||||
|
||||
## Create Task YAML Configuration [](#create-task-yaml-configuration)
|
||||
|
||||
Create a new YAML file in `workflows/simbox/core/configs/tasks/ `:
|
||||
yaml
|
||||
```
|
||||
# =============================================================================
|
||||
# New Task Configuration
|
||||
# =============================================================================
|
||||
tasks:
|
||||
- name: new_task
|
||||
asset_root: workflows/simbox/assets
|
||||
task: BananaBaseTask
|
||||
task_id: 0
|
||||
offset: null
|
||||
render: True
|
||||
|
||||
# =========================================================================
|
||||
# Arena Configuration
|
||||
# =========================================================================
|
||||
arena_file: workflows/simbox/core/configs/arenas/example.yaml
|
||||
|
||||
# =========================================================================
|
||||
# Environment Map (Lighting)
|
||||
# =========================================================================
|
||||
env_map:
|
||||
envmap_lib: envmap_lib
|
||||
apply_randomization: False
|
||||
intensity_range: [4000, 7000]
|
||||
rotation_range: [0, 180]
|
||||
|
||||
# =========================================================================
|
||||
# Robots
|
||||
# =========================================================================
|
||||
robots:
|
||||
- name: "new_robot"
|
||||
robot_config_file: workflows/simbox/core/configs/robots/new_robot.yaml
|
||||
euler: [0.0, 0.0, 0.0]
|
||||
ignore_substring: ["material", "table", "floor"]
|
||||
|
||||
# =========================================================================
|
||||
# Objects
|
||||
# =========================================================================
|
||||
objects:
|
||||
- name: obj0
|
||||
path: new_task/new_objs/new_obj0/Aligned_obj.usd
|
||||
target_class: RigidObject
|
||||
dataset: custom
|
||||
category: new_object
|
||||
prim_path_child: Aligned
|
||||
translation: [0.3, 0.0, 0.0]
|
||||
euler: [0.0, 0.0, 0.0]
|
||||
scale: [1, 1, 1]
|
||||
apply_randomization: False
|
||||
|
||||
- name: obj1
|
||||
path: new_task/new_objs/new_obj1/Aligned_obj.usd
|
||||
target_class: RigidObject
|
||||
dataset: custom
|
||||
category: new_object
|
||||
prim_path_child: Aligned
|
||||
translation: [0.0, 0.2, 0.0]
|
||||
euler: [0.0, 0.0, 0.0]
|
||||
scale: [1, 1, 1]
|
||||
apply_randomization: False
|
||||
|
||||
- name: obj2
|
||||
path: new_task/new_objs/new_obj2/Aligned_obj.usd
|
||||
target_class: RigidObject
|
||||
dataset: custom
|
||||
category: new_object
|
||||
prim_path_child: Aligned
|
||||
translation: [0.0, -0.2, 0.0]
|
||||
euler: [0.0, 0.0, 0.0]
|
||||
scale: [1, 1, 1]
|
||||
apply_randomization: False
|
||||
|
||||
# =========================================================================
|
||||
# Regions (Object Placement)
|
||||
# =========================================================================
|
||||
regions:
|
||||
- object: obj0
|
||||
target: table
|
||||
random_type: A_on_B_region_sampler
|
||||
random_config:
|
||||
pos_range: [[0.2, -0.15, 0.0], [0.4, 0.15, 0.0]]
|
||||
yaw_rotation: [-30.0, 30.0]
|
||||
|
||||
- object: obj1
|
||||
target: table
|
||||
random_type: A_on_B_region_sampler
|
||||
random_config:
|
||||
pos_range: [[-0.4, -0.15, 0.0], [-0.2, 0.15, 0.0]]
|
||||
yaw_rotation: [-180.0, 180.0]
|
||||
|
||||
- object: obj2
|
||||
target: table
|
||||
random_type: A_on_B_region_sampler
|
||||
random_config:
|
||||
pos_range: [[-0.4, -0.15, 0.0], [-0.2, 0.15, 0.0]]
|
||||
yaw_rotation: [-180.0, 180.0]
|
||||
|
||||
# =========================================================================
|
||||
# Cameras
|
||||
# =========================================================================
|
||||
cameras:
|
||||
- name: head_camera
|
||||
translation: [0.5, 0.0, 0.8]
|
||||
orientation: [0.924, 0.383, 0.0, 0.0]
|
||||
camera_axes: usd
|
||||
camera_file: workflows/simbox/core/configs/cameras/realsense_d455.yaml
|
||||
parent: ""
|
||||
apply_randomization: False
|
||||
|
||||
- name: wrist_camera_left
|
||||
translation: [0.0, 0.05, 0.03]
|
||||
orientation: [0.0, 0.0, 0.0, 1.0]
|
||||
camera_axes: usd
|
||||
camera_file: workflows/simbox/core/configs/cameras/realsense_d435.yaml
|
||||
parent: "new_robot/path/to/fl_ee_link"
|
||||
apply_randomization: False
|
||||
|
||||
- name: wrist_camera_right
|
||||
translation: [0.0, -0.05, 0.03]
|
||||
orientation: [0.0, 0.0, 0.0, 1.0]
|
||||
camera_axes: usd
|
||||
camera_file: workflows/simbox/core/configs/cameras/realsense_d435.yaml
|
||||
parent: "new_robot/path/to/fr_ee_link"
|
||||
apply_randomization: False
|
||||
|
||||
# =========================================================================
|
||||
# Data Settings
|
||||
# =========================================================================
|
||||
data:
|
||||
task_dir: "new_task_demo"
|
||||
language_instruction: "New task."
|
||||
detailed_language_instruction: "New task."
|
||||
collect_info: "Custom task with new robot and skill"
|
||||
version: "v1.0"
|
||||
update: True
|
||||
max_episode_length: 500
|
||||
|
||||
# =========================================================================
|
||||
# Skills
|
||||
# =========================================================================
|
||||
# Dual-arm mode: left arm operates obj0, right arm operates obj1 and obj2
|
||||
skills:
|
||||
- new_robot:
|
||||
- left:
|
||||
- name: skill0
|
||||
objects: [obj0]
|
||||
- right:
|
||||
- name: skill1
|
||||
objects: [obj1, obj2]
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
10
|
||||
11
|
||||
12
|
||||
13
|
||||
14
|
||||
15
|
||||
16
|
||||
17
|
||||
18
|
||||
19
|
||||
20
|
||||
21
|
||||
22
|
||||
23
|
||||
24
|
||||
25
|
||||
26
|
||||
27
|
||||
28
|
||||
29
|
||||
30
|
||||
31
|
||||
32
|
||||
33
|
||||
34
|
||||
35
|
||||
36
|
||||
37
|
||||
38
|
||||
39
|
||||
40
|
||||
41
|
||||
42
|
||||
43
|
||||
44
|
||||
45
|
||||
46
|
||||
47
|
||||
48
|
||||
49
|
||||
50
|
||||
51
|
||||
52
|
||||
53
|
||||
54
|
||||
55
|
||||
56
|
||||
57
|
||||
58
|
||||
59
|
||||
60
|
||||
61
|
||||
62
|
||||
63
|
||||
64
|
||||
65
|
||||
66
|
||||
67
|
||||
68
|
||||
69
|
||||
70
|
||||
71
|
||||
72
|
||||
73
|
||||
74
|
||||
75
|
||||
76
|
||||
77
|
||||
78
|
||||
79
|
||||
80
|
||||
81
|
||||
82
|
||||
83
|
||||
84
|
||||
85
|
||||
86
|
||||
87
|
||||
88
|
||||
89
|
||||
90
|
||||
91
|
||||
92
|
||||
93
|
||||
94
|
||||
95
|
||||
96
|
||||
97
|
||||
98
|
||||
99
|
||||
100
|
||||
101
|
||||
102
|
||||
103
|
||||
104
|
||||
105
|
||||
106
|
||||
107
|
||||
108
|
||||
109
|
||||
110
|
||||
111
|
||||
112
|
||||
113
|
||||
114
|
||||
115
|
||||
116
|
||||
117
|
||||
118
|
||||
119
|
||||
120
|
||||
121
|
||||
122
|
||||
123
|
||||
124
|
||||
125
|
||||
126
|
||||
127
|
||||
128
|
||||
129
|
||||
130
|
||||
131
|
||||
132
|
||||
133
|
||||
134
|
||||
135
|
||||
136
|
||||
137
|
||||
138
|
||||
139
|
||||
140
|
||||
141
|
||||
142
|
||||
143
|
||||
144
|
||||
145
|
||||
146
|
||||
147
|
||||
148
|
||||
|
||||
## Task Modes [](#task-modes)
|
||||
|
||||
The task configuration supports multiple execution modes. Here are common patterns:
|
||||
|
||||
### Single-Arm Task [](#single-arm-task)
|
||||
|
||||
For single-arm robots, configure only one arm in the skills section. Skills execute sequentially — each skill starts only after the previous one completes. The task finishes when all skills are done.
|
||||
|
||||
**Left Arm Example: **
|
||||
yaml
|
||||
```
|
||||
skills:
|
||||
- new_robot:
|
||||
- left:
|
||||
- name: skill0
|
||||
objects: [obj0]
|
||||
- name: skill1
|
||||
objects: [obj1]
|
||||
- name: skill2
|
||||
objects: [obj2]
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
|
||||
**Right Arm Example: **
|
||||
yaml
|
||||
```
|
||||
skills:
|
||||
- new_robot:
|
||||
- right:
|
||||
- name: skill0
|
||||
objects: [obj0]
|
||||
- name: skill1
|
||||
objects: [obj1]
|
||||
- name: skill2
|
||||
objects: [obj2]
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
|
||||
### Dual-Arm Sequential Task [](#dual-arm-sequential-task)
|
||||
|
||||
For dual-arm robots operating sequentially. In this pattern, one arm completes all its skills before the other arm begins. The example below shows the left arm executing first, followed by the right arm.
|
||||
yaml
|
||||
```
|
||||
# Left arm skills execute first, then right arm skills
|
||||
skills:
|
||||
- new_robot:
|
||||
- left:
|
||||
- name: skill0
|
||||
objects: [obj0]
|
||||
- name: skill1
|
||||
objects: [obj1]
|
||||
- name: skill2
|
||||
objects: [obj2]
|
||||
- right:
|
||||
- name: skill3
|
||||
objects: [obj3]
|
||||
- name: skill4
|
||||
objects: [obj4]
|
||||
- name: skill5
|
||||
objects: [obj5]
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
10
|
||||
11
|
||||
12
|
||||
13
|
||||
14
|
||||
15
|
||||
16
|
||||
17
|
||||
|
||||
### Dual-Arm Simultaneous Task [](#dual-arm-simultaneous-task)
|
||||
|
||||
For dual-arm robots operating simultaneously. Both arms start at the same time and execute their skills independently. Within each arm, skills still execute sequentially. The task finishes when all skills from both arms are complete.
|
||||
yaml
|
||||
```
|
||||
# Left and right arm skills start simultaneously
|
||||
skills:
|
||||
- new_robot:
|
||||
- left:
|
||||
- name: skill0
|
||||
objects: [obj0]
|
||||
- name: skill1
|
||||
objects: [obj1]
|
||||
- name: skill2
|
||||
objects: [obj2]
|
||||
right:
|
||||
- name: skill3
|
||||
objects: [obj3]
|
||||
- name: skill4
|
||||
objects: [obj4]
|
||||
- name: skill5
|
||||
objects: [obj5]
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
10
|
||||
11
|
||||
12
|
||||
13
|
||||
14
|
||||
15
|
||||
16
|
||||
17
|
||||
|
||||
### Complex Task Example [](#complex-task-example)
|
||||
|
||||
You can freely combine single-arm, dual-arm sequential, and dual-arm simultaneous tasks in any order. This example demonstrates a tableware arrangement task:
|
||||
|
||||
- **Phase 1 (Sequential) **: Right arm picks a plate, places it on the table, then returns home
|
||||
- **Phase 2 (Simultaneous) **: Left arm picks and places the fork while right arm picks and places the spoon
|
||||
yaml
|
||||
```
|
||||
# Source: workflows/simbox/core/configs/tasks/basic/lift2/arrange_the_tableware/
|
||||
skills:
|
||||
- lift2:
|
||||
- right:
|
||||
- name: pick
|
||||
objects: [plate]
|
||||
filter_z_dir: ["forward", 80]
|
||||
filter_x_dir: ["downward", 130]
|
||||
pre_grasp_offset: 0.05
|
||||
gripper_change_steps: 10
|
||||
ignore_substring: ["plate_shelf"]
|
||||
post_grasp_offset_min: 0.075
|
||||
post_grasp_offset_max: 0.125
|
||||
- name: place
|
||||
objects: [plate, table]
|
||||
place_direction: vertical
|
||||
filter_z_dir: ["forward", 10]
|
||||
filter_y_dir: ["upward", 60, 30]
|
||||
filter_x_dir: ["downward", 120, 150]
|
||||
position_constraint: object
|
||||
x_ratio_range: [0.5, 0.5]
|
||||
y_ratio_range: [0.12, 0.20]
|
||||
pre_place_z_offset: 0.15
|
||||
place_z_offset: 0.1
|
||||
post_place_vector: [-0.05, 0.0, 0.0]
|
||||
success_mode: xybbox
|
||||
- name: heuristic__skill
|
||||
mode: home
|
||||
gripper_state: 1.0
|
||||
- left:
|
||||
- name: pick
|
||||
objects: [fork]
|
||||
filter_z_dir: ["forward", 80]
|
||||
filter_x_dir: ["downward", 130]
|
||||
pre_grasp_offset: 0.05
|
||||
gripper_change_steps: 10
|
||||
post_grasp_offset_min: 0.125
|
||||
post_grasp_offset_max: 0.175
|
||||
- name: place
|
||||
objects: [fork, plate]
|
||||
place_direction: vertical
|
||||
filter_z_dir: ["forward", 20]
|
||||
filter_x_dir: ["downward", 150]
|
||||
x_ratio_range: [-0.25, -0.15]
|
||||
y_ratio_range: [0.30, 0.70]
|
||||
pre_place_z_offset: 0.175
|
||||
place_z_offset: 0.125
|
||||
success_mode: left
|
||||
threshold: 0.01
|
||||
- name: heuristic__skill
|
||||
mode: home
|
||||
gripper_state: 1.0
|
||||
right:
|
||||
- name: pick
|
||||
objects: [spoon]
|
||||
filter_z_dir: ["forward", 80]
|
||||
filter_x_dir: ["downward", 130]
|
||||
pre_grasp_offset: 0.05
|
||||
gripper_change_steps: 10
|
||||
post_grasp_offset_min: 0.125
|
||||
post_grasp_offset_max: 0.175
|
||||
- name: place
|
||||
objects: [spoon, plate]
|
||||
place_direction: vertical
|
||||
filter_z_dir: ["forward", 20]
|
||||
filter_x_dir: ["downward", 150]
|
||||
x_ratio_range: [1.15, 1.25]
|
||||
y_ratio_range: [0.30, 0.70]
|
||||
pre_place_z_offset: 0.175
|
||||
place_z_offset: 0.125
|
||||
success_mode: right
|
||||
threshold: 0.01
|
||||
- name: heuristic__skill
|
||||
mode: home
|
||||
gripper_state: 1.0
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
10
|
||||
11
|
||||
12
|
||||
13
|
||||
14
|
||||
15
|
||||
16
|
||||
17
|
||||
18
|
||||
19
|
||||
20
|
||||
21
|
||||
22
|
||||
23
|
||||
24
|
||||
25
|
||||
26
|
||||
27
|
||||
28
|
||||
29
|
||||
30
|
||||
31
|
||||
32
|
||||
33
|
||||
34
|
||||
35
|
||||
36
|
||||
37
|
||||
38
|
||||
39
|
||||
40
|
||||
41
|
||||
42
|
||||
43
|
||||
44
|
||||
45
|
||||
46
|
||||
47
|
||||
48
|
||||
49
|
||||
50
|
||||
51
|
||||
52
|
||||
53
|
||||
54
|
||||
55
|
||||
56
|
||||
57
|
||||
58
|
||||
59
|
||||
60
|
||||
61
|
||||
62
|
||||
63
|
||||
64
|
||||
65
|
||||
66
|
||||
67
|
||||
68
|
||||
69
|
||||
70
|
||||
71
|
||||
72
|
||||
73
|
||||
74
|
||||
75
|
||||
|
||||
## Run the Task [](#run-the-task)
|
||||
|
||||
Run the simulation with your task configuration:
|
||||
bash
|
||||
```
|
||||
# Plan with render mode (suitable for debugging)
|
||||
bash scripts/simbox/simbox_plan_with_render.sh new_task [num_samples] [random_seed]
|
||||
|
||||
# Plan and render mode
|
||||
bash scripts/simbox/simbox_plan_and_render.sh new_task [num_samples] [random_seed]
|
||||
|
||||
# DE pipeline mode (suitable for data generation)
|
||||
bash scripts/simbox/simbox_pipe.sh new_task [num_samples] [random_seed]
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
186
docs_crawled/guides_installation.md
Normal file
186
docs_crawled/guides_installation.md
Normal file
@@ -0,0 +1,186 @@
|
||||
# Source: https://internrobotics.github.io/InternDataEngine-Docs/guides/installation.html
|
||||
|
||||
# Installation [](#installation)
|
||||
|
||||
This guide walks you through setting up InternDataEngine, including cloning the repository, preparing Isaac Sim, downloading assets, and installing dependencies. Follow the steps below to get your simulation environment ready for data generation.
|
||||
|
||||
## Prerequisites [](#prerequisites)
|
||||
|
||||
Before installing InternDataEngine, ensure the following requirements are met:
|
||||
|
||||
| Dependency | Version | Description |
|
||||
| NVIDIA Isaac Sim | 4.1.0 (recommended) / 4.2.0 / 4.5.0 | Simulation engine |
|
||||
| Python | 3.10+ (recommended 3.10 or 3.11) | Runtime |
|
||||
| CUDA | 11.8+ | GPU-accelerated motion planning |
|
||||
|
||||
## Step 1: Clone the Repository [](#step-1-clone-the-repository)
|
||||
bash
|
||||
```
|
||||
git clone https://github.com/InternRobotics/InternDataEngine.git
|
||||
cd InternDataEngine
|
||||
```
|
||||
1
|
||||
2
|
||||
|
||||
## Step 2: Prepare Isaac Sim [](#step-2-prepare-isaac-sim)
|
||||
|
||||
InternDataEngine relies on NVIDIA Isaac Sim for physics simulation. Please install it according to the version requirements above. Version **4.1.0 **is recommended.
|
||||
|
||||
## Step 3: Download Assets [](#step-3-download-assets)
|
||||
|
||||
All assets and dependency packages are hosted on HuggingFace: [InternDataAssets](https://huggingface.co/datasets/InternRobotics/InternData-A1/tree/main/InternDataAssets)
|
||||
|
||||
Three components need to be downloaded:
|
||||
text
|
||||
```
|
||||
InternDataAssets/
|
||||
├── assets/ # Scene and task assets
|
||||
├── curobo/ # CuRobo motion planning library
|
||||
└── panda_drake/ # Drake kinematics library
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
|
||||
### 3.1 Scene Assets [](#_3-1-scene-assets)
|
||||
|
||||
**Required assets **(needed for all tasks):
|
||||
|
||||
- `background_textures `, `envmap_lib `, `floor_textures `, `table_textures `— Domain Randomization materials
|
||||
- `table0 `, `table_info.json `— Table scene
|
||||
|
||||
>
|
||||
|
||||
The Randomization material directories contain many files. For quick testing, you can download just a few samples from each directory.
|
||||
|
||||
**Robot models **(choose as needed):
|
||||
|
||||
- `lift2 `, `franka `, `frankarobotiq `, `split_aloha_mid_360 `, `G1_120s `
|
||||
|
||||
**Task assets **(choose as needed):
|
||||
|
||||
- `basic `, `art `, `long_horizon `, `pick_and_place `
|
||||
|
||||
We provide a download script at `scripts/download_assets.sh `for selective downloading:
|
||||
bash
|
||||
```
|
||||
bash scripts/download_assets.sh [OPTIONS]
|
||||
```
|
||||
1
|
||||
|
||||
| Option | Description |
|
||||
| `--min ` | Download only required scene assets (for quick testing) |
|
||||
| `--full ` | Download all scene assets including all robots and tasks (default) |
|
||||
| `--with-curobo ` | Also download the CuRobo package |
|
||||
| `--with-drake ` | Also download the panda_drake package |
|
||||
| `--local-dir DIR ` | Specify download directory (default: current directory) |
|
||||
bash
|
||||
```
|
||||
# Minimum assets + CuRobo + panda_drake
|
||||
bash scripts/download_assets.sh --min --with-curobo --with-drake
|
||||
|
||||
# Full download (~200GB)
|
||||
bash scripts/download_assets.sh --full --with-curobo --with-drake
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
|
||||
Hint
|
||||
|
||||
The full asset collection is large, so download selectively based on your needs. Because the background, floor, and table textures contain many images for domain randomization, if your download speed is slow or disk space is limited, you can download only a small subset (e.g., 10+ images per directory) for debugging.
|
||||
|
||||
### 3.2 CuRobo [](#_3-2-curobo)
|
||||
|
||||
If you already have CuRobo installed and don't need to download it via the script above, simply merge the contents of ``[curobo/src/curobo/content](https://huggingface.co/datasets/InternRobotics/InternData-A1/tree/main/InternDataAssets/curobo/src/curobo/content)from HuggingFace into your local `YOUR_CUROBO_PATH/src/curobo/content `(contains robot URDFs and CuRobo configuration files).
|
||||
|
||||
If CuRobo is not yet installed, you can also get the source from [NVlabs/curobo] ( [https://github.com/NVlabs/curobo](https://github.com/NVlabs/curobo)).
|
||||
|
||||
## Step 4: Create Symlinks [](#step-4-create-symlinks)
|
||||
bash
|
||||
```
|
||||
cd InternDataEngine/workflows/simbox
|
||||
ln -s YOUR_PATH_TO_ASSETS assets
|
||||
ln -s YOUR_PATH_TO_CUROBO curobo
|
||||
ln -s YOUR_PATH_TO_PANDA_DRAKE panda_drake
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
|
||||
## Step 5: Install Python Dependencies [](#step-5-install-python-dependencies)
|
||||
|
||||
### Option A: Using Isaac Sim's Built-in Python [](#option-a-using-isaac-sim-s-built-in-python)
|
||||
bash
|
||||
```
|
||||
cd InternDataEngine
|
||||
YOUR_PATH_TO_ISAACSIM/python.sh -m pip install --upgrade pip
|
||||
YOUR_PATH_TO_ISAACSIM/python.sh -m pip install -r requirements.txt
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
|
||||
### Option B: Using Conda [](#option-b-using-conda)
|
||||
bash
|
||||
```
|
||||
conda create -n banana python=3.10
|
||||
conda activate banana
|
||||
source YOUR_PATH_TO_ISAACSIM/setup_conda_env.sh
|
||||
cd InternDataEngine
|
||||
pip install --upgrade pip
|
||||
pip install -r requirements.txt
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
|
||||
>
|
||||
|
||||
**Note **: The only difference between the two options is the Python launch command — Option A uses `YOUR_PATH_TO_ISAACSIM/python.sh `, while Option B uses `python `. This documentation uses `YOUR_PATH_TO_ISAACSIM/python.sh `throughout for consistency.
|
||||
|
||||
## Step 6: Install CuRobo [](#step-6-install-curobo)
|
||||
|
||||
Refer to the [CuRobo installation docs](https://curobo.org/get_started/1_install_instructions.html), specifically the **Install for use in Isaac Sim **section, then run:
|
||||
bash
|
||||
```
|
||||
cd InternDataEngine/workflows/simbox/curobo
|
||||
YOUR_PATH_TO_ISAACSIM/python.sh -m pip install -e .[isaacsim] --no-build-isolation
|
||||
```
|
||||
1
|
||||
2
|
||||
|
||||
## Troubleshooting [](#troubleshooting)
|
||||
|
||||
### Isaac Sim Not Found [](#isaac-sim-not-found)
|
||||
|
||||
Ensure the `ISAAC_SIM_PATH `environment variable is set correctly:
|
||||
bash
|
||||
```
|
||||
export ISAAC_SIM_PATH=/path/to/isaac-sim
|
||||
```
|
||||
1
|
||||
|
||||
### CUDA Out of Memory [](#cuda-out-of-memory)
|
||||
|
||||
Reduce the batch size in the configuration, or use a GPU with more VRAM. CuRobo motion planning benefits from larger GPU memory.
|
||||
|
||||
### Import Errors [](#import-errors)
|
||||
|
||||
Ensure all symlinks are set up correctly:
|
||||
bash
|
||||
```
|
||||
ls -la workflows/simbox/assets
|
||||
ls -la workflows/simbox/curobo
|
||||
ls -la workflows/simbox/panda_drake
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
261
docs_crawled/guides_quickstart.md
Normal file
261
docs_crawled/guides_quickstart.md
Normal file
@@ -0,0 +1,261 @@
|
||||
# Source: https://internrobotics.github.io/InternDataEngine-Docs/guides/quickstart.html
|
||||
|
||||
# Quick Start [](#quick-start)
|
||||
|
||||
This guide walks you through running your first InternDataEngine data generation task and understanding the core configuration concepts.
|
||||
|
||||
## Running Your First Task [](#running-your-first-task)
|
||||
|
||||
The quickest way to start:
|
||||
bash
|
||||
```
|
||||
/isaac-sim/python.sh launcher.py \
|
||||
--config configs/simbox/de_plan_with_render_template.yaml
|
||||
```
|
||||
1
|
||||
2
|
||||
|
||||
You can also use the wrapper script (same effect, simpler arguments):
|
||||
bash
|
||||
```
|
||||
bash scripts/simbox/simbox_plan_with_render.sh <task_config_path> [num_samples] [random_seed]
|
||||
|
||||
# Example
|
||||
bash scripts/simbox/simbox_plan_with_render.sh \
|
||||
workflows/simbox/core/configs/tasks/basic/split_aloha/track_the_targets/track_the_targets.yaml 10
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
|
||||
>
|
||||
|
||||
See the script file for more usage details.
|
||||
|
||||
### Command Line Arguments [](#command-line-arguments)
|
||||
|
||||
| Argument | Description |
|
||||
| `--config ` | **Required **. Path to the execution config file |
|
||||
| `--random_seed ` | Optional. Fix random seed for reproducibility |
|
||||
| `--debug ` | Optional. Debug mode — exceptions are raised immediately |
|
||||
|
||||
Any field in the config file can be overridden via the command line using dot-separated paths:
|
||||
bash
|
||||
```
|
||||
--load_stage.layout_random_generator.args.random_num=500
|
||||
--load_stage.scene_loader.args.simulator.headless=false
|
||||
```
|
||||
1
|
||||
2
|
||||
|
||||
This is equivalent to modifying the config file directly.
|
||||
|
||||
## Execution Modes [](#execution-modes)
|
||||
|
||||
The engine provides multiple execution modes. Switch between them by changing the config file passed to `--config `:
|
||||
|
||||
| Config File | Mode | Description |
|
||||
| `de_plan_with_render_template.yaml ` | Plan + Render simultaneous | Simplest; good for debugging. Required for fluid tasks |
|
||||
| `de_pipe_template.yaml ` | Plan / Render pipelined | Best performance (memory-dependent); ideal for large-scale production |
|
||||
| `de_plan_and_render_template.yaml ` | Plan and Render sequential | For serial debugging of the Pipe mode |
|
||||
| `de_plan_template.yaml ` | Planning only | Generate trajectories without rendering |
|
||||
| `de_render_template.yaml ` | Rendering only | Render images from existing trajectories; re-render with different backgrounds/materials |
|
||||
|
||||
**Recommended **: Use `de_plan_with_render_template.yaml `or `de_plan_and_render_template.yaml `during development, and `de_pipe_template.yaml `for production. Due to potential interference between Isaac Sim multi-process instances, it is recommended to run in containerized environments — e.g., launch multiple single-GPU containers on a cluster to execute the pipeline script.
|
||||
bash
|
||||
```
|
||||
# Debug mode
|
||||
/isaac-sim/python.sh launcher.py --config configs/simbox/de_plan_with_render_template.yaml
|
||||
|
||||
# Production mode
|
||||
/isaac-sim/python.sh launcher.py --config configs/simbox/de_pipe_template.yaml
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
|
||||
## Understanding the Configuration [](#understanding-the-configuration)
|
||||
|
||||
The engine uses two types of config files:
|
||||
|
||||
- **Execution configs **( `configs/simbox/de_*.yaml `): Define the pipeline execution mode and stage orchestration
|
||||
- **Task configs **( `workflows/simbox/core/configs/tasks/... `): Define the specific task — robots, objects, skills, etc.
|
||||
|
||||
### Execution Config Details [](#execution-config-details)
|
||||
|
||||
The data pipeline consists of four stages: **Load **-> **Plan **-> **Render **-> **Store **.
|
||||
|
||||
Using `de_plan_and_render_template.yaml `as an example:
|
||||
yaml
|
||||
```
|
||||
load_stage:
|
||||
scene_loader: # Scene loader
|
||||
type: env_loader
|
||||
args:
|
||||
workflow_type: SimBoxDualWorkFlow
|
||||
cfg_path: workflows/simbox/core/configs/tasks/... # Task config path
|
||||
simulator:
|
||||
physics_dt: 1/30 # Physics update rate
|
||||
rendering_dt: 1/30 # Render update rate
|
||||
headless: True # Headless mode (no GUI)
|
||||
anti_aliasing: 0 # Anti-aliasing level
|
||||
layout_random_generator: # Scene randomization
|
||||
type: env_randomizer
|
||||
args:
|
||||
random_num: 5 # Number of random samples
|
||||
strict_mode: true # true: output count must equal random_num
|
||||
|
||||
plan_stage:
|
||||
seq_planner:
|
||||
type: env_planner # Trajectory planner
|
||||
|
||||
render_stage:
|
||||
renderer:
|
||||
type: env_renderer # Renderer
|
||||
|
||||
store_stage:
|
||||
writer:
|
||||
type: env_writer
|
||||
args:
|
||||
batch_async: true # Async writes (better perf, more memory)
|
||||
output_dir: output/${name}/ # Output directory
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
10
|
||||
11
|
||||
12
|
||||
13
|
||||
14
|
||||
15
|
||||
16
|
||||
17
|
||||
18
|
||||
19
|
||||
20
|
||||
21
|
||||
22
|
||||
23
|
||||
24
|
||||
25
|
||||
26
|
||||
27
|
||||
28
|
||||
29
|
||||
30
|
||||
31
|
||||
|
||||
### Task Config [](#task-config)
|
||||
|
||||
A task config defines the complete scene for a data generation run:
|
||||
|
||||
| Field | Description |
|
||||
| robots | Robot model and parameters |
|
||||
| objects | Interactive objects in the scene |
|
||||
| camera | Viewpoint and image capture settings |
|
||||
| skills | Manipulation skill sequence to execute |
|
||||
| arena | Object placement regions and scene layout |
|
||||
|
||||
## Example Tasks [](#example-tasks)
|
||||
|
||||
### Pick and Place [](#pick-and-place)
|
||||
bash
|
||||
```
|
||||
/isaac-sim/python.sh launcher.py \
|
||||
--config configs/simbox/de_plan_with_render_template.yaml \
|
||||
--load_stage.scene_loader.args.cfg_path=workflows/simbox/core/configs/tasks/basic/lift2/insert_the_markpen_in_penholder/left/insert_the_markpen_in_penholder_part0.yaml
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
|
||||
### Pouring Task [](#pouring-task)
|
||||
bash
|
||||
```
|
||||
/isaac-sim/python.sh launcher.py \
|
||||
--config configs/simbox/de_plan_with_render_template.yaml \
|
||||
--load_stage.scene_loader.args.cfg_path=workflows/simbox/core/configs/tasks/basic/lift2/pour_redwine_left.yaml
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
|
||||
### Long-Horizon Task [](#long-horizon-task)
|
||||
bash
|
||||
```
|
||||
/isaac-sim/python.sh launcher.py \
|
||||
--config configs/simbox/de_plan_with_render_template.yaml \
|
||||
--load_stage.scene_loader.args.cfg_path=workflows/simbox/core/configs/tasks/long_horizon/lift2/dexpnp/sort_parts_0.yaml
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
|
||||
## Output Structure [](#output-structure)
|
||||
|
||||
Output is saved to the path specified in `store_stage.writer.args.output_dir `:
|
||||
text
|
||||
```
|
||||
output_dir/
|
||||
├── <task_type>/
|
||||
│ └── <robot>/
|
||||
│ └── <task_name>/
|
||||
│ └── <arm>/
|
||||
│ ├── <timestamp1>/
|
||||
│ │ ├── images.rgb.head/
|
||||
│ │ ├── images.rgb.hand_right/
|
||||
│ │ ├── images.rgb.hand_left/
|
||||
│ │ └── lmdb/
|
||||
│ └── <timestamp2>/
|
||||
│ └── ...
|
||||
├── de_config.yaml # Copy of the execution config
|
||||
├── de_time_profile_*.log # Execution time statistics
|
||||
├── de_p*_w*_time_profile*.log # (Pipe mode) Per-process timing
|
||||
└── de_supervisor_p*_w*.log # (Pipe mode) Process monitor logs
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
7
|
||||
8
|
||||
9
|
||||
10
|
||||
11
|
||||
12
|
||||
13
|
||||
14
|
||||
15
|
||||
16
|
||||
|
||||
## Debugging Tips [](#debugging-tips)
|
||||
|
||||
### Enable Visualization [](#enable-visualization)
|
||||
|
||||
Disable headless mode to show the simulation GUI:
|
||||
bash
|
||||
```
|
||||
--load_stage.scene_loader.args.simulator.headless=false
|
||||
```
|
||||
1
|
||||
|
||||
### Common Issues [](#common-issues)
|
||||
|
||||
| Issue | Troubleshooting |
|
||||
| Scene setup errors | Check `set_up_scene() `in `workflows/simbox/core/tasks/banana.py ` |
|
||||
| Reset failures | Check `reset() `in `workflows/simbox_dual_workflow.py ` |
|
||||
| Motion planning failures | Check robot config in task YAML, object collision settings, `ignore_substring `list |
|
||||
| UnicodeDecodeError | Set `export PYTHONUTF8=1 ` |
|
||||
83
docs_crawled/policy_training.md
Normal file
83
docs_crawled/policy_training.md
Normal file
@@ -0,0 +1,83 @@
|
||||
# Source: https://internrobotics.github.io/InternDataEngine-Docs/policy/training.html
|
||||
|
||||
# Training [](#training)
|
||||
|
||||
This guide covers data format conversion and policy training for validating generated simulation data.
|
||||
|
||||
## Part 1: LMDB to LeRobot Data Conversion [](#part-1-lmdb-to-lerobot-data-conversion)
|
||||
|
||||
The simulation data generated by InternDataEngine is stored in LMDB format. To use this data for policy training, you need to convert it to LeRobot format.
|
||||
|
||||
### Step 1: Install LeRobot v2.1 [](#step-1-install-lerobot-v2-1)
|
||||
|
||||
We use LeRobot v2.1 format for data storage. Install the LeRobot 2.1 repo.
|
||||
|
||||
### Step 2: Convert LMDB to LeRobot v2.1 [](#step-2-convert-lmdb-to-lerobot-v2-1)
|
||||
|
||||
Use the conversion scripts in ``[policy/lmdb2lerobotv21](https://github.com/InternRobotics/InternDataEngine/tree/master/policy/lmdb2lerobotv21)directory.
|
||||
|
||||
We provide conversion scripts for different robot platforms:
|
||||
|
||||
- **lmdb2lerobot_lift2_a1.py **( script ): Lift2 (ARX).
|
||||
- **lmdb2lerobot_split_aloha_a1.py **( script ): Split Aloha.
|
||||
- **lmdb2lerobot_genie1_a1.py **( script ): Genie1.
|
||||
- **lmdb2lerobot_franka_a1.py **( script ): Franka FR3.
|
||||
- **lmdb2lerobot_frankarobotiq_a1.py **( script ): Franka with Robotiq gripper.
|
||||
|
||||
Example usage:
|
||||
bash
|
||||
```
|
||||
python lmdb2lerobot_lift2_a1.py \
|
||||
--src_path ${src_path} \
|
||||
--save_path ${save_path} \
|
||||
--repo_id ${repo_id} \
|
||||
--num-threads ${num_threads} \
|
||||
--num_demos ${num_demos}
|
||||
```
|
||||
1
|
||||
2
|
||||
3
|
||||
4
|
||||
5
|
||||
6
|
||||
|
||||
**Parameters: **
|
||||
|
||||
- **--src_path **( str ): Path to the source LMDB data directory.
|
||||
- **--save_path **( str ): Path to save the converted LeRobot dataset.
|
||||
- **--repo_id **( str ): Dataset repository identifier.
|
||||
- **--num-threads **( int ): Number of threads for parallel processing.
|
||||
- **--num_demos **( int ): Number of demonstrations to convert (optional).
|
||||
|
||||
### Step 3: Convert to LeRobot v3.0 (Optional) [](#step-3-convert-to-lerobot-v3-0-optional)
|
||||
|
||||
If you need LeRobot v3.0 format for training, please install LeRobot 3.0. Then use the conversion script:
|
||||
bash
|
||||
```
|
||||
python convertv21_to_v30.py --input_path ${v21_path} --output_path ${v30_path}
|
||||
```
|
||||
1
|
||||
|
||||
The conversion code is available at ``[policy/lmdb2lerobotv21/convertv21_to_v30.py](https://github.com/InternRobotics/InternDataEngine/tree/master/policy/lmdb2lerobotv21/convertv21_to_v30.py).
|
||||
|
||||
## Part 2: Policy Training with π 0 [](#part-2-policy-training-with-π0)
|
||||
|
||||
As described in the [InternData-A1 paper](https://arxiv.org/pdf/2511.16651), we used multi-machine, multi-GPU JAX-based π 0 for data validation.
|
||||
|
||||
We have implemented a JAX-based, multi-nodes, multi-GPU training pipeline that supports multi-dataset mixed training for π 0 .
|
||||
|
||||
### Features [](#features)
|
||||
|
||||
- **Multi-machine, multi-GPU training **: Scale training across multiple nodes
|
||||
- **Multi-dataset mixed training **: Train on multiple datasets simultaneously
|
||||
- **JAX-based implementation **: High-performance training with JAX/Flax
|
||||
|
||||
### Installation, Training, and Deployment [](#installation-training-and-deployment)
|
||||
|
||||
For detailed instructions on installation, training, and deployment, please refer to the [openpi-InternData-A1 README](https://github.com/InternRobotics/InternDataEngine/blob/master/policy/openpi-InternData-A1/README.md).
|
||||
|
||||
## References [](#references)
|
||||
|
||||
- [LeRobot](https://github.com/huggingface/lerobot)- HuggingFace LeRobot
|
||||
- [InternData-A1 Paper](https://arxiv.org/pdf/2511.16651)- InternData-A1: A High-Fidelity Synthetic Data Generator for Robotic Manipulation
|
||||
- [openpi-InternData-A1](https://github.com/InternRobotics/InternDataEngine/blob/master/policy/openpi-InternData-A1/)- JAX-based π 0 training code
|
||||
33
install.md
Normal file
33
install.md
Normal file
@@ -0,0 +1,33 @@
|
||||
conda create -n banana450 python=3.10
|
||||
conda activate banana450
|
||||
# 看看12.8安装了么?
|
||||
conda list | grep cuda
|
||||
# 安装12.8
|
||||
conda install -y cuda-toolkit=12.8
|
||||
# 其他的cuda版本在conda中的需要卸载
|
||||
conda list | grep cuda
|
||||
source ~/isaacsim450/setup_conda_env.sh
|
||||
# 导入conda环境的12.8cuda环境
|
||||
export CUDA_HOME="$CONDA_PREFIX"
|
||||
export PATH="$CONDA_PREFIX/bin:$PATH"
|
||||
# 看一下应该是12.8
|
||||
nvcc -V
|
||||
# 换掉torch版本,换成cu128编译的版本
|
||||
pip list | grep torch
|
||||
pip install torch==2.7.0 torchvision==0.22.0 torchaudio==2.7.0 --index-url https://download.pytorch.org/whl/cu128
|
||||
pip list | grep torch
|
||||
pip install -r requirements.txt
|
||||
pip list | grep cuda
|
||||
# 卸载掉cu11的那些包
|
||||
pip uninstall nvidia-cuda-cupti-cu11 nvidia-cuda-nvrtc-cu11 nvidia-cuda-runtime-cu11
|
||||
|
||||
# 安装curobo
|
||||
cd workflows/simbox/curobo
|
||||
# 12.0是显卡的算力 要自己去查 不要信AI的 PRO6000是12.0
|
||||
export TORCH_CUDA_ARCH_LIST="12.0+PTX"
|
||||
pip install -e .[isaacsim] --no-build-isolation
|
||||
|
||||
# 降级numpy
|
||||
pip install numpy==1.26.0
|
||||
pip install opencv-python==4.11.0.86
|
||||
python launcher.py --config configs/simbox/de_plan_and_render_template.yaml
|
||||
328
migrate/crawl_docs.py
Normal file
328
migrate/crawl_docs.py
Normal file
@@ -0,0 +1,328 @@
|
||||
"""
|
||||
Crawl InternDataEngine online docs and save as local markdown files.
|
||||
|
||||
Usage:
|
||||
python migrate/crawl_docs.py
|
||||
python migrate/crawl_docs.py --output docs_crawled
|
||||
"""
|
||||
import argparse
|
||||
import os
|
||||
import re
|
||||
import time
|
||||
import urllib.request
|
||||
from html.parser import HTMLParser
|
||||
|
||||
|
||||
BASE_URL = "https://internrobotics.github.io/InternDataEngine-Docs"
|
||||
|
||||
# All pages from the sitemap (extracted from VitePress hash map)
|
||||
PAGES = [
|
||||
# Getting Started
|
||||
"/guides/installation.html",
|
||||
"/guides/quickstart.html",
|
||||
# Core Concepts
|
||||
"/concepts/workflows.html",
|
||||
"/concepts/skills.html",
|
||||
"/concepts/skills/overview.html",
|
||||
"/concepts/skills/pick.html",
|
||||
"/concepts/skills/place.html",
|
||||
"/concepts/skills/articulation.html",
|
||||
"/concepts/objects.html",
|
||||
"/concepts/cameras.html",
|
||||
"/concepts/robots.html",
|
||||
"/concepts/controllers.html",
|
||||
# Configuration
|
||||
"/config/yaml.html",
|
||||
"/config/dr.html",
|
||||
"/config/assets.html",
|
||||
# Customization
|
||||
"/custom/assets.html",
|
||||
"/custom/robot.html",
|
||||
"/custom/controller.html",
|
||||
"/custom/skill.html",
|
||||
"/custom/task.html",
|
||||
# Policy
|
||||
"/policy/training.html",
|
||||
# API
|
||||
"/api/controllers.html",
|
||||
"/api/skills.html",
|
||||
# Chinese versions
|
||||
"/zh/guides/installation.html",
|
||||
"/zh/guides/quickstart.html",
|
||||
"/zh/concepts/workflows.html",
|
||||
"/zh/concepts/skills.html",
|
||||
"/zh/concepts/skills/overview.html",
|
||||
"/zh/concepts/skills/pick.html",
|
||||
"/zh/concepts/skills/place.html",
|
||||
"/zh/concepts/skills/articulation.html",
|
||||
"/zh/concepts/tasks.html",
|
||||
"/zh/concepts/cameras.html",
|
||||
"/zh/concepts/robots.html",
|
||||
"/zh/concepts/controllers.html",
|
||||
"/zh/config/yaml.html",
|
||||
"/zh/config/dr.html",
|
||||
"/zh/config/assets.html",
|
||||
"/zh/custom/assets.html",
|
||||
"/zh/custom/robot.html",
|
||||
"/zh/custom/controller.html",
|
||||
"/zh/custom/skill.html",
|
||||
"/zh/custom/task.html",
|
||||
]
|
||||
|
||||
|
||||
class HTMLToMarkdown(HTMLParser):
|
||||
"""Simple HTML to Markdown converter for VitePress content."""
|
||||
|
||||
def __init__(self):
|
||||
super().__init__()
|
||||
self.output = []
|
||||
self.current_tag = None
|
||||
self.in_content = False
|
||||
self.in_code = False
|
||||
self.code_lang = ""
|
||||
self.skip_tags = {"script", "style", "nav", "header", "footer", "button"}
|
||||
self.skip_depth = 0
|
||||
self.heading_level = 0
|
||||
self.in_li = False
|
||||
self.in_pre = False
|
||||
self.in_a = False
|
||||
self.a_href = ""
|
||||
self.a_text = ""
|
||||
|
||||
def handle_starttag(self, tag, attrs):
|
||||
attrs_dict = dict(attrs)
|
||||
classes = attrs_dict.get("class", "")
|
||||
|
||||
# Skip navigation, header, footer
|
||||
if tag in self.skip_tags:
|
||||
self.skip_depth += 1
|
||||
return
|
||||
if self.skip_depth > 0:
|
||||
return
|
||||
|
||||
# Track content area
|
||||
if "vp-doc" in classes or "VPDoc" in classes:
|
||||
self.in_content = True
|
||||
|
||||
if not self.in_content:
|
||||
return
|
||||
|
||||
if tag in ("h1", "h2", "h3", "h4", "h5", "h6"):
|
||||
self.heading_level = int(tag[1])
|
||||
self.output.append("\n" + "#" * self.heading_level + " ")
|
||||
elif tag == "p":
|
||||
self.output.append("\n\n")
|
||||
elif tag == "pre":
|
||||
self.in_pre = True
|
||||
elif tag == "code":
|
||||
if self.in_pre:
|
||||
self.in_code = True
|
||||
lang = attrs_dict.get("class", "")
|
||||
lang_match = re.search(r"language-(\w+)", lang)
|
||||
self.code_lang = lang_match.group(1) if lang_match else ""
|
||||
self.output.append(f"\n```{self.code_lang}\n")
|
||||
else:
|
||||
self.output.append("`")
|
||||
elif tag == "a":
|
||||
self.in_a = True
|
||||
self.a_href = attrs_dict.get("href", "")
|
||||
self.a_text = ""
|
||||
elif tag == "ul":
|
||||
self.output.append("\n")
|
||||
elif tag == "ol":
|
||||
self.output.append("\n")
|
||||
elif tag == "li":
|
||||
self.in_li = True
|
||||
self.output.append("- ")
|
||||
elif tag == "strong" or tag == "b":
|
||||
self.output.append("**")
|
||||
elif tag == "em" or tag == "i":
|
||||
self.output.append("*")
|
||||
elif tag == "br":
|
||||
self.output.append("\n")
|
||||
elif tag == "img":
|
||||
alt = attrs_dict.get("alt", "")
|
||||
src = attrs_dict.get("src", "")
|
||||
self.output.append(f"")
|
||||
elif tag == "table":
|
||||
self.output.append("\n")
|
||||
elif tag == "tr":
|
||||
self.output.append("| ")
|
||||
elif tag == "th" or tag == "td":
|
||||
pass
|
||||
elif tag == "blockquote":
|
||||
self.output.append("\n> ")
|
||||
|
||||
def handle_endtag(self, tag):
|
||||
if tag in self.skip_tags:
|
||||
self.skip_depth -= 1
|
||||
return
|
||||
if self.skip_depth > 0:
|
||||
return
|
||||
if not self.in_content:
|
||||
return
|
||||
|
||||
if tag in ("h1", "h2", "h3", "h4", "h5", "h6"):
|
||||
self.output.append("\n")
|
||||
self.heading_level = 0
|
||||
elif tag == "pre":
|
||||
self.in_pre = False
|
||||
elif tag == "code":
|
||||
if self.in_code:
|
||||
self.in_code = False
|
||||
self.output.append("\n```\n")
|
||||
else:
|
||||
self.output.append("`")
|
||||
elif tag == "a":
|
||||
self.in_a = False
|
||||
if self.a_href and self.a_text:
|
||||
self.output.append(f"[{self.a_text.strip()}]({self.a_href})")
|
||||
self.a_text = ""
|
||||
elif tag == "li":
|
||||
self.in_li = False
|
||||
self.output.append("\n")
|
||||
elif tag == "strong" or tag == "b":
|
||||
self.output.append("**")
|
||||
elif tag == "em" or tag == "i":
|
||||
self.output.append("*")
|
||||
elif tag == "tr":
|
||||
self.output.append("\n")
|
||||
elif tag == "th" or tag == "td":
|
||||
self.output.append(" | ")
|
||||
elif tag == "p":
|
||||
self.output.append("\n")
|
||||
|
||||
def handle_data(self, data):
|
||||
if self.skip_depth > 0:
|
||||
return
|
||||
|
||||
if self.in_a:
|
||||
self.a_text += data
|
||||
return
|
||||
|
||||
if self.in_content:
|
||||
if self.in_code:
|
||||
self.output.append(data)
|
||||
else:
|
||||
text = data.strip()
|
||||
if text:
|
||||
self.output.append(text + " ")
|
||||
|
||||
def get_markdown(self):
|
||||
text = "".join(self.output)
|
||||
# Clean up
|
||||
text = re.sub(r"\n{3,}", "\n\n", text)
|
||||
text = re.sub(r"[ \t]+\n", "\n", text)
|
||||
return text.strip()
|
||||
|
||||
|
||||
def fetch_page(url):
|
||||
"""Fetch a page and return HTML content."""
|
||||
try:
|
||||
req = urllib.request.Request(url, headers={"User-Agent": "Mozilla/5.0"})
|
||||
with urllib.request.urlopen(req, timeout=15) as resp:
|
||||
return resp.read().decode("utf-8")
|
||||
except Exception as e:
|
||||
print(f" ERROR: {e}")
|
||||
return None
|
||||
|
||||
|
||||
def html_to_markdown(html_content):
|
||||
"""Convert HTML to markdown."""
|
||||
parser = HTMLToMarkdown()
|
||||
parser.feed(html_content)
|
||||
return parser.get_markdown()
|
||||
|
||||
|
||||
def main():
|
||||
parser = argparse.ArgumentParser(description="Crawl InternDataEngine docs")
|
||||
parser.add_argument("--output", default="docs_crawled", help="Output directory")
|
||||
parser.add_argument("--zh-only", action="store_true", help="Only crawl Chinese docs")
|
||||
parser.add_argument("--en-only", action="store_true", help="Only crawl English docs")
|
||||
args = parser.parse_args()
|
||||
|
||||
os.makedirs(args.output, exist_ok=True)
|
||||
|
||||
pages = PAGES
|
||||
if args.zh_only:
|
||||
pages = [p for p in PAGES if p.startswith("/zh/")]
|
||||
elif args.en_only:
|
||||
pages = [p for p in PAGES if not p.startswith("/zh/")]
|
||||
|
||||
print(f"Crawling {len(pages)} pages to {args.output}/\n")
|
||||
|
||||
for page_path in pages:
|
||||
url = BASE_URL + page_path
|
||||
# Convert path to filename: /guides/installation.html -> guides_installation.md
|
||||
md_name = page_path.strip("/").replace("/", "_").replace(".html", ".md")
|
||||
md_path = os.path.join(args.output, md_name)
|
||||
|
||||
print(f" {page_path} -> {md_name}", end=" ")
|
||||
|
||||
html = fetch_page(url)
|
||||
if html is None:
|
||||
print("FAILED")
|
||||
continue
|
||||
|
||||
md = html_to_markdown(html)
|
||||
if not md or len(md) < 50:
|
||||
# VitePress SPA - content is loaded via JS, try fetching the raw .md source
|
||||
# VitePress stores source at /InternDataEngine-Docs/page.html but the actual
|
||||
# markdown might be accessible differently
|
||||
print(f"(sparse content: {len(md)} chars, SPA rendering)")
|
||||
else:
|
||||
print(f"OK ({len(md)} chars)")
|
||||
|
||||
with open(md_path, "w") as f:
|
||||
f.write(f"# Source: {url}\n\n")
|
||||
f.write(md)
|
||||
|
||||
time.sleep(0.3)
|
||||
|
||||
# Also try fetching raw markdown from GitHub
|
||||
print("\n\nAttempting raw markdown from GitHub...")
|
||||
gh_base = "https://raw.githubusercontent.com/InternRobotics/InternDataEngine/master/docs"
|
||||
# VitePress source files
|
||||
raw_pages = {
|
||||
"guides/installation.md": "guides_installation_raw.md",
|
||||
"guides/quickstart.md": "guides_quickstart_raw.md",
|
||||
"concepts/workflows.md": "concepts_workflows_raw.md",
|
||||
"concepts/objects.md": "concepts_objects_raw.md",
|
||||
"concepts/cameras.md": "concepts_cameras_raw.md",
|
||||
"concepts/robots.md": "concepts_robots_raw.md",
|
||||
"concepts/controllers.md": "concepts_controllers_raw.md",
|
||||
"concepts/skills/overview.md": "concepts_skills_overview_raw.md",
|
||||
"concepts/skills/pick.md": "concepts_skills_pick_raw.md",
|
||||
"concepts/skills/place.md": "concepts_skills_place_raw.md",
|
||||
"concepts/skills/articulation.md": "concepts_skills_articulation_raw.md",
|
||||
"config/yaml.md": "config_yaml_raw.md",
|
||||
"config/dr.md": "config_dr_raw.md",
|
||||
"config/assets.md": "config_assets_raw.md",
|
||||
"custom/assets.md": "custom_assets_raw.md",
|
||||
"custom/robot.md": "custom_robot_raw.md",
|
||||
"custom/controller.md": "custom_controller_raw.md",
|
||||
"custom/skill.md": "custom_skill_raw.md",
|
||||
"custom/task.md": "custom_task_raw.md",
|
||||
"policy/training.md": "policy_training_raw.md",
|
||||
"api/controllers.md": "api_controllers_raw.md",
|
||||
"api/skills.md": "api_skills_raw.md",
|
||||
}
|
||||
|
||||
for src, dst in raw_pages.items():
|
||||
url = f"{gh_base}/{src}"
|
||||
dst_path = os.path.join(args.output, dst)
|
||||
print(f" {src}", end=" ")
|
||||
content = fetch_page(url)
|
||||
if content and len(content) > 50 and not content.strip().startswith("<!DOCTYPE"):
|
||||
with open(dst_path, "w") as f:
|
||||
f.write(content)
|
||||
print(f"OK ({len(content)} chars)")
|
||||
else:
|
||||
print("NOT FOUND or HTML")
|
||||
time.sleep(0.3)
|
||||
|
||||
print(f"\nDone. Files saved to {args.output}/")
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
main()
|
||||
303
migrate/custom_task_guide.md
Normal file
303
migrate/custom_task_guide.md
Normal file
@@ -0,0 +1,303 @@
|
||||
# 自定义任务创建指南:从 USDC 资产到完整任务
|
||||
|
||||
本文档记录了将外部 USDC 资产(以试管为例)转换为 InternDataEngine 可用任务的完整流程。
|
||||
|
||||
## 前提条件
|
||||
|
||||
- InternDataEngine 项目已配置完成(IS 5.0.0 + banana500 环境)
|
||||
- 有现成的 USD/USDC 3D 模型文件
|
||||
- conda 环境 `banana450`(用于 grasp 标注生成,pyarmor 兼容)
|
||||
|
||||
## 完整流程
|
||||
|
||||
### Step 1: 准备资产目录
|
||||
|
||||
在 `workflows/simbox/example_assets/task/` 下创建任务目录:
|
||||
|
||||
```bash
|
||||
mkdir -p workflows/simbox/example_assets/task/pick_test_tube/test_tube
|
||||
mkdir -p workflows/simbox/example_assets/task/pick_test_tube/test_tube_rack
|
||||
```
|
||||
|
||||
### Step 2: 从 USDC 导出三角化 OBJ
|
||||
|
||||
InternDataEngine 的 grasp 生成工具需要 OBJ 格式输入,且必须是纯三角面。使用 `migrate/usdc_to_obj.py` 从 USDC 提取并三角化:
|
||||
|
||||
```bash
|
||||
conda activate banana500
|
||||
python migrate/usdc_to_obj.py \
|
||||
--input /path/to/your/model.usdc \
|
||||
--output workflows/simbox/example_assets/task/pick_test_tube/test_tube/
|
||||
```
|
||||
|
||||
输出文件:`Aligned_obj.obj`(三角化的 OBJ)
|
||||
|
||||
**注意**:原始 USDC 中的面可能是四边形或多边形,脚本会自动进行 fan 三角化。
|
||||
|
||||
### Step 3: 重新打包 USD 结构
|
||||
|
||||
InternDataEngine 要求 USD 资产具有特定的层级结构:
|
||||
|
||||
```
|
||||
/World (defaultPrim, Xform, 无物理属性)
|
||||
├── /Looks (Scope, 材质)
|
||||
│ ├── Material_0
|
||||
│ └── Material_1
|
||||
├── /Aligned (Xform, PhysicsRigidBodyAPI + PhysicsMassAPI)
|
||||
│ └── /mesh (Mesh, PhysicsCollisionAPI + PhysicsMeshCollisionAPI)
|
||||
└── /PhysicsMaterial (Material, PhysicsMaterialAPI)
|
||||
```
|
||||
|
||||
**关键要求**:
|
||||
- `/World` 必须是 defaultPrim,且不能有任何物理 schema
|
||||
- `/Aligned` 是 `prim_path_child`,必须有 `PhysicsRigidBodyAPI`
|
||||
- 碰撞体必须使用 `convexHull` 近似(不能用 triangle mesh)
|
||||
- `/Looks` 必须和 `/Aligned` 平级(在同一引用范围内)
|
||||
|
||||
使用 `migrate/repackage_test_tube.py` 自动重构:
|
||||
|
||||
```bash
|
||||
python migrate/repackage_test_tube.py
|
||||
```
|
||||
|
||||
脚本逻辑:
|
||||
1. 创建新 USD,定义 `/World` 为 defaultPrim(纯净 Xform,不挂引用)
|
||||
2. 在 `/World/Aligned` 上添加引用,指向源 USD 的子节点(如 `/Test_Tube_AA_01/Test_Tube`)
|
||||
3. 在 `/World/Looks` 上添加引用,指向源 USD 的材质(如 `/Test_Tube_AA_01/Looks`)
|
||||
4. 给 `/World/Aligned` 添加 `PhysicsRigidBodyAPI` 和 `PhysicsMassAPI`
|
||||
5. 给碰撞 mesh 设置 `convexHull` 近似
|
||||
|
||||
**重新绑定材质**:由于引用子节点后,原始材质绑定路径超出引用范围,需要手动重新绑定:
|
||||
|
||||
```bash
|
||||
python migrate/fix_test_tube_materials.py
|
||||
```
|
||||
|
||||
### Step 4: 生成 Grasp 抓取标注
|
||||
|
||||
使用项目自带的 grasp 生成工具(需要 `banana450` 环境,因为 pyarmor 加密对 Python 版本敏感):
|
||||
|
||||
```bash
|
||||
conda activate banana450
|
||||
python workflows/simbox/tools/grasp/gen_sparse_label.py \
|
||||
--obj_path workflows/simbox/example_assets/task/pick_test_tube/test_tube/Aligned_obj.obj \
|
||||
--unit m --sparse_num 3000 --max_widths 0.1
|
||||
```
|
||||
|
||||
输出:`Aligned_grasp_sparse.npy`(3000 x 17 的数组)
|
||||
|
||||
**可视化验证**:
|
||||
|
||||
```bash
|
||||
python workflows/simbox/tools/grasp/vis_grasp.py \
|
||||
--obj_path workflows/simbox/example_assets/task/pick_test_tube/test_tube/Aligned_obj.obj \
|
||||
--unit m --N 200
|
||||
```
|
||||
|
||||
会弹出 Open3D 窗口,蓝色线条表示 gripper 姿态,应该合理地分布在物体周围。
|
||||
|
||||
**Grasp 标注格式(N x 17)**:
|
||||
|
||||
| 列 | 维度 | 含义 |
|
||||
|---|---|---|
|
||||
| 0 | 1 | score(质量分数,0.1-1.0,越小越好) |
|
||||
| 1 | 1 | width(夹持器开口宽度) |
|
||||
| 2 | 1 | height |
|
||||
| 3 | 1 | depth |
|
||||
| 4:13 | 9 | 旋转矩阵(3x3,row-major) |
|
||||
| 13:16 | 3 | 抓取中心点位置(物体坐标系) |
|
||||
| 16 | 1 | obj_id(通常为 -1) |
|
||||
|
||||
### Step 5: 创建任务配置 YAML
|
||||
|
||||
文件:`workflows/simbox/core/configs/tasks/example/pick_test_tube.yaml`
|
||||
|
||||
```yaml
|
||||
tasks:
|
||||
-
|
||||
name: banana_base_task
|
||||
asset_root: workflows/simbox/example_assets
|
||||
task: BananaBaseTask
|
||||
task_id: 0
|
||||
offset: null
|
||||
render: True
|
||||
neglect_collision_names: ["table"]
|
||||
|
||||
arena_file: workflows/simbox/core/configs/arenas/example.yaml
|
||||
|
||||
env_map:
|
||||
envmap_lib: envmap_lib
|
||||
apply_randomization: False
|
||||
intensity_range: [5000, 5000]
|
||||
rotation_range: [0, 0]
|
||||
|
||||
robots:
|
||||
-
|
||||
name: "split_aloha"
|
||||
robot_config_file: workflows/simbox/core/configs/robots/split_aloha.yaml
|
||||
euler: [0.0, 0.0, 90.0]
|
||||
ignore_substring: ["material", "table", "test_tube_rack"]
|
||||
|
||||
objects:
|
||||
-
|
||||
name: test_tube_right
|
||||
path: task/pick_test_tube/test_tube/Aligned_obj.usd
|
||||
target_class: RigidObject
|
||||
dataset: custom
|
||||
category: test_tube
|
||||
prim_path_child: Aligned
|
||||
translation: [0.0, 0.0, 0.0]
|
||||
euler: [0.0, 0.0, 0.0]
|
||||
scale: [1, 1, 1]
|
||||
apply_randomization: False
|
||||
orientation_mode: keep
|
||||
|
||||
regions:
|
||||
-
|
||||
object: test_tube_right
|
||||
target: table
|
||||
random_type: A_on_B_region_sampler
|
||||
random_config:
|
||||
pos_range: [[0.05, -0.05, 0.0], [0.15, 0.05, 0.0]]
|
||||
yaw_rotation: [0.0, 0.0]
|
||||
-
|
||||
object: split_aloha
|
||||
target: table
|
||||
random_type: A_on_B_region_sampler
|
||||
random_config:
|
||||
pos_range: [[0.0, -0.86, -0.75], [0.0, -0.86, -0.75]]
|
||||
yaw_rotation: [0.0, 0.0]
|
||||
|
||||
cameras:
|
||||
# ... 复用 split_aloha 的相机配置(详见完整配置文件)
|
||||
|
||||
data:
|
||||
task_dir: "pick_test_tube"
|
||||
language_instruction: "Pick up the test tube from the table."
|
||||
detailed_language_instruction: "Use the right arm to grasp the test tube."
|
||||
collect_info: "Test tube picking task"
|
||||
version: "v1.0"
|
||||
update: True
|
||||
max_episode_length: 2000
|
||||
|
||||
skills:
|
||||
-
|
||||
split_aloha:
|
||||
-
|
||||
right:
|
||||
-
|
||||
name: pick
|
||||
objects: [test_tube_right]
|
||||
npy_name: Aligned_grasp_sparse.npy
|
||||
filter_y_dir: ["forward", 60]
|
||||
filter_z_dir: ["downward", 150]
|
||||
pre_grasp_offset: 0.05
|
||||
gripper_change_steps: 10
|
||||
t_eps: 0.025
|
||||
o_eps: 1
|
||||
process_valid: True
|
||||
lift_th: 0.02
|
||||
post_grasp_offset_min: 0.10
|
||||
post_grasp_offset_max: 0.15
|
||||
-
|
||||
name: heuristic__skill
|
||||
mode: home
|
||||
gripper_state: 1.0
|
||||
```
|
||||
|
||||
**Skill 名称注意**:使用 `register_skill` 装饰器注册的名称(类名转 snake_case),例如:
|
||||
- `Pick` → `pick`
|
||||
- `Heuristic_Skill` → `heuristic__skill`(双下划线)
|
||||
- `Goto_Pose` → `goto__pose`(双下划线)
|
||||
|
||||
### Step 6: 创建 Pipeline 配置
|
||||
|
||||
文件:`configs/simbox/de_pick_test_tube.yaml`
|
||||
|
||||
```yaml
|
||||
name: simbox_pick_test_tube
|
||||
load_stage:
|
||||
scene_loader:
|
||||
type: env_loader
|
||||
args:
|
||||
workflow_type: SimBoxDualWorkFlow
|
||||
cfg_path: workflows/simbox/core/configs/tasks/example/pick_test_tube.yaml
|
||||
simulator:
|
||||
physics_dt: 1/30
|
||||
rendering_dt: 1/30
|
||||
stage_units_in_meters: 1.0
|
||||
headless: False # 调试时用 False(GUI),生产时改 True
|
||||
renderer: "RayTracedLighting"
|
||||
anti_aliasing: 0
|
||||
layout_random_generator:
|
||||
type: env_randomizer
|
||||
args:
|
||||
random_num: 1 # 调试时用 1,生产时增大
|
||||
strict_mode: true
|
||||
plan_stage:
|
||||
seq_planner:
|
||||
type: env_planner
|
||||
render_stage:
|
||||
renderer:
|
||||
type: env_renderer
|
||||
store_stage:
|
||||
writer:
|
||||
type: env_writer
|
||||
args:
|
||||
batch_async: true
|
||||
output_dir: output/${name}/
|
||||
```
|
||||
|
||||
### Step 7: 运行测试
|
||||
|
||||
```bash
|
||||
conda activate banana500
|
||||
|
||||
# GUI 模式调试(headless: False)
|
||||
python launcher.py --config configs/simbox/de_pick_test_tube.yaml
|
||||
|
||||
# 确认后改 headless: True,增大 random_num 批量生产
|
||||
```
|
||||
|
||||
### Step 8: 检查输出
|
||||
|
||||
输出目录:`output/simbox_pick_test_tube/`
|
||||
|
||||
```
|
||||
output/simbox_pick_test_tube/
|
||||
├── pick_test_tube/split_aloha/<task>/right/
|
||||
│ ├── <timestamp>/
|
||||
│ │ ├── images.rgb.head/
|
||||
│ │ ├── images.rgb.hand_right/
|
||||
│ │ ├── images.rgb.hand_left/
|
||||
│ │ └── lmdb/
|
||||
│ └── ...
|
||||
└── de_config.yaml
|
||||
```
|
||||
|
||||
## 常见问题
|
||||
|
||||
### Q: `gen_sparse_label.py` 报 `_PyFloat_Pack8` 错误
|
||||
A: pyarmor 加密对 Python 版本敏感,使用 `banana450` 环境(Python 3.10 + 旧版依赖)。
|
||||
|
||||
### Q: USD 打开后材质丢失
|
||||
A: 引用子节点时材质路径超出引用范围。需要用 `fix_test_tube_materials.py` 重新绑定。
|
||||
|
||||
### Q: `RigidContactView` 报 `sensor_count` 错误
|
||||
A: USD 结构不对。确保 `/World` (defaultPrim) 没有 `PhysicsRigidBodyAPI`,物理属性只在 `/World/Aligned` 子节点上。
|
||||
|
||||
### Q: OBJ 导出后 grasp 生成为空(0 条)
|
||||
A: OBJ 文件包含非三角形面。使用 `migrate/usdc_to_obj.py` 导出时会自动三角化。
|
||||
|
||||
### Q: Plan 不收敛
|
||||
A: 检查 grasp 标注质量(用 `vis_grasp.py` 可视化),确认姿态合理。调整 `filter_y_dir` / `filter_z_dir` 放宽过滤条件。
|
||||
|
||||
## 工具脚本一览
|
||||
|
||||
| 脚本 | 用途 |
|
||||
|------|------|
|
||||
| `migrate/usdc_to_obj.py` | USDC → 三角化 OBJ |
|
||||
| `migrate/repackage_test_tube.py` | 重构 USD 层级结构 |
|
||||
| `migrate/fix_test_tube_materials.py` | 修复材质绑定 |
|
||||
| `workflows/simbox/tools/grasp/gen_sparse_label.py` | 生成 grasp 标注(需 banana450) |
|
||||
| `workflows/simbox/tools/grasp/vis_grasp.py` | 可视化 grasp 标注 |
|
||||
47
migrate/fix_test_tube_materials.py
Normal file
47
migrate/fix_test_tube_materials.py
Normal file
@@ -0,0 +1,47 @@
|
||||
"""
|
||||
Fix material bindings on repackaged test tube USD.
|
||||
|
||||
The referenced meshes have bindings pointing to /Test_Tube_AA_01/Looks/...
|
||||
which is outside the reference scope. This script overrides them to
|
||||
point to /World/Looks/... instead.
|
||||
|
||||
Usage:
|
||||
python migrate/fix_test_tube_materials.py
|
||||
"""
|
||||
from pxr import Usd, UsdShade
|
||||
|
||||
USD_PATH = "workflows/simbox/example_assets/task/pick_test_tube/test_tube/Aligned_obj.usd"
|
||||
|
||||
# Mapping: mesh prim path -> material path in new structure
|
||||
MATERIAL_BINDINGS = {
|
||||
"/World/Aligned/_______005": "/World/Looks/SimPBR_Translucent",
|
||||
"/World/Aligned/tags/_______007": "/World/Looks/OmniPBR",
|
||||
"/World/Aligned/Test_Tube_lid/_______006": "/World/Looks/OmniPBR_01",
|
||||
}
|
||||
|
||||
|
||||
def fix():
|
||||
stage = Usd.Stage.Open(USD_PATH)
|
||||
|
||||
for mesh_path, mat_path in MATERIAL_BINDINGS.items():
|
||||
mesh_prim = stage.GetPrimAtPath(mesh_path)
|
||||
mat_prim = stage.GetPrimAtPath(mat_path)
|
||||
|
||||
if not mesh_prim.IsValid():
|
||||
print(f" SKIP: {mesh_path} not found")
|
||||
continue
|
||||
if not mat_prim.IsValid():
|
||||
print(f" SKIP: material {mat_path} not found")
|
||||
continue
|
||||
|
||||
mat = UsdShade.Material(mat_prim)
|
||||
UsdShade.MaterialBindingAPI.Apply(mesh_prim)
|
||||
UsdShade.MaterialBindingAPI(mesh_prim).Bind(mat)
|
||||
print(f" Bound {mesh_path} -> {mat_path}")
|
||||
|
||||
stage.GetRootLayer().Save()
|
||||
print(f"\nSaved: {USD_PATH}")
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
fix()
|
||||
159
migrate/fix_usd_metadata.py
Normal file
159
migrate/fix_usd_metadata.py
Normal file
@@ -0,0 +1,159 @@
|
||||
"""
|
||||
Batch fix USD metadata for IS 5.0.0 compatibility.
|
||||
|
||||
IS 4.5.0 auto-added 'Rotate:unitsResolve' and 'Scale:unitsResolve' xformOps
|
||||
to compensate for metersPerUnit/upAxis differences. IS 5.0.0 no longer does this,
|
||||
causing RigidObject physics to break (objects fly away).
|
||||
|
||||
Fix: Change metersPerUnit to 1.0 and upAxis to Z in USD metadata.
|
||||
Vertex data stays unchanged (already in correct scale for the scene).
|
||||
|
||||
Usage:
|
||||
# Scan only (dry run):
|
||||
python migrate/fix_usd_metadata.py --root workflows/simbox/example_assets --dry-run
|
||||
|
||||
# Fix all:
|
||||
python migrate/fix_usd_metadata.py --root workflows/simbox/example_assets
|
||||
|
||||
# Fix specific pattern:
|
||||
python migrate/fix_usd_metadata.py --root workflows/simbox/example_assets --pattern "Aligned_obj.usd"
|
||||
|
||||
# Skip specific directories (e.g. robot models, curobo assets):
|
||||
python migrate/fix_usd_metadata.py --root . --skip curobo,robot
|
||||
|
||||
# Restore from backups:
|
||||
python migrate/fix_usd_metadata.py --root workflows/simbox/example_assets --restore
|
||||
"""
|
||||
import argparse
|
||||
import glob
|
||||
import os
|
||||
import shutil
|
||||
import sys
|
||||
|
||||
from pxr import Usd, UsdGeom
|
||||
|
||||
|
||||
def fix_usd_files(root: str, pattern: str = "*.usd", target_mpu: float = 1.0,
|
||||
target_up: str = "Z", dry_run: bool = False, skip: list = None):
|
||||
usd_files = glob.glob(os.path.join(root, "**", pattern), recursive=True)
|
||||
usd_files = [f for f in usd_files if not f.endswith(".bak")]
|
||||
usd_files.sort()
|
||||
|
||||
skip = skip or []
|
||||
|
||||
print(f"Scanning {len(usd_files)} USD files under: {root}")
|
||||
if dry_run:
|
||||
print("[DRY RUN] No files will be modified.\n")
|
||||
print()
|
||||
|
||||
fixed = 0
|
||||
skipped = 0
|
||||
skipped_dir = 0
|
||||
errors = 0
|
||||
|
||||
for fpath in usd_files:
|
||||
rel = os.path.relpath(fpath, root)
|
||||
|
||||
# Check skip patterns
|
||||
if any(s in rel for s in skip):
|
||||
print(f" SKIP (dir filter): {rel}")
|
||||
skipped_dir += 1
|
||||
continue
|
||||
|
||||
try:
|
||||
stage = Usd.Stage.Open(fpath)
|
||||
if stage is None:
|
||||
print(f" ERROR: Cannot open {rel}")
|
||||
errors += 1
|
||||
continue
|
||||
|
||||
mpu = UsdGeom.GetStageMetersPerUnit(stage)
|
||||
up = UsdGeom.GetStageUpAxis(stage)
|
||||
|
||||
needs_fix = (mpu != target_mpu) or (up != target_up)
|
||||
if not needs_fix:
|
||||
print(f" OK: {rel} (mpu={mpu}, up={up})")
|
||||
skipped += 1
|
||||
continue
|
||||
|
||||
if dry_run:
|
||||
print(f" WOULD FIX: {rel} (mpu={mpu}, up={up} -> mpu={target_mpu}, up={target_up})")
|
||||
fixed += 1
|
||||
continue
|
||||
|
||||
# Backup
|
||||
bak = fpath + ".bak"
|
||||
if not os.path.exists(bak):
|
||||
shutil.copy2(fpath, bak)
|
||||
|
||||
# Fix
|
||||
UsdGeom.SetStageMetersPerUnit(stage, target_mpu)
|
||||
UsdGeom.SetStageUpAxis(stage, UsdGeom.Tokens.z if target_up == "Z" else UsdGeom.Tokens.y)
|
||||
stage.GetRootLayer().Save()
|
||||
|
||||
print(f" FIXED: {rel} (mpu={mpu}/{up} -> {target_mpu}/{target_up})")
|
||||
fixed += 1
|
||||
|
||||
except Exception as e:
|
||||
print(f" ERROR: {rel} -> {e}")
|
||||
errors += 1
|
||||
|
||||
print(f"\nDone: {fixed} {'would fix' if dry_run else 'fixed'}, {skipped} already OK, "
|
||||
f"{skipped_dir} skipped (dir filter), {errors} errors.")
|
||||
|
||||
if not dry_run and fixed > 0:
|
||||
print("Backups saved as *.bak.")
|
||||
print("To restore: python migrate/fix_usd_metadata.py --root <DIR> --restore")
|
||||
|
||||
return fixed
|
||||
|
||||
|
||||
def restore_backups(root: str, pattern: str = "*.usd"):
|
||||
bak_files = glob.glob(os.path.join(root, "**", pattern + ".bak"), recursive=True)
|
||||
bak_files.sort()
|
||||
|
||||
if not bak_files:
|
||||
print(f"No .bak files found under: {root}")
|
||||
return
|
||||
|
||||
print(f"Found {len(bak_files)} backup files. Restoring...")
|
||||
for bak in bak_files:
|
||||
original = bak[:-4] # remove .bak
|
||||
shutil.copy2(bak, original)
|
||||
print(f" Restored: {os.path.relpath(original, root)}")
|
||||
print(f"\nDone: {len(bak_files)} files restored.")
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
parser = argparse.ArgumentParser(
|
||||
description="Batch fix USD metersPerUnit/upAxis metadata for IS 5.0.0 compatibility",
|
||||
formatter_class=argparse.RawDescriptionHelpFormatter,
|
||||
epilog="""
|
||||
Examples:
|
||||
# Dry run on example assets:
|
||||
python migrate/fix_usd_metadata.py --root workflows/simbox/example_assets --dry-run
|
||||
|
||||
# Fix all Aligned_obj.usd in example assets:
|
||||
python migrate/fix_usd_metadata.py --root workflows/simbox/example_assets --pattern "Aligned_obj.usd"
|
||||
|
||||
# Fix everything except robot/curobo dirs:
|
||||
python migrate/fix_usd_metadata.py --root . --skip curobo,robot
|
||||
|
||||
# Restore all backups:
|
||||
python migrate/fix_usd_metadata.py --root workflows/simbox/example_assets --restore
|
||||
""")
|
||||
parser.add_argument("--root", default="workflows/simbox/example_assets",
|
||||
help="Root directory to scan (default: workflows/simbox/example_assets)")
|
||||
parser.add_argument("--pattern", default="*.usd", help="Filename glob pattern (default: *.usd)")
|
||||
parser.add_argument("--target-mpu", type=float, default=1.0, help="Target metersPerUnit (default: 1.0)")
|
||||
parser.add_argument("--target-up", choices=["Y", "Z"], default="Z", help="Target upAxis (default: Z)")
|
||||
parser.add_argument("--dry-run", action="store_true", help="Scan and report only, do not modify files")
|
||||
parser.add_argument("--skip", default="", help="Comma-separated dir substrings to skip (e.g. 'curobo,robot')")
|
||||
parser.add_argument("--restore", action="store_true", help="Restore all .bak files to originals")
|
||||
args = parser.parse_args()
|
||||
|
||||
if args.restore:
|
||||
restore_backups(args.root, args.pattern)
|
||||
else:
|
||||
skip_list = [s.strip() for s in args.skip.split(",") if s.strip()]
|
||||
fix_usd_files(args.root, args.pattern, args.target_mpu, args.target_up, args.dry_run, skip_list)
|
||||
51
migrate/gen_tube_grasp.py
Normal file
51
migrate/gen_tube_grasp.py
Normal file
@@ -0,0 +1,51 @@
|
||||
"""
|
||||
Generate test tube grasp annotations by adapting working bottle grasps.
|
||||
|
||||
Strategy: Load verified working bottle grasps, scale positions to match
|
||||
test tube dimensions. The rotation conventions are already correct.
|
||||
|
||||
Bottle: ~5cm radius, ~10cm height
|
||||
Test tube: ~1.5cm radius, ~10.6cm height (similar height, 3x smaller radius)
|
||||
|
||||
Usage:
|
||||
python migrate/gen_tube_grasp.py
|
||||
"""
|
||||
import numpy as np
|
||||
import os
|
||||
|
||||
BOTTLE_GRASP = "workflows/simbox/example_assets/task/sort_the_rubbish/recyclable_garbage/bottle_0/Aligned_grasp_sparse.npy"
|
||||
OUTPUT = "workflows/simbox/example_assets/task/pick_test_tube/test_tube/Aligned_grasp_sparse.npy"
|
||||
|
||||
|
||||
def main():
|
||||
# Load working bottle grasps
|
||||
bottle = np.load(BOTTLE_GRASP)
|
||||
print(f"Loaded {len(bottle)} bottle grasps")
|
||||
print(f"Bottle pos range: X[{bottle[:,13].min():.4f},{bottle[:,13].max():.4f}] "
|
||||
f"Y[{bottle[:,14].min():.4f},{bottle[:,14].max():.4f}] "
|
||||
f"Z[{bottle[:,15].min():.4f},{bottle[:,15].max():.4f}]")
|
||||
|
||||
tube = bottle.copy()
|
||||
|
||||
# Scale XY positions (radius: bottle ~3cm -> tube ~1.5cm, factor ~0.5)
|
||||
# Keep Z positions similar (both ~10cm height)
|
||||
xy_scale = 0.5
|
||||
tube[:, 13] *= xy_scale # X position
|
||||
tube[:, 14] *= xy_scale # Y position
|
||||
# Z positions stay the same (similar height)
|
||||
|
||||
# Reduce gripper width for smaller object
|
||||
# Bottle width: 0.044-0.10, Tube needs: 0.02-0.06
|
||||
tube[:, 1] = np.clip(tube[:, 1] * 0.6, 0.02, 0.06)
|
||||
|
||||
print(f"\nTube pos range: X[{tube[:,13].min():.4f},{tube[:,13].max():.4f}] "
|
||||
f"Y[{tube[:,14].min():.4f},{tube[:,14].max():.4f}] "
|
||||
f"Z[{tube[:,15].min():.4f},{tube[:,15].max():.4f}]")
|
||||
print(f"Tube width range: [{tube[:,1].min():.3f},{tube[:,1].max():.3f}]")
|
||||
|
||||
np.save(OUTPUT, tube)
|
||||
print(f"\nSaved {len(tube)} grasps to: {OUTPUT}")
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
main()
|
||||
199
migrate/migrate.md
Normal file
199
migrate/migrate.md
Normal file
@@ -0,0 +1,199 @@
|
||||
# Isaac Sim 4.5.0 -> 5.0.0 Migration Guide
|
||||
|
||||
## Background
|
||||
|
||||
- GPU: NVIDIA RTX PRO 6000 Blackwell (SM_120, compute capability 12.0)
|
||||
- IS 4.5.0 = Kit 106.5.0, DLSS Ray Reconstruction not supported on Blackwell (needs Kit >= 106.5.3), rendering has noise
|
||||
- IS 5.0.0 = Kit 107.x, fixes Blackwell rendering noise
|
||||
- IS 5.1.0 headless camera rendering completely broken (known bug GitHub #3250), abandoned
|
||||
|
||||
## Issues & Solutions
|
||||
|
||||
### 1. SimulationApp import path changed
|
||||
|
||||
**Error:** `ModuleNotFoundError: No module named 'omni.isaac.kit'`
|
||||
|
||||
**Cause:** IS 5.x changed the import path.
|
||||
|
||||
**Fix** (`nimbus_extension/components/load/env_loader.py`):
|
||||
```python
|
||||
try:
|
||||
from isaacsim import SimulationApp # IS 5.x
|
||||
except ImportError:
|
||||
from omni.isaac.kit import SimulationApp # IS 4.x
|
||||
```
|
||||
|
||||
### 2. USD metersPerUnit / upAxis not auto-compensated
|
||||
|
||||
**Error:** RigidObject Z coordinate flying to 109.75+ after `world.reset()`, curobo `plan_single()` fails with "Plan did not converge" (goal_pos Z = 25261 meters).
|
||||
|
||||
**Cause:** IS 4.5.0 auto-added `Rotate:unitsResolve` (X=90) and `Scale:unitsResolve` (0.01, 0.01, 0.01) xformOps to compensate for USD files with `metersPerUnit=0.01, upAxis=Y`. IS 5.0.0 no longer does this, causing PhysX to misinterpret RigidObject positions.
|
||||
|
||||
GeometryObjects (no physics) were unaffected — only RigidObjects with PhysX simulation had the issue.
|
||||
|
||||
**Fix:** Change USD metadata directly using pxr scripting. Run `fix_usd_metadata.py`:
|
||||
```python
|
||||
from pxr import Usd, UsdGeom
|
||||
stage = Usd.Stage.Open(usd_path)
|
||||
UsdGeom.SetStageMetersPerUnit(stage, 1.0) # was 0.01
|
||||
UsdGeom.SetStageUpAxis(stage, UsdGeom.Tokens.z) # was Y
|
||||
stage.GetRootLayer().Save()
|
||||
```
|
||||
|
||||
All 14 `Aligned_obj.usd` files under `workflows/simbox/example_assets` have been batch-fixed. Backups saved as `.bak`.
|
||||
|
||||
**Verification:** After fix, pick_object_right Z went from 109.75 to 0.7968 (normal).
|
||||
|
||||
### 3. scipy `scalar_first` parameter not supported
|
||||
|
||||
**Error:** `Rotation.as_quat() takes no keyword arguments`
|
||||
|
||||
**Cause:** IS 5.0.0 ships scipy < 1.11 which doesn't support `scalar_first` parameter in `Rotation.from_quat()` / `Rotation.as_quat()`. Dozens of files use this parameter.
|
||||
|
||||
**Fix** (`launcher.py`): Monkey-patch via subclass at startup:
|
||||
```python
|
||||
try:
|
||||
from scipy.spatial.transform import Rotation as _R
|
||||
_R.from_quat([1, 0, 0, 0], scalar_first=True)
|
||||
except TypeError:
|
||||
# Install Rotation subclass that handles scalar_first
|
||||
# See launcher.py for full implementation
|
||||
pass
|
||||
```
|
||||
|
||||
### 4. `arena_file_path` is None on second reset
|
||||
|
||||
**Error:** `arena_file_path` becomes None after first episode.
|
||||
|
||||
**Cause:** `self.task_cfg.pop("arena_file", None)` on line 107 of `simbox_dual_workflow.py` deletes the key after first use.
|
||||
|
||||
**Fix** (`workflows/simbox_dual_workflow.py`): Cache the value:
|
||||
```python
|
||||
self._arena_file_path = None # in __init__
|
||||
|
||||
# in reset():
|
||||
arena_file_path = self.task_cfg.get("arena_file", None) or self._arena_file_path
|
||||
if arena_file_path:
|
||||
self._arena_file_path = arena_file_path
|
||||
```
|
||||
|
||||
### 5. "Task name should be unique in the world"
|
||||
|
||||
**Error:** `AssertionError` when calling `world.add_task()` on second episode.
|
||||
|
||||
**Cause:** World retains tasks from previous episode.
|
||||
|
||||
**Fix** (`workflows/simbox_dual_workflow.py`):
|
||||
```python
|
||||
self.world._current_tasks.clear()
|
||||
self.world.add_task(self.task)
|
||||
```
|
||||
|
||||
### 6. "A prim already exists at prim path"
|
||||
|
||||
**Error:** Scene setup tries to re-create existing prims on repeated `world.reset()` calls.
|
||||
|
||||
**Fix** (`workflows/simbox/core/tasks/banana.py`): Add `_scene_initialized` guard:
|
||||
```python
|
||||
def set_up_scene(self, scene):
|
||||
if getattr(self, '_scene_initialized', False):
|
||||
self._task_objects = {}
|
||||
self._task_objects |= (
|
||||
getattr(self, 'fixtures', {}) |
|
||||
getattr(self, 'objects', {}) |
|
||||
getattr(self, 'robots', {}) |
|
||||
getattr(self, 'cameras', {})
|
||||
)
|
||||
return
|
||||
self._scene_initialized = True
|
||||
super().set_up_scene(scene)
|
||||
```
|
||||
|
||||
### 7. Collision group prim already exists
|
||||
|
||||
**Error:** Collision group prims persist across resets.
|
||||
|
||||
**Fix** (`workflows/simbox/core/utils/collision_utils.py`): Remove existing collision prims before re-creating:
|
||||
```python
|
||||
collision_prim = stage.GetPrimAtPath(collision_root_path)
|
||||
if collision_prim.IsValid():
|
||||
stage.RemovePrim(collision_root_path)
|
||||
```
|
||||
|
||||
### 8. DomeLight environment map tilted
|
||||
|
||||
**Error:** HDR environment map appears rotated/tilted in viewport and rendered output.
|
||||
|
||||
**Cause:** DomeLight rotation was randomized on all 3 axes (X, Y, Z). Rotating X/Y tilts the environment.
|
||||
|
||||
**Fix** (`workflows/simbox/core/tasks/banana.py`): Only rotate Z axis:
|
||||
```python
|
||||
# Before:
|
||||
rotation = [random.uniform(r[0], r[1]) for _ in range(3)]
|
||||
# After:
|
||||
rotation = [0.0, 0.0, random.uniform(r[0], r[1])]
|
||||
```
|
||||
|
||||
## Files Modified
|
||||
|
||||
| File | Change |
|
||||
|------|--------|
|
||||
| `nimbus_extension/components/load/env_loader.py` | SimulationApp import compatibility |
|
||||
| `launcher.py` | scipy Rotation monkey-patch |
|
||||
| `workflows/simbox_dual_workflow.py` | arena_file caching, task clearing, task reuse |
|
||||
| `workflows/simbox/core/tasks/banana.py` | Scene re-init guard, DomeLight rotation fix |
|
||||
| `workflows/simbox/core/utils/collision_utils.py` | Collision group cleanup |
|
||||
| `workflows/simbox/example_assets/**/Aligned_obj.usd` | metersPerUnit=1.0, upAxis=Z |
|
||||
| `fix_usd_metadata.py` | Batch USD metadata fix script |
|
||||
|
||||
## Tools
|
||||
|
||||
Migration tools are located in the `migrate/` directory.
|
||||
|
||||
### scan_usd_metadata.py — Scan USD metadata
|
||||
|
||||
Scan all USD files and report their `metersPerUnit` / `upAxis`:
|
||||
|
||||
```bash
|
||||
conda activate banana500
|
||||
|
||||
# Scan entire project
|
||||
python migrate/scan_usd_metadata.py --root .
|
||||
|
||||
# Scan specific directory
|
||||
python migrate/scan_usd_metadata.py --root workflows/simbox/example_assets
|
||||
```
|
||||
|
||||
Exit code: 0 = all OK, 1 = found files with non-standard metadata.
|
||||
建议扫描后丢给大模型分析一下然后再做下一步
|
||||
### fix_usd_metadata.py — Batch fix USD metadata
|
||||
|
||||
Fix `metersPerUnit` and `upAxis` in USD files, with backup/restore support:
|
||||
|
||||
```bash
|
||||
conda activate banana500
|
||||
|
||||
# Dry run — see what would be fixed, no changes made
|
||||
python migrate/fix_usd_metadata.py --root . --dry-run --skip curobo,robot
|
||||
|
||||
# Fix example assets only (default)
|
||||
python migrate/fix_usd_metadata.py --root workflows/simbox/example_assets
|
||||
|
||||
# Fix all USD in project, skip robot/curobo models
|
||||
python migrate/fix_usd_metadata.py --root . --skip curobo,robot
|
||||
|
||||
# Fix only Aligned_obj.usd files
|
||||
python migrate/fix_usd_metadata.py --root . --pattern "Aligned_obj.usd"
|
||||
|
||||
# Restore from backups (undo all fixes)
|
||||
python migrate/fix_usd_metadata.py --root workflows/simbox/example_assets --restore
|
||||
```
|
||||
|
||||
**Important:** Do NOT fix robot USD (curobo, split_aloha) — their metersPerUnit/upAxis are intentionally set for their own coordinate systems. Use `--skip` to exclude them.
|
||||
|
||||
## Notes
|
||||
|
||||
- `plan_single()` occasionally returns None for edge-case target poses (workspace boundary). This is normal and happens in IS 4.5.0 too.
|
||||
- Example HDR is only 1k resolution — production should use 4k/8k for better background quality.
|
||||
- Example `envmap_lib` only has 1 HDR file — add more for randomization diversity.
|
||||
- `non_recyclable_garbage/obj_0` does not exist in example assets (only obj_1~obj_11). Config changed to use `obj_1`.
|
||||
177
migrate/migrate_imports.py
Normal file
177
migrate/migrate_imports.py
Normal file
@@ -0,0 +1,177 @@
|
||||
"""
|
||||
Batch migrate omni.isaac.* imports to use core.compat module.
|
||||
|
||||
Usage:
|
||||
python migrate/migrate_imports.py --dry-run # preview changes
|
||||
python migrate/migrate_imports.py # apply changes
|
||||
"""
|
||||
import argparse
|
||||
import os
|
||||
import re
|
||||
|
||||
# Files to process (relative to project root)
|
||||
SCAN_DIRS = [
|
||||
"workflows/simbox/core/cameras",
|
||||
"workflows/simbox/core/controllers",
|
||||
"workflows/simbox/core/objects",
|
||||
"workflows/simbox/core/robots",
|
||||
"workflows/simbox/core/skills",
|
||||
"workflows/simbox/core/tasks",
|
||||
"workflows/simbox/core/utils",
|
||||
"workflows/simbox/solver",
|
||||
"workflows/", # simbox_dual_workflow.py
|
||||
"nimbus_extension/components/load",
|
||||
]
|
||||
|
||||
# Skip these files/dirs
|
||||
SKIP = ["curobo", "__pycache__", "compat.py", "tools/art"]
|
||||
|
||||
# Mapping: old import pattern -> compat import
|
||||
# Format: (regex_pattern, replacement_imports_from_compat)
|
||||
IMPORT_MAP = {
|
||||
# Full module imports
|
||||
r"from omni\.isaac\.core import World": "from core.compat import World",
|
||||
r"from omni\.isaac\.core\.controllers import BaseController": "from core.compat import BaseController",
|
||||
r"from omni\.isaac\.core\.tasks import BaseTask": "from core.compat import BaseTask",
|
||||
r"from omni\.isaac\.core\.robots\.robot import Robot": "from core.compat import Robot",
|
||||
r"from omni\.isaac\.core\.robots import Robot": "from core.compat import Robot",
|
||||
r"from omni\.isaac\.core\.prims import XFormPrim": "from core.compat import XFormPrim",
|
||||
r"from omni\.isaac\.core\.prims import RigidPrim": "from core.compat import RigidPrim",
|
||||
r"from omni\.isaac\.core\.prims import GeometryPrim": "from core.compat import GeometryPrim",
|
||||
r"from omni\.isaac\.core\.prims import RigidContactView": "from core.compat import RigidContactView",
|
||||
r"from omni\.isaac\.core\.prims import RigidContactView, XFormPrim": "from core.compat import RigidContactView, XFormPrim",
|
||||
r"from omni\.isaac\.core\.articulations\.articulation import Articulation": "from core.compat import Articulation",
|
||||
r"from omni\.isaac\.core\.objects\.cylinder import VisualCylinder": "from core.compat import VisualCylinder",
|
||||
r"from omni\.isaac\.core\.objects import cuboid, sphere": "from core.compat import cuboid, sphere",
|
||||
r"from omni\.isaac\.core\.objects import cuboid": "from core.compat import cuboid",
|
||||
r"from omni\.isaac\.core\.objects import sphere": "from core.compat import sphere",
|
||||
r"from omni\.isaac\.core\.materials import PreviewSurface": "from core.compat import PreviewSurface",
|
||||
r"from omni\.isaac\.core\.materials import OmniPBR": "from core.compat import OmniPBR",
|
||||
r"from omni\.isaac\.core\.materials\.omni_pbr import OmniPBR.*": "from core.compat import OmniPBR",
|
||||
r"from omni\.isaac\.core\.materials import OmniGlass, OmniPBR": "from core.compat import OmniGlass, OmniPBR",
|
||||
r"from omni\.isaac\.core\.materials import OmniGlass": "from core.compat import OmniGlass",
|
||||
r"from omni\.isaac\.core\.scenes\.scene import Scene": "from core.compat import Scene",
|
||||
r"from omni\.isaac\.sensor import Camera": "from core.compat import Camera",
|
||||
|
||||
# Utils
|
||||
r"from omni\.isaac\.core\.utils\.prims import get_prim_at_path\b(?!,)": "from core.compat import get_prim_at_path",
|
||||
r"from omni\.isaac\.core\.utils\.prims import create_prim, get_prim_at_path": "from core.compat import create_prim, get_prim_at_path",
|
||||
r"from omni\.isaac\.core\.utils\.prims import create_prim, is_prim_path_valid": "from core.compat import create_prim, is_prim_path_valid",
|
||||
r"from omni\.isaac\.core\.utils\.prims import is_prim_path_valid": "from core.compat import is_prim_path_valid",
|
||||
r"from omni\.isaac\.core\.utils\.prims import create_prim\b": "from core.compat import create_prim",
|
||||
r"from omni\.isaac\.core\.utils\.transformations import get_relative_transform\b(?!,)": "from core.compat import get_relative_transform",
|
||||
r"from omni\.isaac\.core\.utils\.transformations import pose_from_tf_matrix": "from core.compat import pose_from_tf_matrix",
|
||||
r"from omni\.isaac\.core\.utils\.stage import get_current_stage": "from core.compat import get_current_stage",
|
||||
r"from omni\.isaac\.core\.utils\.stage import add_reference_to_stage": "from core.compat import add_reference_to_stage",
|
||||
r"from omni\.isaac\.core\.utils\.stage import get_stage_units": "from core.compat import get_stage_units",
|
||||
r"from omni\.isaac\.core\.utils\.xforms import get_world_pose": "from core.compat import get_world_pose",
|
||||
r"from omni\.isaac\.core\.utils\.types import ArticulationAction": "from core.compat import ArticulationAction",
|
||||
r"from omni\.isaac\.core\.utils\.viewports import set_camera_view": "from core.compat import set_camera_view",
|
||||
r"from omni\.isaac\.core\.utils\.semantics import add_update_semantics": "from core.compat import add_update_semantics",
|
||||
r"from omni\.isaac\.core\.utils\.string import find_unique_string_name": "from core.compat import find_unique_string_name",
|
||||
r"from omni\.isaac\.core\.utils\.extensions import enable_extension": "from core.compat import enable_extension",
|
||||
r"from omni\.isaac\.core\.utils\.nucleus import get_assets_root_path as nucleus_path": "from core.compat import nucleus_path",
|
||||
}
|
||||
|
||||
# Multi-line import blocks that need special handling
|
||||
MULTILINE_PATTERNS = [
|
||||
# get_relative_transform, pose_from_tf_matrix block
|
||||
(
|
||||
r"from omni\.isaac\.core\.utils\.transformations import \(\s*\n\s*get_relative_transform,\s*\n\s*pose_from_tf_matrix,?\s*\n\s*\)",
|
||||
"from core.compat import get_relative_transform, pose_from_tf_matrix",
|
||||
),
|
||||
# prims multi-import blocks
|
||||
(
|
||||
r"from omni\.isaac\.core\.utils\.prims import \(\s*\n\s*get_prim_at_path,\s*\n\s*create_prim,\s*\n\s*is_prim_path_valid,?\s*\n\s*\)",
|
||||
"from core.compat import get_prim_at_path, create_prim, is_prim_path_valid",
|
||||
),
|
||||
(
|
||||
r"from omni\.isaac\.core\.utils\.prims import \(\s*\n[^)]+\)",
|
||||
None, # skip complex blocks, handle manually
|
||||
),
|
||||
]
|
||||
|
||||
|
||||
def should_skip(filepath):
|
||||
for s in SKIP:
|
||||
if s in filepath:
|
||||
return True
|
||||
return False
|
||||
|
||||
|
||||
def migrate_file(filepath, dry_run=False):
|
||||
with open(filepath, "r") as f:
|
||||
content = f.read()
|
||||
|
||||
original = content
|
||||
changes = []
|
||||
|
||||
# Handle multi-line imports first
|
||||
for pattern, replacement in MULTILINE_PATTERNS:
|
||||
if replacement is None:
|
||||
continue
|
||||
matches = list(re.finditer(pattern, content))
|
||||
for m in matches:
|
||||
changes.append(f" MULTI: {m.group()[:60]}... -> {replacement}")
|
||||
content = re.sub(pattern, replacement, content)
|
||||
|
||||
# Handle single-line imports
|
||||
for pattern, replacement in IMPORT_MAP.items():
|
||||
matches = list(re.finditer(pattern, content))
|
||||
for m in matches:
|
||||
changes.append(f" {m.group().strip()} -> {replacement}")
|
||||
content = re.sub(pattern, replacement, content)
|
||||
|
||||
if content != original:
|
||||
if not dry_run:
|
||||
with open(filepath, "w") as f:
|
||||
f.write(content)
|
||||
return changes
|
||||
return []
|
||||
|
||||
|
||||
def main():
|
||||
parser = argparse.ArgumentParser(description="Migrate omni.isaac imports to core.compat")
|
||||
parser.add_argument("--dry-run", action="store_true", help="Preview changes without modifying files")
|
||||
parser.add_argument("--root", default=".", help="Project root directory")
|
||||
args = parser.parse_args()
|
||||
|
||||
total_files = 0
|
||||
total_changes = 0
|
||||
|
||||
for scan_dir in SCAN_DIRS:
|
||||
full_dir = os.path.join(args.root, scan_dir)
|
||||
if not os.path.exists(full_dir):
|
||||
continue
|
||||
|
||||
if os.path.isfile(full_dir):
|
||||
files = [full_dir]
|
||||
else:
|
||||
files = []
|
||||
for root, dirs, filenames in os.walk(full_dir):
|
||||
for fn in filenames:
|
||||
if fn.endswith(".py"):
|
||||
files.append(os.path.join(root, fn))
|
||||
|
||||
for filepath in sorted(files):
|
||||
if should_skip(filepath):
|
||||
continue
|
||||
|
||||
rel = os.path.relpath(filepath, args.root)
|
||||
changes = migrate_file(filepath, args.dry_run)
|
||||
if changes:
|
||||
total_files += 1
|
||||
total_changes += len(changes)
|
||||
print(f"\n{rel}:")
|
||||
for c in changes:
|
||||
print(c)
|
||||
|
||||
action = "would change" if args.dry_run else "changed"
|
||||
print(f"\n{'='*60}")
|
||||
print(f"Done: {total_changes} imports {action} in {total_files} files.")
|
||||
if args.dry_run:
|
||||
print("Run without --dry-run to apply changes.")
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
main()
|
||||
140
migrate/repackage_test_tube.py
Normal file
140
migrate/repackage_test_tube.py
Normal file
@@ -0,0 +1,140 @@
|
||||
"""
|
||||
Repackage test tube USD to match InternDataEngine's expected format.
|
||||
|
||||
Target structure (same as Aligned_obj.usd):
|
||||
/World (Xform, defaultPrim, NO physics schemas)
|
||||
/Looks (Scope) - materials referenced from source
|
||||
/Aligned (Xform) - PhysicsRigidBodyAPI, PhysicsMassAPI
|
||||
/mesh (first child mesh, PhysicsCollisionAPI)
|
||||
/PhysicsMaterial (Material, PhysicsMaterialAPI)
|
||||
|
||||
Strategy:
|
||||
- /World is a clean Xform (no reference, no inherited schemas)
|
||||
- /World/Aligned references /Test_Tube_AA_01/Test_Tube from source
|
||||
- /World/Looks references /Test_Tube_AA_01/Looks from source
|
||||
- Physics applied as overrides on /World/Aligned
|
||||
|
||||
Usage:
|
||||
python migrate/repackage_test_tube.py
|
||||
"""
|
||||
from pxr import Usd, UsdGeom, UsdPhysics, UsdShade, Sdf, Gf
|
||||
import os
|
||||
|
||||
SRC_PATH = os.path.abspath(
|
||||
"/home/tangger/LYT/maic_usd_assets_moudle/laboratory_equipment/Test_Tube/Test_Tube_AA_01.usdc"
|
||||
)
|
||||
DST_DIR = "workflows/simbox/example_assets/task/pick_test_tube/test_tube"
|
||||
DST_PATH = os.path.join(DST_DIR, "Aligned_obj.usd")
|
||||
|
||||
|
||||
def repackage():
|
||||
# Read source to understand structure
|
||||
src_stage = Usd.Stage.Open(SRC_PATH)
|
||||
src_dp = src_stage.GetDefaultPrim()
|
||||
print(f"Source: {SRC_PATH}")
|
||||
print(f"Source defaultPrim: {src_dp.GetPath()}")
|
||||
|
||||
# Remove old output
|
||||
if os.path.exists(DST_PATH):
|
||||
os.remove(DST_PATH)
|
||||
|
||||
# Create new stage
|
||||
dst_stage = Usd.Stage.CreateNew(DST_PATH)
|
||||
UsdGeom.SetStageMetersPerUnit(dst_stage, 1.0)
|
||||
UsdGeom.SetStageUpAxis(dst_stage, UsdGeom.Tokens.z)
|
||||
|
||||
# --- /World: clean Xform, no reference, no inherited schemas ---
|
||||
world_xform = UsdGeom.Xform.Define(dst_stage, "/World")
|
||||
dst_stage.SetDefaultPrim(world_xform.GetPrim())
|
||||
|
||||
# --- /World/Aligned: reference Test_Tube child from source ---
|
||||
aligned_xform = UsdGeom.Xform.Define(dst_stage, "/World/Aligned")
|
||||
aligned_prim = aligned_xform.GetPrim()
|
||||
aligned_prim.GetReferences().AddReference(
|
||||
SRC_PATH,
|
||||
f"{src_dp.GetPath()}/Test_Tube"
|
||||
)
|
||||
# Add RigidBody physics
|
||||
UsdPhysics.RigidBodyAPI.Apply(aligned_prim)
|
||||
mass_api = UsdPhysics.MassAPI.Apply(aligned_prim)
|
||||
mass_api.GetMassAttr().Set(0.005)
|
||||
print("Created /World/Aligned with RigidBodyAPI + MassAPI (0.005 kg)")
|
||||
|
||||
# Set collision approximation on mesh children
|
||||
for child_prim in aligned_prim.GetAllChildren():
|
||||
if child_prim.HasAPI(UsdPhysics.CollisionAPI):
|
||||
mesh_api = UsdPhysics.MeshCollisionAPI(child_prim)
|
||||
if mesh_api:
|
||||
mesh_api.GetApproximationAttr().Set("convexHull")
|
||||
print(f" Set convexHull on {child_prim.GetPath()}")
|
||||
|
||||
# --- /World/Looks: reference Looks from source ---
|
||||
looks_prim = dst_stage.DefinePrim("/World/Looks", "Scope")
|
||||
looks_prim.GetReferences().AddReference(
|
||||
SRC_PATH,
|
||||
f"{src_dp.GetPath()}/Looks"
|
||||
)
|
||||
print("Created /World/Looks referencing source materials")
|
||||
|
||||
# --- Fix material bindings: remap from source paths to new paths ---
|
||||
# Source materials are at /Test_Tube_AA_01/Looks/XXX
|
||||
# In our new stage they are at /World/Looks/XXX
|
||||
# The mesh bindings from the reference point to /Test_Tube_AA_01/Looks/XXX
|
||||
# which is outside scope. We need to override the bindings.
|
||||
src_material_map = {
|
||||
"SimPBR_Translucent": "/World/Looks/SimPBR_Translucent",
|
||||
"OmniPBR": "/World/Looks/OmniPBR",
|
||||
"OmniPBR_01": "/World/Looks/OmniPBR_01",
|
||||
}
|
||||
|
||||
# Find all mesh prims under /World/Aligned and rebind materials
|
||||
for prim in dst_stage.Traverse():
|
||||
if not str(prim.GetPath()).startswith("/World/Aligned"):
|
||||
continue
|
||||
binding = UsdShade.MaterialBindingAPI(prim)
|
||||
if not binding:
|
||||
continue
|
||||
# Check if there's a direct binding
|
||||
mat_path_rel = binding.GetDirectBinding().GetMaterialPath()
|
||||
if mat_path_rel and str(mat_path_rel) != "":
|
||||
mat_name = str(mat_path_rel).split("/")[-1]
|
||||
if mat_name in src_material_map:
|
||||
new_mat_path = src_material_map[mat_name]
|
||||
new_mat = UsdShade.Material(dst_stage.GetPrimAtPath(new_mat_path))
|
||||
if new_mat:
|
||||
UsdShade.MaterialBindingAPI.Apply(prim)
|
||||
UsdShade.MaterialBindingAPI(prim).Bind(new_mat)
|
||||
print(f" Rebound material on {prim.GetPath()} -> {new_mat_path}")
|
||||
|
||||
# --- /World/PhysicsMaterial ---
|
||||
phys_mat_prim = dst_stage.DefinePrim("/World/PhysicsMaterial", "Material")
|
||||
UsdPhysics.MaterialAPI.Apply(phys_mat_prim)
|
||||
phys_mat = UsdPhysics.MaterialAPI(phys_mat_prim)
|
||||
phys_mat.GetStaticFrictionAttr().Set(0.5)
|
||||
phys_mat.GetDynamicFrictionAttr().Set(0.5)
|
||||
phys_mat.GetRestitutionAttr().Set(0.1)
|
||||
print("Created /World/PhysicsMaterial")
|
||||
|
||||
# Save
|
||||
dst_stage.GetRootLayer().Save()
|
||||
print(f"\nSaved: {DST_PATH}")
|
||||
|
||||
# --- Verify ---
|
||||
print(f"\n{'='*60}")
|
||||
print("Verification:")
|
||||
print(f"{'='*60}")
|
||||
v_stage = Usd.Stage.Open(DST_PATH)
|
||||
dp = v_stage.GetDefaultPrim()
|
||||
print(f"DefaultPrim: {dp.GetPath()}")
|
||||
print(f" Type: {dp.GetTypeName()}")
|
||||
print(f" Schemas: {dp.GetAppliedSchemas()}")
|
||||
for c in dp.GetChildren():
|
||||
print(f" /{c.GetName()} [{c.GetTypeName()}] schemas={c.GetAppliedSchemas()}")
|
||||
for gc in c.GetAllChildren():
|
||||
schemas = gc.GetAppliedSchemas()
|
||||
s = f" schemas={schemas}" if schemas else ""
|
||||
print(f" /{gc.GetName()} [{gc.GetTypeName()}]{s}")
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
repackage()
|
||||
222
migrate/runtime_warnings.md
Normal file
222
migrate/runtime_warnings.md
Normal file
@@ -0,0 +1,222 @@
|
||||
# Runtime Warnings & Errors Analysis
|
||||
|
||||
Pipeline: `python launcher.py --config configs/simbox/de_plan_and_render_template.yaml`
|
||||
Environment: IS 5.0.0, RTX PRO 6000 Blackwell, conda `banana500`
|
||||
Date: 2026-04-03
|
||||
|
||||
---
|
||||
|
||||
## Errors
|
||||
|
||||
### 1. PhysicsUSD: triangle mesh collision on dynamic body
|
||||
|
||||
```
|
||||
[Error] PhysicsUSD: Parse collision - triangle mesh collision (approximation None/MeshSimplification)
|
||||
cannot be a part of a dynamic body, falling back to convexHull approximation:
|
||||
/World/task_0/split_aloha/.../lifting_link/collisions
|
||||
```
|
||||
|
||||
**Severity:** Medium (PhysX auto-fallback, but logs error every reset)
|
||||
**Root cause:** Robot USD `lifting_link/collisions` mesh 使用 `meshSimplification` 碰撞近似,PhysX 不支持动态物体使用 triangle mesh collision。
|
||||
**Fix:** 修改 robot USD 将 `MeshCollisionAPI.approximation` 从 `meshSimplification` 改为 `convexHull`。
|
||||
|
||||
```python
|
||||
from pxr import Usd, UsdPhysics
|
||||
stage = Usd.Stage.Open('workflows/simbox/example_assets/split_aloha_mid_360/robot.usd')
|
||||
prim = stage.GetPrimAtPath('/Root/.../lifting_link/collisions')
|
||||
UsdPhysics.MeshCollisionAPI(prim).GetApproximationAttr().Set('convexHull')
|
||||
stage.GetRootLayer().Save()
|
||||
```
|
||||
|
||||
**Status:** FIXED. Backup: `robot.usd.bak`
|
||||
|
||||
---
|
||||
|
||||
### 2. Physics scenes stepping mismatch
|
||||
|
||||
```
|
||||
[Error] Physics scenes stepping is not the same, step subscription will be send with later step,
|
||||
per scene step is not yet supported.
|
||||
```
|
||||
|
||||
**Severity:** Low (仅首次 reset 时出现一次)
|
||||
**Root cause:** IS 5.0.0 内部 physics scene 步进调度问题。physics_dt 和 rendering_dt 均为 1/30,配置一致。
|
||||
**Status:** IGNORED. IS 内部行为,不影响仿真结果。
|
||||
|
||||
---
|
||||
|
||||
## Warnings — Fixed
|
||||
|
||||
### 3. Camera aperture inconsistent with resolution
|
||||
|
||||
```
|
||||
[Warning] 'verticalAperture' (1.529) and 'horizontalAperture' (2.095) are inconsistent with
|
||||
the pixel resolution aspect ratio (1.333). Setting 'verticalAperture' to 1.572 to ensure square pixels.
|
||||
```
|
||||
|
||||
**Severity:** Low (IS 自动修正,但每个相机打 2 条 warning)
|
||||
**Root cause:** `custom_camera.py` 在 `self.initialize()` 之后才设置 aperture/focal_length,但 `initialize()` 时就用默认 aperture 做一致性检查。
|
||||
**Fix:** 重构 `custom_camera.py`,将 aperture/focal_length 设置移到 `initialize()` 之前。
|
||||
|
||||
```python
|
||||
# Before (wrong order):
|
||||
super().__init__(...)
|
||||
self.initialize() # <-- checks aperture here with default values
|
||||
# ... later ...
|
||||
self.set_horizontal_aperture(...) # too late, warning already printed
|
||||
|
||||
# After (correct order):
|
||||
super().__init__(...)
|
||||
self.set_horizontal_aperture(...) # set aperture first
|
||||
self.set_vertical_aperture(...)
|
||||
self.set_focal_length(...)
|
||||
self.initialize() # now checks with correct values
|
||||
```
|
||||
|
||||
**Status:** FIXED in `workflows/simbox/core/cameras/custom_camera.py`
|
||||
|
||||
---
|
||||
|
||||
### 4. Camera.set_projection_type deprecated
|
||||
|
||||
```
|
||||
[Warning] Camera.set_projection_type is deprecated and will be removed in a future release.
|
||||
Please use Camera.set_lens_distortion_model instead.
|
||||
```
|
||||
|
||||
**Severity:** Low
|
||||
**Fix:** 替换 API 调用,带 fallback 兼容旧版本。
|
||||
|
||||
```python
|
||||
# Before:
|
||||
self.set_projection_type("pinhole")
|
||||
# After:
|
||||
try:
|
||||
self.set_lens_distortion_model("pinhole")
|
||||
except AttributeError:
|
||||
self.set_projection_type("pinhole")
|
||||
```
|
||||
|
||||
**Status:** FIXED in `workflows/simbox/core/cameras/custom_camera.py`
|
||||
|
||||
---
|
||||
|
||||
## Warnings — Requires Manual Action
|
||||
|
||||
### 5. CPU powersave mode
|
||||
|
||||
```
|
||||
[Warning] CPU performance profile is set to powersave. This profile sets the CPU to the
|
||||
lowest frequency reducing performance.
|
||||
```
|
||||
|
||||
**Severity:** Medium (影响整体性能)
|
||||
**Fix:** 需要 sudo 权限手动设置。
|
||||
|
||||
```bash
|
||||
# 临时切换到 performance 模式 (重启后恢复)
|
||||
echo performance | sudo tee /sys/devices/system/cpu/cpu*/cpufreq/scaling_governor
|
||||
|
||||
# 永久设置 (Ubuntu)
|
||||
sudo apt install cpufrequtils
|
||||
echo 'GOVERNOR="performance"' | sudo tee /etc/default/cpufrequtils
|
||||
sudo systemctl restart cpufrequtils
|
||||
```
|
||||
|
||||
**Status:** MANUAL. 需要用户自行设置。
|
||||
|
||||
---
|
||||
|
||||
## Warnings — Ignored (Safe)
|
||||
|
||||
### 6. IS 5.0 API deprecation warnings (~100 条)
|
||||
|
||||
```
|
||||
[Warning] omni.isaac.core has been deprecated in favor of isaacsim.core.api.
|
||||
Please update your code accordingly.
|
||||
```
|
||||
|
||||
**Severity:** None
|
||||
**说明:** IS 5.0 对所有 `omni.isaac.*` 模块重命名为 `isaacsim.*`。旧 API 仍然可用,仅打印 deprecation 提示。不影响功能,无需修改。如果将来升级到 IS 6.x 可能需要迁移。
|
||||
|
||||
---
|
||||
|
||||
### 7. Curobo warp cache warnings
|
||||
|
||||
```
|
||||
[Warning] [curobo] Object already in warp cache, using existing instance for:
|
||||
/World/task_0/pick_object_left/Aligned/mesh
|
||||
```
|
||||
|
||||
**Severity:** None
|
||||
**说明:** Curobo 内部 warp kernel 缓存机制。同一 mesh 在多次 world update 中被重复加载时复用缓存。完全正常,无害。
|
||||
|
||||
---
|
||||
|
||||
### 8. Robot dummy_base inertia tensor warnings
|
||||
|
||||
```
|
||||
[Warning] The rigid body at .../dummy_base_rotate has a possibly invalid inertia tensor of
|
||||
{1.0, 1.0, 1.0} and a negative mass, small sphere approximated inertia was used.
|
||||
```
|
||||
|
||||
**Severity:** None
|
||||
**说明:** Robot USD 中 `dummy_base_rotate/x/y` 是虚拟关节(用于全局位移),不需要真实质量属性。PhysX 自动使用球体近似惯性张量,功能正常。
|
||||
|
||||
---
|
||||
|
||||
### 9. Table mesh corrupted normal primvar
|
||||
|
||||
```
|
||||
[Warning] Mesh '/World/task_0/table/Instance/Group_default_00/SM_08_component6_0' has corrupted
|
||||
data in primvar 'normal': buffer size 14880 doesn't match expected size 2482
|
||||
```
|
||||
|
||||
**Severity:** Low
|
||||
**说明:** Table USD 中一个子网格的 normal 数据大小不匹配。IS 会忽略损坏的 normal 并自动计算。不影响渲染和物理。如需修复,需在 DCC 工具(Blender/Maya)中重新导出 table USD。
|
||||
|
||||
---
|
||||
|
||||
### 10. GPU / Hardware warnings
|
||||
|
||||
```
|
||||
[Warning] Skipping unsupported non-NVIDIA GPU: AMD Ryzen 7 9800X3D (RADV RAPHAEL_MENDOCINO)
|
||||
[Warning] ECC is enabled on physical device 0
|
||||
[Warning] IOMMU is enabled.
|
||||
```
|
||||
|
||||
**Severity:** None
|
||||
**说明:** 系统有 AMD 集显(跳过正常)。RTX PRO 6000 默认开启 ECC(牺牲约 6% 显存带宽换数据可靠性)。IOMMU 已启用。均为信息提示。
|
||||
|
||||
---
|
||||
|
||||
### 11. SdRenderVarPtr missing LdrColorSDhost
|
||||
|
||||
```
|
||||
[Warning] SdRenderVarPtr missing valid input renderVar LdrColorSDhost
|
||||
```
|
||||
|
||||
**Severity:** None
|
||||
**说明:** Synthetic data pipeline 中 LDR color 渲染变量在 headless 模式下首帧未就绪。后续帧正常。不影响输出。
|
||||
|
||||
---
|
||||
|
||||
### 12. trimesh sampling warning
|
||||
|
||||
```
|
||||
[Warning] [trimesh] only got 3/4 samples!
|
||||
```
|
||||
|
||||
**Severity:** Low
|
||||
**说明:** Grasp pose 采样时某个物体只获得 3 个(期望 4 个)抓取采样点。不影响功能,pipeline 会使用获得的采样继续运行。
|
||||
|
||||
---
|
||||
|
||||
## Summary
|
||||
|
||||
| Category | Count | Fixed | Ignored | Manual |
|
||||
|----------|-------|-------|---------|--------|
|
||||
| Errors | 2 | 1 | 1 | 0 |
|
||||
| Warnings (actionable) | 3 | 2 | 0 | 1 |
|
||||
| Warnings (safe to ignore) | 7 | 0 | 7 | 0 |
|
||||
| **Total** | **12** | **3** | **8** | **1** |
|
||||
70
migrate/scan_usd_metadata.py
Normal file
70
migrate/scan_usd_metadata.py
Normal file
@@ -0,0 +1,70 @@
|
||||
"""
|
||||
Scan all USD files in the project and report their metersPerUnit / upAxis metadata.
|
||||
|
||||
Usage:
|
||||
python migrate/scan_usd_metadata.py [--root DIR]
|
||||
|
||||
Default root: current working directory (project root).
|
||||
"""
|
||||
import argparse
|
||||
import glob
|
||||
import os
|
||||
import sys
|
||||
|
||||
from pxr import Usd, UsdGeom
|
||||
|
||||
|
||||
def scan(root: str, target_mpu: float = 1.0, target_up: str = "Z"):
|
||||
usd_files = glob.glob(os.path.join(root, "**", "*.usd"), recursive=True)
|
||||
usd_files = [f for f in usd_files if not f.endswith(".bak")]
|
||||
usd_files.sort()
|
||||
|
||||
ok_files = []
|
||||
diff_files = []
|
||||
error_files = []
|
||||
|
||||
for fpath in usd_files:
|
||||
try:
|
||||
stage = Usd.Stage.Open(fpath)
|
||||
if stage is None:
|
||||
error_files.append((fpath, "Cannot open stage"))
|
||||
continue
|
||||
mpu = UsdGeom.GetStageMetersPerUnit(stage)
|
||||
up = UsdGeom.GetStageUpAxis(stage)
|
||||
rel = os.path.relpath(fpath, root)
|
||||
if mpu == target_mpu and up == target_up:
|
||||
ok_files.append((rel, mpu, up))
|
||||
else:
|
||||
diff_files.append((rel, mpu, up))
|
||||
except Exception as e:
|
||||
error_files.append((fpath, str(e)))
|
||||
|
||||
# Report
|
||||
print(f"Scanned {len(ok_files) + len(diff_files) + len(error_files)} USD files under: {root}")
|
||||
print(f" OK (mpu={target_mpu}, up={target_up}): {len(ok_files)}")
|
||||
print(f" Different: {len(diff_files)}")
|
||||
print(f" Errors: {len(error_files)}")
|
||||
|
||||
if diff_files:
|
||||
print(f"\n{'='*80}")
|
||||
print(f"Files with non-standard metadata (mpu != {target_mpu} or up != {target_up}):")
|
||||
print(f"{'='*80}")
|
||||
for rel, mpu, up in diff_files:
|
||||
print(f" mpu={mpu:<8} up={up:<4} {rel}")
|
||||
|
||||
if error_files:
|
||||
print(f"\n{'='*80}")
|
||||
print("Files with errors:")
|
||||
print(f"{'='*80}")
|
||||
for fpath, err in error_files:
|
||||
print(f" ERROR: {fpath} -> {err}")
|
||||
|
||||
return diff_files
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
parser = argparse.ArgumentParser(description="Scan USD files for metersPerUnit/upAxis metadata")
|
||||
parser.add_argument("--root", default=os.getcwd(), help="Root directory to scan (default: cwd)")
|
||||
args = parser.parse_args()
|
||||
diff = scan(args.root)
|
||||
sys.exit(1 if diff else 0)
|
||||
64
migrate/usdc_to_obj.py
Normal file
64
migrate/usdc_to_obj.py
Normal file
@@ -0,0 +1,64 @@
|
||||
"""
|
||||
Extract mesh from USD/USDC and export as OBJ file.
|
||||
|
||||
Usage:
|
||||
python migrate/usdc_to_obj.py --input path/to/file.usdc --output path/to/output/
|
||||
"""
|
||||
import argparse
|
||||
import os
|
||||
import numpy as np
|
||||
from pxr import Usd, UsdGeom
|
||||
|
||||
|
||||
def main():
|
||||
parser = argparse.ArgumentParser()
|
||||
parser.add_argument("--input", required=True)
|
||||
parser.add_argument("--output", default=".")
|
||||
args = parser.parse_args()
|
||||
|
||||
os.makedirs(args.output, exist_ok=True)
|
||||
obj_path = os.path.join(args.output, "Aligned_obj.obj")
|
||||
|
||||
stage = Usd.Stage.Open(args.input)
|
||||
vert_offset = 0
|
||||
|
||||
with open(obj_path, "w") as f:
|
||||
f.write("# Exported from USD\n\n")
|
||||
|
||||
for prim in stage.Traverse():
|
||||
if prim.GetTypeName() != "Mesh":
|
||||
continue
|
||||
|
||||
mesh = UsdGeom.Mesh(prim)
|
||||
points = mesh.GetPointsAttr().Get()
|
||||
if not points:
|
||||
continue
|
||||
|
||||
face_counts = mesh.GetFaceVertexCountsAttr().Get()
|
||||
face_indices = mesh.GetFaceVertexIndicesAttr().Get()
|
||||
|
||||
name = str(prim.GetPath()).replace("/", "_").strip("_")
|
||||
f.write(f"o {name}\n")
|
||||
print(f" Mesh: {prim.GetPath()} ({len(points)} verts)")
|
||||
|
||||
for p in points:
|
||||
f.write(f"v {p[0]:.8f} {p[1]:.8f} {p[2]:.8f}\n")
|
||||
|
||||
if face_counts and face_indices:
|
||||
idx = 0
|
||||
for fc in face_counts:
|
||||
verts = []
|
||||
for j in range(fc):
|
||||
verts.append(face_indices[idx] + 1 + vert_offset)
|
||||
idx += 1
|
||||
# Triangulate: fan from first vertex
|
||||
for j in range(1, len(verts) - 1):
|
||||
f.write(f"f {verts[0]} {verts[j]} {verts[j+1]}\n")
|
||||
|
||||
vert_offset += len(points)
|
||||
|
||||
print(f"\nSaved: {obj_path} ({vert_offset} total vertices)")
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
main()
|
||||
@@ -75,7 +75,7 @@ class EnvLoader(SceneLoader):
|
||||
)
|
||||
|
||||
self.logger.info(f"simulator params: physics dt={physics_dt}, rendering dt={rendering_dt}")
|
||||
from omni.isaac.core import World
|
||||
from core.compat import World
|
||||
|
||||
world = World(
|
||||
physics_dt=physics_dt,
|
||||
|
||||
168
scripts/download_assets_direct.py
Normal file
168
scripts/download_assets_direct.py
Normal file
@@ -0,0 +1,168 @@
|
||||
#!/usr/bin/env python3
|
||||
"""
|
||||
Direct HuggingFace dataset downloader that avoids full repo enumeration.
|
||||
Uses the HF tree API per-directory, then downloads files via HTTP.
|
||||
|
||||
Usage:
|
||||
python scripts/download_assets_direct.py [OPTIONS]
|
||||
|
||||
Options:
|
||||
--min Download only required scene assets
|
||||
--full Download all scene assets (default)
|
||||
--with-curobo Also download CuRobo package
|
||||
--with-drake Also download panda_drake package
|
||||
--local-dir DIR Where to save (default: current directory)
|
||||
--mirror URL HF mirror base URL (default: https://hf-mirror.com)
|
||||
"""
|
||||
|
||||
import os
|
||||
import sys
|
||||
import argparse
|
||||
import time
|
||||
from pathlib import Path
|
||||
from concurrent.futures import ThreadPoolExecutor, as_completed
|
||||
|
||||
import requests
|
||||
|
||||
REPO_ID = "InternRobotics/InternData-A1"
|
||||
ASSET_PREFIX = "InternDataAssets"
|
||||
|
||||
def get_token():
|
||||
token = os.environ.get("HF_TOKEN", "")
|
||||
if not token:
|
||||
token_file = Path.home() / ".cache/huggingface/token"
|
||||
if token_file.exists():
|
||||
token = token_file.read_text().strip()
|
||||
return token
|
||||
|
||||
def list_dir(api_base, repo_id, path, token, session):
|
||||
"""List files in a specific directory via HF tree API (non-recursive for speed)."""
|
||||
url = f"{api_base}/api/datasets/{repo_id}/tree/main/{path}"
|
||||
headers = {"Authorization": f"Bearer {token}"} if token else {}
|
||||
files = []
|
||||
cursor = None
|
||||
while True:
|
||||
params = {"expand": "false", "recursive": "true", "limit": "1000"}
|
||||
if cursor:
|
||||
params["cursor"] = cursor
|
||||
r = session.get(url, headers=headers, params=params, timeout=30)
|
||||
r.raise_for_status()
|
||||
data = r.json()
|
||||
if isinstance(data, list):
|
||||
items = data
|
||||
cursor = None
|
||||
else:
|
||||
items = data.get("items", [])
|
||||
cursor = data.get("nextCursor")
|
||||
for item in items:
|
||||
if item.get("type") == "file":
|
||||
files.append(item["path"])
|
||||
if not cursor or not items:
|
||||
break
|
||||
return files
|
||||
|
||||
def download_file(mirror_base, repo_id, file_path, local_dir, token, session):
|
||||
"""Download a single file."""
|
||||
url = f"{mirror_base}/datasets/{repo_id}/resolve/main/{file_path}"
|
||||
headers = {"Authorization": f"Bearer {token}"} if token else {}
|
||||
local_path = Path(local_dir) / file_path
|
||||
local_path.parent.mkdir(parents=True, exist_ok=True)
|
||||
if local_path.exists():
|
||||
return file_path, "skipped"
|
||||
for attempt in range(3):
|
||||
try:
|
||||
with session.get(url, headers=headers, stream=True, timeout=60) as r:
|
||||
r.raise_for_status()
|
||||
with open(local_path, "wb") as f:
|
||||
for chunk in r.iter_content(chunk_size=1024 * 1024):
|
||||
f.write(chunk)
|
||||
return file_path, "ok"
|
||||
except Exception as e:
|
||||
if attempt == 2:
|
||||
return file_path, f"error: {e}"
|
||||
time.sleep(2 ** attempt)
|
||||
|
||||
def download_dir(api_base, mirror_base, repo_id, path, local_dir, token, label, workers=8):
|
||||
print(f"[INFO] Listing {label} ...")
|
||||
session = requests.Session()
|
||||
try:
|
||||
files = list_dir(api_base, repo_id, path, token, session)
|
||||
except Exception as e:
|
||||
print(f"[ERROR] Failed to list {path}: {e}")
|
||||
return
|
||||
print(f"[INFO] Downloading {label} ({len(files)} files) ...")
|
||||
errors = []
|
||||
done = 0
|
||||
with ThreadPoolExecutor(max_workers=workers) as pool:
|
||||
futures = {pool.submit(download_file, mirror_base, repo_id, f, local_dir, token, session): f for f in files}
|
||||
for fut in as_completed(futures):
|
||||
fp, status = fut.result()
|
||||
done += 1
|
||||
if "error" in status:
|
||||
errors.append((fp, status))
|
||||
print(f" [{done}/{len(files)}] FAIL {fp}: {status}")
|
||||
else:
|
||||
print(f" [{done}/{len(files)}] {status.upper()} {fp}", end="\r")
|
||||
print()
|
||||
if errors:
|
||||
print(f"[WARN] {len(errors)} files failed in {label}")
|
||||
|
||||
def download_file_single(api_base, mirror_base, repo_id, file_path, local_dir, token, label):
|
||||
print(f"[INFO] Downloading {label} ...")
|
||||
session = requests.Session()
|
||||
fp, status = download_file(mirror_base, repo_id, file_path, local_dir, token, session)
|
||||
if "error" in status:
|
||||
print(f"[ERROR] {fp}: {status}")
|
||||
else:
|
||||
print(f"[INFO] {label} done.")
|
||||
|
||||
def main():
|
||||
parser = argparse.ArgumentParser()
|
||||
parser.add_argument("--min", action="store_true")
|
||||
parser.add_argument("--full", action="store_true")
|
||||
parser.add_argument("--with-curobo", action="store_true")
|
||||
parser.add_argument("--with-drake", action="store_true")
|
||||
parser.add_argument("--local-dir", default=".")
|
||||
parser.add_argument("--mirror", default="https://hf-mirror.com")
|
||||
parser.add_argument("--workers", type=int, default=8)
|
||||
args = parser.parse_args()
|
||||
|
||||
mode = "min" if args.min else "full"
|
||||
mirror = os.environ.get("HF_ENDPOINT", args.mirror).rstrip("/")
|
||||
api_base = mirror
|
||||
token = get_token()
|
||||
local_dir = args.local_dir
|
||||
|
||||
if not token:
|
||||
print("[WARN] No HF token found. Gated datasets will fail.")
|
||||
|
||||
print(f"[INFO] Mirror: {mirror}, mode={mode}, curobo={args.with_curobo}, drake={args.with_drake}")
|
||||
|
||||
base = f"{ASSET_PREFIX}/assets"
|
||||
|
||||
# Required scene assets
|
||||
print("[INFO] ========== Downloading required scene assets ==========")
|
||||
for d in ["background_textures", "envmap_lib", "floor_textures", "table_textures", "table0"]:
|
||||
download_dir(api_base, mirror, REPO_ID, f"{base}/{d}", local_dir, token, d, args.workers)
|
||||
download_file_single(api_base, mirror, REPO_ID, f"{base}/table_info.json", local_dir, token, "table_info.json")
|
||||
|
||||
# Full mode extras
|
||||
if mode == "full":
|
||||
print("[INFO] ========== Downloading all robots and tasks ==========")
|
||||
for robot in ["lift2", "franka", "frankarobotiq", "split_aloha_mid_360", "G1_120s"]:
|
||||
download_dir(api_base, mirror, REPO_ID, f"{base}/{robot}", local_dir, token, f"robot:{robot}", args.workers)
|
||||
for task in ["basic", "art", "long_horizon", "pick_and_place"]:
|
||||
download_dir(api_base, mirror, REPO_ID, f"{base}/{task}", local_dir, token, f"task:{task}", args.workers)
|
||||
|
||||
if args.with_curobo:
|
||||
print("[INFO] ========== Downloading CuRobo ==========")
|
||||
download_dir(api_base, mirror, REPO_ID, f"{ASSET_PREFIX}/curobo", local_dir, token, "curobo", args.workers)
|
||||
|
||||
if args.with_drake:
|
||||
print("[INFO] ========== Downloading panda_drake ==========")
|
||||
download_dir(api_base, mirror, REPO_ID, f"{ASSET_PREFIX}/panda_drake", local_dir, token, "panda_drake", args.workers)
|
||||
|
||||
print(f"[INFO] Done!")
|
||||
|
||||
if __name__ == "__main__":
|
||||
main()
|
||||
@@ -2,13 +2,10 @@ import numpy as np
|
||||
import omni.replicator.core as rep
|
||||
from core.cameras.base_camera import register_camera
|
||||
from core.utils.camera_utils import get_src
|
||||
from omni.isaac.core.prims import XFormPrim
|
||||
from omni.isaac.core.utils.prims import get_prim_at_path
|
||||
from omni.isaac.core.utils.transformations import (
|
||||
get_relative_transform,
|
||||
pose_from_tf_matrix,
|
||||
)
|
||||
from omni.isaac.sensor import Camera
|
||||
from core.compat import XFormPrim
|
||||
from core.compat import get_prim_at_path
|
||||
from core.compat import get_relative_transform, pose_from_tf_matrix
|
||||
from core.compat import Camera
|
||||
|
||||
|
||||
@register_camera
|
||||
@@ -32,14 +29,44 @@ class CustomCamera(Camera):
|
||||
reference_path: Reference prim path for camera mounting
|
||||
name: Camera name
|
||||
"""
|
||||
# ===== From cfg =====
|
||||
pixel_size = cfg["params"].get("pixel_size")
|
||||
f_number = cfg["params"].get("f_number")
|
||||
focus_distance = cfg["params"].get("focus_distance")
|
||||
fx, fy, cx, cy = cfg["params"].get("camera_params")
|
||||
width = cfg["params"].get("resolution_width")
|
||||
height = cfg["params"].get("resolution_height")
|
||||
self.output_mode = cfg.get("output_mode", "rgb")
|
||||
|
||||
horizontal_aperture = pixel_size * 1e-3 * width / 10.0
|
||||
vertical_aperture = pixel_size * 1e-3 * height / 10.0
|
||||
focal_length_x = fx * pixel_size * 1e-3
|
||||
focal_length_y = fy * pixel_size * 1e-3
|
||||
focal_length = (focal_length_x + focal_length_y) / 2 / 10.0
|
||||
|
||||
# ===== Initialize camera =====
|
||||
# Note: Camera.__init__ triggers aperture consistency warnings with default USD values.
|
||||
# These are cosmetic — IS auto-corrects, and we override with correct values below.
|
||||
super().__init__(
|
||||
prim_path=prim_path,
|
||||
name=name,
|
||||
resolution=(cfg["params"]["resolution_width"], cfg["params"]["resolution_height"]),
|
||||
resolution=(width, height),
|
||||
*args,
|
||||
**kwargs,
|
||||
)
|
||||
|
||||
# ===== Set camera parameters =====
|
||||
self.set_focal_length(focal_length)
|
||||
self.set_focus_distance(focus_distance)
|
||||
self.set_lens_aperture(f_number * 100.0)
|
||||
self.set_horizontal_aperture(horizontal_aperture)
|
||||
self.set_vertical_aperture(vertical_aperture)
|
||||
self.set_clipping_range(0.05, 1.0e5)
|
||||
try:
|
||||
self.set_lens_distortion_model("pinhole")
|
||||
except AttributeError:
|
||||
self.set_projection_type("pinhole")
|
||||
|
||||
self.initialize()
|
||||
self.with_distance = cfg["params"].get("with_distance", True)
|
||||
self.with_semantic = cfg["params"].get("with_semantic", False)
|
||||
@@ -61,30 +88,6 @@ class CustomCamera(Camera):
|
||||
if self.with_motion_vector:
|
||||
self.add_motion_vectors_to_frame()
|
||||
|
||||
# ===== From cfg =====
|
||||
pixel_size = cfg["params"].get("pixel_size")
|
||||
f_number = cfg["params"].get("f_number")
|
||||
focus_distance = cfg["params"].get("focus_distance")
|
||||
fx, fy, cx, cy = cfg["params"].get("camera_params")
|
||||
width = cfg["params"].get("resolution_width")
|
||||
height = cfg["params"].get("resolution_height")
|
||||
self.output_mode = cfg.get("output_mode", "rgb")
|
||||
|
||||
# ===== Compute and set camera parameters =====
|
||||
horizontal_aperture = pixel_size * 1e-3 * width
|
||||
vertical_aperture = pixel_size * 1e-3 * height
|
||||
focal_length_x = fx * pixel_size * 1e-3
|
||||
focal_length_y = fy * pixel_size * 1e-3
|
||||
focal_length = (focal_length_x + focal_length_y) / 2
|
||||
|
||||
self.set_focal_length(focal_length / 10.0)
|
||||
self.set_focus_distance(focus_distance)
|
||||
self.set_lens_aperture(f_number * 100.0)
|
||||
self.set_horizontal_aperture(horizontal_aperture / 10.0)
|
||||
self.set_vertical_aperture(vertical_aperture / 10.0)
|
||||
self.set_clipping_range(0.05, 1.0e5)
|
||||
self.set_projection_type("pinhole")
|
||||
|
||||
fx = width * self.get_focal_length() / self.get_horizontal_aperture()
|
||||
fy = height * self.get_focal_length() / self.get_vertical_aperture()
|
||||
self.is_camera_matrix = np.array([[fx, 0.0, cx], [0.0, fy, cy], [0.0, 0.0, 1.0]])
|
||||
|
||||
198
workflows/simbox/core/compat.py
Normal file
198
workflows/simbox/core/compat.py
Normal file
@@ -0,0 +1,198 @@
|
||||
"""
|
||||
Isaac Sim 4.x / 5.x API compatibility layer.
|
||||
|
||||
IS 5.0 renamed all `omni.isaac.*` modules to `isaacsim.*`.
|
||||
This module provides unified imports that work across both versions.
|
||||
Import from here instead of directly from omni.isaac.* or isaacsim.*.
|
||||
"""
|
||||
|
||||
# ===== Core =====
|
||||
try:
|
||||
from isaacsim.core.api import World
|
||||
except ImportError:
|
||||
from omni.isaac.core import World
|
||||
|
||||
# ===== Controllers =====
|
||||
try:
|
||||
from isaacsim.core.api.controllers.base_controller import BaseController
|
||||
except ImportError:
|
||||
from omni.isaac.core.controllers import BaseController
|
||||
|
||||
# ===== Tasks =====
|
||||
try:
|
||||
from isaacsim.core.api.tasks.base_task import BaseTask
|
||||
except ImportError:
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
|
||||
# ===== Robots =====
|
||||
try:
|
||||
from isaacsim.core.api.robots.robot import Robot
|
||||
except ImportError:
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
|
||||
# ===== Prims (class names changed in IS 5.x) =====
|
||||
try:
|
||||
from isaacsim.core.prims import SingleXFormPrim as XFormPrim
|
||||
except ImportError:
|
||||
from omni.isaac.core.prims import XFormPrim
|
||||
|
||||
try:
|
||||
from isaacsim.core.prims import SingleRigidPrim as RigidPrim
|
||||
except ImportError:
|
||||
from omni.isaac.core.prims import RigidPrim
|
||||
|
||||
try:
|
||||
from isaacsim.core.prims import SingleGeometryPrim as GeometryPrim
|
||||
except ImportError:
|
||||
from omni.isaac.core.prims import GeometryPrim
|
||||
|
||||
try:
|
||||
from isaacsim.core.api.sensors.rigid_contact_view import RigidContactView
|
||||
except ImportError:
|
||||
from omni.isaac.core.prims import RigidContactView
|
||||
|
||||
# ===== Articulations =====
|
||||
try:
|
||||
from isaacsim.core.prims import SingleArticulation as Articulation
|
||||
except ImportError:
|
||||
from omni.isaac.core.articulations.articulation import Articulation
|
||||
|
||||
# ===== Objects =====
|
||||
try:
|
||||
from isaacsim.core.api.objects.cylinder import VisualCylinder
|
||||
except ImportError:
|
||||
from omni.isaac.core.objects.cylinder import VisualCylinder
|
||||
|
||||
try:
|
||||
from isaacsim.core.api.objects import cuboid, sphere
|
||||
except ImportError:
|
||||
from omni.isaac.core.objects import cuboid, sphere
|
||||
|
||||
# ===== Materials =====
|
||||
try:
|
||||
from isaacsim.core.api.materials import PreviewSurface
|
||||
except ImportError:
|
||||
from omni.isaac.core.materials import PreviewSurface
|
||||
|
||||
try:
|
||||
from isaacsim.core.api.materials import OmniPBR
|
||||
except ImportError:
|
||||
try:
|
||||
from omni.isaac.core.materials import OmniPBR
|
||||
except ImportError:
|
||||
from omni.isaac.core.materials.omni_pbr import OmniPBR
|
||||
|
||||
try:
|
||||
from isaacsim.core.api.materials import OmniGlass
|
||||
except ImportError:
|
||||
from omni.isaac.core.materials import OmniGlass
|
||||
|
||||
# ===== Scenes =====
|
||||
try:
|
||||
from isaacsim.core.api.scenes.scene import Scene
|
||||
except ImportError:
|
||||
from omni.isaac.core.scenes.scene import Scene
|
||||
|
||||
# ===== Utils: prims =====
|
||||
try:
|
||||
from isaacsim.core.utils.prims import (
|
||||
get_prim_at_path,
|
||||
create_prim,
|
||||
delete_prim,
|
||||
is_prim_path_valid,
|
||||
)
|
||||
except ImportError:
|
||||
from omni.isaac.core.utils.prims import (
|
||||
get_prim_at_path,
|
||||
create_prim,
|
||||
delete_prim,
|
||||
is_prim_path_valid,
|
||||
)
|
||||
|
||||
# ===== Utils: transformations =====
|
||||
try:
|
||||
from isaacsim.core.utils.transformations import (
|
||||
get_relative_transform,
|
||||
pose_from_tf_matrix,
|
||||
tf_matrix_from_pose,
|
||||
tf_matrices_from_poses,
|
||||
)
|
||||
except ImportError:
|
||||
from omni.isaac.core.utils.transformations import (
|
||||
get_relative_transform,
|
||||
pose_from_tf_matrix,
|
||||
tf_matrix_from_pose,
|
||||
tf_matrices_from_poses,
|
||||
)
|
||||
|
||||
# ===== Utils: stage =====
|
||||
try:
|
||||
from isaacsim.core.utils.stage import (
|
||||
get_current_stage,
|
||||
add_reference_to_stage,
|
||||
)
|
||||
except ImportError:
|
||||
from omni.isaac.core.utils.stage import (
|
||||
get_current_stage,
|
||||
add_reference_to_stage,
|
||||
)
|
||||
|
||||
# ===== Utils: xforms =====
|
||||
try:
|
||||
from isaacsim.core.utils.xforms import get_world_pose
|
||||
except ImportError:
|
||||
from omni.isaac.core.utils.xforms import get_world_pose
|
||||
|
||||
# ===== Utils: types =====
|
||||
try:
|
||||
from isaacsim.core.utils.types import ArticulationAction
|
||||
except ImportError:
|
||||
from omni.isaac.core.utils.types import ArticulationAction
|
||||
|
||||
# ===== Utils: viewports =====
|
||||
try:
|
||||
from isaacsim.core.utils.viewports import set_camera_view
|
||||
except ImportError:
|
||||
from omni.isaac.core.utils.viewports import set_camera_view
|
||||
|
||||
# ===== Utils: semantics =====
|
||||
try:
|
||||
from isaacsim.core.utils.semantics import add_update_semantics
|
||||
except ImportError:
|
||||
from omni.isaac.core.utils.semantics import add_update_semantics
|
||||
|
||||
# ===== Utils: string =====
|
||||
try:
|
||||
from isaacsim.core.utils.string import find_unique_string_name
|
||||
except ImportError:
|
||||
from omni.isaac.core.utils.string import find_unique_string_name
|
||||
|
||||
# ===== Utils: stage units =====
|
||||
try:
|
||||
from isaacsim.core.utils.stage import get_stage_units
|
||||
except ImportError:
|
||||
from omni.isaac.core.utils.stage import get_stage_units
|
||||
|
||||
# ===== Utils: extensions =====
|
||||
try:
|
||||
from isaacsim.core.utils.extensions import enable_extension
|
||||
except ImportError:
|
||||
from omni.isaac.core.utils.extensions import enable_extension
|
||||
|
||||
# ===== Utils: nucleus =====
|
||||
try:
|
||||
from isaacsim.storage.native import get_assets_root_path as nucleus_path
|
||||
except ImportError:
|
||||
from omni.isaac.core.utils.nucleus import get_assets_root_path as nucleus_path
|
||||
|
||||
# ===== Sensor: Camera =====
|
||||
try:
|
||||
from isaacsim.sensors.camera import Camera
|
||||
except ImportError:
|
||||
from omni.isaac.sensor import Camera
|
||||
|
||||
# ===== SimulationApp =====
|
||||
try:
|
||||
from isaacsim import SimulationApp
|
||||
except ImportError:
|
||||
from omni.isaac.kit import SimulationApp
|
||||
152
workflows/simbox/core/configs/tasks/example/pick_test_tube.yaml
Normal file
152
workflows/simbox/core/configs/tasks/example/pick_test_tube.yaml
Normal file
@@ -0,0 +1,152 @@
|
||||
tasks:
|
||||
-
|
||||
name: banana_base_task
|
||||
asset_root: workflows/simbox/example_assets
|
||||
task: BananaBaseTask
|
||||
task_id: 0
|
||||
|
||||
offset: null
|
||||
render: True
|
||||
|
||||
neglect_collision_names: ["table"]
|
||||
|
||||
# Arena configuration
|
||||
arena_file: workflows/simbox/core/configs/arenas/example.yaml
|
||||
|
||||
env_map:
|
||||
envmap_lib: envmap_lib
|
||||
apply_randomization: False
|
||||
intensity_range: [5000, 5000]
|
||||
rotation_range: [0, 0]
|
||||
|
||||
robots:
|
||||
-
|
||||
name: "split_aloha"
|
||||
robot_config_file: workflows/simbox/core/configs/robots/split_aloha.yaml
|
||||
euler: [0.0, 0.0, 90.0]
|
||||
ignore_substring: ["material", "table", "test_tube_rack"]
|
||||
|
||||
objects:
|
||||
# Test tube - graspable rigid object
|
||||
-
|
||||
name: test_tube_right
|
||||
path: task/pick_test_tube/test_tube/Aligned_obj.usd
|
||||
target_class: RigidObject
|
||||
dataset: custom
|
||||
category: test_tube
|
||||
prim_path_child: Aligned
|
||||
translation: [0.0, 0.0, 0.0]
|
||||
euler: [0.0, 0.0, 0.0]
|
||||
scale: [1, 1, 1]
|
||||
apply_randomization: False
|
||||
orientation_mode: keep
|
||||
|
||||
# Test tube rack - static geometry
|
||||
-
|
||||
name: test_tube_rack
|
||||
path: task/pick_test_tube/test_tube_rack/Test_Tube_Rack_AA_01.usdc
|
||||
target_class: GeometryObject
|
||||
dataset: custom
|
||||
category: rack
|
||||
prim_path_child: Test_Tube_Rack_AA_01
|
||||
translation: [0.0, 0.0, 0.0]
|
||||
euler: [0.0, 0.0, 0.0]
|
||||
scale: [1, 1, 1]
|
||||
apply_randomization: False
|
||||
|
||||
regions:
|
||||
# Test tube on table (right side of robot)
|
||||
-
|
||||
object: test_tube_right
|
||||
target: table
|
||||
random_type: A_on_B_region_sampler
|
||||
random_config:
|
||||
pos_range: [
|
||||
[0.05, -0.05, 0.0],
|
||||
[0.15, 0.05, 0.0]
|
||||
]
|
||||
yaw_rotation: [0.0, 0.0]
|
||||
|
||||
# Test tube rack on table (left side)
|
||||
-
|
||||
object: test_tube_rack
|
||||
target: table
|
||||
random_type: A_on_B_region_sampler
|
||||
random_config:
|
||||
pos_range: [
|
||||
[-0.25, -0.05, 0.0],
|
||||
[-0.25, -0.05, 0.0]
|
||||
]
|
||||
yaw_rotation: [0.0, 0.0]
|
||||
|
||||
# Robot position
|
||||
-
|
||||
object: split_aloha
|
||||
target: table
|
||||
random_type: A_on_B_region_sampler
|
||||
random_config:
|
||||
pos_range: [
|
||||
[0.0, -0.86, -0.75],
|
||||
[0.0, -0.86, -0.75]
|
||||
]
|
||||
yaw_rotation: [0.0, 0.0]
|
||||
|
||||
cameras:
|
||||
-
|
||||
name: split_aloha_hand_left
|
||||
translation: [0.0, 0.08, 0.05]
|
||||
orientation: [0.0, 0.0, 0.965, 0.259]
|
||||
camera_axes: usd
|
||||
camera_file: workflows/simbox/core/configs/cameras/astra.yaml
|
||||
parent: "split_aloha/split_aloha_mid_360_with_piper/split_aloha_mid_360_with_piper/fl/link6"
|
||||
apply_randomization: False
|
||||
-
|
||||
name: split_aloha_hand_right
|
||||
translation: [0.0, 0.08, 0.04]
|
||||
orientation: [0.0, 0.0, 0.972, 0.233]
|
||||
camera_axes: usd
|
||||
camera_file: workflows/simbox/core/configs/cameras/astra.yaml
|
||||
parent: "split_aloha/split_aloha_mid_360_with_piper/split_aloha_mid_360_with_piper/fr/link6"
|
||||
apply_randomization: False
|
||||
-
|
||||
name: split_aloha_head
|
||||
translation: [0.0, -0.00818, 0.1]
|
||||
orientation: [0.658, 0.259, -0.282, -0.648]
|
||||
camera_axes: usd
|
||||
camera_file: workflows/simbox/core/configs/cameras/realsense_d455_v3.yaml
|
||||
parent: "split_aloha/split_aloha_mid_360_with_piper/split_aloha_mid_360_with_piper/top_camera_link"
|
||||
|
||||
data:
|
||||
task_dir: "pick_test_tube"
|
||||
language_instruction: "Pick up the test tube from the table."
|
||||
detailed_language_instruction: "Use the right arm to grasp the test tube from the table and lift it up."
|
||||
collect_info: "Test tube picking task with Split Aloha"
|
||||
version: "v1.0"
|
||||
update: True
|
||||
max_episode_length: 2000
|
||||
|
||||
skills:
|
||||
-
|
||||
split_aloha:
|
||||
-
|
||||
right:
|
||||
# Pick the test tube with right arm
|
||||
-
|
||||
name: pick
|
||||
objects: [test_tube_right]
|
||||
npy_name: Aligned_grasp_sparse.npy
|
||||
filter_y_dir: ["forward", 60]
|
||||
filter_z_dir: ["downward", 150]
|
||||
pre_grasp_offset: 0.05
|
||||
gripper_change_steps: 10
|
||||
t_eps: 0.025
|
||||
o_eps: 1
|
||||
process_valid: True
|
||||
lift_th: 0.02
|
||||
post_grasp_offset_min: 0.10
|
||||
post_grasp_offset_max: 0.15
|
||||
# Return to home
|
||||
-
|
||||
name: heuristic__skill
|
||||
mode: home
|
||||
gripper_state: 1.0
|
||||
@@ -29,7 +29,7 @@ tasks:
|
||||
objects:
|
||||
-
|
||||
name: pick_object_left
|
||||
path: task/sort_the_rubbish/non_recyclable_garbage/obj_0/Aligned_obj.usd
|
||||
path: task/sort_the_rubbish/non_recyclable_garbage/obj_1/Aligned_obj.usd
|
||||
target_class: RigidObject
|
||||
dataset: oo3d
|
||||
category: bottle
|
||||
|
||||
@@ -34,15 +34,12 @@ from curobo.wrap.reacher.motion_gen import (
|
||||
MotionGenPlanConfig,
|
||||
PoseCostMetric,
|
||||
)
|
||||
from omni.isaac.core import World
|
||||
from omni.isaac.core.controllers import BaseController
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
from omni.isaac.core.utils.prims import get_prim_at_path
|
||||
from omni.isaac.core.utils.transformations import (
|
||||
get_relative_transform,
|
||||
pose_from_tf_matrix,
|
||||
)
|
||||
from omni.isaac.core.utils.types import ArticulationAction
|
||||
from core.compat import World
|
||||
from core.compat import BaseController
|
||||
from core.compat import BaseTask
|
||||
from core.compat import get_prim_at_path
|
||||
from core.compat import get_relative_transform, pose_from_tf_matrix
|
||||
from core.compat import ArticulationAction
|
||||
|
||||
|
||||
# pylint: disable=line-too-long,unused-argument
|
||||
@@ -249,6 +246,12 @@ class TemplateController(BaseController):
|
||||
obstacles = self.usd_help.get_obstacles_from_stage(
|
||||
ignore_substring=self.ignore_substring, reference_prim_path=self.reference_prim_path
|
||||
).get_collision_check_world()
|
||||
# Diagnostic: print what curobo sees as the collision world
|
||||
n_cuboid = len(obstacles.cuboid) if obstacles.cuboid else 0
|
||||
n_mesh = len(obstacles.mesh) if obstacles.mesh else 0
|
||||
mesh_names = [m.name for m in obstacles.mesh] if obstacles.mesh else []
|
||||
print(f"[CUROBO_WORLD] cuboids={n_cuboid}, meshes={n_mesh}, "
|
||||
f"mesh_names={mesh_names[:5]}{'...' if n_mesh > 5 else ''}", flush=True)
|
||||
if self.motion_gen is not None:
|
||||
self.motion_gen.update_world(obstacles)
|
||||
self.world_cfg = obstacles
|
||||
@@ -277,6 +280,10 @@ class TemplateController(BaseController):
|
||||
self.T_world_base_init = get_relative_transform(
|
||||
get_prim_at_path(self.robot_base_path), get_prim_at_path(self.task.root_prim_path)
|
||||
)
|
||||
print(f"[TRANSFORM_DBG] robot_base_path={self.robot_base_path}", flush=True)
|
||||
print(f"[TRANSFORM_DBG] root_prim_path={self.task.root_prim_path}", flush=True)
|
||||
print(f"[TRANSFORM_DBG] T_world_base_init translation={self.T_world_base_init[:3, 3]}", flush=True)
|
||||
print(f"[TRANSFORM_DBG] T_world_base_init full=\n{self.T_world_base_init}", flush=True)
|
||||
self.T_world_ee_init = self.T_world_base_init @ self.T_base_ee_init
|
||||
self._ee_trans, self._ee_ori = self.get_ee_pose()
|
||||
self._ee_trans = self.tensor_args.to_device(self._ee_trans)
|
||||
|
||||
@@ -5,11 +5,11 @@ import random
|
||||
|
||||
import numpy as np
|
||||
from core.objects.base_object import register_object
|
||||
from omni.isaac.core.articulations.articulation import Articulation
|
||||
from omni.isaac.core.utils.stage import add_reference_to_stage
|
||||
from core.compat import Articulation
|
||||
from core.compat import add_reference_to_stage
|
||||
|
||||
try:
|
||||
from omni.isaac.core.materials.omni_pbr import OmniPBR # Isaac Sim 4.1.0 / 4.2.0
|
||||
from core.compat import OmniPBR
|
||||
except ImportError:
|
||||
from isaacsim.core.api.materials import OmniPBR # Isaac Sim 4.5.0
|
||||
|
||||
|
||||
@@ -1,8 +1,8 @@
|
||||
import os
|
||||
|
||||
from core.objects.base_object import register_object
|
||||
from omni.isaac.core.prims import GeometryPrim
|
||||
from omni.isaac.core.utils.prims import create_prim
|
||||
from core.compat import GeometryPrim
|
||||
from core.compat import create_prim
|
||||
from pxr import Gf, UsdPhysics
|
||||
|
||||
|
||||
|
||||
@@ -3,15 +3,11 @@ import os
|
||||
import random
|
||||
|
||||
from core.objects.base_object import register_object
|
||||
from omni.isaac.core.prims import GeometryPrim
|
||||
from omni.isaac.core.utils.prims import (
|
||||
create_prim,
|
||||
get_prim_at_path,
|
||||
is_prim_path_valid,
|
||||
)
|
||||
from core.compat import GeometryPrim
|
||||
from core.compat import create_prim, get_prim_at_path, is_prim_path_valid
|
||||
|
||||
try:
|
||||
from omni.isaac.core.materials.omni_pbr import OmniPBR # Isaac Sim 4.1.0 / 4.2.0
|
||||
from core.compat import OmniPBR
|
||||
except ImportError:
|
||||
from isaacsim.core.api.materials import OmniPBR # Isaac Sim 4.5.0
|
||||
|
||||
|
||||
@@ -3,12 +3,12 @@ import os
|
||||
import random
|
||||
|
||||
from core.objects.base_object import register_object
|
||||
from omni.isaac.core.prims import XFormPrim
|
||||
from omni.isaac.core.utils.prims import is_prim_path_valid
|
||||
from omni.isaac.core.utils.stage import get_current_stage
|
||||
from core.compat import XFormPrim
|
||||
from core.compat import is_prim_path_valid
|
||||
from core.compat import get_current_stage
|
||||
|
||||
try:
|
||||
from omni.isaac.core.materials.omni_pbr import OmniPBR # Isaac Sim 4.1.0 / 4.2.0
|
||||
from core.compat import OmniPBR
|
||||
except ImportError:
|
||||
from isaacsim.core.api.materials import OmniPBR # Isaac Sim 4.5.0
|
||||
|
||||
|
||||
@@ -3,11 +3,11 @@ import os
|
||||
import random
|
||||
|
||||
from core.objects.base_object import register_object
|
||||
from omni.isaac.core.prims import RigidPrim
|
||||
from omni.isaac.core.utils.prims import create_prim, get_prim_at_path
|
||||
from core.compat import RigidPrim
|
||||
from core.compat import create_prim, get_prim_at_path
|
||||
|
||||
try:
|
||||
from omni.isaac.core.materials.omni_pbr import OmniPBR # Isaac Sim 4.1.0 / 4.2.0
|
||||
from core.compat import OmniPBR
|
||||
except ImportError:
|
||||
from isaacsim.core.api.materials import OmniPBR # Isaac Sim 4.5.0
|
||||
|
||||
@@ -47,6 +47,21 @@ class RigidObject(RigidPrim):
|
||||
self.base_prim_path = prim_path
|
||||
rigid_prim_path = os.path.join(self.base_prim_path, cfg["prim_path_child"])
|
||||
self.mesh_prim_path = str(get_prim_at_path(rigid_prim_path).GetChildren()[0].GetPrimPath())
|
||||
# [LOAD_DBG] Print xformOps right after create_prim, before physics
|
||||
try:
|
||||
from pxr import UsdGeom
|
||||
_xf = UsdGeom.Xformable(get_prim_at_path(rigid_prim_path))
|
||||
for _op in _xf.GetOrderedXformOps():
|
||||
print(f"[LOAD_DBG] {cfg_name} after_create_prim: {_op.GetName()} = {_op.Get()}", flush=True)
|
||||
_l2w = _xf.ComputeLocalToWorldTransform(0)
|
||||
print(f"[LOAD_DBG] {cfg_name} after_create_prim l2w=({_l2w[3][0]:.6f}, {_l2w[3][1]:.6f}, {_l2w[3][2]:.6f})", flush=True)
|
||||
# Also check the USD file's own metersPerUnit
|
||||
_ref_stage = get_prim_at_path(prim_path).GetStage()
|
||||
_mpu = UsdGeom.GetStageMetersPerUnit(_ref_stage)
|
||||
_up = UsdGeom.GetStageUpAxis(_ref_stage)
|
||||
print(f"[LOAD_DBG] {cfg_name} stage metersPerUnit={_mpu} upAxis={_up}", flush=True)
|
||||
except Exception as _e:
|
||||
print(f"[LOAD_DBG] {cfg_name} error: {_e}", flush=True)
|
||||
super().__init__(prim_path=rigid_prim_path, name=cfg["name"], *args, **kwargs)
|
||||
|
||||
def get_observations(self):
|
||||
|
||||
@@ -3,10 +3,10 @@ import os
|
||||
import random
|
||||
|
||||
from core.objects.base_object import register_object
|
||||
from omni.isaac.core.prims import GeometryPrim
|
||||
from core.compat import GeometryPrim
|
||||
|
||||
try:
|
||||
from omni.isaac.core.materials.omni_pbr import OmniPBR # Isaac Sim 4.1.0 / 4.2.0
|
||||
from core.compat import OmniPBR
|
||||
except ImportError:
|
||||
from isaacsim.core.api.materials import OmniPBR # Isaac Sim 4.5.0
|
||||
|
||||
|
||||
@@ -3,11 +3,11 @@ import os
|
||||
import random
|
||||
|
||||
from core.objects.base_object import register_object
|
||||
from omni.isaac.core.prims import XFormPrim
|
||||
from omni.isaac.core.utils.prims import create_prim, is_prim_path_valid
|
||||
from core.compat import XFormPrim
|
||||
from core.compat import create_prim, is_prim_path_valid
|
||||
|
||||
try:
|
||||
from omni.isaac.core.materials.omni_pbr import OmniPBR # Isaac Sim 4.1.0 / 4.2.0
|
||||
from core.compat import OmniPBR
|
||||
except ImportError:
|
||||
from isaacsim.core.api.materials import OmniPBR # Isaac Sim 4.5.0
|
||||
|
||||
|
||||
@@ -7,12 +7,9 @@ from copy import deepcopy
|
||||
|
||||
import numpy as np
|
||||
from core.robots.base_robot import register_robot
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
from omni.isaac.core.utils.prims import create_prim, get_prim_at_path
|
||||
from omni.isaac.core.utils.transformations import (
|
||||
get_relative_transform,
|
||||
tf_matrix_from_pose,
|
||||
)
|
||||
from core.compat import Robot
|
||||
from core.compat import create_prim, get_prim_at_path
|
||||
from core.compat import get_relative_transform, tf_matrix_from_pose
|
||||
from scipy.interpolate import interp1d
|
||||
|
||||
|
||||
|
||||
@@ -3,15 +3,11 @@ import numpy as np
|
||||
from core.skills.base_skill import BaseSkill, register_skill
|
||||
from core.utils.interpolate_utils import linear_interpolation
|
||||
from omegaconf import DictConfig
|
||||
from omni.isaac.core.controllers import BaseController
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
from omni.isaac.core.utils.prims import get_prim_at_path
|
||||
from omni.isaac.core.utils.transformations import (
|
||||
get_relative_transform,
|
||||
pose_from_tf_matrix,
|
||||
tf_matrix_from_pose,
|
||||
)
|
||||
from core.compat import BaseController
|
||||
from core.compat import Robot
|
||||
from core.compat import BaseTask
|
||||
from core.compat import get_prim_at_path
|
||||
from core.compat import get_relative_transform, pose_from_tf_matrix, tf_matrix_from_pose
|
||||
from scipy.spatial.transform import Rotation as R
|
||||
|
||||
|
||||
|
||||
@@ -3,11 +3,11 @@ from copy import deepcopy
|
||||
import numpy as np
|
||||
from core.skills.base_skill import BaseSkill, register_skill
|
||||
from omegaconf import DictConfig
|
||||
from omni.isaac.core.controllers import BaseController
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
from omni.isaac.core.utils.prims import get_prim_at_path
|
||||
from omni.isaac.core.utils.transformations import get_relative_transform
|
||||
from core.compat import BaseController
|
||||
from core.compat import Robot
|
||||
from core.compat import BaseTask
|
||||
from core.compat import get_prim_at_path
|
||||
from core.compat import get_relative_transform
|
||||
from solver.planner import KPAMPlanner
|
||||
|
||||
|
||||
|
||||
@@ -3,11 +3,11 @@ from copy import deepcopy
|
||||
import numpy as np
|
||||
from core.skills.base_skill import BaseSkill, register_skill
|
||||
from omegaconf import DictConfig
|
||||
from omni.isaac.core.controllers import BaseController
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
from omni.isaac.core.utils.prims import get_prim_at_path
|
||||
from omni.isaac.core.utils.transformations import get_relative_transform
|
||||
from core.compat import BaseController
|
||||
from core.compat import Robot
|
||||
from core.compat import BaseTask
|
||||
from core.compat import get_prim_at_path
|
||||
from core.compat import get_relative_transform
|
||||
from scipy.spatial.transform import Rotation as R
|
||||
from solver.planner import KPAMPlanner
|
||||
|
||||
|
||||
@@ -4,15 +4,11 @@ from copy import deepcopy
|
||||
import numpy as np
|
||||
from core.skills.base_skill import BaseSkill, register_skill
|
||||
from omegaconf import DictConfig, OmegaConf
|
||||
from omni.isaac.core.controllers import BaseController
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
from omni.isaac.core.utils.prims import get_prim_at_path
|
||||
from omni.isaac.core.utils.transformations import (
|
||||
get_relative_transform,
|
||||
pose_from_tf_matrix,
|
||||
tf_matrix_from_pose,
|
||||
)
|
||||
from core.compat import BaseController
|
||||
from core.compat import Robot
|
||||
from core.compat import BaseTask
|
||||
from core.compat import get_prim_at_path
|
||||
from core.compat import get_relative_transform, pose_from_tf_matrix, tf_matrix_from_pose
|
||||
|
||||
|
||||
# pylint: disable=unused-argument
|
||||
|
||||
@@ -5,15 +5,11 @@ import numpy as np
|
||||
from core.skills.base_skill import BaseSkill, register_skill
|
||||
from core.utils.usd_geom_utils import compute_bbox
|
||||
from omegaconf import DictConfig, OmegaConf
|
||||
from omni.isaac.core.controllers import BaseController
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
from omni.isaac.core.utils.prims import get_prim_at_path
|
||||
from omni.isaac.core.utils.transformations import (
|
||||
get_relative_transform,
|
||||
pose_from_tf_matrix,
|
||||
tf_matrix_from_pose,
|
||||
)
|
||||
from core.compat import BaseController
|
||||
from core.compat import Robot
|
||||
from core.compat import BaseTask
|
||||
from core.compat import get_prim_at_path
|
||||
from core.compat import get_relative_transform, pose_from_tf_matrix, tf_matrix_from_pose
|
||||
from scipy.spatial.transform import Rotation as R
|
||||
from scipy.spatial.transform import Slerp
|
||||
|
||||
|
||||
@@ -12,14 +12,11 @@ from core.utils.plan_utils import (
|
||||
)
|
||||
from core.utils.transformation_utils import poses_from_tf_matrices
|
||||
from omegaconf import DictConfig
|
||||
from omni.isaac.core.controllers import BaseController
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
from omni.isaac.core.utils.prims import get_prim_at_path
|
||||
from omni.isaac.core.utils.transformations import (
|
||||
get_relative_transform,
|
||||
tf_matrix_from_pose,
|
||||
)
|
||||
from core.compat import BaseController
|
||||
from core.compat import Robot
|
||||
from core.compat import BaseTask
|
||||
from core.compat import get_prim_at_path
|
||||
from core.compat import get_relative_transform, tf_matrix_from_pose
|
||||
from omni.timeline import get_timeline_interface
|
||||
from scipy.spatial.transform import Rotation as R
|
||||
|
||||
|
||||
@@ -5,15 +5,11 @@ from copy import deepcopy
|
||||
import numpy as np
|
||||
from core.skills.base_skill import BaseSkill, register_skill
|
||||
from omegaconf import DictConfig
|
||||
from omni.isaac.core.controllers import BaseController
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
from omni.isaac.core.utils.prims import get_prim_at_path
|
||||
from omni.isaac.core.utils.transformations import (
|
||||
get_relative_transform,
|
||||
pose_from_tf_matrix,
|
||||
tf_matrix_from_pose,
|
||||
)
|
||||
from core.compat import BaseController
|
||||
from core.compat import Robot
|
||||
from core.compat import BaseTask
|
||||
from core.compat import get_prim_at_path
|
||||
from core.compat import get_relative_transform, pose_from_tf_matrix, tf_matrix_from_pose
|
||||
|
||||
|
||||
# pylint: disable=unused-argument
|
||||
|
||||
@@ -3,15 +3,11 @@ from copy import deepcopy
|
||||
import numpy as np
|
||||
from core.skills.base_skill import BaseSkill, register_skill
|
||||
from omegaconf import DictConfig
|
||||
from omni.isaac.core.controllers import BaseController
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
from omni.isaac.core.utils.prims import get_prim_at_path
|
||||
from omni.isaac.core.utils.transformations import (
|
||||
get_relative_transform,
|
||||
pose_from_tf_matrix,
|
||||
tf_matrix_from_pose,
|
||||
)
|
||||
from core.compat import BaseController
|
||||
from core.compat import Robot
|
||||
from core.compat import BaseTask
|
||||
from core.compat import get_prim_at_path
|
||||
from core.compat import get_relative_transform, pose_from_tf_matrix, tf_matrix_from_pose
|
||||
from scipy.spatial.transform import Rotation as R
|
||||
|
||||
|
||||
|
||||
@@ -10,14 +10,11 @@ from core.utils.transformation_utils import (
|
||||
poses_from_tf_matrices,
|
||||
)
|
||||
from omegaconf import DictConfig
|
||||
from omni.isaac.core.controllers import BaseController
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
from omni.isaac.core.utils.prims import get_prim_at_path
|
||||
from omni.isaac.core.utils.transformations import (
|
||||
get_relative_transform,
|
||||
tf_matrix_from_pose,
|
||||
)
|
||||
from core.compat import BaseController
|
||||
from core.compat import Robot
|
||||
from core.compat import BaseTask
|
||||
from core.compat import get_prim_at_path
|
||||
from core.compat import get_relative_transform, tf_matrix_from_pose
|
||||
from scipy.spatial.transform import Rotation as R
|
||||
from scipy.spatial.transform import Slerp
|
||||
|
||||
|
||||
@@ -1,9 +1,9 @@
|
||||
import numpy as np
|
||||
from core.skills.base_skill import BaseSkill, register_skill
|
||||
from omegaconf import DictConfig
|
||||
from omni.isaac.core.controllers import BaseController
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
from core.compat import BaseController
|
||||
from core.compat import Robot
|
||||
from core.compat import BaseTask
|
||||
|
||||
|
||||
# pylint: disable=unused-argument
|
||||
|
||||
@@ -1,13 +1,10 @@
|
||||
import numpy as np
|
||||
from core.skills.base_skill import BaseSkill, register_skill
|
||||
from omegaconf import DictConfig
|
||||
from omni.isaac.core.controllers import BaseController
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
from omni.isaac.core.utils.transformations import (
|
||||
pose_from_tf_matrix,
|
||||
tf_matrix_from_pose,
|
||||
)
|
||||
from core.compat import BaseController
|
||||
from core.compat import Robot
|
||||
from core.compat import BaseTask
|
||||
from core.compat import pose_from_tf_matrix, tf_matrix_from_pose
|
||||
|
||||
|
||||
# pylint: disable=unused-argument
|
||||
|
||||
@@ -1,9 +1,9 @@
|
||||
import numpy as np
|
||||
from core.skills.base_skill import BaseSkill, register_skill
|
||||
from omegaconf import DictConfig
|
||||
from omni.isaac.core.controllers import BaseController
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
from core.compat import BaseController
|
||||
from core.compat import Robot
|
||||
from core.compat import BaseTask
|
||||
|
||||
|
||||
# pylint: disable=unused-argument
|
||||
|
||||
@@ -4,9 +4,9 @@ import torch
|
||||
from core.skills.base_skill import BaseSkill, register_skill
|
||||
from core.utils.interpolate_utils import linear_interpolation
|
||||
from omegaconf import DictConfig
|
||||
from omni.isaac.core.controllers import BaseController
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
from core.compat import BaseController
|
||||
from core.compat import Robot
|
||||
from core.compat import BaseTask
|
||||
|
||||
|
||||
# pylint: disable=unused-argument
|
||||
|
||||
@@ -12,14 +12,11 @@ from core.utils.plan_utils import (
|
||||
)
|
||||
from core.utils.transformation_utils import poses_from_tf_matrices
|
||||
from omegaconf import DictConfig
|
||||
from omni.isaac.core.controllers import BaseController
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
from omni.isaac.core.utils.prims import get_prim_at_path
|
||||
from omni.isaac.core.utils.transformations import (
|
||||
get_relative_transform,
|
||||
tf_matrix_from_pose,
|
||||
)
|
||||
from core.compat import BaseController
|
||||
from core.compat import Robot
|
||||
from core.compat import BaseTask
|
||||
from core.compat import get_prim_at_path
|
||||
from core.compat import get_relative_transform, tf_matrix_from_pose
|
||||
|
||||
|
||||
@register_skill
|
||||
|
||||
@@ -1,9 +1,9 @@
|
||||
import numpy as np
|
||||
from core.skills.base_skill import BaseSkill, register_skill
|
||||
from omegaconf import DictConfig
|
||||
from omni.isaac.core.controllers import BaseController
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
from core.compat import BaseController
|
||||
from core.compat import Robot
|
||||
from core.compat import BaseTask
|
||||
|
||||
|
||||
# pylint: disable=unused-argument
|
||||
|
||||
@@ -1,9 +1,9 @@
|
||||
import numpy as np
|
||||
from core.skills.base_skill import BaseSkill, register_skill
|
||||
from omegaconf import DictConfig
|
||||
from omni.isaac.core.controllers import BaseController
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
from core.compat import BaseController
|
||||
from core.compat import Robot
|
||||
from core.compat import BaseTask
|
||||
|
||||
|
||||
# pylint: disable=unused-argument
|
||||
|
||||
@@ -1,9 +1,9 @@
|
||||
import numpy as np
|
||||
from core.skills.base_skill import BaseSkill, register_skill
|
||||
from omegaconf import DictConfig
|
||||
from omni.isaac.core.controllers import BaseController
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
from core.compat import BaseController
|
||||
from core.compat import Robot
|
||||
from core.compat import BaseTask
|
||||
from scipy.spatial.transform import Rotation as R
|
||||
|
||||
|
||||
|
||||
@@ -3,11 +3,11 @@ from copy import deepcopy
|
||||
import numpy as np
|
||||
from core.skills.base_skill import BaseSkill, register_skill
|
||||
from omegaconf import DictConfig
|
||||
from omni.isaac.core.controllers import BaseController
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
from omni.isaac.core.utils.prims import get_prim_at_path
|
||||
from omni.isaac.core.utils.transformations import get_relative_transform
|
||||
from core.compat import BaseController
|
||||
from core.compat import Robot
|
||||
from core.compat import BaseTask
|
||||
from core.compat import get_prim_at_path
|
||||
from core.compat import get_relative_transform
|
||||
from scipy.spatial.transform import Rotation as R
|
||||
from solver.planner import KPAMPlanner
|
||||
|
||||
|
||||
@@ -11,14 +11,11 @@ from core.utils.plan_utils import (
|
||||
)
|
||||
from core.utils.transformation_utils import poses_from_tf_matrices
|
||||
from omegaconf import DictConfig
|
||||
from omni.isaac.core.controllers import BaseController
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
from omni.isaac.core.utils.prims import get_prim_at_path
|
||||
from omni.isaac.core.utils.transformations import (
|
||||
get_relative_transform,
|
||||
tf_matrix_from_pose,
|
||||
)
|
||||
from core.compat import BaseController
|
||||
from core.compat import Robot
|
||||
from core.compat import BaseTask
|
||||
from core.compat import get_prim_at_path
|
||||
from core.compat import get_relative_transform, tf_matrix_from_pose
|
||||
|
||||
|
||||
# pylint: disable=unused-argument
|
||||
@@ -284,8 +281,49 @@ class Pick(BaseSkill):
|
||||
if frame == "body":
|
||||
return self.T_obj_ee
|
||||
|
||||
T_world_obj = tf_matrix_from_pose(*self.pick_obj.get_local_pose())
|
||||
local_pose = self.pick_obj.get_local_pose()
|
||||
world_pose = self.pick_obj.get_world_pose()
|
||||
print(f"[PICK_DBG] prim_path={self.pick_obj.prim_path}", flush=True)
|
||||
print(f"[PICK_DBG] local_pose trans={local_pose[0]}", flush=True)
|
||||
print(f"[PICK_DBG] world_pose trans={world_pose[0]}", flush=True)
|
||||
print(f"[PICK_DBG] local_pose ori={local_pose[1]}", flush=True)
|
||||
print(f"[PICK_DBG] world_pose ori={world_pose[1]}", flush=True)
|
||||
parent_prim = get_prim_at_path(self.pick_obj.prim_path).GetParent()
|
||||
print(f"[PICK_DBG] parent_prim_path={parent_prim.GetPrimPath()}", flush=True)
|
||||
grandparent_prim = parent_prim.GetParent()
|
||||
print(f"[PICK_DBG] grandparent_prim_path={grandparent_prim.GetPrimPath()}", flush=True)
|
||||
try:
|
||||
from pxr import UsdGeom
|
||||
obj_prim = get_prim_at_path(self.pick_obj.prim_path)
|
||||
obj_xf = UsdGeom.Xformable(obj_prim)
|
||||
xform_ops = obj_xf.GetOrderedXformOps()
|
||||
print(f"[PICK_DBG] obj_xformOps_count={len(xform_ops)}", flush=True)
|
||||
for op in xform_ops:
|
||||
print(f"[PICK_DBG] obj_xformOp: {op.GetName()} val={op.Get()}", flush=True)
|
||||
obj_l2w = obj_xf.ComputeLocalToWorldTransform(0)
|
||||
print(f"[PICK_DBG] obj_USD_l2w=({obj_l2w[3][0]:.6f}, {obj_l2w[3][1]:.6f}, {obj_l2w[3][2]:.6f})", flush=True)
|
||||
parent_xf = UsdGeom.Xformable(parent_prim)
|
||||
parent_l2w = parent_xf.ComputeLocalToWorldTransform(0)
|
||||
print(f"[PICK_DBG] parent_l2w_translate=({parent_l2w[3][0]}, {parent_l2w[3][1]}, {parent_l2w[3][2]})", flush=True)
|
||||
gp_xf = UsdGeom.Xformable(grandparent_prim)
|
||||
gp_l2w = gp_xf.ComputeLocalToWorldTransform(0)
|
||||
print(f"[PICK_DBG] grandparent_l2w_translate=({gp_l2w[3][0]}, {gp_l2w[3][1]}, {gp_l2w[3][2]})", flush=True)
|
||||
stage = parent_prim.GetStage()
|
||||
mpu = UsdGeom.GetStageMetersPerUnit(stage)
|
||||
print(f"[PICK_DBG] stage_metersPerUnit={mpu}", flush=True)
|
||||
# Check get_local_pose source
|
||||
glp_method = type(self.pick_obj).get_local_pose
|
||||
print(f"[PICK_DBG] get_local_pose_from={glp_method.__qualname__}", flush=True)
|
||||
except Exception as e:
|
||||
import traceback
|
||||
print(f"[PICK_DBG] UsdGeom error: {e}", flush=True)
|
||||
traceback.print_exc()
|
||||
print(f"[PICK_DBG] root_prim_path={self.task.root_prim_path}", flush=True)
|
||||
print(f"[PICK_DBG] reference_prim_path={self.controller.reference_prim_path}", flush=True)
|
||||
T_world_obj = tf_matrix_from_pose(*local_pose)
|
||||
print(f"[PICK_DBG] T_world_obj translation={T_world_obj[:3,3]}", flush=True)
|
||||
T_world_ee = T_world_obj[None] @ self.T_obj_ee
|
||||
print(f"[PICK_DBG] T_world_ee[0] translation={T_world_ee[0,:3,3]}", flush=True)
|
||||
|
||||
if frame == "world":
|
||||
return T_world_ee
|
||||
@@ -294,8 +332,11 @@ class Pick(BaseSkill):
|
||||
T_world_base = get_relative_transform(
|
||||
get_prim_at_path(self.controller.reference_prim_path), get_prim_at_path(self.task.root_prim_path)
|
||||
)
|
||||
print(f"[PICK_DBG] T_world_base translation={T_world_base[:3,3]}", flush=True)
|
||||
T_base_world = np.linalg.inv(T_world_base)
|
||||
print(f"[PICK_DBG] T_base_world translation={T_base_world[:3,3]}", flush=True)
|
||||
T_base_ee = T_base_world[None] @ T_world_ee
|
||||
print(f"[PICK_DBG] T_base_ee[0] translation={T_base_ee[0,:3,3]}", flush=True)
|
||||
return T_base_ee
|
||||
|
||||
def get_contact(self, contact_threshold=0.0):
|
||||
|
||||
@@ -12,15 +12,11 @@ from core.utils.plan_utils import (
|
||||
from core.utils.transformation_utils import create_pose_matrices, poses_from_tf_matrices
|
||||
from core.utils.usd_geom_utils import compute_bbox
|
||||
from omegaconf import DictConfig
|
||||
from omni.isaac.core.controllers import BaseController
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
from omni.isaac.core.utils.prims import get_prim_at_path
|
||||
from omni.isaac.core.utils.transformations import (
|
||||
get_relative_transform,
|
||||
pose_from_tf_matrix,
|
||||
tf_matrix_from_pose,
|
||||
)
|
||||
from core.compat import BaseController
|
||||
from core.compat import Robot
|
||||
from core.compat import BaseTask
|
||||
from core.compat import get_prim_at_path
|
||||
from core.compat import get_relative_transform, pose_from_tf_matrix, tf_matrix_from_pose
|
||||
from scipy.spatial.transform import Rotation as R
|
||||
|
||||
|
||||
|
||||
@@ -7,9 +7,9 @@ from core.utils.transformation_utils import (
|
||||
perturb_position,
|
||||
)
|
||||
from omegaconf import DictConfig
|
||||
from omni.isaac.core.controllers import BaseController
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
from core.compat import BaseController
|
||||
from core.compat import Robot
|
||||
from core.compat import BaseTask
|
||||
from scipy.spatial.transform import Rotation as R
|
||||
|
||||
|
||||
|
||||
@@ -3,11 +3,11 @@ from copy import deepcopy
|
||||
import numpy as np
|
||||
from core.skills.base_skill import BaseSkill, register_skill
|
||||
from omegaconf import DictConfig, OmegaConf
|
||||
from omni.isaac.core.controllers import BaseController
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
from omni.isaac.core.utils.prims import get_prim_at_path
|
||||
from omni.isaac.core.utils.transformations import get_relative_transform
|
||||
from core.compat import BaseController
|
||||
from core.compat import Robot
|
||||
from core.compat import BaseTask
|
||||
from core.compat import get_prim_at_path
|
||||
from core.compat import get_relative_transform
|
||||
from scipy.spatial.transform import Rotation as R
|
||||
from solver.planner import KPAMPlanner
|
||||
|
||||
|
||||
@@ -3,15 +3,11 @@ import torch
|
||||
from core.skills.base_skill import BaseSkill, register_skill
|
||||
from core.utils.interpolate_utils import linear_interpolation
|
||||
from omegaconf import DictConfig
|
||||
from omni.isaac.core.controllers import BaseController
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
from omni.isaac.core.utils.prims import get_prim_at_path
|
||||
from omni.isaac.core.utils.transformations import (
|
||||
get_relative_transform,
|
||||
pose_from_tf_matrix,
|
||||
tf_matrix_from_pose,
|
||||
)
|
||||
from core.compat import BaseController
|
||||
from core.compat import Robot
|
||||
from core.compat import BaseTask
|
||||
from core.compat import get_prim_at_path
|
||||
from core.compat import get_relative_transform, pose_from_tf_matrix, tf_matrix_from_pose
|
||||
from scipy.spatial.transform import Rotation as R
|
||||
|
||||
|
||||
|
||||
@@ -1,15 +1,11 @@
|
||||
import numpy as np
|
||||
from core.skills.base_skill import BaseSkill, register_skill
|
||||
from omegaconf import DictConfig
|
||||
from omni.isaac.core.controllers import BaseController
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
from omni.isaac.core.utils.prims import get_prim_at_path
|
||||
from omni.isaac.core.utils.transformations import (
|
||||
get_relative_transform,
|
||||
pose_from_tf_matrix,
|
||||
tf_matrix_from_pose,
|
||||
)
|
||||
from core.compat import BaseController
|
||||
from core.compat import Robot
|
||||
from core.compat import BaseTask
|
||||
from core.compat import get_prim_at_path
|
||||
from core.compat import get_relative_transform, pose_from_tf_matrix, tf_matrix_from_pose
|
||||
from scipy.spatial.transform import Rotation as R
|
||||
|
||||
|
||||
|
||||
@@ -3,15 +3,12 @@ from core.skills.base_skill import BaseSkill, register_skill
|
||||
from core.utils.transformation_utils import get_orientation, perturb_orientation
|
||||
from core.utils.usd_geom_utils import compute_bbox
|
||||
from omegaconf import DictConfig
|
||||
from omni.isaac.core.controllers import BaseController
|
||||
from omni.isaac.core.objects.cylinder import VisualCylinder
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
from omni.isaac.core.utils.prims import get_prim_at_path
|
||||
from omni.isaac.core.utils.transformations import (
|
||||
get_relative_transform,
|
||||
tf_matrix_from_pose,
|
||||
)
|
||||
from core.compat import BaseController
|
||||
from core.compat import VisualCylinder
|
||||
from core.compat import Robot
|
||||
from core.compat import BaseTask
|
||||
from core.compat import get_prim_at_path
|
||||
from core.compat import get_relative_transform, tf_matrix_from_pose
|
||||
from scipy.spatial.transform import Rotation as R
|
||||
|
||||
|
||||
@@ -143,6 +140,8 @@ class Track(BaseSkill):
|
||||
def cal_table_2_base(self):
|
||||
tgt = self.task.fixtures["table"]
|
||||
bbox_tgt = compute_bbox(tgt.prim)
|
||||
print(f"[BBOX_DBG] table bbox min={list(bbox_tgt.min)}, max={list(bbox_tgt.max)}", flush=True)
|
||||
print(f"[BBOX_DBG] T_base_2_world translation={self.T_base_2_world[:3, 3]}", flush=True)
|
||||
table_center = (np.asarray(bbox_tgt.min) + np.asarray(bbox_tgt.max)) / 2
|
||||
tgt_z_max = bbox_tgt.max[2]
|
||||
table_center[2] = tgt_z_max
|
||||
|
||||
@@ -1,9 +1,9 @@
|
||||
import numpy as np
|
||||
from core.skills.base_skill import BaseSkill, register_skill
|
||||
from omegaconf import DictConfig
|
||||
from omni.isaac.core.controllers import BaseController
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
from core.compat import BaseController
|
||||
from core.compat import Robot
|
||||
from core.compat import BaseTask
|
||||
|
||||
|
||||
# pylint: disable=consider-using-generator,too-many-public-methods,unused-argument
|
||||
|
||||
@@ -18,16 +18,12 @@ from core.utils.scene_utils import deactivate_selected_prims
|
||||
from core.utils.transformation_utils import get_orientation
|
||||
from core.utils.visual_distractor import set_distractors
|
||||
from omegaconf import DictConfig
|
||||
from omni.isaac.core.materials import PreviewSurface
|
||||
from omni.isaac.core.prims import RigidContactView, XFormPrim
|
||||
from omni.isaac.core.scenes.scene import Scene
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
from omni.isaac.core.utils.prims import (
|
||||
delete_prim,
|
||||
get_prim_at_path,
|
||||
is_prim_path_valid,
|
||||
)
|
||||
from omni.isaac.core.utils.stage import get_current_stage
|
||||
from core.compat import PreviewSurface
|
||||
from core.compat import RigidContactView, XFormPrim
|
||||
from core.compat import Scene
|
||||
from core.compat import BaseTask
|
||||
from core.compat import delete_prim, get_prim_at_path, is_prim_path_valid
|
||||
from core.compat import get_current_stage
|
||||
from omni.physx.scripts import particleUtils
|
||||
from pxr import Gf, PhysxSchema, Sdf, Usd, UsdGeom, UsdLux, UsdShade, Vt
|
||||
from scipy.spatial.transform import Rotation as R
|
||||
@@ -335,6 +331,14 @@ class BananaBaseTask(BaseTask):
|
||||
orientation = get_orientation(cfg.get("euler"), cfg.get("quaternion"))
|
||||
obj.set_local_pose(translation=cfg.get("translation"), orientation=orientation)
|
||||
obj.set_local_scale(cfg.get("scale", [1.0, 1.0, 1.0]))
|
||||
# [LOAD_DBG] Print after set_local_pose
|
||||
try:
|
||||
from pxr import UsdGeom
|
||||
_xf = UsdGeom.Xformable(get_prim_at_path(obj.prim_path))
|
||||
for _op in _xf.GetOrderedXformOps():
|
||||
print(f"[LOAD_DBG] {cfg['name']} after_set_local_pose: {_op.GetName()} = {_op.Get()}", flush=True)
|
||||
except Exception as _e:
|
||||
print(f"[LOAD_DBG] {cfg['name']} after_set_local_pose error: {_e}", flush=True)
|
||||
obj.set_visibility(cfg.get("visible", True))
|
||||
|
||||
# Extra behavior per type
|
||||
@@ -490,7 +494,7 @@ class BananaBaseTask(BaseTask):
|
||||
if cfg.get("apply_randomization", False):
|
||||
envmap_id = random.randint(0, len(envmap_hdr_path_list) - 1)
|
||||
intensity = random.uniform(cfg["intensity_range"][0], cfg["intensity_range"][1])
|
||||
rotation = [random.uniform(cfg["rotation_range"][0], cfg["rotation_range"][1]) for _ in range(3)]
|
||||
rotation = [0.0, 0.0, random.uniform(cfg["rotation_range"][0], cfg["rotation_range"][1])]
|
||||
else:
|
||||
envmap_id = 0
|
||||
intensity = 1000.0
|
||||
|
||||
@@ -1,7 +1,7 @@
|
||||
import numpy as np
|
||||
from omni.isaac.core.utils.prims import get_prim_at_path
|
||||
from omni.isaac.core.utils.transformations import get_relative_transform
|
||||
from omni.isaac.sensor import Camera
|
||||
from core.compat import get_prim_at_path
|
||||
from core.compat import get_relative_transform
|
||||
from core.compat import Camera
|
||||
|
||||
|
||||
def _get_annotator(camera: Camera, annotator_name: str):
|
||||
|
||||
@@ -1,5 +1,5 @@
|
||||
import numpy as np
|
||||
from omni.isaac.core.utils.transformations import pose_from_tf_matrix
|
||||
from core.compat import pose_from_tf_matrix
|
||||
from scipy.spatial.transform import Rotation as R
|
||||
|
||||
|
||||
|
||||
@@ -18,7 +18,7 @@ logging.getLogger("urllib3").setLevel(logging.WARNING)
|
||||
|
||||
|
||||
def set_semantic_label(prim: Prim, label):
|
||||
from omni.isaac.core.utils.semantics import add_update_semantics
|
||||
from core.compat import add_update_semantics
|
||||
|
||||
if prim.GetTypeName() == "Mesh":
|
||||
add_update_semantics(prim, semantic_label=label, type_label="class")
|
||||
@@ -28,7 +28,7 @@ def set_semantic_label(prim: Prim, label):
|
||||
|
||||
|
||||
def set_plane_semantic_label(prim: Prim, label):
|
||||
from omni.isaac.core.utils.semantics import add_update_semantics
|
||||
from core.compat import add_update_semantics
|
||||
|
||||
if prim.GetTypeName() == "Plane":
|
||||
add_update_semantics(prim, semantic_label=label, type_label="class")
|
||||
@@ -38,7 +38,7 @@ def set_plane_semantic_label(prim: Prim, label):
|
||||
|
||||
|
||||
def set_robot_semantic_label(robot: Prim, parent_name: str):
|
||||
from omni.isaac.core.utils.semantics import add_update_semantics
|
||||
from core.compat import add_update_semantics
|
||||
|
||||
if robot.GetTypeName() == "Mesh":
|
||||
prim_path = str(robot.GetPrimPath())
|
||||
|
||||
Binary file not shown.
Binary file not shown.
Binary file not shown.
BIN
workflows/simbox/example_assets/table0/instance.usd.bak
Normal file
BIN
workflows/simbox/example_assets/table0/instance.usd.bak
Normal file
Binary file not shown.
Binary file not shown.
Binary file not shown.
File diff suppressed because it is too large
Load Diff
Binary file not shown.
@@ -0,0 +1 @@
|
||||
/home/tangger/LYT/maic_usd_assets_moudle/laboratory_equipment/Test_Tube_Rack/Test_Tube_Rack_AA_01.usdc
|
||||
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user