File size: 11,688 Bytes
b60a439
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
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
# How to prepare your modality configuration

## Overview

The modality configuration defines how your robot's data should be loaded, processed, and interpreted by the model. This configuration bridges your dataset's physical structure (defined in `meta/modality.json`) and the model's data processing pipeline.

Each embodiment requires a Python configuration file that specifies:
- Which observations to use (video cameras, proprioceptive states)
- How to sample data temporally (current frame, historical frames, future action horizons)
- How actions should be interpreted and transformed
- Which language annotations to use

## Configuration Structure

A modality configuration is a Python dictionary containing four top-level keys: `"video"`, `"state"`, `"action"`, and `"language"`. Each key maps to a `ModalityConfig` object.

Here's the [SO-100 example](../examples/SO100/so100_config.py):

```python
from gr00t.configs.data.embodiment_configs import register_modality_config
from gr00t.data.types import ModalityConfig, ActionConfig, ActionRepresentation, ActionType, ActionFormat

so100_config = {
    "video": ModalityConfig(...),
    "state": ModalityConfig(...),
    "action": ModalityConfig(...),
    "language": ModalityConfig(...),
}

register_modality_config(so100_config, embodiment_tag=EmbodimentTag.NEW_EMBODIMENT)
```

## Understanding `ModalityConfig`

Each `ModalityConfig` specifies two required fields and several optional ones:

### Required Fields

**1. `delta_indices` (list[int])**

Defines which temporal offsets to sample relative to the current timestep:
- Current observation: Use [0] for the current timestep (recommended for video and state)                                                                     
- Future actions: Use positive indices (e.g., list(range(0, 16))) for action prediction horizons                                                            

> **Note:** Negative indices (e.g., [-2, -1, 0]) are supported by the data loader for historical context, but no current N1.7 embodiment config uses them. Stick with [0] for video and state unless you have a specific reason to stack frames.

Examples:
```python
# Single current frame for video
delta_indices=[0]


# 16-step action prediction horizon
delta_indices=list(range(0, 16))
```

> **Note:** If you modify `delta_indices` for the action modality (e.g., changing the action horizon from 16 to 8), you **must** regenerate the dataset statistics by re-running `python gr00t/data/stats.py --dataset-path <dataset_path> --embodiment-tag <embodiment_tag>`. The normalization statistics (especially `meta/relative_stats.json`) are computed based on the original `delta_indices` length, and a mismatch will cause errors during training.

<details>
<summary>Example: What happens if you change <code>delta_indices</code> without regenerating stats?</summary>

Suppose your action config originally uses a 16-step horizon:

```python
"action": ModalityConfig(
    delta_indices=list(range(0, 16)),  # 16 steps
    ...
)
```

Running `python gr00t/data/stats.py` generates `meta/relative_stats.json` with per-step statistics of shape `(16, D)`, where `D` is the action dimension.

If you later change the horizon to 8 steps:

```python
"action": ModalityConfig(
    delta_indices=list(range(0, 8)),  # 8 steps
    ...
)
```

The training data will now have shape `(8, D)`, but the normalization parameters from `relative_stats.json` still have shape `(16, D)`. This dimension mismatch causes an `IndexError` during normalization:

```
IndexError: boolean index did not match indexed array along dimension 0;
dimension is 8 but corresponding boolean dimension is 16
```

**Fix:** Re-run `python gr00t/data/stats.py --dataset-path <dataset_path> --embodiment-tag <embodiment_tag>` after changing `delta_indices` to regenerate matching statistics.

</details>


**2. `modality_keys` (list[str])**

Specifies which keys to load from your dataset. These keys **must match** the keys defined in your `meta/modality.json` file.

For the SO-100 example:
- **Video keys**: Must match keys in `meta/modality.json` under `"video"` (e.g., `"front"`, `"wrist"`)
- **State keys**: Must match keys in `meta/modality.json` under `"state"` (e.g., `"single_arm"`, `"gripper"`)
- **Action keys**: Must match keys in `meta/modality.json` under `"action"` (e.g., `"single_arm"`, `"gripper"`)
- **Language keys**: Must match keys in `meta/modality.json` under `"annotation"` (e.g., `"annotation.human.task_description"` for SO-100)

### Optional Fields

**3. `sin_cos_embedding_keys` (list[str] | None)**

Specifies which state keys should use sine/cosine encoding. Best for dimensions that are in radians (e.g., joint angles). If not specified, min-max normalization is used. Note that this will duplicate the number of dimensions by 2, and is only recommended for proprioceptive states.

```python
"state": ModalityConfig(
    delta_indices=[0],
    modality_keys=["single_arm", "gripper"],
    sin_cos_embedding_keys=["single_arm"],  # Apply sin/cos to joint angles
)
```

**4. `mean_std_embedding_keys` (list[str] | None)**

Specifies which keys should use mean/standard deviation normalization instead of min-max normalization.

**5. `action_configs` (list[ActionConfig] | None)**

