API¤

RING¤

RING(lam, Ts, **kwargs) ¤

Creates the RING network.

Parameters:
  • lam (list[int] | None) –

    parent array, if None must be given via ringnet.apply(..., lam=lam)

  • Ts

    sampling interval of IMU data; time delta in seconds

Returns:
  • AbstractFilter

    ring.ml.AbstractFilter: An instantiation of ring.ml.ringnet.RING with trained parameters.

Examples:

>>> import ring
>>> import numpy as np
>>>
>>> T  : int       = 30        # sequence length     [s]
>>> Ts : float     = 0.01      # sampling interval   [s]
>>> B  : int       = 1         # batch size
>>> lam: list[int] = [0, 1, 2] # parent array
>>> N  : int       = len(lam)  # number of bodies
>>> T_i: int       = int(T/Ts) # number of timesteps
>>>
>>> X = np.zeros((B, T_i, N, 9))
>>> # where X is structured as follows:
>>> # X[..., :3]  = acc
>>> # X[..., 3:6] = gyr
>>> # X[..., 6:9] = jointaxis
>>>
>>> # let's assume we have an IMU on each outer segment of the
>>> # three-segment kinematic chain
>>> X[:, :, 0, :3]  = acc_segment1
>>> X[:, :, 2, :3]  = acc_segment3
>>> X[:, :, 0, 3:6] = gyr_segment1
>>> X[:, :, 2, 3:6] = gyr_segment3
>>>
>>> ringnet = ring.RING(lam, Ts)
>>>
>>> yhat, _ = ringnet.apply(X)
>>> # yhat : unit quaternions, shape = (B, T_i, N, 4)
>>> # yhat[b, :, i] is the orientation from body `i` to parent body `lam[i]`
>>>
>>> # use `jax.jit` to compile the forward pass
>>> jit_apply = jax.jit(ringnet.apply)
>>> yhat, _ = jit_apply(X)
>>>
>>> # manually pass in and out the hidden state like so
>>> initial_state = None
>>> yhat, state = ringnet.apply(X, state=initial_state)
>>> # state: final hidden state, shape = (B, N, 2*H)
Source code in src/ring/__init__.py
 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
def RING(lam: list[int] | None, Ts: float | None, **kwargs) -> ml.AbstractFilter:
    """Creates the RING network.

    Params:
        lam: parent array, if `None` must be given via `ringnet.apply(..., lam=lam)`
        Ts : sampling interval of IMU data; time delta in seconds

    Returns:
        ring.ml.AbstractFilter: An instantiation of `ring.ml.ringnet.RING` with trained
            parameters.

    Examples:
        >>> import ring
        >>> import numpy as np
        >>>
        >>> T  : int       = 30        # sequence length     [s]
        >>> Ts : float     = 0.01      # sampling interval   [s]
        >>> B  : int       = 1         # batch size
        >>> lam: list[int] = [0, 1, 2] # parent array
        >>> N  : int       = len(lam)  # number of bodies
        >>> T_i: int       = int(T/Ts) # number of timesteps
        >>>
        >>> X = np.zeros((B, T_i, N, 9))
        >>> # where X is structured as follows:
        >>> # X[..., :3]  = acc
        >>> # X[..., 3:6] = gyr
        >>> # X[..., 6:9] = jointaxis
        >>>
        >>> # let's assume we have an IMU on each outer segment of the
        >>> # three-segment kinematic chain
        >>> X[:, :, 0, :3]  = acc_segment1
        >>> X[:, :, 2, :3]  = acc_segment3
        >>> X[:, :, 0, 3:6] = gyr_segment1
        >>> X[:, :, 2, 3:6] = gyr_segment3
        >>>
        >>> ringnet = ring.RING(lam, Ts)
        >>>
        >>> yhat, _ = ringnet.apply(X)
        >>> # yhat : unit quaternions, shape = (B, T_i, N, 4)
        >>> # yhat[b, :, i] is the orientation from body `i` to parent body `lam[i]`
        >>>
        >>> # use `jax.jit` to compile the forward pass
        >>> jit_apply = jax.jit(ringnet.apply)
        >>> yhat, _ = jit_apply(X)
        >>>
        >>> # manually pass in and out the hidden state like so
        >>> initial_state = None
        >>> yhat, state = ringnet.apply(X, state=initial_state)
        >>> # state: final hidden state, shape = (B, N, 2*H)
    """
    from pathlib import Path
    import warnings

    config = dict(
        use_100Hz_RING=True,
        use_lpf=True,
        lpf_cutoff_freq=ml._LPF_CUTOFF_FREQ,
    )
    config.update(kwargs)

    if Ts is not None and (Ts > (1 / 40) or Ts < (1 / 200)):
        warnings.warn(
            "RING was only trained on sampling rates between 40 to 200 Hz "
            f"but found {1 / Ts}Hz"
        )

    if Ts is not None and Ts == 0.01 and config["use_100Hz_RING"]:
        # this set of parameters was trained exclusively on 100Hz data; it also
        # expects F=9 features per node and not F=10 where the last features is
        # the sampling interval Ts
        params = Path(__file__).parent.joinpath("ml/params/0x1d76628065a71e0f.pickle")
        add_Ts = False
    else:
        # this set of parameters was trained on sampling rates from 40 to 200 Hz
        params = Path(__file__).parent.joinpath("ml/params/0x13e3518065c21cd8.pickle")
        add_Ts = True

    ringnet = ml.RING(
        params=params, lam=None if lam is None else tuple(lam), jit=False, name="RING"
    )
    ringnet = ml.base.ScaleX_FilterWrapper(ringnet)
    if config["use_lpf"]:
        ringnet = ml.base.LPF_FilterWrapper(
            ringnet,
            config["lpf_cutoff_freq"],
            samp_freq=None if Ts is None else 1 / Ts,
            quiet=True,
        )
    ringnet = ml.base.GroundTruthHeading_FilterWrapper(ringnet)
    if add_Ts:
        ringnet = ml.base.AddTs_FilterWrapper(ringnet, Ts)
    return ringnet

RING ¤

Source code in src/ring/ml/ringnet.py
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
class RING(ml_base.AbstractFilter):
    def __init__(
        self,
        params=None,
        lam=None,
        jit: bool = True,
        name=None,
        forward_factory=make_ring,
        **kwargs,
    ):
        "Untrained RING network"
        self.forward_lam_factory = partial(forward_factory, **kwargs)
        self.params = self._load_params(params)
        self.lam = lam
        self._name = name

        if jit:
            self.apply = jax.jit(self.apply, static_argnames="lam")

    def apply(self, X, params=None, state=None, y=None, lam=None):
        if lam is None:
            assert self.lam is not None
            lam = self.lam

        return super().apply(X, params, state, y, tuple(lam))

    def init(self, bs: Optional[int] = None, X=None, lam=None, seed: int = 1):
        assert X is not None, "Providing `X` via in `ringnet.init(X=X)` is required"
        if bs is not None:
            assert X.ndim == 4

        if X.ndim == 4:
            if bs is not None:
                assert bs == X.shape[0]
            else:
                bs = X.shape[0]
            X = X[0]

        # (T, N, F) -> (1, N, F) for faster .init call
        X = X[0:1]

        if lam is None:
            assert self.lam is not None
            lam = self.lam

        key = jax.random.PRNGKey(seed)
        params, state = self.forward_lam_factory(lam=lam).init(key, X)

        if bs is not None:
            state = jax.tree_map(lambda arr: jnp.repeat(arr[None], bs, axis=0), state)

        return params, state

    def _apply_batched(self, X, params, state, y, lam):
        if (params is None and self.params is None) or state is None:
            _params, _state = self.init(bs=X.shape[0], X=X, lam=lam)

        if params is None and self.params is None:
            params = _params
        elif params is None:
            params = self.params
        else:
            pass

        if state is None:
            state = _state

        yhat, next_state = jax.vmap(
            self.forward_lam_factory(lam=lam).apply, in_axes=(None, 0, 0)
        )(params, state, X)

        return yhat, next_state

    @staticmethod
    def _load_params(params: str | dict | None | Path):
        assert isinstance(params, (str, dict, type(None), Path))
        if isinstance(params, (Path, str)):
            return pickle_load(params)
        return params

    def nojit(self) -> "RING":
        ringnet = RING(params=self.params, lam=self.lam, jit=False)
        ringnet.forward_lam_factory = self.forward_lam_factory
        return ringnet

    def _pre_save(self, params=None, lam=None) -> None:
        if params is not None:
            self.params = params
        if lam is not None:
            self.lam = lam

    @staticmethod
    def _post_load(ringnet: "RING", jit: bool = True) -> "RING":
        if jit:
            ringnet.apply = jax.jit(ringnet.apply, static_argnames="lam")
        return ringnet
