Spaces:
Sleeping
Sleeping
File size: 23,542 Bytes
66c9c8a | 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 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 360 361 362 363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397 398 399 400 401 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 | # Copyright (c) 2022 NVIDIA CORPORATION. All rights reserved.
# NVIDIA CORPORATION and its licensors retain all intellectual property
# and proprietary rights in and to this software, related documentation
# and any modifications thereto. Any use, reproduction, disclosure or
# distribution of this software and related documentation without an express
# license agreement from NVIDIA CORPORATION is strictly prohibited.
import warp as wp
from .utils import quat_decompose, quat_twist
@wp.func
def compute_2d_rotational_dofs(
axis_0: wp.vec3,
axis_1: wp.vec3,
q0: float,
q1: float,
qd0: float,
qd1: float,
):
"""
Computes the rotation quaternion and 3D angular velocity given the joint axes, coordinates and velocities.
"""
q_off = wp.quat_from_matrix(wp.mat33(axis_0, axis_1, wp.cross(axis_0, axis_1)))
# body local axes
local_0 = wp.quat_rotate(q_off, wp.vec3(1.0, 0.0, 0.0))
local_1 = wp.quat_rotate(q_off, wp.vec3(0.0, 1.0, 0.0))
axis_0 = local_0
q_0 = wp.quat_from_axis_angle(axis_0, q0)
axis_1 = wp.quat_rotate(q_0, local_1)
q_1 = wp.quat_from_axis_angle(axis_1, q1)
rot = q_1 * q_0
vel = axis_0 * qd0 + axis_1 * qd1
return rot, vel
@wp.func
def invert_2d_rotational_dofs(
axis_0: wp.vec3,
axis_1: wp.vec3,
q_p: wp.quat,
q_c: wp.quat,
w_err: wp.vec3,
):
"""
Computes generalized joint position and velocity coordinates for a 2D rotational joint given the joint axes, relative orientations and angular velocity differences between the two bodies the joint connects.
"""
q_off = wp.quat_from_matrix(wp.mat33(axis_0, axis_1, wp.cross(axis_0, axis_1)))
q_pc = wp.quat_inverse(q_off) * wp.quat_inverse(q_p) * q_c * q_off
# decompose to a compound rotation each axis
angles = quat_decompose(q_pc)
# find rotation axes
local_0 = wp.quat_rotate(q_off, wp.vec3(1.0, 0.0, 0.0))
local_1 = wp.quat_rotate(q_off, wp.vec3(0.0, 1.0, 0.0))
local_2 = wp.quat_rotate(q_off, wp.vec3(0.0, 0.0, 1.0))
axis_0 = local_0
q_0 = wp.quat_from_axis_angle(axis_0, angles[0])
axis_1 = wp.quat_rotate(q_0, local_1)
q_1 = wp.quat_from_axis_angle(axis_1, angles[1])
axis_2 = wp.quat_rotate(q_1 * q_0, local_2)
# convert angular velocity to local space
w_err_p = wp.quat_rotate_inv(q_p, w_err)
# given joint axes and angular velocity error, solve for joint velocities
c12 = wp.cross(axis_1, axis_2)
c02 = wp.cross(axis_0, axis_2)
vel = wp.vec2(wp.dot(w_err_p, c12) / wp.dot(axis_0, c12), wp.dot(w_err_p, c02) / wp.dot(axis_1, c02))
return wp.vec2(angles[0], angles[1]), vel
@wp.func
def compute_3d_rotational_dofs(
axis_0: wp.vec3,
axis_1: wp.vec3,
axis_2: wp.vec3,
q0: float,
q1: float,
q2: float,
qd0: float,
qd1: float,
qd2: float,
):
"""
Computes the rotation quaternion and 3D angular velocity given the joint axes, coordinates and velocities.
"""
q_off = wp.quat_from_matrix(wp.mat33(axis_0, axis_1, axis_2))
# body local axes
local_0 = wp.quat_rotate(q_off, wp.vec3(1.0, 0.0, 0.0))
local_1 = wp.quat_rotate(q_off, wp.vec3(0.0, 1.0, 0.0))
local_2 = wp.quat_rotate(q_off, wp.vec3(0.0, 0.0, 1.0))
# reconstruct rotation axes, todo: can probably use fact that rz'*ry'*rx' == rx*ry*rz to avoid some work here
axis_0 = local_0
q_0 = wp.quat_from_axis_angle(axis_0, q0)
axis_1 = wp.quat_rotate(q_0, local_1)
q_1 = wp.quat_from_axis_angle(axis_1, q1)
axis_2 = wp.quat_rotate(q_1 * q_0, local_2)
q_2 = wp.quat_from_axis_angle(axis_2, q2)
rot = q_2 * q_1 * q_0
vel = axis_0 * qd0 + axis_1 * qd1 + axis_2 * qd2
return rot, vel
@wp.func
def invert_3d_rotational_dofs(
axis_0: wp.vec3, axis_1: wp.vec3, axis_2: wp.vec3, q_p: wp.quat, q_c: wp.quat, w_err: wp.vec3
):
"""
Computes generalized joint position and velocity coordinates for a 3D rotational joint given the joint axes, relative orientations and angular velocity differences between the two bodies the joint connects.
"""
q_off = wp.quat_from_matrix(wp.mat33(axis_0, axis_1, axis_2))
q_pc = wp.quat_inverse(q_off) * wp.quat_inverse(q_p) * q_c * q_off
# decompose to a compound rotation each axis
angles = quat_decompose(q_pc)
# find rotation axes
local_0 = wp.quat_rotate(q_off, wp.vec3(1.0, 0.0, 0.0))
local_1 = wp.quat_rotate(q_off, wp.vec3(0.0, 1.0, 0.0))
local_2 = wp.quat_rotate(q_off, wp.vec3(0.0, 0.0, 1.0))
axis_0 = local_0
q_0 = wp.quat_from_axis_angle(axis_0, angles[0])
axis_1 = wp.quat_rotate(q_0, local_1)
q_1 = wp.quat_from_axis_angle(axis_1, angles[1])
axis_2 = wp.quat_rotate(q_1 * q_0, local_2)
# convert angular velocity to local space
w_err_p = wp.quat_rotate_inv(q_p, w_err)
# given joint axes and angular velocity error, solve for joint velocities
c12 = wp.cross(axis_1, axis_2)
c02 = wp.cross(axis_0, axis_2)
c01 = wp.cross(axis_0, axis_1)
velocities = wp.vec3(
wp.dot(w_err_p, c12) / wp.dot(axis_0, c12),
wp.dot(w_err_p, c02) / wp.dot(axis_1, c02),
wp.dot(w_err_p, c01) / wp.dot(axis_2, c01),
)
return angles, velocities
@wp.kernel
def eval_articulation_fk(
articulation_start: wp.array(dtype=int),
articulation_mask: wp.array(
dtype=int
), # used to enable / disable FK for an articulation, if None then treat all as enabled
joint_q: wp.array(dtype=float),
joint_qd: wp.array(dtype=float),
joint_q_start: wp.array(dtype=int),
joint_qd_start: wp.array(dtype=int),
joint_type: wp.array(dtype=int),
joint_parent: wp.array(dtype=int),
joint_child: wp.array(dtype=int),
joint_X_p: wp.array(dtype=wp.transform),
joint_X_c: wp.array(dtype=wp.transform),
joint_axis: wp.array(dtype=wp.vec3),
joint_axis_start: wp.array(dtype=int),
joint_axis_dim: wp.array(dtype=int, ndim=2),
body_com: wp.array(dtype=wp.vec3),
# outputs
body_q: wp.array(dtype=wp.transform),
body_qd: wp.array(dtype=wp.spatial_vector),
):
tid = wp.tid()
# early out if disabling FK for this articulation
if articulation_mask:
if articulation_mask[tid] == 0:
return
joint_start = articulation_start[tid]
joint_end = articulation_start[tid + 1]
for i in range(joint_start, joint_end):
parent = joint_parent[i]
child = joint_child[i]
# compute transform across the joint
type = joint_type[i]
X_pj = joint_X_p[i]
X_cj = joint_X_c[i]
# parent anchor frame in world space
X_wpj = X_pj
# velocity of parent anchor point in world space
v_wpj = wp.spatial_vector()
if parent >= 0:
X_wp = body_q[parent]
X_wpj = X_wp * X_wpj
r_p = wp.transform_get_translation(X_wpj) - wp.transform_point(X_wp, body_com[parent])
v_wp = body_qd[parent]
w_p = wp.spatial_top(v_wp)
v_p = wp.spatial_bottom(v_wp) + wp.cross(w_p, r_p)
v_wpj = wp.spatial_vector(w_p, v_p)
q_start = joint_q_start[i]
qd_start = joint_qd_start[i]
axis_start = joint_axis_start[i]
lin_axis_count = joint_axis_dim[i, 0]
ang_axis_count = joint_axis_dim[i, 1]
X_j = wp.transform_identity()
v_j = wp.spatial_vector(wp.vec3(), wp.vec3())
if type == wp.sim.JOINT_PRISMATIC:
axis = joint_axis[axis_start]
q = joint_q[q_start]
qd = joint_qd[qd_start]
X_j = wp.transform(axis * q, wp.quat_identity())
v_j = wp.spatial_vector(wp.vec3(), axis * qd)
if type == wp.sim.JOINT_REVOLUTE:
axis = joint_axis[axis_start]
q = joint_q[q_start]
qd = joint_qd[qd_start]
X_j = wp.transform(wp.vec3(), wp.quat_from_axis_angle(axis, q))
v_j = wp.spatial_vector(axis * qd, wp.vec3())
if type == wp.sim.JOINT_BALL:
r = wp.quat(joint_q[q_start + 0], joint_q[q_start + 1], joint_q[q_start + 2], joint_q[q_start + 3])
w = wp.vec3(joint_qd[qd_start + 0], joint_qd[qd_start + 1], joint_qd[qd_start + 2])
X_j = wp.transform(wp.vec3(), r)
v_j = wp.spatial_vector(w, wp.vec3())
if type == wp.sim.JOINT_FREE or type == wp.sim.JOINT_DISTANCE:
t = wp.transform(
wp.vec3(joint_q[q_start + 0], joint_q[q_start + 1], joint_q[q_start + 2]),
wp.quat(joint_q[q_start + 3], joint_q[q_start + 4], joint_q[q_start + 5], joint_q[q_start + 6]),
)
v = wp.spatial_vector(
wp.vec3(joint_qd[qd_start + 0], joint_qd[qd_start + 1], joint_qd[qd_start + 2]),
wp.vec3(joint_qd[qd_start + 3], joint_qd[qd_start + 4], joint_qd[qd_start + 5]),
)
X_j = t
v_j = v
if type == wp.sim.JOINT_COMPOUND:
rot, vel_w = compute_3d_rotational_dofs(
joint_axis[axis_start],
joint_axis[axis_start + 1],
joint_axis[axis_start + 2],
joint_q[q_start + 0],
joint_q[q_start + 1],
joint_q[q_start + 2],
joint_qd[qd_start + 0],
joint_qd[qd_start + 1],
joint_qd[qd_start + 2],
)
t = wp.transform(wp.vec3(0.0, 0.0, 0.0), rot)
v = wp.spatial_vector(vel_w, wp.vec3(0.0, 0.0, 0.0))
X_j = t
v_j = v
if type == wp.sim.JOINT_UNIVERSAL:
rot, vel_w = compute_2d_rotational_dofs(
joint_axis[axis_start],
joint_axis[axis_start + 1],
joint_q[q_start + 0],
joint_q[q_start + 1],
joint_qd[qd_start + 0],
joint_qd[qd_start + 1],
)
t = wp.transform(wp.vec3(0.0, 0.0, 0.0), rot)
v = wp.spatial_vector(vel_w, wp.vec3(0.0, 0.0, 0.0))
X_j = t
v_j = v
if type == wp.sim.JOINT_D6:
pos = wp.vec3(0.0)
rot = wp.quat_identity()
vel_v = wp.vec3(0.0)
vel_w = wp.vec3(0.0)
# unroll for loop to ensure joint actions remain differentiable
# (since differentiating through a for loop that updates a local variable is not supported)
if lin_axis_count > 0:
axis = joint_axis[axis_start + 0]
pos += axis * joint_q[q_start + 0]
vel_v += axis * joint_qd[qd_start + 0]
if lin_axis_count > 1:
axis = joint_axis[axis_start + 1]
pos += axis * joint_q[q_start + 1]
vel_v += axis * joint_qd[qd_start + 1]
if lin_axis_count > 2:
axis = joint_axis[axis_start + 2]
pos += axis * joint_q[q_start + 2]
vel_v += axis * joint_qd[qd_start + 2]
ia = axis_start + lin_axis_count
iq = q_start + lin_axis_count
iqd = qd_start + lin_axis_count
if ang_axis_count == 1:
axis = joint_axis[axis_start + lin_axis_count + 0]
qi = wp.quat_from_axis_angle(axis, joint_q[q_start + lin_axis_count + 0])
rot = qi * rot
vel_w = joint_qd[qd_start + lin_axis_count + 0] * axis
if ang_axis_count == 2:
rot, vel_w = compute_2d_rotational_dofs(
joint_axis[ia + 0],
joint_axis[ia + 1],
joint_q[iq + 0],
joint_q[iq + 1],
joint_qd[iqd + 0],
joint_qd[iqd + 1],
)
if ang_axis_count == 3:
rot, vel_w = compute_3d_rotational_dofs(
joint_axis[ia + 0],
joint_axis[ia + 1],
joint_axis[ia + 2],
joint_q[iq + 0],
joint_q[iq + 1],
joint_q[iq + 2],
joint_qd[iqd + 0],
joint_qd[iqd + 1],
joint_qd[iqd + 2],
)
X_j = wp.transform(pos, rot)
v_j = wp.spatial_vector(vel_w, vel_v)
# transform from world to joint anchor frame at child body
X_wcj = X_wpj * X_j
# transform from world to child body frame
X_wc = X_wcj * wp.transform_inverse(X_cj)
# transform velocity across the joint to world space
angular_vel = wp.transform_vector(X_wpj, wp.spatial_top(v_j))
linear_vel = wp.transform_vector(X_wpj, wp.spatial_bottom(v_j))
v_wc = v_wpj + wp.spatial_vector(angular_vel, linear_vel)
body_q[child] = X_wc
body_qd[child] = v_wc
# updates state body information based on joint coordinates
def eval_fk(model, joint_q, joint_qd, mask, state):
"""
Evaluates the model's forward kinematics given the joint coordinates and updates the state's body information (:attr:`State.body_q` and :attr:`State.body_qd`).
Args:
model (Model): The model to evaluate.
joint_q (array): Generalized joint position coordinates, shape [joint_coord_count], float
joint_qd (array): Generalized joint velocity coordinates, shape [joint_dof_count], float
mask (array): The mask to use to enable / disable FK for an articulation. If None then treat all as enabled, shape [articulation_count], int
state (State): The state to update.
"""
wp.launch(
kernel=eval_articulation_fk,
dim=model.articulation_count,
inputs=[
model.articulation_start,
mask,
joint_q,
joint_qd,
model.joint_q_start,
model.joint_qd_start,
model.joint_type,
model.joint_parent,
model.joint_child,
model.joint_X_p,
model.joint_X_c,
model.joint_axis,
model.joint_axis_start,
model.joint_axis_dim,
model.body_com,
],
outputs=[
state.body_q,
state.body_qd,
],
device=model.device,
)
@wp.func
def reconstruct_angular_q_qd(q_pc: wp.quat, w_err: wp.vec3, X_wp: wp.transform, axis: wp.vec3):
"""
Reconstructs the angular joint coordinates and velocities given the relative rotation and angular velocity
between a parent and child body.
Args:
q_pc (quat): The relative rotation between the parent and child body.
w_err (vec3): The angular velocity between the parent and child body.
X_wp (transform): The parent body's transform in world space.
axis (vec3): The joint axis in the frame of the parent body.
Returns:
q (float): The joint position coordinate.
qd (float): The joint velocity coordinate.
"""
axis_p = wp.transform_vector(X_wp, axis)
twist = quat_twist(axis, q_pc)
q = wp.acos(twist[3]) * 2.0 * wp.sign(wp.dot(axis, wp.vec3(twist[0], twist[1], twist[2])))
qd = wp.dot(w_err, axis_p)
return q, qd
@wp.kernel
def eval_articulation_ik(
body_q: wp.array(dtype=wp.transform),
body_qd: wp.array(dtype=wp.spatial_vector),
body_com: wp.array(dtype=wp.vec3),
joint_type: wp.array(dtype=int),
joint_parent: wp.array(dtype=int),
joint_child: wp.array(dtype=int),
joint_X_p: wp.array(dtype=wp.transform),
joint_X_c: wp.array(dtype=wp.transform),
joint_axis: wp.array(dtype=wp.vec3),
joint_axis_start: wp.array(dtype=int),
joint_axis_dim: wp.array(dtype=int, ndim=2),
joint_q_start: wp.array(dtype=int),
joint_qd_start: wp.array(dtype=int),
joint_q: wp.array(dtype=float),
joint_qd: wp.array(dtype=float),
):
tid = wp.tid()
parent = joint_parent[tid]
child = joint_child[tid]
X_pj = joint_X_p[tid]
X_cj = joint_X_c[tid]
w_p = wp.vec3()
v_p = wp.vec3()
v_wp = wp.spatial_vector()
# parent anchor frame in world space
X_wpj = X_pj
if parent >= 0:
X_wp = body_q[parent]
X_wpj = X_wp * X_pj
r_p = wp.transform_get_translation(X_wpj) - wp.transform_point(X_wp, body_com[parent])
v_wp = body_qd[parent]
w_p = wp.spatial_top(v_wp)
v_p = wp.spatial_bottom(v_wp) + wp.cross(w_p, r_p)
# child transform and moment arm
X_wc = body_q[child]
X_wcj = X_wc * X_cj
v_wc = body_qd[child]
w_c = wp.spatial_top(v_wc)
v_c = wp.spatial_bottom(v_wc)
# joint properties
type = joint_type[tid]
# compute position and orientation differences between anchor frames
x_p = wp.transform_get_translation(X_wpj)
x_c = wp.transform_get_translation(X_wcj)
q_p = wp.transform_get_rotation(X_wpj)
q_c = wp.transform_get_rotation(X_wcj)
x_err = x_c - x_p
v_err = v_c - v_p
w_err = w_c - w_p
q_start = joint_q_start[tid]
qd_start = joint_qd_start[tid]
axis_start = joint_axis_start[tid]
lin_axis_count = joint_axis_dim[tid, 0]
ang_axis_count = joint_axis_dim[tid, 1]
if type == wp.sim.JOINT_PRISMATIC:
axis = joint_axis[axis_start]
# world space joint axis
axis_p = wp.quat_rotate(q_p, axis)
# evaluate joint coordinates
q = wp.dot(x_err, axis_p)
qd = wp.dot(v_err, axis_p)
joint_q[q_start] = q
joint_qd[qd_start] = qd
return
if type == wp.sim.JOINT_REVOLUTE:
axis = joint_axis[axis_start]
q_pc = wp.quat_inverse(q_p) * q_c
q, qd = reconstruct_angular_q_qd(q_pc, w_err, X_wpj, axis)
joint_q[q_start] = q
joint_qd[qd_start] = qd
return
if type == wp.sim.JOINT_BALL:
q_pc = wp.quat_inverse(q_p) * q_c
joint_q[q_start + 0] = q_pc[0]
joint_q[q_start + 1] = q_pc[1]
joint_q[q_start + 2] = q_pc[2]
joint_q[q_start + 3] = q_pc[3]
ang_vel = wp.transform_vector(wp.transform_inverse(X_wpj), w_err)
joint_qd[qd_start + 0] = ang_vel[0]
joint_qd[qd_start + 1] = ang_vel[1]
joint_qd[qd_start + 2] = ang_vel[2]
return
if type == wp.sim.JOINT_FIXED:
return
if type == wp.sim.JOINT_FREE or type == wp.sim.JOINT_DISTANCE:
q_pc = wp.quat_inverse(q_p) * q_c
x_err_c = wp.quat_rotate_inv(q_p, x_err)
v_err_c = wp.quat_rotate_inv(q_p, v_err)
w_err_c = wp.quat_rotate_inv(q_p, w_err)
joint_q[q_start + 0] = x_err_c[0]
joint_q[q_start + 1] = x_err_c[1]
joint_q[q_start + 2] = x_err_c[2]
joint_q[q_start + 3] = q_pc[0]
joint_q[q_start + 4] = q_pc[1]
joint_q[q_start + 5] = q_pc[2]
joint_q[q_start + 6] = q_pc[3]
joint_qd[qd_start + 0] = w_err_c[0]
joint_qd[qd_start + 1] = w_err_c[1]
joint_qd[qd_start + 2] = w_err_c[2]
joint_qd[qd_start + 3] = v_err_c[0]
joint_qd[qd_start + 4] = v_err_c[1]
joint_qd[qd_start + 5] = v_err_c[2]
return
if type == wp.sim.JOINT_COMPOUND:
axis_0 = joint_axis[axis_start + 0]
axis_1 = joint_axis[axis_start + 1]
axis_2 = joint_axis[axis_start + 2]
qs, qds = invert_3d_rotational_dofs(axis_0, axis_1, axis_2, q_p, q_c, w_err)
joint_q[q_start + 0] = qs[0]
joint_q[q_start + 1] = qs[1]
joint_q[q_start + 2] = qs[2]
joint_qd[qd_start + 0] = qds[0]
joint_qd[qd_start + 1] = qds[1]
joint_qd[qd_start + 2] = qds[2]
return
if type == wp.sim.JOINT_UNIVERSAL:
axis_0 = joint_axis[axis_start + 0]
axis_1 = joint_axis[axis_start + 1]
qs2, qds2 = invert_2d_rotational_dofs(axis_0, axis_1, q_p, q_c, w_err)
joint_q[q_start + 0] = qs2[0]
joint_q[q_start + 1] = qs2[1]
joint_qd[qd_start + 0] = qds2[0]
joint_qd[qd_start + 1] = qds2[1]
return
if type == wp.sim.JOINT_D6:
x_err_c = wp.quat_rotate_inv(q_p, x_err)
v_err_c = wp.quat_rotate_inv(q_p, v_err)
if lin_axis_count > 0:
axis = joint_axis[axis_start + 0]
joint_q[q_start + 0] = wp.dot(x_err_c, axis)
joint_qd[qd_start + 0] = wp.dot(v_err_c, axis)
if lin_axis_count > 1:
axis = joint_axis[axis_start + 1]
joint_q[q_start + 1] = wp.dot(x_err_c, axis)
joint_qd[qd_start + 1] = wp.dot(v_err_c, axis)
if lin_axis_count > 2:
axis = joint_axis[axis_start + 2]
joint_q[q_start + 2] = wp.dot(x_err_c, axis)
joint_qd[qd_start + 2] = wp.dot(v_err_c, axis)
if ang_axis_count == 1:
axis = joint_axis[axis_start]
q_pc = wp.quat_inverse(q_p) * q_c
q, qd = reconstruct_angular_q_qd(q_pc, w_err, X_wpj, joint_axis[axis_start + lin_axis_count])
joint_q[q_start + lin_axis_count] = q
joint_qd[qd_start + lin_axis_count] = qd
if ang_axis_count == 2:
axis_0 = joint_axis[axis_start + lin_axis_count + 0]
axis_1 = joint_axis[axis_start + lin_axis_count + 1]
qs2, qds2 = invert_2d_rotational_dofs(axis_0, axis_1, q_p, q_c, w_err)
joint_q[q_start + lin_axis_count + 0] = qs2[0]
joint_q[q_start + lin_axis_count + 1] = qs2[1]
joint_qd[qd_start + lin_axis_count + 0] = qds2[0]
joint_qd[qd_start + lin_axis_count + 1] = qds2[1]
if ang_axis_count == 3:
axis_0 = joint_axis[axis_start + lin_axis_count + 0]
axis_1 = joint_axis[axis_start + lin_axis_count + 1]
axis_2 = joint_axis[axis_start + lin_axis_count + 2]
qs3, qds3 = invert_3d_rotational_dofs(axis_0, axis_1, axis_2, q_p, q_c, w_err)
joint_q[q_start + lin_axis_count + 0] = qs3[0]
joint_q[q_start + lin_axis_count + 1] = qs3[1]
joint_q[q_start + lin_axis_count + 2] = qs3[2]
joint_qd[qd_start + lin_axis_count + 0] = qds3[0]
joint_qd[qd_start + lin_axis_count + 1] = qds3[1]
joint_qd[qd_start + lin_axis_count + 2] = qds3[2]
return
# given maximal coordinate model computes ik (closest point projection)
def eval_ik(model, state, joint_q, joint_qd):
"""
Evaluates the model's inverse kinematics given the state's body information (:attr:`State.body_q` and :attr:`State.body_qd`) and updates the generalized joint coordinates `joint_q` and `joint_qd`.
Args:
model (Model): The model to evaluate.
state (State): The state with the body's maximal coordinates (positions :attr:`State.body_q` and velocities :attr:`State.body_qd`) to use.
joint_q (array): Generalized joint position coordinates, shape [joint_coord_count], float
joint_qd (array): Generalized joint velocity coordinates, shape [joint_dof_count], float
"""
wp.launch(
kernel=eval_articulation_ik,
dim=model.joint_count,
inputs=[
state.body_q,
state.body_qd,
model.body_com,
model.joint_type,
model.joint_parent,
model.joint_child,
model.joint_X_p,
model.joint_X_c,
model.joint_axis,
model.joint_axis_start,
model.joint_axis_dim,
model.joint_q_start,
model.joint_qd_start,
],
outputs=[joint_q, joint_qd],
device=model.device,
)
|