Required for the `"action"` modality. Defines how each action modality should be interpreted and transformed. The list must have the **same length and same order** as `modality_keys``action_configs[0]` applies to `modality_keys[0]`, `action_configs[1]` to `modality_keys[1]`, etc. A mismatch in ordering will silently apply the wrong representation (e.g., RELATIVE to a gripper that should be ABSOLUTE). See more details in the [Action Modality](#understanding-actionconfig) section.

## Configuring Each Modality

### Video Modality

Defines which camera views to use:

```python
"video": ModalityConfig(
    delta_indices=[0],  # Current frame only
    modality_keys=[
        "front",  # Must match a key in meta/modality.json under "video"
    ],
)
```

For multiple cameras:
```python
"video": ModalityConfig(
    delta_indices=[0],
    modality_keys=["front", "wrist"],
)
```

### State Modality

Defines proprioceptive observations (joint positions, gripper states, etc.):

```python
"state": ModalityConfig(
    delta_indices=[0],  # Current state
    modality_keys=[
        "single_arm",      # Must match keys in meta/modality.json under "state"
        "gripper",
    ],
)
```

### Action Modality

Defines the action space and prediction horizon:

```python
"action": ModalityConfig(
    delta_indices=list(range(0, 16)),  # Predict 16 steps into the future
    modality_keys=[
        "single_arm",      # Must match keys in meta/modality.json under "action"
        "gripper",
    ],
    action_configs=[
        # One ActionConfig per modality_key
        # single_arm
        ActionConfig(
            rep=ActionRepresentation.RELATIVE,  # relative control of the single arm
            type=ActionType.NON_EEF,
            format=ActionFormat.DEFAULT,
        ),
        # gripper
        ActionConfig(
            rep=ActionRepresentation.ABSOLUTE,  # absolute control of the gripper
            type=ActionType.NON_EEF,
            format=ActionFormat.DEFAULT,
        ),
    ],
)
```

#### Understanding `ActionConfig`

Each `ActionConfig` has three required fields and one optional field:

**1. `rep` (ActionRepresentation)**

Defines how actions should be interpreted:
- `RELATIVE`: Actions are deltas from the current state (introduced in the UMI paper)
- `ABSOLUTE`: Actions are target positions

Using relative actions will lead to smoother actions, but might suffer from drifting. If you want to use relative actions, please make sure the state and action stored in the dataset are absolute, and the absolute to relative will be handled in the processor.

**2. `type` (ActionType)**

Specifies the control space:
- `EEF`: End-effector/Cartesian space control (Expecting a 9-dimensional vector: x, y, z positions + rotation 6D)
- `NON_EEF`: Joint space control and other non-EEF control spaces (joint angles, positions, gripper positions, etc.)

**3. `format` (ActionFormat)**

Defines the action representation format:
- `DEFAULT`: Standard format (e.g., joint angles, gripper positions)
- `XYZ_ROT6D`: 3D position + 6D rotation representation for end-effector control
- `XYZ_ROTVEC`: 3D position + rotation vector for end-effector control

**4. `state_key` (str | None)**

Optional. Specifies the corresponding reference state key for computing relative actions when `rep=RELATIVE`. If not provided, the system will use the action key as the reference state key.

Example with `state_key`:
```python
"joint_pos_action_left": ActionConfig(
    rep=ActionRepresentation.RELATIVE,
    type=ActionType.NON_EEF,
    format=ActionFormat.DEFAULT,
    state_key="joint_pos_obs_left",  # Use this state to compute relative action
)
```

### Language Modality

Defines which language annotations to use:

```python
"language": ModalityConfig(
    delta_indices=[0],
    modality_keys=["annotation.human.task_description"],  # Must match annotation keys in meta/modality.json
)
```

## Complete Example: SO-100

Here's the complete SO-100 configuration with explanations:

```python
so100_config = {
    "video": ModalityConfig(
        delta_indices=[0],
        modality_keys=["front", "wrist"],
    ),
    "state": ModalityConfig(
        delta_indices=[0],
        modality_keys=[
            "single_arm",
            "gripper",
        ],
    ),
    "action": ModalityConfig(
        delta_indices=list(range(0, 16)),
        modality_keys=[
            "single_arm",
            "gripper",
        ],
        action_configs=[
            ActionConfig(
                rep=ActionRepresentation.RELATIVE,
                type=ActionType.NON_EEF,
                format=ActionFormat.DEFAULT,
            ),
            ActionConfig(
                rep=ActionRepresentation.ABSOLUTE,
                type=ActionType.NON_EEF,
                format=ActionFormat.DEFAULT,
            ),
        ],
    ),
    "language": ModalityConfig(
        delta_indices=[0],
        modality_keys=["annotation.human.task_description"],
    ),
}
```

## Key Relationships with `meta/modality.json`

The modality configuration's `modality_keys` must reference keys that exist in your dataset's `meta/modality.json`:

**Example `meta/modality.json`:**
```json
{
    "state": {
        "single_arm": {"start": 0, "end": 5},
        "gripper": {"start": 5, "end": 6},
    },
    "action": {
        "single_arm": {"start": 0, "end": 5},
        "gripper": {"start": 5, "end": 6},
    },
    "video": {
        "front": {"original_key": "observation.images.front"},
        "wrist": {"original_key": "observation.images.wrist"},
    },
    "annotation": {
        "human.task_description": {
            "original_key": "task_index"
        }
    }
}
```

The system will:
1. Use `modality_keys` to look up the corresponding entries in `meta/modality.json`
2. Extract the correct slices from the concatenated state/action arrays
3. Apply the specified transformations (normalization, action representation conversion)

## Registering Your Configuration

After defining your configuration, register it so it's available to the training and inference pipelines:

```python
from gr00t.configs.data.embodiment_configs import register_modality_config

your_modality_config = {
    ...
}

register_modality_config(your_modality_config, embodiment_tag=EmbodimentTag.NEW_EMBODIMENT)
```

Save your configuration to a Python file and pass the path to the `modality_config_path` argument when running the finetuning script.