mink 0.0.5__py3-none-any.whl → 0.0.7__py3-none-any.whl

This diff represents the content of publicly available package versions that have been released to one of the supported registries. The information contained in this diff is provided for informational purposes only and reflects changes between package versions as they appear in their respective public registries.
mink/__init__.py CHANGED
@@ -28,6 +28,7 @@ from .solve_ik import build_ik, solve_ik
28
28
  from .tasks import (
29
29
  ComTask,
30
30
  DampingTask,
31
+ EqualityConstraintTask,
31
32
  FrameTask,
32
33
  Objective,
33
34
  PostureTask,
@@ -39,6 +40,7 @@ from .utils import (
39
40
  custom_configuration_vector,
40
41
  get_body_geom_ids,
41
42
  get_freejoint_dims,
43
+ get_subtree_body_ids,
42
44
  get_subtree_geom_ids,
43
45
  move_mocap_to_frame,
44
46
  )
@@ -53,6 +55,7 @@ __all__ = (
53
55
  "RelativeFrameTask",
54
56
  "PostureTask",
55
57
  "Task",
58
+ "EqualityConstraintTask",
56
59
  "Objective",
57
60
  "ConfigurationLimit",
58
61
  "VelocityLimit",
@@ -81,4 +84,5 @@ __all__ = (
81
84
  "move_mocap_to_frame",
82
85
  "get_subtree_geom_ids",
83
86
  "get_body_geom_ids",
87
+ "get_subtree_body_ids",
84
88
  )
mink/configuration.py CHANGED
@@ -43,8 +43,8 @@ class Configuration:
43
43
 
44
44
  Args:
45
45
  model: Mujoco model.
46
- q: Configuration to initialize from. If None, the configuration
47
- is initialized to the default configuration `qpos0`.
46
+ q: Configuration to initialize from. If None, the configuration is
47
+ initialized to the default configuration `qpos0`.
48
48
  """
49
49
  self.model = model
50
50
  self.data = mujoco.MjData(model)
@@ -62,6 +62,8 @@ class Configuration:
62
62
  # mj_kinematics. An extra call to mj_comPos is required for updated Jacobians.
63
63
  mujoco.mj_kinematics(self.model, self.data)
64
64
  mujoco.mj_comPos(self.model, self.data)
65
+ if self.model.neq > 0:
66
+ mujoco.mj_makeConstraint(self.model, self.data)
65
67
 
66
68
  def update_from_keyframe(self, key_name: str) -> None:
67
69
  """Update the configuration from a keyframe.
@@ -104,7 +106,7 @@ class Configuration:
104
106
  model=self.model,
105
107
  )
106
108
  else:
107
- logging.warning(
109
+ logging.debug(
108
110
  f"Value {qval:.2f} at index {jnt} is outside of its limits: "
109
111
  f"[{qmin:.2f}, {qmax:.2f}]"
110
112
  )
@@ -0,0 +1,8 @@
1
+ """contrib: additional functionality for mink."""
2
+
3
+ from .keyboard_teleop import TeleopMocap, keycodes
4
+
5
+ __all__ = (
6
+ "TeleopMocap",
7
+ "keycodes",
8
+ )
@@ -0,0 +1,82 @@
1
+ # Keyboard Controls for Teleoperation
2
+ This document explains the keyboard input handling system implemented in the `TeleopMocap` class for teleoperation.
3
+ The system allows users to toggle different movement modes, adjust speeds, and control the movement of a mocap body in a simulation.
4
+
5
+ ---
6
+
7
+ ## Overview
8
+ The `TeleopMocap` class provides keyboard-based control for moving and rotating the mocap body in a Mujoco simulation.
9
+ Features:
10
+ - 6 degrees of freedom (DOF) movement
11
+ - Toggling between manual and non-manual movement
12
+ - Switching between rotation and translation
13
+ - Adjusting movement and rotation step sizes
14
+ - Alternating between different mocap data
15
+
16
+ ---
17
+
18
+ ## Key Mappings
19
+ | Key | Action |
20
+ |-----|--------|
21
+ | `9` | Toggle teleoperation On/Off. |
22
+ | `n` | Toggle between manual and non-manual mode. |
23
+ | `.` | Toggle between rotation and translation mode. |
24
+ | `8` | Cycle through different mocap data. |
25
+ | `+` | Increase movement step size or movement speed. |
26
+ | `-` | Decrease movement step size or movement speed. |
27
+ | **Arrow Keys** | **Move (rotation / translation) along the X, Y, and Z axes** |
28
+ | `Up` | Move forward (+X) or rotates around X-axis in positive direction. |
29
+ | `Down` | Move backward (-X) or rotates around X-axis in negative direction. |
30
+ | `Right` | Move right (+Y) or rotates around Y-axis in positive direction. |
31
+ | `Left` | Move left (-Y) or rotates around Y-axis in negative direction. |
32
+ | `7` | Move up (+Z) or rotates around Z-axis in positive direction. |
33
+ | `6` | Move down (-Z) or rotates around Z-axis in negative direction. |
34
+
35
+ ---
36
+
37
+ ## Modes
38
+ ### **Manual vs. Non-Manual Mode:**
39
+ - **Manual Mode**: Iterative movement using arrow keys.
40
+ - **Non-Manual Mode**: Continuous movement using arrow keys (to stop continuous movement, re-click the arrow key).
41
+
42
+ ### **Rotation vs. Translation Mode:**
43
+ - **Rotation Mode**: Rotation around an axis.
44
+ - **Translation Mode**: Movement along an axis.
45
+
46
+ ---
47
+
48
+ ## Example Usage
49
+ To use the `TeleopMocap` class, instantiate it and pass the `mjData`.
50
+ Pass the `key_callback_data` method as a `key_callback` in the mujoco viewer.
51
+ Call the `auto_key_move()` in the viewer loop.
52
+
53
+ ```python
54
+ import mink
55
+ ...
56
+ data = MjData(model)
57
+ ...
58
+ # Initialize the key callback handler
59
+ key_callback = mink.TeleopMocap(data)
60
+
61
+ # Pass the key callback function into the viewer
62
+ with mujoco.viewer.launch_passive(
63
+ model=model, data=data,
64
+ show_left_ui=False, show_right_ui=False,
65
+ key_callback=key_callback.key_callback_data
66
+ ) as viewer:
67
+ while viewer.is_running():
68
+ ...
69
+ key_callback.auto_key_move()
70
+ ...
71
+ ```
72
+
73
+ ---
74
+
75
+ ## Limitations
76
+ `Mink` uses the `mujoco.viewer.launch_passive()` for visualization and maintaining the simulation loop.
77
+ To pass keyboard callbacks, we have to pass a callback function `key_callback(key)` as an argument to the `launch_passive()`.
78
+ However, this has several limitations:
79
+ - Only being able to register one key press at a time.
80
+ - It can only register one key action (which is the action PRESS); can't register key holds (act.HOLD) or releases (act.RELEASE).
81
+ - Doesn't support key + modifier combinations in (e.g., Ctrl + Arrow keys).
82
+ - Viewer has a lot of default keybinds, which limits the amount of free keys to use for movement.
@@ -0,0 +1,9 @@
1
+ """keyboard_teleop: Class to handle keyboard input for teleoperation."""
2
+
3
+ from . import keycodes
4
+ from .teleop_mocap import TeleopMocap
5
+
6
+ __all__ = (
7
+ "keycodes",
8
+ "TeleopMocap",
9
+ )
@@ -0,0 +1,109 @@
1
+ """
2
+ This file contains key codes for keyboard input handling.
3
+ """
4
+
5
+ KEY_UNKNOWN = -1
6
+ KEY_SPACE = 32
7
+ KEY_APOSTROPHE = 39
8
+ KEY_COMMA = 44
9
+ KEY_MINUS = 45
10
+ KEY_PERIOD = 46
11
+ KEY_SLASH = 47
12
+ KEY_0 = 48
13
+ KEY_1 = 49
14
+ KEY_2 = 50
15
+ KEY_3 = 51
16
+ KEY_4 = 52
17
+ KEY_5 = 53
18
+ KEY_6 = 54
19
+ KEY_7 = 55
20
+ KEY_8 = 56
21
+ KEY_9 = 57
22
+ KEY_SEMICOLON = 59
23
+ KEY_EQUAL = 61
24
+ KEY_A = 65
25
+ KEY_B = 66
26
+ KEY_C = 67
27
+ KEY_D = 68
28
+ KEY_E = 69
29
+ KEY_F = 70
30
+ KEY_G = 71
31
+ KEY_H = 72
32
+ KEY_I = 73
33
+ KEY_J = 74
34
+ KEY_K = 75
35
+ KEY_L = 76
36
+ KEY_M = 77
37
+ KEY_N = 78
38
+ KEY_O = 79
39
+ KEY_P = 80
40
+ KEY_Q = 81
41
+ KEY_R = 82
42
+ KEY_S = 83
43
+ KEY_T = 84
44
+ KEY_U = 85
45
+ KEY_V = 86
46
+ KEY_W = 87
47
+ KEY_X = 88
48
+ KEY_Y = 89
49
+ KEY_Z = 90
50
+ KEY_LEFT_BRACKET = 91
51
+ KEY_BACKSLASH = 92
52
+ KEY_RIGHT_BRACKET = 93
53
+ KEY_GRAVE_ACCENT = 96
54
+ KEY_ESCAPE = 256
55
+ KEY_ENTER = 257
56
+ KEY_TAB = 258
57
+ KEY_BACKSPACE = 259
58
+ KEY_INSERT = 260
59
+ KEY_DELETE = 261
60
+ KEY_RIGHT = 262
61
+ KEY_LEFT = 263
62
+ KEY_DOWN = 264
63
+ KEY_UP = 265
64
+ KEY_PAGE_UP = 266
65
+ KEY_PAGE_DOWN = 267
66
+ KEY_HOME = 268
67
+ KEY_END = 269
68
+ KEY_CAPS_LOCK = 280
69
+ KEY_SCROLL_LOCK = 281
70
+ KEY_NUM_LOCK = 282
71
+ KEY_PRINT_SCREEN = 283
72
+ KEY_PAUSE = 284
73
+ KEY_F1 = 290
74
+ KEY_F2 = 291
75
+ KEY_F3 = 292
76
+ KEY_F4 = 293
77
+ KEY_F5 = 294
78
+ KEY_F6 = 295
79
+ KEY_F7 = 296
80
+ KEY_F8 = 297
81
+ KEY_F9 = 298
82
+ KEY_F10 = 299
83
+ KEY_F11 = 300
84
+ KEY_F12 = 301
85
+ KEY_KP_0 = 320
86
+ KEY_KP_1 = 321
87
+ KEY_KP_2 = 322
88
+ KEY_KP_3 = 323
89
+ KEY_KP_4 = 324
90
+ KEY_KP_5 = 325
91
+ KEY_KP_6 = 326
92
+ KEY_KP_7 = 327
93
+ KEY_KP_8 = 328
94
+ KEY_KP_9 = 329
95
+ KEY_KP_DECIMAL = 330
96
+ KEY_KP_DIVIDE = 331
97
+ KEY_KP_MULTIPLY = 332
98
+ KEY_KP_SUBTRACT = 333
99
+ KEY_KP_ADD = 334
100
+ KEY_KP_ENTER = 335
101
+ KEY_KP_EQUAL = 336
102
+ KEY_LEFT_SHIFT = 340
103
+ KEY_LEFT_CONTROL = 341
104
+ KEY_LEFT_ALT = 342
105
+ KEY_LEFT_SUPER = 343
106
+ KEY_RIGHT_SHIFT = 344
107
+ KEY_RIGHT_CONTROL = 345
108
+ KEY_RIGHT_ALT = 346
109
+ KEY_RIGHT_SUPER = 347
@@ -0,0 +1,229 @@
1
+ from functools import partial
2
+
3
+ import mujoco
4
+ import numpy as np
5
+
6
+ from . import keycodes
7
+
8
+
9
+ class TeleopMocap:
10
+ """
11
+ Class to handle keyboard input for teleoperation.
12
+ The class provides methods to toggle teleoperation on/off,
13
+ switch between manual and non-manual modes,
14
+ adjust step sizes / speed for movement and rotation,
15
+ and select movements based on key presses.
16
+ """
17
+
18
+ def __init__(self, data):
19
+ self.on = False
20
+ self.data = data
21
+ self.reset_state()
22
+ self.actions = {
23
+ keycodes.KEY_N: self.toggle_manual, # n: toggle non-manual mode
24
+ keycodes.KEY_PERIOD: self.toggle_rotation, # .: toggle rotation mode
25
+ keycodes.KEY_8: self.toggle_mocap, # 8: toggle mocap data
26
+ keycodes.KEY_EQUAL: partial(self.toggle_speed, 1), # =/+: increase speed
27
+ keycodes.KEY_MINUS: partial(self.toggle_speed, -1), # -: decrease speed
28
+ keycodes.KEY_UP: partial(
29
+ self.movement_select, keycodes.KEY_UP, 0, 1
30
+ ), # Up arrow
31
+ keycodes.KEY_DOWN: partial(
32
+ self.movement_select, keycodes.KEY_DOWN, 0, -1
33
+ ), # Down arrow
34
+ keycodes.KEY_RIGHT: partial(
35
+ self.movement_select, keycodes.KEY_RIGHT, 1, 1
36
+ ), # Right arrow
37
+ keycodes.KEY_LEFT: partial(
38
+ self.movement_select, keycodes.KEY_LEFT, 1, -1
39
+ ), # Left arrow
40
+ keycodes.KEY_7: partial(self.movement_select, keycodes.KEY_7, 2, 1), # 6
41
+ keycodes.KEY_6: partial(self.movement_select, keycodes.KEY_6, 2, -1), # 7
42
+ }
43
+ self.movements = {
44
+ keycodes.KEY_UP: partial(self.movement_select, -1, 0, 1), # Up arrow
45
+ keycodes.KEY_DOWN: partial(self.movement_select, -1, 0, -1), # Down arrow
46
+ keycodes.KEY_RIGHT: partial(self.movement_select, -1, 1, 1), # Right arrow
47
+ keycodes.KEY_LEFT: partial(self.movement_select, -1, 1, -1), # Left arrow
48
+ keycodes.KEY_7: partial(self.movement_select, -1, 2, 1), # 6
49
+ keycodes.KEY_6: partial(self.movement_select, -1, 2, -1), # 7
50
+ }
51
+ self.opposite_keys = {
52
+ keycodes.KEY_UP: keycodes.KEY_DOWN,
53
+ keycodes.KEY_DOWN: keycodes.KEY_UP,
54
+ keycodes.KEY_RIGHT: keycodes.KEY_LEFT,
55
+ keycodes.KEY_LEFT: keycodes.KEY_RIGHT,
56
+ keycodes.KEY_7: keycodes.KEY_6,
57
+ keycodes.KEY_6: keycodes.KEY_7,
58
+ }
59
+
60
+ def __call__(self, key):
61
+ # Toggle teleop on/off
62
+ if key == keycodes.KEY_9: # 9
63
+ self.toggle_on()
64
+ return
65
+
66
+ # Do nothing if teleop is off
67
+ if not self.on:
68
+ return
69
+
70
+ if key in self.actions:
71
+ self.actions[key]()
72
+
73
+ def auto_key_move(self):
74
+ """
75
+ Automatically move the mocap body based on key presses.
76
+ """
77
+
78
+ if not self.on:
79
+ return
80
+
81
+ for key, action in self.movements.items():
82
+ if self.keys[key]:
83
+ action()
84
+
85
+ def movement_select(self, key, axis, direction):
86
+ """
87
+ Select the movement direction based on the key pressed.
88
+ """
89
+
90
+ if not self.manual and key != -1:
91
+ self.keys[key] = not self.keys[key]
92
+ self.keys[self.opposite_keys[key]] = False
93
+ elif not self.manual and key == -1:
94
+ self.rot_or_trans(key, axis, direction)
95
+ elif self.manual:
96
+ self.rot_or_trans(key, axis, direction)
97
+
98
+ def rot_or_trans(self, key, axis, direction):
99
+ """
100
+ Adjust the position or rotation of the mocap body based on rotation mode.
101
+ """
102
+
103
+ if self.rotation:
104
+ self.adjust_rotation(key, axis, direction)
105
+ else:
106
+ self.adjust_position(key, axis, direction)
107
+
108
+ def adjust_position(self, key, axis, direction):
109
+ """
110
+ Adjust the position of the mocap body in the specified direction
111
+ based on the axis and step size.
112
+ """
113
+
114
+ q = self.data.mocap_quat[self.mocap_idx].copy()
115
+ unit_vec = self.unit_vec_from_quat(q, axis)
116
+ step_size = self.m_step_size if self.manual else self.nm_step_size
117
+ self.data.mocap_pos[self.mocap_idx] += direction * step_size * unit_vec
118
+
119
+ def adjust_rotation(self, key, axis, direction):
120
+ """
121
+ Adjust the rotation of the mocap body in the specified direction
122
+ based on the axis and step size.
123
+ """
124
+
125
+ q = self.data.mocap_quat[self.mocap_idx].copy()
126
+ unit_vec = self.unit_vec_from_quat(q, axis)
127
+
128
+ # Rotate the quaternion by the specified angle around the axis.
129
+ quat_rot = np.zeros(shape=(4,), dtype=np.float64)
130
+ result = np.zeros(shape=(4,), dtype=np.float64)
131
+ step_size = self.m_rotation_step if self.manual else self.nm_rotation_step
132
+ angle = direction * step_size
133
+ angle_rad = np.deg2rad(angle)
134
+ unit_vec = unit_vec / np.linalg.norm(unit_vec)
135
+ mujoco.mju_axisAngle2Quat(quat_rot, unit_vec, angle_rad)
136
+ mujoco.mju_mulQuat(result, quat_rot, q)
137
+
138
+ self.data.mocap_quat[self.mocap_idx] = result
139
+
140
+ def unit_vec_from_quat(self, q, axis):
141
+ """
142
+ Compute the unit vector corresponding to the specified axis
143
+ from the given quaternion.
144
+ """
145
+
146
+ rot = np.zeros(shape=(9,), dtype=np.float64)
147
+ mujoco.mju_quat2Mat(rot, q)
148
+ rot = rot.reshape((3, 3))
149
+ unit_vec = rot[:, axis]
150
+
151
+ return unit_vec
152
+
153
+ def toggle_on(self):
154
+ self.on = not self.on
155
+ state = "On" if self.on else "Off"
156
+ print(f"Keyboard Teleoperation toggled: {state}!")
157
+ self.reset_state()
158
+ print()
159
+
160
+ def toggle_manual(self):
161
+ self.manual = not self.manual
162
+ manual_state = "On" if self.manual else "Off"
163
+ print(f"Manual mode toggled: {manual_state}!")
164
+ self.reset_keys()
165
+ print()
166
+
167
+ def toggle_rotation(self):
168
+ self.rotation = not self.rotation
169
+ state = "On" if self.rotation else "Off"
170
+ print(f"Rotation mode toggled: {state}!")
171
+ self.reset_keys()
172
+ print()
173
+
174
+ def toggle_speed(self, direction):
175
+ factor = 1.10 if direction == 1 else 0.9
176
+ if self.manual:
177
+ if self.rotation:
178
+ self.m_rotation_step *= factor
179
+ else:
180
+ self.m_step_size *= factor
181
+ else:
182
+ if self.rotation:
183
+ self.nm_rotation_step *= factor
184
+ else:
185
+ self.nm_step_size *= factor
186
+
187
+ output = "Manual" if self.manual else "Non-manual"
188
+ mode = "Rotation" if self.rotation else "Translation"
189
+ if self.manual:
190
+ step_size = self.m_rotation_step if self.rotation else self.m_step_size
191
+ else:
192
+ step_size = self.nm_rotation_step if self.rotation else self.nm_step_size
193
+ print(f"{output} {mode} step size: {step_size:.8f}")
194
+
195
+ def toggle_mocap(self):
196
+ self.mocap_idx = (self.mocap_idx + 1) % self.data.mocap_pos.shape[
197
+ 0
198
+ ] # cycle through mocap data
199
+ print(f"Current mocap index: {self.mocap_idx}")
200
+
201
+ def reset_keys(self):
202
+ self.keys = {
203
+ keycodes.KEY_UP: False,
204
+ keycodes.KEY_DOWN: False,
205
+ keycodes.KEY_RIGHT: False,
206
+ keycodes.KEY_LEFT: False,
207
+ keycodes.KEY_7: False,
208
+ keycodes.KEY_6: False,
209
+ }
210
+
211
+ def reset_step_size(self):
212
+ self.m_step_size = 0.01 # manual step size
213
+ self.m_rotation_step = 10 # manual rotation step
214
+ self.nm_step_size = 1e-4 # non-manual step size
215
+ self.nm_rotation_step = 5e-2 # non-manual rotation step
216
+ print("Step sizes have been reset!")
217
+
218
+ def reset_state(self):
219
+ self.reset_keys()
220
+ self.reset_step_size()
221
+ self.manual = True
222
+ self.rotation = False
223
+ self.mocap_idx = 0
224
+ str = f"States have been reset: \n \
225
+ - Manual mode: {self.manual} \
226
+ - Rotation mode: {self.rotation} \n \
227
+ - Mocap index: {self.mocap_idx}"
228
+
229
+ print(str)
mink/lie/se3.py CHANGED
@@ -54,10 +54,7 @@ class SE3(MatrixLieGroup):
54
54
  @classmethod
55
55
  def from_rotation(cls, rotation: SO3) -> SE3:
56
56
  return SE3.from_rotation_and_translation(
57
- rotation=rotation,
58
- translation=np.zeros(
59
- SE3.space_dim,
60
- ),
57
+ rotation=rotation, translation=np.zeros(SE3.space_dim)
61
58
  )
62
59
 
63
60
  @classmethod
mink/lie/so3.py CHANGED
@@ -79,7 +79,7 @@ class SO3(MatrixLieGroup):
79
79
  @classmethod
80
80
  def from_matrix(cls, matrix: np.ndarray) -> SO3:
81
81
  assert matrix.shape == (SO3.matrix_dim, SO3.matrix_dim)
82
- wxyz = np.zeros(SO3.parameters_dim, dtype=np.float64)
82
+ wxyz = np.empty(SO3.parameters_dim, dtype=np.float64)
83
83
  mujoco.mju_mat2Quat(wxyz, matrix.ravel())
84
84
  return SO3(wxyz=wxyz)
85
85
 
@@ -109,7 +109,7 @@ class SO3(MatrixLieGroup):
109
109
 
110
110
  # Eq. 138.
111
111
  def as_matrix(self) -> np.ndarray:
112
- mat = np.zeros(9, dtype=np.float64)
112
+ mat = np.empty(9, dtype=np.float64)
113
113
  mujoco.mju_quat2Mat(mat, self.wxyz)
114
114
  return mat.reshape(3, 3)
115
115
 
@@ -2,7 +2,7 @@
2
2
 
3
3
  import itertools
4
4
  from dataclasses import dataclass
5
- from typing import List, Sequence, Union
5
+ from typing import List, Sequence, Tuple, Union
6
6
 
7
7
  import mujoco
8
8
  import numpy as np
@@ -13,12 +13,29 @@ from .limit import Constraint, Limit
13
13
  # Type aliases.
14
14
  Geom = Union[int, str]
15
15
  GeomSequence = Sequence[Geom]
16
- CollisionPair = tuple[GeomSequence, GeomSequence]
16
+ CollisionPair = Tuple[GeomSequence, GeomSequence]
17
17
  CollisionPairs = Sequence[CollisionPair]
18
18
 
19
19
 
20
20
  @dataclass(frozen=True)
21
21
  class Contact:
22
+ """Struct to store contact information between two geoms.
23
+
24
+ Attributes:
25
+ dist: Smallest signed distance between geom1 and geom2. If no collision of
26
+ distance smaller than distmax is found, this value is equal to distmax [1].
27
+ fromto: Segment connecting the closest points on geom1 and geom2. The first
28
+ three elements are the coordinates of the closest point on geom1, and the
29
+ last three elements are the coordinates of the closest point on geom2.
30
+ geom1: ID of geom1.
31
+ geom2: ID of geom2.
32
+ distmax: Maximum distance between geom1 and geom2.
33
+
34
+ References:
35
+ [1] MuJoCo API documentation. `mj_geomDistance` function.
36
+ https://mujoco.readthedocs.io/en/latest/APIreference/APIfunctions.html
37
+ """
38
+
22
39
  dist: float
23
40
  fromto: np.ndarray
24
41
  geom1: int
@@ -27,12 +44,16 @@ class Contact:
27
44
 
28
45
  @property
29
46
  def normal(self) -> np.ndarray:
47
+ """Contact normal pointing from geom1 to geom2."""
30
48
  normal = self.fromto[3:] - self.fromto[:3]
31
- return normal / (np.linalg.norm(normal) + 1e-9)
49
+ mujoco.mju_normalize3(normal)
50
+ return normal
32
51
 
33
52
  @property
34
53
  def inactive(self) -> bool:
35
- return self.dist == self.distmax and not self.fromto.any()
54
+ """Returns True if no distance smaller than distmax is detected between geom1
55
+ and geom2."""
56
+ return self.dist == self.distmax
36
57
 
37
58
 
38
59
  def compute_contact_normal_jacobian(
@@ -210,7 +231,7 @@ class CollisionAvoidanceLimit(Limit):
210
231
  def _homogenize_geom_id_list(self, geom_list: GeomSequence) -> List[int]:
211
232
  """Take a heterogeneous list of geoms (specified via ID or name) and return
212
233
  a homogenous list of IDs (int)."""
213
- list_of_int: list[int] = []
234
+ list_of_int: List[int] = []
214
235
  for g in geom_list:
215
236
  if isinstance(g, int):
216
237
  list_of_int.append(g)
@@ -1,5 +1,7 @@
1
1
  """Joint position limit."""
2
2
 
3
+ from typing import List
4
+
3
5
  import mujoco
4
6
  import numpy as np
5
7
 
@@ -38,7 +40,7 @@ class ConfigurationLimit(Limit):
38
40
  f"{self.__class__.__name__} gain must be in the range (0, 1]"
39
41
  )
40
42
 
41
- index_list: list[int] = [] # DoF indices that are limited.
43
+ index_list: List[int] = [] # DoF indices that are limited.
42
44
  lower = np.full(model.nq, -mujoco.mjMAXVAL)
43
45
  upper = np.full(model.nq, mujoco.mjMAXVAL)
44
46
  for jnt in range(model.njnt):
mink/limits/limit.py CHANGED
@@ -15,9 +15,7 @@ class Constraint(NamedTuple):
15
15
  """
16
16
 
17
17
  G: Optional[np.ndarray] = None
18
- """Shape (nv, nv)."""
19
18
  h: Optional[np.ndarray] = None
20
- """Shape (nv,)."""
21
19
 
22
20
  @property
23
21
  def inactive(self) -> bool: