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.
@@ -1,6 +1,6 @@
1
1
  """Joint velocity limit."""
2
2
 
3
- from typing import Mapping
3
+ from typing import List, Mapping, Optional
4
4
 
5
5
  import mujoco
6
6
  import numpy as np
@@ -18,16 +18,17 @@ class VelocityLimit(Limit):
18
18
  Floating base joints are ignored.
19
19
 
20
20
  Attributes:
21
- indices: Tangent indices corresponding to velocity-limited joints.
21
+ indices: Tangent indices corresponding to velocity-limited joints. Shape (nb,).
22
22
  limit: Maximum allowed velocity magnitude for velocity-limited joints, in
23
- [m]/[s] for slide joints and [rad]/[s] for hinge joints.
23
+ [m]/[s] for slide joints and [rad]/[s] for hinge joints. Shape (nb,).
24
24
  projection_matrix: Projection from tangent space to subspace with
25
- velocity-limited joints.
25
+ velocity-limited joints. Shape (nb, nv) where nb is the dimension of the
26
+ velocity-limited subspace and nv is the dimension of the tangent space.
26
27
  """
27
28
 
28
29
  indices: np.ndarray
29
30
  limit: np.ndarray
30
- projection_matrix: np.ndarray
31
+ projection_matrix: Optional[np.ndarray]
31
32
 
32
33
  def __init__(
33
34
  self,
@@ -41,31 +42,31 @@ class VelocityLimit(Limit):
41
42
  velocities: Dictionary mapping joint name to maximum allowed magnitude in
42
43
  [m]/[s] for slide joints and [rad]/[s] for hinge joints.
43
44
  """
44
- limit_list: list[float] = []
45
- index_list: list[int] = []
45
+ limit_list: List[float] = []
46
+ index_list: List[int] = []
46
47
  for joint_name, max_vel in velocities.items():
47
48
  jid = model.joint(joint_name).id
48
49
  jnt_type = model.jnt_type[jid]
49
- jnt_dim = dof_width(jnt_type)
50
- jnt_id = model.jnt_dofadr[jid]
51
50
  if jnt_type == mujoco.mjtJoint.mjJNT_FREE:
52
51
  raise LimitDefinitionError(f"Free joint {joint_name} is not supported")
52
+ vadr = model.jnt_dofadr[jid]
53
+ vdim = dof_width(jnt_type)
53
54
  max_vel = np.atleast_1d(max_vel)
54
- if max_vel.shape != (jnt_dim,):
55
+ if max_vel.shape != (vdim,):
55
56
  raise LimitDefinitionError(
56
- f"Joint {joint_name} must have a limit of shape ({jnt_dim},). "
57
+ f"Joint {joint_name} must have a limit of shape ({vdim},). "
57
58
  f"Got: {max_vel.shape}"
58
59
  )
59
- index_list.extend(range(jnt_id, jnt_id + jnt_dim))
60
- limit_list.extend(max_vel.tolist())
60
+ index_list.extend(range(vadr, vadr + vdim))
61
+ limit_list.extend(max_vel.tolist()) # type: ignore
61
62
 
62
63
  self.indices = np.array(index_list)
63
64
  self.indices.setflags(write=False)
64
65
  self.limit = np.array(limit_list)
65
66
  self.limit.setflags(write=False)
66
67
 
67
- dim = len(self.indices)
68
- self.projection_matrix = np.eye(model.nv)[self.indices] if dim > 0 else None
68
+ nb = len(self.indices)
69
+ self.projection_matrix = np.eye(model.nv)[self.indices] if nb > 0 else None
69
70
 
70
71
  def compute_qp_inequalities(
71
72
  self, configuration: Configuration, dt: float
@@ -89,7 +90,8 @@ class VelocityLimit(Limit):
89
90
 
90
91
  Returns:
91
92
  Pair :math:`(G, h)` representing the inequality constraint as
92
- :math:`G \Delta q \leq h`, or ``None`` if there is no limit.
93
+ :math:`G \Delta q \leq h`, or ``None`` if there is no limit. G has
94
+ shape (2nb, nv) and h has shape (2nb,).
93
95
  """
94
96
  del configuration # Unused.
95
97
  if self.projection_matrix is None:
mink/solve_ik.py CHANGED
@@ -1,6 +1,6 @@
1
1
  """Build and solve the inverse kinematics problem."""
2
2
 
3
- from typing import Optional, Sequence
3
+ from typing import List, Optional, Sequence, Tuple
4
4
 
5
5
  import numpy as np
6
6
  import qpsolvers
@@ -24,11 +24,11 @@ def _compute_qp_objective(
24
24
 
25
25
  def _compute_qp_inequalities(
26
26
  configuration: Configuration, limits: Optional[Sequence[Limit]], dt: float
27
- ) -> tuple[Optional[np.ndarray], Optional[np.ndarray]]:
27
+ ) -> Tuple[Optional[np.ndarray], Optional[np.ndarray]]:
28
28
  if limits is None:
29
29
  limits = [ConfigurationLimit(configuration.model)]
30
- G_list: list[np.ndarray] = []
31
- h_list: list[np.ndarray] = []
30
+ G_list: List[np.ndarray] = []
31
+ h_list: List[np.ndarray] = []
32
32
  for limit in limits:
33
33
  inequality = limit.compute_qp_inequalities(configuration, dt)
34
34
  if not inequality.inactive:
mink/tasks/__init__.py CHANGED
@@ -2,7 +2,9 @@
2
2
 
3
3
  from .com_task import ComTask
4
4
  from .damping_task import DampingTask
5
+ from .equality_constraint_task import EqualityConstraintTask
5
6
  from .exceptions import (
7
+ InvalidConstraint,
6
8
  InvalidDamping,
7
9
  InvalidGain,
8
10
  InvalidTarget,
@@ -25,6 +27,8 @@ __all__ = (
25
27
  "TargetNotSet",
26
28
  "InvalidTarget",
27
29
  "TaskDefinitionError",
30
+ "InvalidConstraint",
28
31
  "InvalidGain",
29
32
  "InvalidDamping",
33
+ "EqualityConstraintTask",
30
34
  )
@@ -0,0 +1,215 @@
1
+ """Equality constraint task implementation."""
2
+
3
+ from __future__ import annotations
4
+
5
+ import logging
6
+ from typing import List, Optional, Sequence
7
+
8
+ import mujoco
9
+ import numpy as np
10
+ import numpy.typing as npt
11
+
12
+ from ..configuration import Configuration
13
+ from .exceptions import InvalidConstraint, TaskDefinitionError
14
+ from .task import Task
15
+
16
+
17
+ def _get_constraint_dim(constraint: int) -> int:
18
+ """Return the dimension of an equality constraint in the efc* arrays."""
19
+ return {
20
+ mujoco.mjtEq.mjEQ_CONNECT.value: 3,
21
+ mujoco.mjtEq.mjEQ_WELD.value: 6,
22
+ mujoco.mjtEq.mjEQ_JOINT.value: 1,
23
+ mujoco.mjtEq.mjEQ_TENDON.value: 1,
24
+ }[constraint]
25
+
26
+
27
+ def _get_dense_constraint_jacobian(
28
+ model: mujoco.MjModel, data: mujoco.MjData
29
+ ) -> np.ndarray:
30
+ """Return the dense constraint Jacobian for a model."""
31
+ if mujoco.mj_isSparse(model):
32
+ efc_J = np.empty((data.nefc, model.nv))
33
+ mujoco.mju_sparse2dense(
34
+ efc_J,
35
+ data.efc_J,
36
+ data.efc_J_rownnz,
37
+ data.efc_J_rowadr,
38
+ data.efc_J_colind,
39
+ )
40
+ return efc_J
41
+ return data.efc_J.reshape((data.nefc, model.nv)).copy()
42
+
43
+
44
+ class EqualityConstraintTask(Task):
45
+ """Regulate equality constraints in a model.
46
+
47
+ Equality constraints are useful, among other things, for modeling "loop joints"
48
+ such as four-bar linkages. In MuJoCo, there are several types of equality
49
+ constraints, including:
50
+
51
+ * ``mjEQ_CONNECT``: Connect two bodies at a point (ball joint).
52
+ * ``mjEQ_WELD``: Fix relative pose of two bodies.
53
+ * ``mjEQ_JOINT``: Couple the values of two scalar joints.
54
+ * ``mjEQ_TENDON``: Couple the values of two tendons.
55
+
56
+ This task can regulate all equality constraints in a model or a specific subset
57
+ identified by name or ID.
58
+
59
+ Attributes:
60
+ equalities: ID or name of the equality constraints to regulate. If not provided,
61
+ the task will regulate all equality constraints in the model.
62
+ cost: Cost vector for the equality constraint task. Either a scalar, in which
63
+ case the same cost is applied to all constraints, or a vector of shape
64
+ ``(neq,)``, where ``neq`` is the number of equality constraints in the
65
+ model.
66
+
67
+ Raises:
68
+ InvalidConstraint: If a specified equality constraint name or ID is not found,
69
+ or if the constraint is not active at the initial configuration.
70
+ TaskDefinitionError: If no equality constraints are found or if cost parameters
71
+ have invalid shape or values.
72
+
73
+ Example:
74
+
75
+ .. code-block:: python
76
+
77
+ # Regulate all equality constraints with the same cost.
78
+ eq_task = EqualityConstraintTask(model, cost=1.0)
79
+
80
+ # Regulate specific equality constraints with different costs.
81
+ eq_task = EqualityConstraintTask(
82
+ model,
83
+ cost=[1.0, 0.5],
84
+ equalities=["connect_right", "connect_left"]
85
+ )
86
+ """
87
+
88
+ def __init__(
89
+ self,
90
+ model: mujoco.MjModel,
91
+ cost: npt.ArrayLike,
92
+ equalities: Optional[Sequence[int | str]] = None,
93
+ gain: float = 1.0,
94
+ lm_damping: float = 0.0,
95
+ ):
96
+ self._eq_ids = self._resolve_equality_ids(model, equalities)
97
+ self._eq_types = model.eq_type[self._eq_ids].copy()
98
+ self._neq_total = len(self._eq_ids)
99
+ self._mask: np.ndarray | None = None
100
+
101
+ super().__init__(cost=np.zeros((1,)), gain=gain, lm_damping=lm_damping)
102
+ self.set_cost(cost)
103
+
104
+ def set_cost(self, cost: npt.ArrayLike) -> None:
105
+ """Set the cost vector for the equality constraint task.
106
+
107
+ Args:
108
+ cost: Cost vector for the equality constraint task.
109
+ """
110
+ cost = np.atleast_1d(cost)
111
+ if cost.ndim != 1 or cost.shape[0] not in (1, self._neq_total):
112
+ raise TaskDefinitionError(
113
+ f"{self.__class__.__name__} cost must be a vector of shape (1,) "
114
+ f"or ({self._neq_total},). Got {cost.shape}."
115
+ )
116
+ if not np.all(cost >= 0.0):
117
+ raise TaskDefinitionError(f"{self.__class__.__name__} cost must be >= 0")
118
+
119
+ # Per constraint cost.
120
+ self._cost = (
121
+ np.full((self._neq_total,), cost[0]) if cost.shape[0] == 1 else cost.copy()
122
+ )
123
+
124
+ # Expanded per constraint dimension.
125
+ repeats = [_get_constraint_dim(eq_type) for eq_type in self._eq_types]
126
+ self.cost = np.repeat(self._cost, repeats)
127
+
128
+ def compute_error(self, configuration: Configuration) -> np.ndarray:
129
+ """Compute the equality constraint task error.
130
+
131
+ Args:
132
+ configuration: Robot configuration :math:`q`.
133
+
134
+ Returns:
135
+ Equality constraint task error vector :math:`e(q)`. The shape of the
136
+ error vector is ``(neq_active * constraint_dim,)``, where ``neq_active``
137
+ is the number of active equality constraints, and ``constraint_dim``
138
+ depends on the type of equality constraint.
139
+ """
140
+ self._update_active_constraints(configuration)
141
+ return configuration.data.efc_pos[self._mask]
142
+
143
+ def compute_jacobian(self, configuration: Configuration) -> np.ndarray:
144
+ """Compute the task Jacobian at a given configuration.
145
+
146
+ Args:
147
+ configuration: Robot configuration :math:`q`.
148
+
149
+ Returns:
150
+ Equality constraint task jacobian :math:`J(q)`. The shape of the Jacobian
151
+ is ``(neq_active * constraint_dim, nv)``, where ``neq_active`` is the
152
+ number of active equality constraints, ``constraint_dim`` depends on the
153
+ type of equality constraint, and ``nv`` is the dimension of the tangent
154
+ space.
155
+ """
156
+ self._update_active_constraints(configuration)
157
+ efc_J = _get_dense_constraint_jacobian(configuration.model, configuration.data)
158
+ return efc_J[self._mask]
159
+
160
+ # Helper functions.
161
+
162
+ def _update_active_constraints(self, configuration: Configuration) -> None:
163
+ self._mask = (
164
+ configuration.data.efc_type == mujoco.mjtConstraint.mjCNSTR_EQUALITY
165
+ ) & np.isin(configuration.data.efc_id, self._eq_ids)
166
+ active_eq_ids = configuration.data.efc_id[self._mask]
167
+ self.cost = self._cost[active_eq_ids]
168
+
169
+ def _resolve_equality_ids(
170
+ self, model: mujoco.MjModel, equalities: Optional[Sequence[int | str]]
171
+ ) -> np.ndarray:
172
+ eq_ids: List[int] = []
173
+
174
+ if equalities is not None:
175
+ for eq_id_or_name in equalities:
176
+ eq_id: int
177
+ if isinstance(eq_id_or_name, str):
178
+ eq_id = mujoco.mj_name2id(
179
+ model, mujoco.mjtObj.mjOBJ_EQUALITY, eq_id_or_name
180
+ )
181
+ if eq_id == -1:
182
+ raise InvalidConstraint(
183
+ f"Equality constraint '{eq_id_or_name}' not found."
184
+ )
185
+ else:
186
+ eq_id = eq_id_or_name
187
+ if eq_id < 0 or eq_id >= model.neq:
188
+ raise InvalidConstraint(
189
+ f"Equality constraint index {eq_id} out of range. "
190
+ f"Must be in range [0, {model.neq})."
191
+ )
192
+ if not model.eq_active0[eq_id]:
193
+ raise InvalidConstraint(
194
+ f"Equality constraint {eq_id} is not active at initial "
195
+ "configuration."
196
+ )
197
+ else:
198
+ eq_ids.append(eq_id)
199
+ # Check for duplicates.
200
+ if len(eq_ids) != len(set(eq_ids)):
201
+ raise TaskDefinitionError(
202
+ f"Duplicate equality constraint IDs provided: {eq_ids}."
203
+ )
204
+ else:
205
+ eq_ids = list(range(model.neq))
206
+ logging.info("Regulating %d equality constraints", len(eq_ids))
207
+
208
+ # Ensure we have at least 1 constraint.
209
+ if len(eq_ids) == 0:
210
+ raise TaskDefinitionError(
211
+ f"{self.__class__.__name__} no equality constraints found in this "
212
+ "model."
213
+ )
214
+
215
+ return np.array(eq_ids)
mink/tasks/exceptions.py CHANGED
@@ -25,3 +25,7 @@ class InvalidGain(MinkError):
25
25
 
26
26
  class InvalidDamping(MinkError):
27
27
  """Exception raised when the damping is outside the valid range."""
28
+
29
+
30
+ class InvalidConstraint(MinkError):
31
+ """Exception raised when a constraint is invalid."""
mink/utils.py CHANGED
@@ -1,4 +1,4 @@
1
- from typing import Optional
1
+ from typing import List, Optional, Tuple
2
2
 
3
3
  import mujoco
4
4
  import numpy as np
@@ -35,7 +35,7 @@ def move_mocap_to_frame(
35
35
  mujoco.mju_mat2Quat(data.mocap_quat[mocap_id], xmat)
36
36
 
37
37
 
38
- def get_freejoint_dims(model: mujoco.MjModel) -> tuple[list[int], list[int]]:
38
+ def get_freejoint_dims(model: mujoco.MjModel) -> Tuple[List[int], List[int]]:
39
39
  """Get all floating joint configuration and tangent indices.
40
40
 
41
41
  Args:
@@ -45,8 +45,8 @@ def get_freejoint_dims(model: mujoco.MjModel) -> tuple[list[int], list[int]]:
45
45
  A (q_ids, v_ids) pair containing all floating joint indices in the
46
46
  configuration and tangent spaces respectively.
47
47
  """
48
- q_ids: list[int] = []
49
- v_ids: list[int] = []
48
+ q_ids: List[int] = []
49
+ v_ids: List[int] = []
50
50
  for j in range(model.njnt):
51
51
  if model.jnt_type[j] == mujoco.mjtJoint.mjJNT_FREE:
52
52
  qadr = model.jnt_qposadr[j]
@@ -90,39 +90,55 @@ def custom_configuration_vector(
90
90
  value = np.atleast_1d(value)
91
91
  if value.shape != (jnt_dim,):
92
92
  raise ValueError(
93
- f"Joint {name} should have a qpos value of {jnt_dim,} but "
93
+ f"Joint {name} should have a qpos value of {(jnt_dim,)} but "
94
94
  f"got {value.shape}"
95
95
  )
96
96
  q[qid : qid + jnt_dim] = value
97
97
  return q
98
98
 
99
99
 
100
- def get_subtree_geom_ids(model: mujoco.MjModel, body_id: int) -> list[int]:
101
- """Get all geoms belonging to subtree starting at a given body.
100
+ def get_body_body_ids(model: mujoco.MjModel, body_id: int) -> List[int]:
101
+ """Get immediate children bodies belonging to a given body.
102
102
 
103
103
  Args:
104
104
  model: Mujoco model.
105
- body_id: ID of body where subtree starts.
105
+ body_id: ID of body.
106
106
 
107
107
  Returns:
108
- A list containing all subtree geom ids.
108
+ A List containing all child body ids.
109
109
  """
110
+ return [
111
+ i
112
+ for i in range(model.nbody)
113
+ if model.body_parentid[i] == body_id
114
+ and body_id != i # Exclude the body itself.
115
+ ]
116
+
117
+
118
+ def get_subtree_body_ids(model: mujoco.MjModel, body_id: int) -> List[int]:
119
+ """Get all bodies belonging to subtree starting at a given body.
110
120
 
111
- def gather_geoms(body_id: int) -> list[int]:
112
- geoms: list[int] = []
113
- geom_start = model.body_geomadr[body_id]
114
- geom_end = geom_start + model.body_geomnum[body_id]
115
- geoms.extend(range(geom_start, geom_end))
116
- children = [i for i in range(model.nbody) if model.body_parentid[i] == body_id]
117
- for child_id in children:
118
- geoms.extend(gather_geoms(child_id))
119
- return geoms
121
+ Args:
122
+ model: Mujoco model.
123
+ body_id: ID of body where subtree starts.
124
+
125
+ Returns:
126
+ A List containing all subtree body ids.
127
+ """
128
+ body_ids: List[int] = []
129
+ stack = [body_id]
130
+ while stack:
131
+ body_id = stack.pop()
132
+ body_ids.append(body_id)
133
+ stack += get_body_body_ids(model, body_id)
134
+ return body_ids
120
135
 
121
- return gather_geoms(body_id)
122
136
 
137
+ def get_body_geom_ids(model: mujoco.MjModel, body_id: int) -> List[int]:
138
+ """Get immediate geoms belonging to a given body.
123
139
 
124
- def get_body_geom_ids(model: mujoco.MjModel, body_id: int) -> list[int]:
125
- """Get all geoms belonging to a given body.
140
+ Here, immediate geoms are those directly attached to the body and not its
141
+ descendants.
126
142
 
127
143
  Args:
128
144
  model: Mujoco model.
@@ -134,3 +150,25 @@ def get_body_geom_ids(model: mujoco.MjModel, body_id: int) -> list[int]:
134
150
  geom_start = model.body_geomadr[body_id]
135
151
  geom_end = geom_start + model.body_geomnum[body_id]
136
152
  return list(range(geom_start, geom_end))
153
+
154
+
155
+ def get_subtree_geom_ids(model: mujoco.MjModel, body_id: int) -> List[int]:
156
+ """Get all geoms belonging to subtree starting at a given body.
157
+
158
+ Here, a subtree is defined as the kinematic tree starting at the body and including
159
+ all its descendants.
160
+
161
+ Args:
162
+ model: Mujoco model.
163
+ body_id: ID of body where subtree starts.
164
+
165
+ Returns:
166
+ A list containing all subtree geom ids.
167
+ """
168
+ geom_ids: List[int] = []
169
+ stack = [body_id]
170
+ while stack:
171
+ body_id = stack.pop()
172
+ geom_ids.extend(get_body_geom_ids(model, body_id))
173
+ stack += get_body_body_ids(model, body_id)
174
+ return geom_ids
@@ -1,33 +1,35 @@
1
- Metadata-Version: 2.1
1
+ Metadata-Version: 2.4
2
2
  Name: mink
3
- Version: 0.0.5
3
+ Version: 0.0.7
4
4
  Summary: mink: MuJoCo inverse kinematics.
5
5
  Keywords: inverse,kinematics,mujoco
6
6
  Author-email: Kevin Zakka <zakka@berkeley.edu>
7
- Requires-Python: >=3.9
7
+ Requires-Python: >=3.8
8
8
  Description-Content-Type: text/markdown
9
9
  Classifier: Development Status :: 5 - Production/Stable
10
10
  Classifier: Framework :: Robot Framework :: Library
11
11
  Classifier: Intended Audience :: Developers
12
12
  Classifier: Intended Audience :: Science/Research
13
13
  Classifier: License :: OSI Approved :: Apache Software License
14
+ Classifier: Programming Language :: Python :: 3.8
14
15
  Classifier: Programming Language :: Python :: 3.9
15
16
  Classifier: Programming Language :: Python :: 3.10
16
17
  Classifier: Programming Language :: Python :: 3.11
17
18
  Classifier: Programming Language :: Python :: 3.12
18
19
  Classifier: Topic :: Scientific/Engineering
20
+ License-File: LICENSE
19
21
  Requires-Dist: mujoco >= 3.1.6
20
22
  Requires-Dist: qpsolvers[quadprog] >= 4.3.1
21
23
  Requires-Dist: typing_extensions
22
24
  Requires-Dist: numpy < 2.0.0
23
- Requires-Dist: mink[examples,dev] ; extra == "all"
25
+ Requires-Dist: mink[examples, dev] ; extra == "all"
24
26
  Requires-Dist: black ; extra == "dev"
25
27
  Requires-Dist: mink[test] ; extra == "dev"
26
28
  Requires-Dist: mypy ; extra == "dev"
27
29
  Requires-Dist: ruff ; extra == "dev"
28
30
  Requires-Dist: dm_control >= 1.0.20 ; extra == "examples"
29
31
  Requires-Dist: loop-rate-limiters >= 0.1.0 ; extra == "examples"
30
- Requires-Dist: qpsolvers[quadprog,osqp] >= 4.3.1 ; extra == "examples"
32
+ Requires-Dist: qpsolvers[quadprog, osqp] >= 4.3.1 ; extra == "examples"
31
33
  Requires-Dist: absl-py ; extra == "test"
32
34
  Requires-Dist: coveralls ; extra == "test"
33
35
  Requires-Dist: pytest ; extra == "test"
@@ -1,10 +1,10 @@
1
- mink/__init__.py,sha256=1-kNZ2BmlC9wD98boMF9tujEz3z9ipx9bTUpE4d8T4c,1717
2
- mink/configuration.py,sha256=SchU0FwPIOjrjwetBVTDbfxTT1OOxLq71tWbLqvvrL4,9110
1
+ mink/__init__.py,sha256=g-eOZoPMgO3l4PtP7RK4ercpo1lyLnIcOT6Tb78T968,1829
2
+ mink/configuration.py,sha256=wbP2ab-Zn5pH844Czk5w8mgDXP44AosMOdNxqwyCSik,9199
3
3
  mink/constants.py,sha256=hcWy4zM4hGI7vvJrTmCjJgs2WtOxKJ1IVtYHucWbOAI,813
4
4
  mink/exceptions.py,sha256=tmExo-ydn_mu9Mny5sP0Ehr7hfo3d79fM8HvvxZBKYM,2931
5
5
  mink/py.typed,sha256=47DEQpj8HBSa-_TImW-5JCeuQeRkm5NMpJWZG3hSuFU,0
6
- mink/solve_ik.py,sha256=hrAnwO5imCoFczmoXQf4v5Rfw5l1wisd0qtmFt-y0vs,3578
7
- mink/utils.py,sha256=-00C_AmtfvkmmWiHpds5Fu83gLcnt9OJ2KmyB01aTa8,4387
6
+ mink/solve_ik.py,sha256=VzPYpfxkJ-JxUZIpwN7-WVOw0Oi2YiIvDZcwB5ROeug,3591
7
+ mink/utils.py,sha256=Eok-pr8xR4LjmjEDEOtD7pvZPDCk53K9gWGdth8TxOA,5329
8
8
  mink/.mypy_cache/.gitignore,sha256=amnaZw0RUw038PDP3HvtMLeOpkNOJPenMgi5guKdMiw,34
9
9
  mink/.mypy_cache/CACHEDIR.TAG,sha256=8cE6_FVTWMkDOw8fMKqhd_6IvaQPS4okWYQA1UeHatw,190
10
10
  mink/.mypy_cache/3.12/@plugins_snapshot.json,sha256=RBNvo1WzZ4oRRq0W9-hknpT7T8If536DEMBg9hyq_4o,2
@@ -326,25 +326,32 @@ mink/.mypy_cache/3.12/unittest/signals.data.json,sha256=1ZiaD7LP0g0iBSmVb5g87M9q
326
326
  mink/.mypy_cache/3.12/unittest/signals.meta.json,sha256=t4kGxxcZb9aDLojvZ5naLIcckL77G1RAB0P2iJsSjM0,1681
327
327
  mink/.mypy_cache/3.12/unittest/suite.data.json,sha256=3XPU9U8rt00fnG-hgEIbpIqS14lI9xQMDiBsl2_mlXQ,12050
328
328
  mink/.mypy_cache/3.12/unittest/suite.meta.json,sha256=5ADDHudtGO-JtLaD0-SB-7_Ekm34XeG_QCXLEDIZeIM,1699
329
+ mink/contrib/__init__.py,sha256=njdlTslt_Ot_fB1Uj6MzRwLhmf-MbRNjwgi8krfCD-k,152
330
+ mink/contrib/keyboard_teleop/KEYBOARD.md,sha256=cYzG3nyOik_ktzha6FZqDiUT7Dn38df8JsXzcGAMmCw,3236
331
+ mink/contrib/keyboard_teleop/__init__.py,sha256=wtG_0D-RurdQiGTPjLYVXXt44ieh6ITTXqpicg6AXxI,185
332
+ mink/contrib/keyboard_teleop/keycodes.py,sha256=1AN3bWpkw99ZjrkIQnu8QdHSz-_boWMYWI2LlZOp5uw,1644
333
+ mink/contrib/keyboard_teleop/teleop_mocap.py,sha256=2cuauiBHsQb6IVruRbGtCumdHQazEGvt9w2L50eKGzw,8095
329
334
  mink/lie/__init__.py,sha256=7tm3ZFnF3o1SDd9MOFO1In13lHMQJHO0FB-ejI6tsgE,202
330
335
  mink/lie/base.py,sha256=ummp2-yROMrcYCtsNCoKEiKoJ7wLF0nSjnOOD95aXaY,4220
331
- mink/lie/se3.py,sha256=R4hH4i0-do5I8bWV0le-huSuAfQ_bwolkAjJNVlDNXs,7914
332
- mink/lie/so3.py,sha256=LkjciJHcVTWYzpDzAo1KuUI7xy0HPnSGAYxQS_q-Kx4,7302
336
+ mink/lie/se3.py,sha256=DudNNLNKgSsS7nMbbpzK-ZdR2z9O_k_AOxzM7yZubpE,7870
337
+ mink/lie/so3.py,sha256=-XWy8qMZ16WdhcscsA4ow-D7CTxUgbnsIU45GGOn9P0,7302
333
338
  mink/lie/utils.py,sha256=DuEl3pj84daLvMKN84-YBvkXnJfqvc5vpvJ9J-pJ11U,403
334
339
  mink/limits/__init__.py,sha256=hX5Dgpri9AE6YtUCkW79AXMBuNAuBhniR9kQ6Rxwv3Y,416
335
- mink/limits/collision_avoidance_limit.py,sha256=pVLpkruWAqrOcAW4yulHc_hIuczMR4EbrXF1x-0Bb80,10973
336
- mink/limits/configuration_limit.py,sha256=areR-8NuuD15wWzPhyQIRtttIdfXPlT3hP81MuDbIN0,4351
340
+ mink/limits/collision_avoidance_limit.py,sha256=MJXesSjvm_2O6RUEz2e4D8uTVOHyTsH9j4UxkPemcn8,11918
341
+ mink/limits/configuration_limit.py,sha256=WspxM4W3-VFIKVo8FLg68x7T9EMmfRmzefiWmi4qrZY,4376
337
342
  mink/limits/exceptions.py,sha256=EnVKgFhUJFM6rNVCtdngb-XMu66PWKMFSDy-XkdKzr8,178
338
- mink/limits/limit.py,sha256=feF9yjgLHWShnuSrJNOH-PfMWtEMRGQi2mDiRia9tFg,1578
339
- mink/limits/velocity_limit.py,sha256=2zPOAb69V9RusKk-U4cJ0lK3-Ek9g4nvr3c8QHbixzw,3506
340
- mink/tasks/__init__.py,sha256=SCS3YMWyuFQpF3XSHiht83px-xmN9IxtFeG-ULkpl64,624
343
+ mink/limits/limit.py,sha256=65K4clGFCPxa3TScGaLhYe1rVYgmJnkMnsFg6DCGjI4,1529
344
+ mink/limits/velocity_limit.py,sha256=2i1Jsh6Y4_qw6CR5_hNxQr-X1YkfJtfeLqlsuqj2b8k,3744
345
+ mink/tasks/__init__.py,sha256=rTx9Ab8XPSohhSa1RUD7lNggTzVi02LOaPzPZFMFvuI,763
341
346
  mink/tasks/com_task.py,sha256=ch6w7pwa5E0GVo2DCAuEF-c8TCN1iMk-ySY9A4B6yoQ,3121
342
347
  mink/tasks/damping_task.py,sha256=SwSfUvMHzoNYNsloQRD1qlPLd4kfoDIWZlTDU9LuKM4,556
343
- mink/tasks/exceptions.py,sha256=1BxQS_t8vuKoTd8RY0MdZOJ_-2RX--iUtVs-Bu3IVgs,708
348
+ mink/tasks/equality_constraint_task.py,sha256=Ou8jBSC1SsZCi_WbzkgdYog4-rXsUF2uMmwGpFSlBZU,8196
349
+ mink/tasks/exceptions.py,sha256=d2P9q_CWaHUXxgSwFjcu-ml87mLuXJYxrVLUwrJp6w8,803
344
350
  mink/tasks/frame_task.py,sha256=DeNg-bEJxqnrRI0FaJK4UHyb8CyF4A7uPF9G-CdN0sg,5307
345
351
  mink/tasks/posture_task.py,sha256=sVDZyalCh5DP8zmCuX5kYuZxiMxRut_mTZUjv5y3b5M,3998
346
352
  mink/tasks/relative_frame_task.py,sha256=9rIiYocI1eEESt0bLZZpQR7K6ggVRZH8iEhdhzkfZa0,5119
347
353
  mink/tasks/task.py,sha256=F16YZT1L9ueNOcKoOhbCyEnZw0DOgrmjqADl0jahVQI,4838
348
- mink-0.0.5.dist-info/WHEEL,sha256=EZbGkh7Ie4PoZfRQ8I0ZuP9VklN_TvcZ6DSE5Uar4z4,81
349
- mink-0.0.5.dist-info/METADATA,sha256=IWndykbTUh_K9MyGE_cAojds8tqJJFOJLBma1nXF-Fo,5501
350
- mink-0.0.5.dist-info/RECORD,,
354
+ mink-0.0.7.dist-info/licenses/LICENSE,sha256=xx0jnfkXJvxRnG63LTGOxlggYnIysveWIZ6H3PNdCrQ,11357
355
+ mink-0.0.7.dist-info/WHEEL,sha256=G2gURzTEtmeR8nrdXUJfNiB3VYVxigPQ-bEQujpNiNs,82
356
+ mink-0.0.7.dist-info/METADATA,sha256=ZcQbHajE_Mda5DlByQ23XGpSn7vh4NXiUOJAidbXkvI,5575
357
+ mink-0.0.7.dist-info/RECORD,,
@@ -1,4 +1,4 @@
1
1
  Wheel-Version: 1.0
2
- Generator: flit 3.9.0
2
+ Generator: flit 3.12.0
3
3
  Root-Is-Purelib: true
4
4
  Tag: py3-none-any