__init__(params=None, lam=None, jit=True, name=None, forward_factory=make_ring, **kwargs) ¤

Untrained RING network

Source code in src/ring/ml/ringnet.py
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
def __init__(
    self,
    params=None,
    lam=None,
    jit: bool = True,
    name=None,
    forward_factory=make_ring,
    **kwargs,
):
    "Untrained RING network"
    self.forward_lam_factory = partial(forward_factory, **kwargs)
    self.params = self._load_params(params)
    self.lam = lam
    self._name = name

    if jit:
        self.apply = jax.jit(self.apply, static_argnames="lam")

RCMG¤

RCMG ¤

Source code in src/ring/algorithms/generator/base.py
 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
class RCMG:
    def __init__(
        self,
        sys: base.System | list[base.System],
        config: jcalc.MotionConfig | list[jcalc.MotionConfig] = jcalc.MotionConfig(),
        setup_fn: Optional[types.SETUP_FN] = None,
        finalize_fn: Optional[types.FINALIZE_FN] = None,
        add_X_imus: bool = False,
        add_X_imus_kwargs: dict = dict(),
        add_X_jointaxes: bool = False,
        add_X_jointaxes_kwargs: dict = dict(),
        add_y_relpose: bool = False,
        add_y_rootincl: bool = False,
        add_y_rootincl_kwargs: dict = dict(),
        sys_ml: Optional[base.System] = None,
        randomize_positions: bool = False,
        randomize_motion_artifacts: bool = False,
        randomize_joint_params: bool = False,
        randomize_hz: bool = False,
        randomize_hz_kwargs: dict = dict(),
        imu_motion_artifacts: bool = False,
        imu_motion_artifacts_kwargs: dict = dict(),
        dynamic_simulation: bool = False,
        dynamic_simulation_kwargs: dict = dict(),
        output_transform: Optional[Callable] = None,
        keep_output_extras: bool = False,
        use_link_number_in_Xy: bool = False,
        cor: bool = False,
        disable_tqdm: bool = False,
    ) -> None:
        "Random Chain Motion Generator"

        sys, config = utils.to_list(sys), utils.to_list(config)
        sys_ml = sys[0] if sys_ml is None else sys_ml

        for c in config:
            assert c.is_feasible()

        self.gens = []
        for _sys in sys:
            self.gens.append(
                _build_mconfig_batched_generator(
                    sys=_sys,
                    config=config,
                    setup_fn=setup_fn,
                    finalize_fn=finalize_fn,
                    add_X_imus=add_X_imus,
                    add_X_imus_kwargs=add_X_imus_kwargs,
                    add_X_jointaxes=add_X_jointaxes,
                    add_X_jointaxes_kwargs=add_X_jointaxes_kwargs,
                    add_y_relpose=add_y_relpose,
                    add_y_rootincl=add_y_rootincl,
                    add_y_rootincl_kwargs=add_y_rootincl_kwargs,
                    sys_ml=sys_ml,
                    randomize_positions=randomize_positions,
                    randomize_motion_artifacts=randomize_motion_artifacts,
                    randomize_joint_params=randomize_joint_params,
                    randomize_hz=randomize_hz,
                    randomize_hz_kwargs=randomize_hz_kwargs,
                    imu_motion_artifacts=imu_motion_artifacts,
                    imu_motion_artifacts_kwargs=imu_motion_artifacts_kwargs,
                    dynamic_simulation=dynamic_simulation,
                    dynamic_simulation_kwargs=dynamic_simulation_kwargs,
                    output_transform=output_transform,
                    keep_output_extras=keep_output_extras,
                    use_link_number_in_Xy=use_link_number_in_Xy,
                    cor=cor,
                )
            )

        self._n_mconfigs = len(config)
        self._size_of_generators = [self._n_mconfigs] * len(self.gens)

        self._disable_tqdm = disable_tqdm

    def _compute_repeats(self, sizes: int | list[int]) -> list[int]:
        "how many times the generators are repeated to create a batch of `sizes`"

        S, L = sum(self._size_of_generators), len(self._size_of_generators)

        def assert_size(size: int):
            assert self._n_mconfigs in utils.primes(size), (
                f"`size`={size} is not divisible by number of "
                + f"`mconfigs`={self._n_mconfigs}"
            )

        if isinstance(sizes, int):
            assert (sizes // S) > 0, f"Batchsize or size too small. {sizes} < {S}"
            assert sizes % S == 0, f"`size`={sizes} not divisible by {S}"
            repeats = L * [sizes // S]
        else:
            for size in sizes:
                assert_size(size)

            assert len(sizes) == len(
                self.gens
            ), f"len(`sizes`)={len(sizes)} != {len(self.gens)}"

            repeats = [
                size // size_of_gen
                for size, size_of_gen in zip(sizes, self._size_of_generators)
            ]
            assert 0 not in repeats

        return repeats

    def to_lazy_gen(
        self, sizes: int | list[int] = 1, jit: bool = True
    ) -> types.BatchedGenerator:
        return batch.generators_lazy(self.gens, self._compute_repeats(sizes), jit)

    @staticmethod
    def _number_of_executions_required(size: int) -> int:
        _, vmap = utils.distribute_batchsize(size)

        eager_threshold = utils.batchsize_thresholds()[1]
        primes = iter(utils.primes(vmap))
        n_calls = 1
        while vmap > eager_threshold:
            prime = next(primes)
            n_calls *= prime
            vmap /= prime

        return n_calls

    def to_list(self, sizes: int | list[int] = 1, seed: int = 1):
        "Returns list of unbatched sequences as numpy arrays."
        repeats = self._compute_repeats(sizes)
        sizes = list(jnp.array(repeats) * jnp.array(self._size_of_generators))

        reduced_repeats = []
        n_calls = []
        for size, repeat in zip(sizes, repeats):
            n_call = self._number_of_executions_required(size)
            gcd = utils.gcd(n_call, repeat)
            n_calls.append(gcd)
            reduced_repeats.append(repeat // gcd)
        jits = [N > 1 for N in n_calls]

        gens = []
        for i in range(len(repeats)):
            gens.append(
                batch.generators_lazy([self.gens[i]], [reduced_repeats[i]], jits[i])
            )

        return batch.generators_eager_to_list(gens, n_calls, seed, self._disable_tqdm)

    def to_pickle(
        self,
        path: str,
        sizes: int | list[int] = 1,
        seed: int = 1,
        overwrite: bool = True,
    ) -> None:
        data = tree_utils.tree_batch(self.to_list(sizes, seed))
        utils.pickle_save(data, path, overwrite=overwrite)

    def to_eager_gen(
        self,
        batchsize: int = 1,
        sizes: int | list[int] = 1,
        seed: int = 1,
        shuffle: bool = True,
        transform=None,
    ) -> types.BatchedGenerator:
        data = self.to_list(sizes, seed)
        assert len(data) >= batchsize
        return self.eager_gen_from_list(data, batchsize, shuffle, transform)

    @staticmethod
    def eager_gen_from_list(
        data: list[tree_utils.PyTree],
        batchsize: int,
        shuffle: bool = True,
        transform=None,
    ) -> types.BatchedGenerator:
        data = data.copy()
        n_batches, i = len(data) // batchsize, 0

        def generator(key: jax.Array):
            nonlocal i
            if shuffle and i == 0:
                random.shuffle(data)

            start, stop = i * batchsize, (i + 1) * batchsize
            batch = tree_utils.tree_batch(data[start:stop], backend="numpy")
            batch = utils.pytree_deepcopy(batch)
            if transform is not None:
                batch = transform(batch)

            i = (i + 1) % n_batches
            return batch

        return generator
__init__(sys, config=jcalc.MotionConfig(), setup_fn=None, finalize_fn=None, add_X_imus=False, add_X_imus_kwargs=dict(), add_X_jointaxes=False, add_X_jointaxes_kwargs=dict(), add_y_relpose=False, add_y_rootincl=False, add_y_rootincl_kwargs=dict(), sys_ml=None, randomize_positions=False, randomize_motion_artifacts=False, randomize_joint_params=False, randomize_hz=False, randomize_hz_kwargs=dict(), imu_motion_artifacts=False, imu_motion_artifacts_kwargs=dict(), dynamic_simulation=False, dynamic_simulation_kwargs=dict(), output_transform=None, keep_output_extras=False, use_link_number_in_Xy=False, cor=False, disable_tqdm=False) ¤

Random Chain Motion Generator

Source code in src/ring/algorithms/generator/base.py
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
def __init__(
    self,
    sys: base.System | list[base.System],
    config: jcalc.MotionConfig | list[jcalc.MotionConfig] = jcalc.MotionConfig(),
    setup_fn: Optional[types.SETUP_FN] = None,
    finalize_fn: Optional[types.FINALIZE_FN] = None,
    add_X_imus: bool = False,
    add_X_imus_kwargs: dict = dict(),
    add_X_jointaxes: bool = False,
    add_X_jointaxes_kwargs: dict = dict(),
    add_y_relpose: bool = False,
    add_y_rootincl: bool = False,
    add_y_rootincl_kwargs: dict = dict(),
    sys_ml: Optional[base.System] = None,
    randomize_positions: bool = False,
    randomize_motion_artifacts: bool = False,
    randomize_joint_params: bool = False,
    randomize_hz: bool = False,
    randomize_hz_kwargs: dict = dict(),
    imu_motion_artifacts: bool = False,
    imu_motion_artifacts_kwargs: dict = dict(),
    dynamic_simulation: bool = False,
    dynamic_simulation_kwargs: dict = dict(),
    output_transform: Optional[Callable] = None,
    keep_output_extras: bool = False,
    use_link_number_in_Xy: bool = False,
    cor: bool = False,
    disable_tqdm: bool = False,
) -> None:
    "Random Chain Motion Generator"

    sys, config = utils.to_list(sys), utils.to_list(config)
    sys_ml = sys[0] if sys_ml is None else sys_ml

    for c in config:
        assert c.is_feasible()

    self.gens = []
    for _sys in sys:
        self.gens.append(
            _build_mconfig_batched_generator(
                sys=_sys,
                config=config,
                setup_fn=setup_fn,
                finalize_fn=finalize_fn,
                add_X_imus=add_X_imus,
                add_X_imus_kwargs=add_X_imus_kwargs,
                add_X_jointaxes=add_X_jointaxes,
                add_X_jointaxes_kwargs=add_X_jointaxes_kwargs,
                add_y_relpose=add_y_relpose,
                add_y_rootincl=add_y_rootincl,
                add_y_rootincl_kwargs=add_y_rootincl_kwargs,
                sys_ml=sys_ml,
                randomize_positions=randomize_positions,
                randomize_motion_artifacts=randomize_motion_artifacts,
                randomize_joint_params=randomize_joint_params,
                randomize_hz=randomize_hz,
                randomize_hz_kwargs=randomize_hz_kwargs,
                imu_motion_artifacts=imu_motion_artifacts,
                imu_motion_artifacts_kwargs=imu_motion_artifacts_kwargs,
                dynamic_simulation=dynamic_simulation,
                dynamic_simulation_kwargs=dynamic_simulation_kwargs,
                output_transform=output_transform,
                keep_output_extras=keep_output_extras,
                use_link_number_in_Xy=use_link_number_in_Xy,
                cor=cor,
            )
        )

    self._n_mconfigs = len(config)
    self._size_of_generators = [self._n_mconfigs] * len(self.gens)

    self._disable_tqdm = disable_tqdm
to_list(sizes=1, seed=1) ¤

Returns list of unbatched sequences as numpy arrays.

Source code in src/ring/algorithms/generator/base.py
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
def to_list(self, sizes: int | list[int] = 1, seed: int = 1):
    "Returns list of unbatched sequences as numpy arrays."
    repeats = self._compute_repeats(sizes)
    sizes = list(jnp.array(repeats) * jnp.array(self._size_of_generators))

    reduced_repeats = []
    n_calls = []
    for size, repeat in zip(sizes, repeats):
        n_call = self._number_of_executions_required(size)
        gcd = utils.gcd(n_call, repeat)
        n_calls.append(gcd)
        reduced_repeats.append(repeat // gcd)
    jits = [N > 1 for N in n_calls]

    gens = []
    for i in range(len(repeats)):
        gens.append(
            batch.generators_lazy([self.gens[i]], [reduced_repeats[i]], jits[i])
        )

    return batch.generators_eager_to_list(gens, n_calls, seed, self._disable_tqdm)

System¤

System ¤

System object. Create using System.create(path_xml)

Source code in src/ring/base.py
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
@struct.dataclass
class System(_Base):
    "System object. Create using `System.create(path_xml)`"
    link_parents: list[int] = struct.field(False)
    links: Link
    link_types: list[str] = struct.field(False)
    link_damping: jax.Array
    link_armature: jax.Array
    link_spring_stiffness: jax.Array
    link_spring_zeropoint: jax.Array
    # simulation timestep size
    dt: float = struct.field(False)
    # geometries in the system
    geoms: list[Geometry]
    # root / base acceleration offset
    gravity: jax.Array = struct.field(default_factory=lambda: jnp.array([0, 0, -9.81]))

    integration_method: str = struct.field(
        False, default_factory=lambda: "semi_implicit_euler"
    )
    mass_mat_iters: int = struct.field(False, default_factory=lambda: 0)

    link_names: list[str] = struct.field(False, default_factory=lambda: [])

    model_name: Optional[str] = struct.field(False, default_factory=lambda: None)

    omc: list[MaxCoordOMC | None] = struct.field(True, default_factory=lambda: [])

    def num_links(self) -> int:
        return len(self.link_parents)

    def q_size(self) -> int:
        return sum([Q_WIDTHS[typ] for typ in self.link_types])

    def qd_size(self) -> int:
        return sum([QD_WIDTHS[typ] for typ in self.link_types])

    def name_to_idx(self, name: str) -> int:
        return self.link_names.index(name)

    def idx_to_name(self, idx: int, allow_world: bool = False) -> str:
        if allow_world and idx == -1:
            return "world"
        assert idx >= 0, "Worldbody index has no name."
        return self.link_names[idx]

    def idx_map(self, type: str) -> dict:
        "type: is either `l` or `q` or `d`"
        dict_int_slices = {}

        def f(_, idx_map, name: str, link_idx: int):
            dict_int_slices[name] = idx_map[type](link_idx)

        self.scan(f, "ll", self.link_names, list(range(self.num_links())))

        return dict_int_slices

    def parent_name(self, name: str) -> str:
        return self.idx_to_name(self.link_parents[self.name_to_idx(name)])

    def add_prefix(self, prefix: str = "") -> "System":
        return self.replace(link_names=[prefix + name for name in self.link_names])

    def change_model_name(
        self,
        new_name: Optional[str] = None,
        prefix: Optional[str] = None,
        suffix: Optional[str] = None,
    ) -> "System":
        if prefix is None:
            prefix = ""
        if suffix is None:
            suffix = ""
        if new_name is None:
            new_name = self.model_name
        name = prefix + new_name + suffix
        return self.replace(model_name=name)

    def change_link_name(self, old_name: str, new_name: str) -> "System":
        old_idx = self.name_to_idx(old_name)
        new_link_names = self.link_names.copy()
        new_link_names[old_idx] = new_name
        return self.replace(link_names=new_link_names)

    def add_prefix_suffix(
        self, prefix: Optional[str] = None, suffix: Optional[str] = None
    ) -> "System":
        if prefix is None:
            prefix = ""
        if suffix is None:
            suffix = ""
        new_link_names = [prefix + name + suffix for name in self.link_names]
        return self.replace(link_names=new_link_names)

    def _replace_free_with_cor(self) -> "System":
        # check that
        # - all free joints connect to -1
        # - all joints connecting to -1 are free joints
        for i, p in enumerate(self.link_parents):
            link_type = self.link_types[i]
            if (p == -1 and link_type != "free") or (link_type == "free" and p != -1):
                raise InvalidSystemError(
                    f"link={self.idx_to_name(i)}, parent="
                    f"{self.idx_to_name(p, allow_world=True)},"
                    f" joint={link_type}. Hint: Try setting `config.cor` to false."
                )

        def logic_replace_free_with_cor(name, olt, ola, old, ols, olz):
            # by default new is equal to old
            nlt, nla, nld, nls, nlz = olt, ola, old, ols, olz

            # old link type == free
            if olt == "free":
                # cor joint is (free, p3d) stacked
                nlt = "cor"
                # entries of old armature are 3*ang (spherical), 3*pos (p3d)
                nla = jnp.concatenate((ola, ola[3:]))
                nld = jnp.concatenate((old, old[3:]))
                nls = jnp.concatenate((ols, ols[3:]))
                nlz = jnp.concatenate((olz, olz[4:]))

            return nlt, nla, nld, nls, nlz

        return _update_sys_if_replace_joint_type(self, logic_replace_free_with_cor)

    def freeze(self, name: str | list[str]):
        if isinstance(name, list):
            sys = self
            for n in name:
                sys = sys.freeze(n)
            return sys

        def logic_freeze(link_name, olt, ola, old, ols, olz):
            nlt, nla, nld, nls, nlz = olt, ola, old, ols, olz

            if link_name == name:
                nlt = "frozen"
                nla = nld = nls = nlz = jnp.array([])

            return nlt, nla, nld, nls, nlz

        return _update_sys_if_replace_joint_type(self, logic_freeze)

    def unfreeze(self, name: str, new_joint_type: str):
        assert self.link_types[self.name_to_idx(name)] == "frozen"
        assert new_joint_type != "frozen"

        return self.change_joint_type(name, new_joint_type)

    def change_joint_type(
        self,
        name: str,
        new_joint_type: str,
        new_arma: Optional[jax.Array] = None,
        new_damp: Optional[jax.Array] = None,
        new_stif: Optional[jax.Array] = None,
        new_zero: Optional[jax.Array] = None,
        seed: int = 1,
    ):
        "By default damping, stiffness are set to zero."
        from ring.algorithms import get_joint_model

        q_size, qd_size = Q_WIDTHS[new_joint_type], QD_WIDTHS[new_joint_type]

        def logic_unfreeze_to_spherical(link_name, olt, ola, old, ols, olz):
            nlt, nla, nld, nls, nlz = olt, ola, old, ols, olz

            if link_name == name:
                nlt = new_joint_type
                q_zeros = jnp.zeros((q_size))
                qd_zeros = jnp.zeros((qd_size,))

                nla = qd_zeros if new_arma is None else new_arma
                nld = qd_zeros if new_damp is None else new_damp
                nls = qd_zeros if new_stif is None else new_stif
                nlz = q_zeros if new_zero is None else new_zero

                # unit quaternion
                if new_joint_type in ["spherical", "free", "cor"] and new_zero is None:
                    nlz = nlz.at[0].set(1.0)

            return nlt, nla, nld, nls, nlz

        sys = _update_sys_if_replace_joint_type(self, logic_unfreeze_to_spherical)

        jm = get_joint_model(new_joint_type)
        if jm.init_joint_params is not None:
            sys = sys.from_str(sys.to_str(), seed=seed)

        return sys

    def findall_imus(self) -> list[str]:
        return [name for name in self.link_names if name[:3] == "imu"]

    def findall_segments(self) -> list[str]:
        imus = self.findall_imus()
        return [name for name in self.link_names if name not in imus]

    def _bodies_indices_to_bodies_name(self, bodies: list[int]) -> list[str]:
        return [self.idx_to_name(i) for i in bodies]

    def findall_bodies_to_world(self, names: bool = False) -> list[int] | list[str]:
        bodies = [i for i, p in enumerate(self.link_parents) if p == -1]
        return self._bodies_indices_to_bodies_name(bodies) if names else bodies

    def find_body_to_world(self, name: bool = False) -> int | str:
        bodies = self.findall_bodies_to_world(names=name)
        assert len(bodies) == 1
        return bodies[0]

    def findall_bodies_with_jointtype(
        self, typ: str, names: bool = False
    ) -> list[int] | list[str]:
        bodies = [i for i, _typ in enumerate(self.link_types) if _typ == typ]
        return self._bodies_indices_to_bodies_name(bodies) if names else bodies

    def scan(self, f: Callable, in_types: str, *args, reverse: bool = False):
        """Scan `f` along each link in system whilst carrying along state.

        Args:
            f (Callable[..., Y]): f(y: Y, *args) -> y
            in_types: string specifying the type of each input arg:
                'l' is an input to be split according to link ranges
                'q' is an input to be split according to q ranges
                'd' is an input to be split according to qd ranges
            args: Arguments passed to `f`, and split to match the link.
            reverse (bool, optional): If `true` from leaves to root. Defaults to False.

        Returns:
            ys: Stacked output y of f.
        """
        return _scan_sys(self, f, in_types, *args, reverse=reverse)

    def parse(self) -> "System":
        """Initial setup of system. System object does not work unless it is parsed.
        Currently it does:
        - some consistency checks
        - populate the spatial inertia tensors
        - check that all names are unique
        - check that names are strings
        - check that all pos_min <= pos_max (unless traced)
        - order geoms in ascending order based on their parent link idx
        - check that all links have the correct size of
            - damping
            - armature
            - stiffness
            - zeropoint
        - check that n_links == len(sys.omc)
        """
        return _parse_system(self)

    def render(
        self,
        xs: Optional[Transform | list[Transform]] = None,
        camera: Optional[str] = None,
        show_pbar: bool = True,
        backend: str = "mujoco",
        render_every_nth: int = 1,
        **scene_kwargs,
    ) -> list[np.ndarray]:
        """Render frames from system and trajectory of maximal coordinates `xs`.

        Args:
            sys (base.System): System to render.
            xs (base.Transform | list[base.Transform]): Single or time-series
            of maximal coordinates `xs`.
            show_pbar (bool, optional): Whether or not to show a progress bar.
            Defaults to True.

        Returns:
            list[np.ndarray]: Stacked rendered frames. Length == len(xs).
        """
        return ring.rendering.render(
            self, xs, camera, show_pbar, backend, render_every_nth, **scene_kwargs
        )

    def render_prediction(
        self,
        xs: Transform | list[Transform],
        yhat: dict | jax.Array | np.ndarray,
        # by default we don't predict the global rotation
        transparent_segment_to_root: bool = True,
        **kwargs,
    ):
        "`xs` matches `sys`. `yhat` matches `sys_noimu`. `yhat` are child-to-parent."
        return ring.rendering.render_prediction(
            self, xs, yhat, transparent_segment_to_root, **kwargs
        )

    def delete_system(self, link_name: str | list[str], strict: bool = True):
        "Cut subsystem starting at `link_name` (inclusive) from tree."
        return ring.sys_composer.delete_subsystem(self, link_name, strict)

    def make_sys_noimu(self, imu_link_names: Optional[list[str]] = None):
        "Returns, e.g., imu_attachment = {'imu1': 'seg1', 'imu2': 'seg3'}"
        return ring.sys_composer.make_sys_noimu(self, imu_link_names)

    def inject_system(self, other_system: "System", at_body: Optional[str] = None):
        """Combine two systems into one.

        Args:
            sys (base.System): Large system.
            sub_sys (base.System): Small system that will be included into the
                large system `sys`.
            at_body (Optional[str], optional): Into which body of the large system
                small system will be included. Defaults to `worldbody`.

        Returns:
            base.System: _description_
        """
        return ring.sys_composer.inject_system(self, other_system, at_body)

    def morph_system(
        self,
        new_parents: Optional[list[int | str]] = None,
        new_anchor: Optional[int | str] = None,
    ):
        """Re-orders the graph underlying the system. Returns a new system.

        Args:
            sys (base.System): System to be modified.
            new_parents (list[int]): Let the i-th entry have value j. Then, after
                morphing the system the system will be such that the link corresponding
                to the i-th link in the old system will have as parent the link
                corresponding to the j-th link in the old system.

        Returns:
            base.System: Modified system.
        """
        return ring.sys_composer.morph_system(self, new_parents, new_anchor)

    @staticmethod
    def from_xml(path: str, seed: int = 1):
        return ring.io.load_sys_from_xml(path, seed)

    @staticmethod
    def from_str(xml: str, seed: int = 1):
        return ring.io.load_sys_from_str(xml, seed)

    def to_str(self) -> str:
        return ring.io.save_sys_to_str(self)

    def to_xml(self, path: str) -> None:
        ring.io.save_sys_to_xml(self, path)

    @classmethod
    def create(cls, path_or_str: str, seed: int = 1) -> "System":
        path = Path(path_or_str).with_suffix(".xml")

        exists = False
        try:
            exists = path.exists()
        except OSError:
            # file length too length
            pass

        if exists:
            return cls.from_xml(path, seed=seed)
        else:
            return cls.from_str(path_or_str)

    def coordinate_vector_to_q(
        self,
        q: jax.Array,
        custom_joints: dict[str, Callable] = {},
    ) -> jax.Array:
        """Map a coordinate vector `q` to the minimal coordinates vector of the sys"""
        # Does, e.g.
        # - normalize quaternions
        # - hinge joints in [-pi, pi]
        q_preproc = []

        def preprocess(_, __, link_type, q):
            to_q = ring.algorithms.jcalc.get_joint_model(
                link_type
            ).coordinate_vector_to_q
            # function in custom_joints has priority over JointModel
            if link_type in custom_joints:
                to_q = custom_joints[link_type]
            if to_q is None:
                raise NotImplementedError(
                    f"Please specify the custom joint `{link_type}`"
                    " either using the `custom_joints` arguments or using the"
                    " JointModel.coordinate_vector_to_q field."
                )
            new_q = to_q(q)
            q_preproc.append(new_q)

        self.scan(preprocess, "lq", self.link_types, q)
        return jnp.concatenate(q_preproc)
idx_map(type) ¤

type: is either l or q or d

Source code in src/ring/base.py
448
449
450
451
452
453
454
455
456
457
def idx_map(self, type: str) -> dict:
    "type: is either `l` or `q` or `d`"
    dict_int_slices = {}

    def f(_, idx_map, name: str, link_idx: int):
        dict_int_slices[name] = idx_map[type](link_idx)

    self.scan(f, "ll", self.link_names, list(range(self.num_links())))

    return dict_int_slices
change_joint_type(name, new_joint_type, new_arma=None, new_damp=None, new_stif=None, new_zero=None, seed=1) ¤

By default damping, stiffness are set to zero.

Source code in src/ring/base.py
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
def change_joint_type(
    self,
    name: str,
    new_joint_type: str,
    new_arma: Optional[jax.Array] = None,
    new_damp: Optional[jax.Array] = None,
    new_stif: Optional[jax.Array] = None,
    new_zero: Optional[jax.Array] = None,
    seed: int = 1,
):
    "By default damping, stiffness are set to zero."
    from ring.algorithms import get_joint_model

    q_size, qd_size = Q_WIDTHS[new_joint_type], QD_WIDTHS[new_joint_type]

    def logic_unfreeze_to_spherical(link_name, olt, ola, old, ols, olz):
        nlt, nla, nld, nls, nlz = olt, ola, old, ols, olz

        if link_name == name:
            nlt = new_joint_type
            q_zeros = jnp.zeros((q_size))
            qd_zeros = jnp.zeros((qd_size,))

            nla = qd_zeros if new_arma is None else new_arma
            nld = qd_zeros if new_damp is None else new_damp
            nls = qd_zeros if new_stif is None else new_stif
            nlz = q_zeros if new_zero is None else new_zero

            # unit quaternion
            if new_joint_type in ["spherical", "free", "cor"] and new_zero is None:
                nlz = nlz.at[0].set(1.0)

        return nlt, nla, nld, nls, nlz

    sys = _update_sys_if_replace_joint_type(self, logic_unfreeze_to_spherical)

    jm = get_joint_model(new_joint_type)
    if jm.init_joint_params is not None:
        sys = sys.from_str(sys.to_str(), seed=seed)

    return sys
scan(f, in_types, *args, reverse=False) ¤

Scan f along each link in system whilst carrying along state.

Parameters:
  • f (Callable[..., Y]) –

    f(y: Y, *args) -> y

  • in_types (str) –

    string specifying the type of each input arg: 'l' is an input to be split according to link ranges 'q' is an input to be split according to q ranges 'd' is an input to be split according to qd ranges

  • args

    Arguments passed to f, and split to match the link.

  • reverse (bool, default: False ) –

    If true from leaves to root. Defaults to False.

Returns:
  • ys

    Stacked output y of f.

Source code in src/ring/base.py
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
def scan(self, f: Callable, in_types: str, *args, reverse: bool = False):
    """Scan `f` along each link in system whilst carrying along state.

    Args:
        f (Callable[..., Y]): f(y: Y, *args) -> y
        in_types: string specifying the type of each input arg:
            'l' is an input to be split according to link ranges
            'q' is an input to be split according to q ranges
            'd' is an input to be split according to qd ranges
        args: Arguments passed to `f`, and split to match the link.
        reverse (bool, optional): If `true` from leaves to root. Defaults to False.

    Returns:
        ys: Stacked output y of f.
    """
    return _scan_sys(self, f, in_types, *args, reverse=reverse)
parse() ¤

Initial setup of system. System object does not work unless it is parsed. Currently it does: - some consistency checks - populate the spatial inertia tensors - check that all names are unique - check that names are strings - check that all pos_min <= pos_max (unless traced) - order geoms in ascending order based on their parent link idx - check that all links have the correct size of - damping - armature - stiffness - zeropoint - check that n_links == len(sys.omc)

Source code in src/ring/base.py
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
def parse(self) -> "System":
    """Initial setup of system. System object does not work unless it is parsed.
    Currently it does:
    - some consistency checks
    - populate the spatial inertia tensors
    - check that all names are unique
    - check that names are strings
    - check that all pos_min <= pos_max (unless traced)
    - order geoms in ascending order based on their parent link idx
    - check that all links have the correct size of
        - damping
        - armature
        - stiffness
        - zeropoint
    - check that n_links == len(sys.omc)
    """
    return _parse_system(self)
render(xs=None, camera=None, show_pbar=True, backend='mujoco', render_every_nth=1, **scene_kwargs) ¤

Render frames from system and trajectory of maximal coordinates xs.

Parameters:
  • sys (System) –

    System to render.

  • xs (Transform | list[Transform], default: None ) –

    Single or time-series

  • show_pbar (bool, default: True ) –

    Whether or not to show a progress bar.

Returns:
  • list[ndarray]

    list[np.ndarray]: Stacked rendered frames. Length == len(xs).

Source code in src/ring/base.py
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
def render(
    self,
    xs: Optional[Transform | list[Transform]] = None,
    camera: Optional[str] = None,
    show_pbar: bool = True,
    backend: str = "mujoco",
    render_every_nth: int = 1,
    **scene_kwargs,
) -> list[np.ndarray]:
    """Render frames from system and trajectory of maximal coordinates `xs`.

    Args:
        sys (base.System): System to render.
        xs (base.Transform | list[base.Transform]): Single or time-series
        of maximal coordinates `xs`.
        show_pbar (bool, optional): Whether or not to show a progress bar.
        Defaults to True.

    Returns:
        list[np.ndarray]: Stacked rendered frames. Length == len(xs).
    """
    return ring.rendering.render(
        self, xs, camera, show_pbar, backend, render_every_nth, **scene_kwargs
    )
render_prediction(xs, yhat, transparent_segment_to_root=True, **kwargs) ¤

xs matches sys. yhat matches sys_noimu. yhat are child-to-parent.

Source code in src/ring/base.py
678
679
680
681
682
683
684
685
686
687
688
689
def render_prediction(
    self,
    xs: Transform | list[Transform],
    yhat: dict | jax.Array | np.ndarray,
    # by default we don't predict the global rotation
    transparent_segment_to_root: bool = True,
    **kwargs,
):
    "`xs` matches `sys`. `yhat` matches `sys_noimu`. `yhat` are child-to-parent."
    return ring.rendering.render_prediction(
        self, xs, yhat, transparent_segment_to_root, **kwargs
    )
delete_system(link_name, strict=True) ¤

Cut subsystem starting at link_name (inclusive) from tree.

Source code in src/ring/base.py
691
692
693
def delete_system(self, link_name: str | list[str], strict: bool = True):
    "Cut subsystem starting at `link_name` (inclusive) from tree."
    return ring.sys_composer.delete_subsystem(self, link_name, strict)
make_sys_noimu(imu_link_names=None) ¤

Returns, e.g., imu_attachment = {'imu1': 'seg1', 'imu2': 'seg3'}

Source code in src/ring/base.py
695
696
697
def make_sys_noimu(self, imu_link_names: Optional[list[str]] = None):
    "Returns, e.g., imu_attachment = {'imu1': 'seg1', 'imu2': 'seg3'}"
    return ring.sys_composer.make_sys_noimu(self, imu_link_names)
inject_system(other_system, at_body=None) ¤

Combine two systems into one.

Parameters:
  • sys (System) –

    Large system.

  • sub_sys (System) –

    Small system that will be included into the large system sys.

  • at_body (Optional[str], default: None ) –

    Into which body of the large system small system will be included. Defaults to worldbody.

Returns:
  • base.System: description

Source code in src/ring/base.py
699
700
701
702
703
704
705
706
707
708
709
710
711
712
def inject_system(self, other_system: "System", at_body: Optional[str] = None):
    """Combine two systems into one.

    Args:
        sys (base.System): Large system.
        sub_sys (base.System): Small system that will be included into the
            large system `sys`.
        at_body (Optional[str], optional): Into which body of the large system
            small system will be included. Defaults to `worldbody`.

    Returns:
        base.System: _description_
    """
    return ring.sys_composer.inject_system(self, other_system, at_body)
morph_system(new_parents=None, new_anchor=None) ¤

Re-orders the graph underlying the system. Returns a new system.

Parameters:
  • sys (System) –

    System to be modified.

  • new_parents (list[int], default: None ) –

    Let the i-th entry have value j. Then, after morphing the system the system will be such that the link corresponding to the i-th link in the old system will have as parent the link corresponding to the j-th link in the old system.

Returns:
  • base.System: Modified system.

Source code in src/ring/base.py
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
def morph_system(
    self,
    new_parents: Optional[list[int | str]] = None,
    new_anchor: Optional[int | str] = None,
):
    """Re-orders the graph underlying the system. Returns a new system.

    Args:
        sys (base.System): System to be modified.
        new_parents (list[int]): Let the i-th entry have value j. Then, after
            morphing the system the system will be such that the link corresponding
            to the i-th link in the old system will have as parent the link
            corresponding to the j-th link in the old system.

    Returns:
        base.System: Modified system.
    """
    return ring.sys_composer.morph_system(self, new_parents, new_anchor)
coordinate_vector_to_q(q, custom_joints={}) ¤

Map a coordinate vector q to the minimal coordinates vector of the sys

Source code in src/ring/base.py
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
def coordinate_vector_to_q(
    self,
    q: jax.Array,
    custom_joints: dict[str, Callable] = {},
) -> jax.Array:
    """Map a coordinate vector `q` to the minimal coordinates vector of the sys"""
    # Does, e.g.
    # - normalize quaternions
    # - hinge joints in [-pi, pi]
    q_preproc = []

    def preprocess(_, __, link_type, q):
        to_q = ring.algorithms.jcalc.get_joint_model(
            link_type
        ).coordinate_vector_to_q
        # function in custom_joints has priority over JointModel
        if link_type in custom_joints:
            to_q = custom_joints[link_type]
        if to_q is None:
            raise NotImplementedError(
                f"Please specify the custom joint `{link_type}`"
                " either using the `custom_joints` arguments or using the"
                " JointModel.coordinate_vector_to_q field."
            )
        new_q = to_q(q)
        q_preproc.append(new_q)

    self.scan(preprocess, "lq", self.link_types, q)
    return jnp.concatenate(q_preproc)

MotionConfig¤

MotionConfig dataclass ¤

Source code in src/ring/algorithms/jcalc.py
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
@dataclass
class MotionConfig:
    T: float = 60.0  # length of random motion
    t_min: float = 0.05  # min time between two generated angles
    t_max: float | TimeDependentFloat = 0.30  # max time ..

    dang_min: float | TimeDependentFloat = 0.1  # minimum angular velocity in rad/s
    dang_max: float | TimeDependentFloat = 3.0  # maximum angular velocity in rad/s

    # minimum angular velocity of euler angles used for `free and spherical joints`
    dang_min_free_spherical: float | TimeDependentFloat = 0.1
    dang_max_free_spherical: float | TimeDependentFloat = 3.0

    # max min allowed actual delta values in radians
    delta_ang_min: float | TimeDependentFloat = 0.0
    delta_ang_max: float | TimeDependentFloat = 2 * jnp.pi
    delta_ang_min_free_spherical: float | TimeDependentFloat = 0.0
    delta_ang_max_free_spherical: float | TimeDependentFloat = 2 * jnp.pi

    dpos_min: float | TimeDependentFloat = 0.001  # speed of translation
    dpos_max: float | TimeDependentFloat = 0.7
    pos_min: float | TimeDependentFloat = -2.5
    pos_max: float | TimeDependentFloat = +2.5

    # used by both `random_angle_*` and `random_pos_*`
    # only used if `randomized_interpolation` is set
    cdf_bins_min: int = 5
    # by default equal to `cdf_bins_min`
    cdf_bins_max: Optional[int] = None

    # flags
    randomized_interpolation_angle: bool = False
    randomized_interpolation_position: bool = False
    interpolation_method: str = "cosine"
    range_of_motion_hinge: bool = True
    range_of_motion_hinge_method: str = "uniform"

    # initial value of joints
    ang0_min: float = -jnp.pi
    ang0_max: float = jnp.pi
    pos0_min: float = 0.0
    pos0_max: float = 0.0

    # cor (center of rotation) custom fields
    cor_t_min: float = 0.2
    cor_t_max: float | TimeDependentFloat = 2.0
    cor_dpos_min: float | TimeDependentFloat = 0.00001
    cor_dpos_max: float | TimeDependentFloat = 0.5
    cor_pos_min: float | TimeDependentFloat = -0.4
    cor_pos_max: float | TimeDependentFloat = 0.4

    def is_feasible(self) -> bool:
        return _is_feasible_config1(self)

    def to_nomotion_config(self) -> "MotionConfig":
        kwargs = asdict(self)
        for key in [
            "dang_min",
            "dang_max",
            "delta_ang_min",
            "dang_min_free_spherical",
            "dang_max_free_spherical",
            "delta_ang_min_free_spherical",
            "dpos_min",
            "dpos_max",
        ]:
            kwargs[key] = 0.0
        nomotion_config = MotionConfig(**kwargs)
        assert nomotion_config.is_feasible()
        return nomotion_config

    @staticmethod
    def from_register(name: str) -> "MotionConfig":
        return _registered_motion_configs[name]

join_motionconfigs(configs, boundaries) ¤

Source code in src/ring/algorithms/jcalc.py
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
def join_motionconfigs(
    configs: list[MotionConfig], boundaries: list[float]
) -> MotionConfig:
    assert len(configs) == (
        len(boundaries) + 1
    ), "length of `boundaries` should be one less than length of `configs`"
    boundaries = jnp.array(boundaries, dtype=float)

    def new_value(field: str):
        scalar_options = jnp.array([getattr(c, field) for c in configs])

        def scalar(t):
            return jax.lax.dynamic_index_in_dim(
                scalar_options, _find_interval(t, boundaries), keepdims=False
            )

        return scalar

    hints = get_type_hints(MotionConfig())
    attrs = MotionConfig().__dict__
    is_time_dependent_field = lambda key: hints[key] == (float | TimeDependentFloat)
    time_dependent_fields = [key for key in attrs if is_time_dependent_field(key)]
    time_independent_fields = [key for key in attrs if not is_time_dependent_field(key)]

    for time_dep_field in time_independent_fields:
        field_values = set([getattr(config, time_dep_field) for config in configs])
        assert (
            len(field_values) == 1
        ), f"MotionConfig.{time_dep_field}={field_values}. Should be one unique value.."

    changes = {field: new_value(field) for field in time_dependent_fields}
    return replace(configs[0], **changes)

Extending the RCMG¤

JointModel dataclass ¤

Source code in src/ring/algorithms/jcalc.py
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
@dataclass
class JointModel:
    # (q, params) -> Transform
    transform: Callable[[jax.Array, jax.Array], base.Transform]
    # len(motion) == len(qd)
    # if callable: joint_params -> base.Motion
    motion: list[base.Motion | Callable[[jax.Array], base.Motion]] = field(
        default_factory=lambda: []
    )
    # (config, key_t, key_value, params) -> jax.Array
    rcmg_draw_fn: Optional[DRAW_FN] = None

    # only used by `pd_control`
    p_control_term: Optional[P_CONTROL_TERM] = None
    qd_from_q: Optional[QD_FROM_Q] = None

    # used by
    # -`inverse_kinematics_endeffector`
    # - System.coordinate_vector_to_q
    coordinate_vector_to_q: Optional[COORDINATE_VECTOR_TO_Q] = None

    # only used by `inverse_kinematics`
    inv_kin: Optional[INV_KIN] = None

    init_joint_params: Optional[INIT_JOINT_PARAMS] = None

    utilities: Optional[dict[str, Any]] = field(default_factory=lambda: dict())

register_new_joint_type(joint_type, joint_model, q_width, qd_width=None, overwrite=False) ¤

Source code in src/ring/algorithms/jcalc.py
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
def register_new_joint_type(
    joint_type: str,
    joint_model: JointModel,
    q_width: int,
    qd_width: Optional[int] = None,
    overwrite: bool = False,
):
    # this name is used
    assert joint_type != "default", "Please use another name."

    exists = joint_type in _joint_types
    if exists and overwrite:
        for dic in [
            base.Q_WIDTHS,
            base.QD_WIDTHS,
            _joint_types,
        ]:
            dic.pop(joint_type)
    else:
        assert (
            not exists
        ), f"joint type `{joint_type}`already exists, use `overwrite=True`"

    if qd_width is None:
        qd_width = q_width

    assert len(joint_model.motion) == qd_width

    _joint_types.update({joint_type: joint_model})
    base.Q_WIDTHS.update({joint_type: q_width})
    base.QD_WIDTHS.update({joint_type: qd_width})

Simulation¤

State ¤

The static and dynamic state of a system in minimal and maximal coordinates. Use .create() to create this object.

Parameters:
  • q (Array) –

    System state in minimal coordinates (equals sys.q_size())

  • qd (Array) –

    System velocity in minimal coordinates (equals sys.qd_size())

  • x

    (Transform): Maximal coordinates of all links. From epsilon-to-link.

Source code in src/ring/base.py
 976
 977
 978
 979
 980
 981
 982
 983
 984
 985
 986
 987
 988
 989
 990
 991
 992
 993
 994
 995
 996
 997
 998
 999
1000
1001
1002
1003
1004
1005
1006
1007
1008
1009
1010
1011
1012
1013
1014
1015
1016
1017
1018
1019
1020
1021
1022
1023
1024
1025
1026
1027
1028
1029
1030
1031
1032
1033
1034
1035
1036
1037
1038
1039
1040
1041
1042
1043
@struct.dataclass
class State(_Base):
    """The static and dynamic state of a system in minimal and maximal coordinates.
    Use `.create()` to create this object.

    Args:
        q (jax.Array): System state in minimal coordinates (equals `sys.q_size()`)
        qd (jax.Array): System velocity in minimal coordinates (equals `sys.qd_size()`)
        x: (Transform): Maximal coordinates of all links. From epsilon-to-link.
    """

    q: jax.Array
    qd: jax.Array
    x: Transform

    @classmethod
    def create(
        cls,
        sys: System,
        q: Optional[jax.Array] = None,
        qd: Optional[jax.Array] = None,
        x: Optional[Transform] = None,
        key: Optional[jax.Array] = None,
        custom_joints: dict[str, Callable] = {},
    ):
        """Create state of system.

        Args:
            sys (System): The system for which to create a state.
            q (jax.Array, optional): The joint values of the system. Defaults to None.
            Which then defaults to zeros.
            qd (jax.Array, optional): The joint velocities of the system.
            Defaults to None. Which then defaults to zeros.

        Returns:
            (State): Create State object.
        """
        if key is not None:
            assert q is None
            q = jax.random.normal(key, shape=(sys.q_size(),))
            q = sys.coordinate_vector_to_q(q, custom_joints)
        elif q is None:
            q = jnp.zeros((sys.q_size(),))

            # free, cor, spherical joints are not zeros but have unit quaternions
            def replace_by_unit_quat(_, idx_map, link_typ, link_idx):
                nonlocal q

                if link_typ in ["free", "cor", "spherical"]:
                    q_idxs_link = idx_map["q"](link_idx)
                    q = q.at[q_idxs_link.start].set(1.0)

            sys.scan(
                replace_by_unit_quat,
                "ll",
                sys.link_types,
                list(range(sys.num_links())),
            )
        else:
            pass

        if qd is None:
            qd = jnp.zeros((sys.qd_size(),))

        if x is None:
            x = Transform.zero((sys.num_links(),))

        return cls(q, qd, x)
create(sys, q=None, qd=None, x=None, key=None, custom_joints={}) classmethod ¤

Create state of system.

Parameters:
  • sys (System) –

    The system for which to create a state.

  • q (Array, default: None ) –

    The joint values of the system. Defaults to None.

  • qd (Array, default: None ) –

    The joint velocities of the system.

Returns:
  • State

    Create State object.

Source code in src/ring/base.py
 991
 992
 993
 994
 995
 996
 997
 998
 999
1000
1001
1002
1003
1004
1005
1006
1007
1008
1009
1010
1011
1012
1013
1014
1015
1016
1017
1018
1019
1020
1021
1022
1023
1024
1025
1026
1027
1028
1029
1030
1031
1032
1033
1034
1035
1036
1037
1038
1039
1040
1041
1042
1043
@classmethod
def create(
    cls,
    sys: System,
    q: Optional[jax.Array] = None,
    qd: Optional[jax.Array] = None,
    x: Optional[Transform] = None,
    key: Optional[jax.Array] = None,
    custom_joints: dict[str, Callable] = {},
):
    """Create state of system.

    Args:
        sys (System): The system for which to create a state.
        q (jax.Array, optional): The joint values of the system. Defaults to None.
        Which then defaults to zeros.
        qd (jax.Array, optional): The joint velocities of the system.
        Defaults to None. Which then defaults to zeros.

    Returns:
        (State): Create State object.
    """
    if key is not None:
        assert q is None
        q = jax.random.normal(key, shape=(sys.q_size(),))
        q = sys.coordinate_vector_to_q(q, custom_joints)
    elif q is None:
        q = jnp.zeros((sys.q_size(),))

        # free, cor, spherical joints are not zeros but have unit quaternions
        def replace_by_unit_quat(_, idx_map, link_typ, link_idx):
            nonlocal q

            if link_typ in ["free", "cor", "spherical"]:
                q_idxs_link = idx_map["q"](link_idx)
                q = q.at[q_idxs_link.start].set(1.0)

        sys.scan(
            replace_by_unit_quat,
            "ll",
            sys.link_types,
            list(range(sys.num_links())),
        )
    else:
        pass

    if qd is None:
        qd = jnp.zeros((sys.qd_size(),))

    if x is None:
        x = Transform.zero((sys.num_links(),))

    return cls(q, qd, x)

step(sys, state, taus=None, n_substeps=1) ¤

Steps the dynamics. Returns the state of next timestep.

Source code in src/ring/algorithms/dynamics.py
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
def step(
    sys: base.System,
    state: base.State,
    taus: Optional[jax.Array] = None,
    n_substeps: int = 1,
) -> base.State:
    "Steps the dynamics. Returns the state of next timestep."
    assert sys.q_size() == state.q.size
    if taus is None:
        taus = jnp.zeros_like(state.qd)
    assert sys.qd_size() == state.qd.size == taus.size
    assert (
        sys.integration_method.lower() == "semi_implicit_euler"
    ), "Currently, nothing else then `semi_implicit_euler` implemented."

    sys = sys.replace(dt=sys.dt / n_substeps)

    for _ in range(n_substeps):
        # update kinematics before stepping; this means that the `x` in `state`
        # will lag one step behind but otherwise we would have to return
        # the system object which would be awkward
        sys, state = kinematics.forward_kinematics(sys, state)
        state = _integration_methods[sys.integration_method.lower()](sys, state, taus)

    return state

Transform ¤

Represents the Transformation from Plücker A to Plücker B, where B is located relative to A at pos in frame A and rot is the relative quaternion from A to B. Create using `Transform.create(pos=..., rot=...)

Source code in src/ring/base.py
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
@struct.dataclass
class Transform(_Base):
    """Represents the Transformation from Plücker A to Plücker B,
    where B is located relative to A at `pos` in frame A and `rot` is the
    relative quaternion from A to B.
    Create using `Transform.create(pos=..., rot=...)
    """

    pos: Vector
    rot: Quaternion

    @classmethod
    def create(cls, pos=None, rot=None):
        assert not (pos is None and rot is None), "One must be given."
        shape_rot = rot.shape[:-1] if rot is not None else ()
        shape_pos = pos.shape[:-1] if pos is not None else ()

        if pos is None:
            pos = jnp.zeros(shape_rot + (3,))
        if rot is None:
            rot = jnp.array([1.0, 0, 0, 0])
            rot = jnp.tile(jnp.array([1.0, 0.0, 0.0, 0.0]), shape_pos + (1,))

        assert pos.shape[:-1] == rot.shape[:-1]

        return Transform(pos, rot)

    @classmethod
    def zero(cls, shape=()) -> "Transform":
        """Returns a zero transform with a batch shape."""
        pos = jnp.zeros(shape + (3,))
        rot = jnp.tile(jnp.array([1.0, 0.0, 0.0, 0.0]), shape + (1,))
        return Transform(pos, rot)

    def as_matrix(self) -> jax.Array:
        E = maths.quat_to_3x3(self.rot)
        return spatial.quadrants(aa=E, bb=E) @ spatial.xlt(self.pos)
zero(shape=()) classmethod ¤

Returns a zero transform with a batch shape.

Source code in src/ring/base.py
139
140
141
142
143
144
@classmethod
def zero(cls, shape=()) -> "Transform":
    """Returns a zero transform with a batch shape."""
    pos = jnp.zeros(shape + (3,))
    rot = jnp.tile(jnp.array([1.0, 0.0, 0.0, 0.0]), shape + (1,))
    return Transform(pos, rot)