mink 0.0.8__py3-none-any.whl → 0.0.10__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/lie/se3.py
CHANGED
@@ -113,130 +113,131 @@ class SE3(MatrixLieGroup):
|
|
113
113
|
|
114
114
|
@classmethod
|
115
115
|
def exp(cls, tangent: np.ndarray) -> SE3:
|
116
|
-
assert tangent.shape == (
|
116
|
+
assert tangent.shape == (cls.tangent_dim,)
|
117
117
|
rotation = SO3.exp(tangent[3:])
|
118
|
-
|
119
|
-
|
120
|
-
|
121
|
-
|
122
|
-
skew_omega = skew(tangent[3:])
|
123
|
-
if use_taylor:
|
124
|
-
V = rotation.as_matrix()
|
118
|
+
theta = np.float64(mujoco.mju_norm3(tangent[3:]))
|
119
|
+
t2 = theta * theta
|
120
|
+
if t2 < get_epsilon(t2.dtype):
|
121
|
+
v_mat = rotation.as_matrix()
|
125
122
|
else:
|
126
|
-
|
123
|
+
skew_omega = skew(tangent[3:])
|
124
|
+
v_mat = (
|
127
125
|
np.eye(3, dtype=np.float64)
|
128
|
-
+ (1.0 - np.cos(
|
129
|
-
+ (
|
130
|
-
/ (theta_squared_safe * theta_safe)
|
131
|
-
* (skew_omega @ skew_omega)
|
126
|
+
+ (1.0 - np.cos(theta)) / t2 * skew_omega
|
127
|
+
+ (theta - np.sin(theta)) / (t2 * theta) * (skew_omega @ skew_omega)
|
132
128
|
)
|
133
|
-
return
|
129
|
+
return cls.from_rotation_and_translation(
|
134
130
|
rotation=rotation,
|
135
|
-
translation=
|
131
|
+
translation=v_mat @ tangent[:3],
|
136
132
|
)
|
137
133
|
|
138
134
|
def inverse(self) -> SE3:
|
139
|
-
|
140
|
-
|
141
|
-
|
142
|
-
|
135
|
+
inverse_wxyz_xyz = np.empty(SE3.parameters_dim, dtype=np.float64)
|
136
|
+
mujoco.mju_negQuat(inverse_wxyz_xyz[:4], self.wxyz_xyz[:4])
|
137
|
+
mujoco.mju_rotVecQuat(
|
138
|
+
inverse_wxyz_xyz[4:], -1.0 * self.wxyz_xyz[4:], inverse_wxyz_xyz[:4]
|
143
139
|
)
|
140
|
+
return SE3(wxyz_xyz=inverse_wxyz_xyz)
|
144
141
|
|
145
142
|
def normalize(self) -> SE3:
|
146
|
-
|
147
|
-
|
148
|
-
|
149
|
-
)
|
143
|
+
normalized_wxyz_xyz = np.array(self.wxyz_xyz)
|
144
|
+
mujoco.mju_normalize4(normalized_wxyz_xyz[:4])
|
145
|
+
return SE3(wxyz_xyz=normalized_wxyz_xyz)
|
150
146
|
|
151
147
|
def apply(self, target: np.ndarray) -> np.ndarray:
|
152
148
|
assert target.shape == (SE3.space_dim,)
|
153
|
-
|
149
|
+
rotated_target = np.empty(SE3.space_dim, dtype=np.float64)
|
150
|
+
mujoco.mju_rotVecQuat(rotated_target, target, self.wxyz_xyz[:4])
|
151
|
+
return rotated_target + self.wxyz_xyz[4:]
|
154
152
|
|
155
153
|
def multiply(self, other: SE3) -> SE3:
|
156
|
-
|
157
|
-
|
158
|
-
|
159
|
-
|
154
|
+
wxyz_xyz = np.empty(SE3.parameters_dim, dtype=np.float64)
|
155
|
+
mujoco.mju_mulQuat(wxyz_xyz[:4], self.wxyz_xyz[:4], other.wxyz_xyz[:4])
|
156
|
+
mujoco.mju_rotVecQuat(wxyz_xyz[4:], other.wxyz_xyz[4:], self.wxyz_xyz[:4])
|
157
|
+
wxyz_xyz[4:] += self.wxyz_xyz[4:]
|
158
|
+
return SE3(wxyz_xyz=wxyz_xyz)
|
160
159
|
|
161
160
|
def log(self) -> np.ndarray:
|
162
161
|
omega = self.rotation().log()
|
163
|
-
|
164
|
-
|
162
|
+
theta = np.float64(mujoco.mju_norm3(omega))
|
163
|
+
t2 = theta * theta
|
165
164
|
skew_omega = skew(omega)
|
166
|
-
|
167
|
-
|
168
|
-
|
169
|
-
|
170
|
-
if use_taylor:
|
171
|
-
V_inv = (
|
172
|
-
np.eye(3, dtype=np.float64) - 0.5 * skew_omega + skew_omega_norm / 12.0
|
165
|
+
skew_omega2 = skew_omega @ skew_omega
|
166
|
+
if t2 < get_epsilon(t2.dtype):
|
167
|
+
vinv_mat = (
|
168
|
+
np.eye(3, dtype=np.float64) - 0.5 * skew_omega + skew_omega2 / 12.0
|
173
169
|
)
|
174
170
|
else:
|
175
|
-
|
171
|
+
half_theta = 0.5 * theta
|
172
|
+
vinv_mat = (
|
176
173
|
np.eye(3, dtype=np.float64)
|
177
174
|
- 0.5 * skew_omega
|
178
|
-
+ (
|
179
|
-
|
180
|
-
|
181
|
-
* np.cos(half_theta_safe)
|
182
|
-
/ (2.0 * np.sin(half_theta_safe))
|
183
|
-
)
|
184
|
-
/ theta_squared_safe
|
185
|
-
* skew_omega_norm
|
175
|
+
+ (1.0 - 0.5 * theta * np.cos(half_theta) / np.sin(half_theta))
|
176
|
+
/ t2
|
177
|
+
* skew_omega2
|
186
178
|
)
|
187
|
-
|
179
|
+
tangent = np.empty(SE3.tangent_dim, dtype=np.float64)
|
180
|
+
tangent[:3] = vinv_mat @ self.translation()
|
181
|
+
tangent[3:] = omega
|
182
|
+
return tangent
|
188
183
|
|
189
184
|
def adjoint(self) -> np.ndarray:
|
190
|
-
|
191
|
-
|
192
|
-
|
193
|
-
|
194
|
-
|
195
|
-
|
196
|
-
|
185
|
+
rotation = self.rotation()
|
186
|
+
rotation_mat = rotation.as_matrix()
|
187
|
+
tangent_mat = skew(self.translation()) @ rotation_mat
|
188
|
+
adjoint_mat = np.zeros((SE3.tangent_dim, SE3.tangent_dim), dtype=np.float64)
|
189
|
+
adjoint_mat[:3, :3] = rotation_mat
|
190
|
+
adjoint_mat[:3, 3:] = tangent_mat
|
191
|
+
adjoint_mat[3:, 3:] = rotation_mat
|
192
|
+
return adjoint_mat
|
197
193
|
|
198
194
|
# Jacobians.
|
199
195
|
|
200
196
|
# Eqn 179 a)
|
201
197
|
@classmethod
|
202
198
|
def ljac(cls, other: np.ndarray) -> np.ndarray:
|
203
|
-
|
204
|
-
if
|
199
|
+
theta_squared = np.float64(mujoco.mju_dot3(other[3:], other[3:]))
|
200
|
+
if theta_squared < get_epsilon(theta_squared.dtype):
|
205
201
|
return np.eye(cls.tangent_dim)
|
206
|
-
|
207
|
-
|
208
|
-
|
209
|
-
|
202
|
+
ljac_se3 = np.zeros((cls.tangent_dim, cls.tangent_dim), dtype=np.float64)
|
203
|
+
ljac_translation = _getQ(other)
|
204
|
+
ljac_so3 = SO3.ljac(other[3:])
|
205
|
+
ljac_se3[:3, :3] = ljac_so3
|
206
|
+
ljac_se3[:3, 3:] = ljac_translation
|
207
|
+
ljac_se3[3:, 3:] = ljac_so3
|
208
|
+
return ljac_se3
|
210
209
|
|
211
210
|
# Eqn 179 b)
|
212
211
|
@classmethod
|
213
212
|
def ljacinv(cls, other: np.ndarray) -> np.ndarray:
|
214
|
-
|
215
|
-
if
|
213
|
+
theta_squared = np.float64(mujoco.mju_dot3(other[3:], other[3:]))
|
214
|
+
if theta_squared < get_epsilon(theta_squared.dtype):
|
216
215
|
return np.eye(cls.tangent_dim)
|
217
|
-
|
218
|
-
|
219
|
-
|
220
|
-
|
216
|
+
ljacinv_se3 = np.zeros((cls.tangent_dim, cls.tangent_dim), dtype=np.float64)
|
217
|
+
ljac_translation = _getQ(other)
|
218
|
+
ljacinv_so3 = SO3.ljacinv(other[3:])
|
219
|
+
ljacinv_se3[:3, :3] = ljacinv_so3
|
220
|
+
ljacinv_se3[:3, 3:] = -ljacinv_so3 @ ljac_translation @ ljacinv_so3
|
221
|
+
ljacinv_se3[3:, 3:] = ljacinv_so3
|
222
|
+
return ljacinv_se3
|
221
223
|
|
222
224
|
|
223
225
|
# Eqn 180.
|
224
226
|
def _getQ(c) -> np.ndarray:
|
225
|
-
|
227
|
+
theta = np.float64(mujoco.mju_norm3(c[3:]))
|
228
|
+
t2 = theta * theta
|
226
229
|
A = 0.5
|
227
|
-
if
|
228
|
-
B = (1.0 / 6.0) + (1.0 / 120.0) *
|
229
|
-
C = -(1.0 / 24.0) + (1.0 / 720.0) *
|
230
|
+
if t2 < get_epsilon(t2.dtype):
|
231
|
+
B = (1.0 / 6.0) + (1.0 / 120.0) * t2
|
232
|
+
C = -(1.0 / 24.0) + (1.0 / 720.0) * t2
|
230
233
|
D = -(1.0 / 60.0)
|
231
234
|
else:
|
232
|
-
|
235
|
+
t4 = t2 * t2
|
233
236
|
sin_theta = np.sin(theta)
|
234
237
|
cos_theta = np.cos(theta)
|
235
|
-
B = (theta - sin_theta) / (
|
236
|
-
C = (1.0 -
|
237
|
-
D = (
|
238
|
-
(2) * theta_sq * theta_sq * theta
|
239
|
-
)
|
238
|
+
B = (theta - sin_theta) / (t2 * theta)
|
239
|
+
C = (1.0 - 0.5 * t2 - cos_theta) / t4
|
240
|
+
D = (2.0 * theta - 3.0 * sin_theta + theta * cos_theta) / (2.0 * t4 * theta)
|
240
241
|
V = skew(c[:3])
|
241
242
|
W = skew(c[3:])
|
242
243
|
VW = V @ W
|
@@ -246,6 +247,6 @@ def _getQ(c) -> np.ndarray:
|
|
246
247
|
return (
|
247
248
|
+A * V
|
248
249
|
+ B * (WV + VW + WVW)
|
249
|
-
- C * (VWW - VWW.T - 3 * WVW)
|
250
|
+
- C * (VWW - VWW.T - 3.0 * WVW)
|
250
251
|
+ D * (WVW @ W + W @ WVW)
|
251
252
|
)
|
mink/lie/so3.py
CHANGED
@@ -7,10 +7,9 @@ import mujoco
|
|
7
7
|
import numpy as np
|
8
8
|
|
9
9
|
from .base import MatrixLieGroup
|
10
|
-
from .utils import get_epsilon
|
10
|
+
from .utils import get_epsilon
|
11
11
|
|
12
12
|
_IDENTITIY_WXYZ = np.array([1.0, 0.0, 0.0, 0.0], dtype=np.float64)
|
13
|
-
_INVERT_QUAT_SIGN = np.array([1.0, -1.0, -1.0, -1.0], dtype=np.float64)
|
14
13
|
|
15
14
|
|
16
15
|
class RollPitchYaw(NamedTuple):
|
@@ -86,6 +85,7 @@ class SO3(MatrixLieGroup):
|
|
86
85
|
assert matrix.shape == (SO3.matrix_dim, SO3.matrix_dim)
|
87
86
|
wxyz = np.empty(SO3.parameters_dim, dtype=np.float64)
|
88
87
|
mujoco.mju_mat2Quat(wxyz, matrix.ravel())
|
88
|
+
# NOTE mju_mat2Quat normalizes the quaternion.
|
89
89
|
return SO3(wxyz=wxyz)
|
90
90
|
|
91
91
|
@classmethod
|
@@ -137,63 +137,49 @@ class SO3(MatrixLieGroup):
|
|
137
137
|
yaw=self.compute_yaw_radians(),
|
138
138
|
)
|
139
139
|
|
140
|
-
# Paragraph above Appendix B.A.
|
141
140
|
def inverse(self) -> SO3:
|
142
|
-
|
141
|
+
conjugate_wxyz = np.empty(4)
|
142
|
+
mujoco.mju_negQuat(conjugate_wxyz, self.wxyz)
|
143
|
+
return SO3(wxyz=conjugate_wxyz)
|
143
144
|
|
144
145
|
def normalize(self) -> SO3:
|
145
|
-
|
146
|
+
normalized_wxyz = np.array(self.wxyz)
|
147
|
+
mujoco.mju_normalize4(normalized_wxyz)
|
148
|
+
return SO3(wxyz=normalized_wxyz)
|
146
149
|
|
147
150
|
# Eq. 136.
|
148
151
|
def apply(self, target: np.ndarray) -> np.ndarray:
|
149
152
|
assert target.shape == (SO3.space_dim,)
|
150
|
-
|
151
|
-
|
153
|
+
rotated_target = np.empty(SO3.space_dim, dtype=np.float64)
|
154
|
+
mujoco.mju_rotVecQuat(rotated_target, target, self.wxyz)
|
155
|
+
return rotated_target
|
152
156
|
|
153
157
|
def multiply(self, other: SO3) -> SO3:
|
154
158
|
res = np.empty(self.parameters_dim, dtype=np.float64)
|
155
159
|
mujoco.mju_mulQuat(res, self.wxyz, other.wxyz)
|
156
160
|
return SO3(wxyz=res)
|
157
161
|
|
158
|
-
##
|
159
|
-
#
|
160
|
-
##
|
161
|
-
|
162
162
|
# Eq. 132.
|
163
163
|
@classmethod
|
164
164
|
def exp(cls, tangent: np.ndarray) -> SO3:
|
165
|
-
|
166
|
-
|
167
|
-
|
168
|
-
|
169
|
-
|
170
|
-
|
171
|
-
|
172
|
-
real = 1.0 - theta_squared / 8.0 + theta_pow_4 / 384.0
|
173
|
-
imaginary = 0.5 - theta_squared / 48.0 + theta_pow_4 / 3840.0
|
174
|
-
else:
|
175
|
-
real = np.cos(safe_half_theta)
|
176
|
-
imaginary = np.sin(safe_half_theta) / safe_theta
|
177
|
-
wxyz = np.concatenate([np.array([real]), imaginary * tangent])
|
165
|
+
axis = np.array(tangent)
|
166
|
+
theta = mujoco.mju_normalize3(axis)
|
167
|
+
wxyz = np.empty(4, dtype=np.float64)
|
168
|
+
# NOTE mju_axisAngle2Quat does not normalize the quaternion but is guaranteed
|
169
|
+
# to return a unit quaternion when axis is a unit vector. In our case,
|
170
|
+
# mju_normalize3 ensures that axis is a unit vector.
|
171
|
+
mujoco.mju_axisAngle2Quat(wxyz, axis, theta)
|
178
172
|
return SO3(wxyz=wxyz)
|
179
173
|
|
180
174
|
# Eq. 133.
|
181
175
|
def log(self) -> np.ndarray:
|
182
|
-
|
183
|
-
|
184
|
-
|
185
|
-
|
186
|
-
|
187
|
-
|
188
|
-
|
189
|
-
atan_factor = 2.0 / w_safe - 2.0 / 3.0 * norm_sq / w_safe**3
|
190
|
-
else:
|
191
|
-
if abs(w) < get_epsilon(w.dtype):
|
192
|
-
scl = 1.0 if w > 0.0 else -1.0
|
193
|
-
atan_factor = scl * np.pi / norm_safe
|
194
|
-
else:
|
195
|
-
atan_factor = 2.0 * atan_n_over_w / norm_safe
|
196
|
-
return atan_factor * self.wxyz[1:]
|
176
|
+
q = np.array(self.wxyz)
|
177
|
+
q *= np.sign(q[0])
|
178
|
+
w, v = q[0], q[1:]
|
179
|
+
norm = mujoco.mju_normalize3(v)
|
180
|
+
if norm < get_epsilon(v.dtype):
|
181
|
+
return np.zeros_like(v)
|
182
|
+
return 2 * np.arctan2(norm, w) * v
|
197
183
|
|
198
184
|
# Eq. 139.
|
199
185
|
def adjoint(self) -> np.ndarray:
|
@@ -204,28 +190,73 @@ class SO3(MatrixLieGroup):
|
|
204
190
|
# Eqn. 145, 174.
|
205
191
|
@classmethod
|
206
192
|
def ljac(cls, other: np.ndarray) -> np.ndarray:
|
207
|
-
theta = np.
|
208
|
-
|
209
|
-
if
|
210
|
-
|
211
|
-
|
212
|
-
|
193
|
+
theta = np.float64(mujoco.mju_norm3(other))
|
194
|
+
t2 = theta * theta
|
195
|
+
if theta < get_epsilon(theta.dtype):
|
196
|
+
alpha = (1.0 / 2.0) * (
|
197
|
+
1.0 - t2 / 12.0 * (1.0 - t2 / 30.0 * (1.0 - t2 / 56.0))
|
198
|
+
)
|
199
|
+
beta = (1.0 / 6.0) * (
|
200
|
+
1.0 - t2 / 20.0 * (1.0 - t2 / 42.0 * (1.0 - t2 / 72.0))
|
201
|
+
)
|
213
202
|
else:
|
214
|
-
|
215
|
-
|
216
|
-
|
217
|
-
|
203
|
+
t3 = t2 * theta
|
204
|
+
alpha = (1 - np.cos(theta)) / t2
|
205
|
+
beta = (theta - np.sin(theta)) / t3
|
206
|
+
# ljac = eye(3) + alpha * skew_other + beta * (skew_other @ skew_other)
|
207
|
+
ljac = np.empty((3, 3))
|
208
|
+
# skew_other @ skew_other == outer(other) - inner(other) * eye(3)
|
209
|
+
mujoco.mju_mulMatMat(ljac, other.reshape(3, 1), other.reshape(1, 3))
|
210
|
+
inner_product = mujoco.mju_dot3(other, other)
|
211
|
+
ljac[0, 0] -= inner_product
|
212
|
+
ljac[1, 1] -= inner_product
|
213
|
+
ljac[2, 2] -= inner_product
|
214
|
+
ljac *= beta
|
215
|
+
# + alpha * skew_other
|
216
|
+
alpha_vec = alpha * other
|
217
|
+
ljac[0, 1] += -alpha_vec[2]
|
218
|
+
ljac[0, 2] += alpha_vec[1]
|
219
|
+
ljac[1, 0] += alpha_vec[2]
|
220
|
+
ljac[1, 2] += -alpha_vec[0]
|
221
|
+
ljac[2, 0] += -alpha_vec[1]
|
222
|
+
ljac[2, 1] += alpha_vec[0]
|
223
|
+
# + eye(3)
|
224
|
+
ljac[0, 0] += 1.0
|
225
|
+
ljac[1, 1] += 1.0
|
226
|
+
ljac[2, 2] += 1.0
|
227
|
+
return ljac
|
218
228
|
|
219
229
|
@classmethod
|
220
230
|
def ljacinv(cls, other: np.ndarray) -> np.ndarray:
|
221
|
-
theta = np.
|
222
|
-
|
223
|
-
if
|
224
|
-
|
225
|
-
|
231
|
+
theta = np.float64(mujoco.mju_norm3(other))
|
232
|
+
t2 = theta * theta
|
233
|
+
if theta < get_epsilon(theta.dtype):
|
234
|
+
beta = (1.0 / 12.0) * (
|
235
|
+
1.0 + t2 / 60.0 * (1.0 + t2 / 42.0 * (1.0 + t2 / 40.0))
|
236
|
+
)
|
226
237
|
else:
|
227
|
-
|
238
|
+
beta = (1.0 / t2) * (
|
228
239
|
1.0 - (theta * np.sin(theta) / (2.0 * (1.0 - np.cos(theta))))
|
229
240
|
)
|
230
|
-
|
231
|
-
|
241
|
+
# ljacinv = eye(3) - 0.5 * skew_other + beta * (skew_other @ skew_other)
|
242
|
+
ljacinv = np.empty((3, 3))
|
243
|
+
# skew_other @ skew_other == outer(other) - inner(other) * eye(3)
|
244
|
+
mujoco.mju_mulMatMat(ljacinv, other.reshape(3, 1), other.reshape(1, 3))
|
245
|
+
inner_product = mujoco.mju_dot3(other, other)
|
246
|
+
ljacinv[0, 0] -= inner_product
|
247
|
+
ljacinv[1, 1] -= inner_product
|
248
|
+
ljacinv[2, 2] -= inner_product
|
249
|
+
ljacinv *= beta
|
250
|
+
# - 0.5 * skew_other
|
251
|
+
alpha_vec = -0.5 * other
|
252
|
+
ljacinv[0, 1] += -alpha_vec[2]
|
253
|
+
ljacinv[0, 2] += alpha_vec[1]
|
254
|
+
ljacinv[1, 0] += alpha_vec[2]
|
255
|
+
ljacinv[1, 2] += -alpha_vec[0]
|
256
|
+
ljacinv[2, 0] += -alpha_vec[1]
|
257
|
+
ljacinv[2, 1] += alpha_vec[0]
|
258
|
+
# + eye(3)
|
259
|
+
ljacinv[0, 0] += 1.0
|
260
|
+
ljacinv[1, 1] += 1.0
|
261
|
+
ljacinv[2, 2] += 1.0
|
262
|
+
return ljacinv
|
@@ -1,6 +1,6 @@
|
|
1
1
|
Metadata-Version: 2.4
|
2
2
|
Name: mink
|
3
|
-
Version: 0.0.
|
3
|
+
Version: 0.0.10
|
4
4
|
Summary: mink: MuJoCo inverse kinematics.
|
5
5
|
Keywords: inverse,kinematics,mujoco
|
6
6
|
Author-email: Kevin Zakka <zakka@berkeley.edu>
|
@@ -21,7 +21,7 @@ License-File: LICENSE
|
|
21
21
|
Requires-Dist: mujoco >= 3.1.6
|
22
22
|
Requires-Dist: qpsolvers[daqp] >= 4.3.1
|
23
23
|
Requires-Dist: typing_extensions
|
24
|
-
Requires-Dist: numpy
|
24
|
+
Requires-Dist: numpy
|
25
25
|
Requires-Dist: mink[examples, dev] ; extra == "all"
|
26
26
|
Requires-Dist: black ; extra == "dev"
|
27
27
|
Requires-Dist: mink[test] ; extra == "dev"
|
@@ -333,8 +333,8 @@ mink/contrib/keyboard_teleop/keycodes.py,sha256=1AN3bWpkw99ZjrkIQnu8QdHSz-_boWMY
|
|
333
333
|
mink/contrib/keyboard_teleop/teleop_mocap.py,sha256=2cuauiBHsQb6IVruRbGtCumdHQazEGvt9w2L50eKGzw,8095
|
334
334
|
mink/lie/__init__.py,sha256=7tm3ZFnF3o1SDd9MOFO1In13lHMQJHO0FB-ejI6tsgE,202
|
335
335
|
mink/lie/base.py,sha256=8TGWWEWRvmoBsJP-9y1YXQHkTC-TFfI8JDvBFKxxP-A,4865
|
336
|
-
mink/lie/se3.py,sha256=
|
337
|
-
mink/lie/so3.py,sha256=
|
336
|
+
mink/lie/se3.py,sha256=cEzAzKEfBAQcbHhbZbhW8QZA8WpfRRaeZ0YGdSmhOx8,8634
|
337
|
+
mink/lie/so3.py,sha256=Goipwo7PRxNecYRNBmueWCiO2D51D7qHlzs2gQiXO-Q,8423
|
338
338
|
mink/lie/utils.py,sha256=DuEl3pj84daLvMKN84-YBvkXnJfqvc5vpvJ9J-pJ11U,403
|
339
339
|
mink/limits/__init__.py,sha256=hX5Dgpri9AE6YtUCkW79AXMBuNAuBhniR9kQ6Rxwv3Y,416
|
340
340
|
mink/limits/collision_avoidance_limit.py,sha256=MJXesSjvm_2O6RUEz2e4D8uTVOHyTsH9j4UxkPemcn8,11918
|
@@ -351,7 +351,7 @@ mink/tasks/frame_task.py,sha256=DeNg-bEJxqnrRI0FaJK4UHyb8CyF4A7uPF9G-CdN0sg,5307
|
|
351
351
|
mink/tasks/posture_task.py,sha256=sVDZyalCh5DP8zmCuX5kYuZxiMxRut_mTZUjv5y3b5M,3998
|
352
352
|
mink/tasks/relative_frame_task.py,sha256=9rIiYocI1eEESt0bLZZpQR7K6ggVRZH8iEhdhzkfZa0,5119
|
353
353
|
mink/tasks/task.py,sha256=F16YZT1L9ueNOcKoOhbCyEnZw0DOgrmjqADl0jahVQI,4838
|
354
|
-
mink-0.0.
|
355
|
-
mink-0.0.
|
356
|
-
mink-0.0.
|
357
|
-
mink-0.0.
|
354
|
+
mink-0.0.10.dist-info/licenses/LICENSE,sha256=xx0jnfkXJvxRnG63LTGOxlggYnIysveWIZ6H3PNdCrQ,11357
|
355
|
+
mink-0.0.10.dist-info/WHEEL,sha256=G2gURzTEtmeR8nrdXUJfNiB3VYVxigPQ-bEQujpNiNs,82
|
356
|
+
mink-0.0.10.dist-info/METADATA,sha256=AJQA0xMmwAZiWYmLgDDQo1rKDBQ7AYJxCUMtd-6nlik,5607
|
357
|
+
mink-0.0.10.dist-info/RECORD,,
|
File without changes
|
File without changes
|