File size: 52,995 Bytes
406662d | 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 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 792 793 794 795 796 797 798 799 800 801 802 803 804 805 806 807 808 809 810 811 812 813 814 815 816 817 818 819 820 821 822 823 824 825 826 827 828 829 830 831 832 833 834 835 836 837 838 839 840 841 842 843 844 845 846 847 848 849 850 851 852 853 854 855 856 857 858 859 860 861 862 863 864 865 866 867 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 899 900 901 902 903 904 905 906 907 908 909 910 911 912 913 914 915 916 917 918 919 920 921 922 923 924 925 926 927 928 929 930 931 932 933 934 935 936 937 938 939 940 941 942 943 944 945 946 947 948 949 950 951 952 953 954 955 956 957 958 959 960 961 962 963 964 965 966 967 968 969 970 971 972 973 974 975 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 1044 1045 1046 1047 1048 1049 1050 1051 1052 1053 1054 1055 1056 1057 1058 1059 1060 1061 1062 1063 1064 1065 1066 1067 1068 1069 1070 1071 1072 1073 1074 1075 1076 1077 1078 1079 1080 1081 1082 1083 1084 1085 1086 1087 1088 1089 1090 1091 1092 1093 1094 1095 1096 1097 1098 1099 1100 1101 1102 1103 1104 1105 1106 1107 1108 1109 1110 1111 1112 1113 1114 1115 1116 1117 1118 1119 1120 1121 1122 1123 1124 1125 1126 1127 1128 1129 1130 1131 1132 1133 1134 1135 1136 1137 1138 1139 1140 1141 1142 1143 1144 1145 1146 1147 1148 1149 1150 1151 1152 1153 1154 1155 1156 1157 1158 1159 1160 1161 1162 1163 1164 1165 1166 1167 1168 1169 1170 1171 1172 1173 1174 1175 1176 1177 1178 1179 1180 1181 1182 1183 1184 1185 1186 1187 1188 1189 1190 1191 1192 1193 1194 1195 1196 1197 1198 1199 1200 1201 1202 1203 1204 1205 1206 1207 1208 1209 1210 1211 1212 1213 1214 1215 1216 1217 1218 1219 1220 1221 1222 1223 1224 1225 1226 1227 1228 1229 1230 1231 1232 1233 1234 1235 1236 1237 1238 1239 1240 1241 1242 1243 1244 1245 1246 1247 1248 1249 1250 1251 1252 1253 1254 1255 1256 1257 1258 1259 1260 1261 1262 1263 1264 1265 1266 1267 1268 1269 1270 1271 1272 1273 1274 1275 1276 1277 1278 1279 1280 1281 1282 1283 1284 1285 1286 1287 1288 1289 1290 1291 1292 1293 1294 1295 1296 1297 1298 1299 1300 1301 1302 1303 1304 1305 1306 1307 1308 1309 1310 1311 1312 1313 1314 1315 1316 1317 1318 1319 1320 1321 1322 1323 1324 1325 1326 1327 1328 1329 1330 1331 1332 1333 1334 1335 1336 1337 1338 1339 1340 1341 1342 1343 1344 1345 1346 1347 1348 1349 1350 1351 1352 1353 1354 1355 1356 1357 1358 1359 1360 1361 1362 1363 1364 1365 1366 1367 1368 1369 1370 1371 1372 1373 1374 1375 1376 1377 1378 1379 1380 1381 1382 1383 1384 1385 1386 1387 1388 1389 1390 1391 1392 1393 1394 1395 1396 1397 1398 1399 1400 1401 1402 1403 1404 1405 1406 1407 1408 1409 1410 1411 1412 1413 1414 1415 1416 1417 1418 1419 1420 1421 1422 1423 1424 1425 1426 1427 1428 1429 1430 1431 1432 1433 1434 1435 1436 1437 1438 1439 1440 1441 1442 1443 1444 1445 1446 1447 1448 1449 1450 1451 1452 1453 1454 1455 1456 1457 1458 1459 1460 1461 1462 1463 1464 1465 1466 1467 1468 1469 1470 1471 1472 1473 1474 1475 1476 1477 1478 1479 1480 1481 1482 1483 1484 1485 1486 1487 1488 1489 1490 1491 1492 1493 1494 1495 1496 1497 1498 1499 1500 1501 1502 1503 1504 1505 1506 1507 1508 1509 1510 1511 1512 1513 1514 1515 1516 1517 1518 1519 1520 1521 1522 1523 1524 1525 1526 1527 1528 1529 1530 1531 1532 1533 1534 1535 1536 1537 1538 1539 1540 1541 1542 1543 1544 1545 1546 1547 1548 1549 1550 1551 1552 1553 1554 1555 1556 1557 1558 1559 1560 1561 1562 1563 1564 1565 1566 1567 1568 1569 1570 1571 1572 1573 1574 1575 1576 1577 1578 1579 1580 1581 1582 1583 1584 1585 1586 1587 1588 1589 1590 1591 1592 1593 1594 1595 1596 1597 1598 1599 1600 1601 1602 1603 1604 1605 1606 1607 1608 1609 1610 1611 1612 1613 1614 1615 1616 1617 1618 1619 1620 1621 1622 1623 1624 1625 1626 1627 1628 1629 1630 1631 1632 1633 1634 1635 1636 1637 1638 1639 1640 1641 1642 1643 1644 1645 1646 1647 1648 1649 1650 1651 1652 1653 1654 1655 1656 1657 1658 1659 1660 1661 1662 1663 1664 1665 1666 1667 1668 1669 1670 1671 1672 1673 | # Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md).
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
"""Launch Isaac Sim Simulator first."""
from isaaclab.app import AppLauncher
# launch omniverse app
simulation_app = AppLauncher(headless=True).app
"""Rest everything follows."""
import pytest
import torch
from isaacsim.core.cloner import GridCloner
import isaaclab.sim as sim_utils
from isaaclab.assets import Articulation
from isaaclab.controllers import OperationalSpaceController, OperationalSpaceControllerCfg
from isaaclab.markers import VisualizationMarkers
from isaaclab.markers.config import FRAME_MARKER_CFG
from isaaclab.sensors import ContactSensor, ContactSensorCfg
from isaaclab.utils.math import (
apply_delta_pose,
combine_frame_transforms,
compute_pose_error,
matrix_from_quat,
quat_apply_inverse,
quat_inv,
subtract_frame_transforms,
)
##
# Pre-defined configs
##
from isaaclab_assets import FRANKA_PANDA_CFG # isort:skip
@pytest.fixture
def sim():
"""Create a simulation context for testing."""
# Wait for spawning
stage = sim_utils.create_new_stage()
# Constants
num_envs = 16
# Load kit helper
sim_cfg = sim_utils.SimulationCfg(dt=0.01)
sim = sim_utils.SimulationContext(sim_cfg)
# TODO: Remove this once we have a better way to handle this.
sim._app_control_on_stop_handle = None
# Create a ground plane
cfg = sim_utils.GroundPlaneCfg()
cfg.func("/World/GroundPlane", cfg)
# Markers
frame_marker_cfg = FRAME_MARKER_CFG.copy()
frame_marker_cfg.markers["frame"].scale = (0.1, 0.1, 0.1)
ee_marker = VisualizationMarkers(frame_marker_cfg.replace(prim_path="/Visuals/ee_current"))
goal_marker = VisualizationMarkers(frame_marker_cfg.replace(prim_path="/Visuals/ee_goal"))
light_cfg = sim_utils.DistantLightCfg(intensity=5.0, exposure=10.0)
light_cfg.func(
"/Light",
light_cfg,
translation=[0, 0, 1],
)
# Create interface to clone the scene
cloner = GridCloner(spacing=2.0)
cloner.define_base_env("/World/envs")
env_prim_paths = cloner.generate_paths("/World/envs/env", num_envs)
# create source prim
stage.DefinePrim(env_prim_paths[0], "Xform")
# clone the env xform
cloner.clone(
source_prim_path=env_prim_paths[0],
prim_paths=env_prim_paths,
replicate_physics=True,
)
robot_cfg = FRANKA_PANDA_CFG.replace(prim_path="/World/envs/env_.*/Robot")
robot_cfg.actuators["panda_shoulder"].stiffness = 0.0
robot_cfg.actuators["panda_shoulder"].damping = 0.0
robot_cfg.actuators["panda_forearm"].stiffness = 0.0
robot_cfg.actuators["panda_forearm"].damping = 0.0
robot_cfg.spawn.rigid_props.disable_gravity = True
# Define the ContactSensor
contact_forces = None
# Define the target sets
ee_goal_abs_pos_set_b = torch.tensor(
[
[0.5, 0.5, 0.7],
[0.5, -0.4, 0.6],
[0.5, 0, 0.5],
],
device=sim.device,
)
ee_goal_abs_quad_set_b = torch.tensor(
[
[0.707, 0.0, 0.707, 0.0],
[0.707, 0.707, 0.0, 0.0],
[0.0, 1.0, 0.0, 0.0],
],
device=sim.device,
)
ee_goal_rel_pos_set = torch.tensor(
[
[0.2, 0.0, 0.0],
[0.2, 0.2, 0.0],
[0.2, 0.2, -0.2],
],
device=sim.device,
)
ee_goal_rel_axisangle_set = torch.tensor(
[
[0.0, torch.pi / 2, 0.0], # for [0.707, 0, 0.707, 0]
[torch.pi / 2, 0.0, 0.0], # for [0.707, 0.707, 0, 0]
[torch.pi / 2, torch.pi / 2, 0.0], # for [0.0, 1.0, 0, 0]
],
device=sim.device,
)
ee_goal_abs_wrench_set_b = torch.tensor(
[
[0.0, 0.0, 10.0, 0.0, -1.0, 0.0],
[0.0, 10.0, 0.0, 0.0, 0.0, 0.0],
[10.0, 0.0, 0.0, 0.0, 0.0, 0.0],
],
device=sim.device,
)
kp_set = torch.tensor(
[
[200.0, 200.0, 200.0, 200.0, 200.0, 200.0],
[240.0, 240.0, 240.0, 240.0, 240.0, 240.0],
[160.0, 160.0, 160.0, 160.0, 160.0, 160.0],
],
device=sim.device,
)
d_ratio_set = torch.tensor(
[
[1.0, 1.0, 1.0, 1.0, 1.0, 1.0],
[1.1, 1.1, 1.1, 1.1, 1.1, 1.1],
[0.9, 0.9, 0.9, 0.9, 0.9, 0.9],
],
device=sim.device,
)
ee_goal_hybrid_set_b = torch.tensor(
[
[0.6, 0.2, 0.5, 0.0, 0.707, 0.0, 0.707, 10.0, 0.0, 0.0, 0.0, 0.0, 0.0],
[0.6, -0.29, 0.6, 0.0, 0.707, 0.0, 0.707, 10.0, 0.0, 0.0, 0.0, 0.0, 0.0],
[0.6, 0.1, 0.8, 0.0, 0.5774, 0.0, 0.8165, 4.0, 0.0, 0.0, 0.0, 0.0, 0.0],
],
device=sim.device,
)
ee_goal_pose_set_tilted_b = torch.tensor(
[
[0.6, 0.15, 0.3, 0.0, 0.92387953, 0.0, 0.38268343],
[0.6, -0.3, 0.3, 0.0, 0.92387953, 0.0, 0.38268343],
[0.8, 0.0, 0.5, 0.0, 0.92387953, 0.0, 0.38268343],
],
device=sim.device,
)
ee_goal_wrench_set_tilted_task = torch.tensor(
[
[0.0, 0.0, 10.0, 0.0, 0.0, 0.0],
[0.0, 0.0, 10.0, 0.0, 0.0, 0.0],
[0.0, 0.0, 10.0, 0.0, 0.0, 0.0],
],
device=sim.device,
)
# Define goals for the arm [xyz]
target_abs_pos_set_b = ee_goal_abs_pos_set_b.clone()
# Define goals for the arm [xyz + quat_wxyz]
target_abs_pose_set_b = torch.cat([ee_goal_abs_pos_set_b, ee_goal_abs_quad_set_b], dim=-1)
# Define goals for the arm [xyz]
target_rel_pos_set = ee_goal_rel_pos_set.clone()
# Define goals for the arm [xyz + axis-angle]
target_rel_pose_set_b = torch.cat([ee_goal_rel_pos_set, ee_goal_rel_axisangle_set], dim=-1)
# Define goals for the arm [force_xyz + torque_xyz]
target_abs_wrench_set = ee_goal_abs_wrench_set_b.clone()
# Define goals for the arm [xyz + quat_wxyz] and variable kp [kp_xyz + kp_rot_xyz]
target_abs_pose_variable_kp_set = torch.cat([target_abs_pose_set_b, kp_set], dim=-1)
# Define goals for the arm [xyz + quat_wxyz] and the variable imp. [kp_xyz + kp_rot_xyz + d_xyz + d_rot_xyz]
target_abs_pose_variable_set = torch.cat([target_abs_pose_set_b, kp_set, d_ratio_set], dim=-1)
# Define goals for the arm pose [xyz + quat_wxyz] and wrench [force_xyz + torque_xyz]
target_hybrid_set_b = ee_goal_hybrid_set_b.clone()
# Define goals for the arm pose, and wrench, and kp
target_hybrid_variable_kp_set = torch.cat([target_hybrid_set_b, kp_set], dim=-1)
# Define goals for the arm pose [xyz + quat_wxyz] in root and and wrench [force_xyz + torque_xyz] in task frame
target_hybrid_set_tilted = torch.cat([ee_goal_pose_set_tilted_b, ee_goal_wrench_set_tilted_task], dim=-1)
# Reference frame for targets
frame = "root"
yield (
sim,
num_envs,
robot_cfg,
ee_marker,
goal_marker,
contact_forces,
target_abs_pos_set_b,
target_abs_pose_set_b,
target_rel_pos_set,
target_rel_pose_set_b,
target_abs_wrench_set,
target_abs_pose_variable_kp_set,
target_abs_pose_variable_set,
target_hybrid_set_b,
target_hybrid_variable_kp_set,
target_hybrid_set_tilted,
frame,
)
# Cleanup
sim.stop()
sim.clear()
sim.clear_all_callbacks()
sim.clear_instance()
@pytest.mark.isaacsim_ci
def test_franka_pose_abs_without_inertial_decoupling(sim):
"""Test absolute pose control with fixed impedance and without inertial dynamics decoupling."""
(
sim_context,
num_envs,
robot_cfg,
ee_marker,
goal_marker,
contact_forces,
_,
target_abs_pose_set_b,
_,
_,
_,
_,
_,
_,
_,
_,
frame,
) = sim
robot = Articulation(cfg=robot_cfg)
osc_cfg = OperationalSpaceControllerCfg(
target_types=["pose_abs"],
impedance_mode="fixed",
inertial_dynamics_decoupling=False,
gravity_compensation=False,
motion_stiffness_task=[400.0, 400.0, 400.0, 100.0, 100.0, 100.0],
motion_damping_ratio_task=[5.0, 5.0, 5.0, 0.001, 0.001, 0.001],
)
osc = OperationalSpaceController(osc_cfg, num_envs=num_envs, device=sim_context.device)
_run_op_space_controller(
robot,
osc,
"panda_hand",
["panda_joint.*"],
target_abs_pose_set_b,
sim_context,
num_envs,
ee_marker,
goal_marker,
contact_forces,
frame,
)
@pytest.mark.isaacsim_ci
def test_franka_pose_abs_with_partial_inertial_decoupling(sim):
"""Test absolute pose control with fixed impedance and partial inertial dynamics decoupling."""
(
sim_context,
num_envs,
robot_cfg,
ee_marker,
goal_marker,
contact_forces,
_,
target_abs_pose_set_b,
_,
_,
_,
_,
_,
_,
_,
_,
frame,
) = sim
robot = Articulation(cfg=robot_cfg)
osc_cfg = OperationalSpaceControllerCfg(
target_types=["pose_abs"],
impedance_mode="fixed",
inertial_dynamics_decoupling=True,
partial_inertial_dynamics_decoupling=True,
gravity_compensation=False,
motion_stiffness_task=1000.0,
motion_damping_ratio_task=1.0,
)
osc = OperationalSpaceController(osc_cfg, num_envs=num_envs, device=sim_context.device)
_run_op_space_controller(
robot,
osc,
"panda_hand",
["panda_joint.*"],
target_abs_pose_set_b,
sim_context,
num_envs,
ee_marker,
goal_marker,
contact_forces,
frame,
)
@pytest.mark.isaacsim_ci
def test_franka_pose_abs_fixed_impedance_with_gravity_compensation(sim):
"""Test absolute pose control with fixed impedance, gravity compensation, and inertial dynamics decoupling."""
(
sim_context,
num_envs,
robot_cfg,
ee_marker,
goal_marker,
contact_forces,
_,
target_abs_pose_set_b,
_,
_,
_,
_,
_,
_,
_,
_,
frame,
) = sim
robot_cfg.spawn.rigid_props.disable_gravity = False
robot = Articulation(cfg=robot_cfg)
osc_cfg = OperationalSpaceControllerCfg(
target_types=["pose_abs"],
impedance_mode="fixed",
inertial_dynamics_decoupling=True,
partial_inertial_dynamics_decoupling=False,
gravity_compensation=True,
motion_stiffness_task=500.0,
motion_damping_ratio_task=1.0,
)
osc = OperationalSpaceController(osc_cfg, num_envs=num_envs, device=sim_context.device)
_run_op_space_controller(
robot,
osc,
"panda_hand",
["panda_joint.*"],
target_abs_pose_set_b,
sim_context,
num_envs,
ee_marker,
goal_marker,
contact_forces,
frame,
)
@pytest.mark.isaacsim_ci
def test_franka_pose_abs(sim):
"""Test absolute pose control with fixed impedance and inertial dynamics decoupling."""
(
sim_context,
num_envs,
robot_cfg,
ee_marker,
goal_marker,
contact_forces,
_,
target_abs_pose_set_b,
_,
_,
_,
_,
_,
_,
_,
_,
frame,
) = sim
robot = Articulation(cfg=robot_cfg)
osc_cfg = OperationalSpaceControllerCfg(
target_types=["pose_abs"],
impedance_mode="fixed",
inertial_dynamics_decoupling=True,
partial_inertial_dynamics_decoupling=False,
gravity_compensation=False,
motion_stiffness_task=500.0,
motion_damping_ratio_task=1.0,
)
osc = OperationalSpaceController(osc_cfg, num_envs=num_envs, device=sim_context.device)
_run_op_space_controller(
robot,
osc,
"panda_hand",
["panda_joint.*"],
target_abs_pose_set_b,
sim_context,
num_envs,
ee_marker,
goal_marker,
contact_forces,
frame,
)
@pytest.mark.isaacsim_ci
def test_franka_pose_rel(sim):
"""Test relative pose control with fixed impedance and inertial dynamics decoupling."""
(
sim_context,
num_envs,
robot_cfg,
ee_marker,
goal_marker,
contact_forces,
_,
_,
_,
target_rel_pose_set_b,
_,
_,
_,
_,
_,
_,
frame,
) = sim
robot = Articulation(cfg=robot_cfg)
osc_cfg = OperationalSpaceControllerCfg(
target_types=["pose_rel"],
impedance_mode="fixed",
inertial_dynamics_decoupling=True,
partial_inertial_dynamics_decoupling=False,
gravity_compensation=False,
motion_stiffness_task=500.0,
motion_damping_ratio_task=1.0,
)
osc = OperationalSpaceController(osc_cfg, num_envs=num_envs, device=sim_context.device)
_run_op_space_controller(
robot,
osc,
"panda_hand",
["panda_joint.*"],
target_rel_pose_set_b,
sim_context,
num_envs,
ee_marker,
goal_marker,
contact_forces,
frame,
)
@pytest.mark.isaacsim_ci
def test_franka_pose_abs_variable_impedance(sim):
"""Test absolute pose control with variable impedance and inertial dynamics decoupling."""
(
sim_context,
num_envs,
robot_cfg,
ee_marker,
goal_marker,
contact_forces,
_,
_,
_,
_,
_,
_,
target_abs_pose_variable_set,
_,
_,
_,
frame,
) = sim
robot = Articulation(cfg=robot_cfg)
osc_cfg = OperationalSpaceControllerCfg(
target_types=["pose_abs"],
impedance_mode="variable",
inertial_dynamics_decoupling=True,
partial_inertial_dynamics_decoupling=False,
gravity_compensation=False,
)
osc = OperationalSpaceController(osc_cfg, num_envs=num_envs, device=sim_context.device)
_run_op_space_controller(
robot,
osc,
"panda_hand",
["panda_joint.*"],
target_abs_pose_variable_set,
sim_context,
num_envs,
ee_marker,
goal_marker,
contact_forces,
frame,
)
@pytest.mark.isaacsim_ci
def test_franka_wrench_abs_open_loop(sim):
"""Test open loop absolute force control."""
(
sim_context,
num_envs,
robot_cfg,
ee_marker,
goal_marker,
contact_forces,
_,
_,
_,
_,
target_abs_wrench_set,
_,
_,
_,
_,
_,
frame,
) = sim
robot = Articulation(cfg=robot_cfg)
obstacle_spawn_cfg = sim_utils.CuboidCfg(
size=(0.7, 0.7, 0.01),
collision_props=sim_utils.CollisionPropertiesCfg(),
visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(1.0, 0.0, 0.0), opacity=0.1),
rigid_props=sim_utils.RigidBodyPropertiesCfg(kinematic_enabled=True),
activate_contact_sensors=True,
)
obstacle_spawn_cfg.func(
"/World/envs/env_.*/obstacle1",
obstacle_spawn_cfg,
translation=(0.2, 0.0, 0.93),
orientation=(0.9848, 0.0, -0.1736, 0.0),
)
obstacle_spawn_cfg.func(
"/World/envs/env_.*/obstacle2",
obstacle_spawn_cfg,
translation=(0.2, 0.35, 0.7),
orientation=(0.707, 0.707, 0.0, 0.0),
)
obstacle_spawn_cfg.func(
"/World/envs/env_.*/obstacle3",
obstacle_spawn_cfg,
translation=(0.55, 0.0, 0.7),
orientation=(0.707, 0.0, 0.707, 0.0),
)
contact_forces_cfg = ContactSensorCfg(
prim_path="/World/envs/env_.*/obstacle.*",
update_period=0.0,
history_length=50,
debug_vis=False,
force_threshold=0.1,
)
contact_forces = ContactSensor(contact_forces_cfg)
osc_cfg = OperationalSpaceControllerCfg(
target_types=["wrench_abs"],
motion_control_axes_task=[0, 0, 0, 0, 0, 0],
contact_wrench_control_axes_task=[1, 1, 1, 1, 1, 1],
)
osc = OperationalSpaceController(osc_cfg, num_envs=num_envs, device=sim_context.device)
_run_op_space_controller(
robot,
osc,
"panda_hand",
["panda_joint.*"],
target_abs_wrench_set,
sim_context,
num_envs,
ee_marker,
goal_marker,
contact_forces,
frame,
)
@pytest.mark.isaacsim_ci
def test_franka_wrench_abs_closed_loop(sim):
"""Test closed loop absolute force control."""
(
sim_context,
num_envs,
robot_cfg,
ee_marker,
goal_marker,
contact_forces,
_,
_,
_,
_,
target_abs_wrench_set,
_,
_,
_,
_,
_,
frame,
) = sim
robot = Articulation(cfg=robot_cfg)
obstacle_spawn_cfg = sim_utils.CuboidCfg(
size=(0.7, 0.7, 0.01),
collision_props=sim_utils.CollisionPropertiesCfg(),
visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(1.0, 0.0, 0.0), opacity=0.1),
rigid_props=sim_utils.RigidBodyPropertiesCfg(kinematic_enabled=True),
activate_contact_sensors=True,
)
obstacle_spawn_cfg.func(
"/World/envs/env_.*/obstacle1",
obstacle_spawn_cfg,
translation=(0.2, 0.0, 0.93),
orientation=(0.9848, 0.0, -0.1736, 0.0),
)
obstacle_spawn_cfg.func(
"/World/envs/env_.*/obstacle2",
obstacle_spawn_cfg,
translation=(0.2, 0.35, 0.7),
orientation=(0.707, 0.707, 0.0, 0.0),
)
obstacle_spawn_cfg.func(
"/World/envs/env_.*/obstacle3",
obstacle_spawn_cfg,
translation=(0.55, 0.0, 0.7),
orientation=(0.707, 0.0, 0.707, 0.0),
)
contact_forces_cfg = ContactSensorCfg(
prim_path="/World/envs/env_.*/obstacle.*",
update_period=0.0,
history_length=2,
debug_vis=False,
force_threshold=0.1,
)
contact_forces = ContactSensor(contact_forces_cfg)
osc_cfg = OperationalSpaceControllerCfg(
target_types=["wrench_abs"],
contact_wrench_stiffness_task=[
0.2,
0.2,
0.2,
0.0,
0.0,
0.0,
], # Zero torque feedback as we cannot contact torque
motion_control_axes_task=[0, 0, 0, 0, 0, 0],
contact_wrench_control_axes_task=[1, 1, 1, 1, 1, 1],
)
osc = OperationalSpaceController(osc_cfg, num_envs=num_envs, device=sim_context.device)
_run_op_space_controller(
robot,
osc,
"panda_hand",
["panda_joint.*"],
target_abs_wrench_set,
sim_context,
num_envs,
ee_marker,
goal_marker,
contact_forces,
frame,
)
@pytest.mark.isaacsim_ci
def test_franka_hybrid_decoupled_motion(sim):
"""Test hybrid control with fixed impedance and partial inertial dynamics decoupling."""
(
sim_context,
num_envs,
robot_cfg,
ee_marker,
goal_marker,
contact_forces,
_,
_,
_,
_,
_,
_,
_,
target_hybrid_set_b,
_,
_,
frame,
) = sim
robot = Articulation(cfg=robot_cfg)
obstacle_spawn_cfg = sim_utils.CuboidCfg(
size=(1.0, 1.0, 0.01),
collision_props=sim_utils.CollisionPropertiesCfg(),
visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(1.0, 0.0, 0.0), opacity=0.1),
rigid_props=sim_utils.RigidBodyPropertiesCfg(kinematic_enabled=True),
activate_contact_sensors=True,
)
obstacle_spawn_cfg.func(
"/World/envs/env_.*/obstacle1",
obstacle_spawn_cfg,
translation=(target_hybrid_set_b[0, 0] + 0.05, 0.0, 0.7),
orientation=(0.707, 0.0, 0.707, 0.0),
)
contact_forces_cfg = ContactSensorCfg(
prim_path="/World/envs/env_.*/obstacle.*",
update_period=0.0,
history_length=2,
debug_vis=False,
force_threshold=0.1,
)
contact_forces = ContactSensor(contact_forces_cfg)
osc_cfg = OperationalSpaceControllerCfg(
target_types=["pose_abs", "wrench_abs"],
impedance_mode="fixed",
inertial_dynamics_decoupling=True,
partial_inertial_dynamics_decoupling=True,
gravity_compensation=False,
motion_stiffness_task=300.0,
motion_damping_ratio_task=1.0,
contact_wrench_stiffness_task=[0.1, 0.0, 0.0, 0.0, 0.0, 0.0],
motion_control_axes_task=[0, 1, 1, 1, 1, 1],
contact_wrench_control_axes_task=[1, 0, 0, 0, 0, 0],
)
osc = OperationalSpaceController(osc_cfg, num_envs=num_envs, device=sim_context.device)
_run_op_space_controller(
robot,
osc,
"panda_leftfinger",
["panda_joint.*"],
target_hybrid_set_b,
sim_context,
num_envs,
ee_marker,
goal_marker,
contact_forces,
frame,
)
@pytest.mark.isaacsim_ci
def test_franka_hybrid_variable_kp_impedance(sim):
"""Test hybrid control with variable kp impedance and inertial dynamics decoupling."""
(
sim_context,
num_envs,
robot_cfg,
ee_marker,
goal_marker,
contact_forces,
_,
_,
_,
_,
_,
_,
_,
target_hybrid_set_b,
target_hybrid_variable_kp_set,
_,
frame,
) = sim
robot = Articulation(cfg=robot_cfg)
obstacle_spawn_cfg = sim_utils.CuboidCfg(
size=(1.0, 1.0, 0.01),
collision_props=sim_utils.CollisionPropertiesCfg(),
visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(1.0, 0.0, 0.0), opacity=0.1),
rigid_props=sim_utils.RigidBodyPropertiesCfg(kinematic_enabled=True),
activate_contact_sensors=True,
)
obstacle_spawn_cfg.func(
"/World/envs/env_.*/obstacle1",
obstacle_spawn_cfg,
translation=(target_hybrid_set_b[0, 0] + 0.05, 0.0, 0.7),
orientation=(0.707, 0.0, 0.707, 0.0),
)
contact_forces_cfg = ContactSensorCfg(
prim_path="/World/envs/env_.*/obstacle.*",
update_period=0.0,
history_length=2,
debug_vis=False,
force_threshold=0.1,
)
contact_forces = ContactSensor(contact_forces_cfg)
osc_cfg = OperationalSpaceControllerCfg(
target_types=["pose_abs", "wrench_abs"],
impedance_mode="variable_kp",
inertial_dynamics_decoupling=True,
partial_inertial_dynamics_decoupling=False,
gravity_compensation=False,
motion_damping_ratio_task=0.8,
contact_wrench_stiffness_task=[0.1, 0.0, 0.0, 0.0, 0.0, 0.0],
motion_control_axes_task=[0, 1, 1, 1, 1, 1],
contact_wrench_control_axes_task=[1, 0, 0, 0, 0, 0],
)
osc = OperationalSpaceController(osc_cfg, num_envs=num_envs, device=sim_context.device)
_run_op_space_controller(
robot,
osc,
"panda_leftfinger",
["panda_joint.*"],
target_hybrid_variable_kp_set,
sim_context,
num_envs,
ee_marker,
goal_marker,
contact_forces,
frame,
)
@pytest.mark.isaacsim_ci
def test_franka_taskframe_pose_abs(sim):
"""Test absolute pose control in task frame with fixed impedance and inertial dynamics decoupling."""
(
sim_context,
num_envs,
robot_cfg,
ee_marker,
goal_marker,
contact_forces,
_,
target_abs_pose_set_b,
_,
_,
_,
_,
_,
_,
_,
_,
frame,
) = sim
robot = Articulation(cfg=robot_cfg)
frame = "task"
osc_cfg = OperationalSpaceControllerCfg(
target_types=["pose_abs"],
impedance_mode="fixed",
inertial_dynamics_decoupling=True,
partial_inertial_dynamics_decoupling=False,
gravity_compensation=False,
motion_stiffness_task=500.0,
motion_damping_ratio_task=1.0,
)
osc = OperationalSpaceController(osc_cfg, num_envs=num_envs, device=sim_context.device)
_run_op_space_controller(
robot,
osc,
"panda_hand",
["panda_joint.*"],
target_abs_pose_set_b,
sim_context,
num_envs,
ee_marker,
goal_marker,
contact_forces,
frame,
)
@pytest.mark.isaacsim_ci
def test_franka_taskframe_pose_rel(sim):
"""Test relative pose control in task frame with fixed impedance and inertial dynamics decoupling."""
(
sim_context,
num_envs,
robot_cfg,
ee_marker,
goal_marker,
contact_forces,
_,
_,
_,
target_rel_pose_set_b,
_,
_,
_,
_,
_,
_,
frame,
) = sim
robot = Articulation(cfg=robot_cfg)
frame = "task"
osc_cfg = OperationalSpaceControllerCfg(
target_types=["pose_rel"],
impedance_mode="fixed",
inertial_dynamics_decoupling=True,
partial_inertial_dynamics_decoupling=False,
gravity_compensation=False,
motion_stiffness_task=500.0,
motion_damping_ratio_task=1.0,
)
osc = OperationalSpaceController(osc_cfg, num_envs=num_envs, device=sim_context.device)
_run_op_space_controller(
robot,
osc,
"panda_hand",
["panda_joint.*"],
target_rel_pose_set_b,
sim_context,
num_envs,
ee_marker,
goal_marker,
contact_forces,
frame,
)
@pytest.mark.isaacsim_ci
def test_franka_taskframe_hybrid(sim):
"""Test hybrid control in task frame with fixed impedance and inertial dynamics decoupling."""
(
sim_context,
num_envs,
robot_cfg,
ee_marker,
goal_marker,
contact_forces,
_,
_,
_,
_,
_,
_,
_,
_,
_,
target_hybrid_set_tilted,
frame,
) = sim
robot = Articulation(cfg=robot_cfg)
frame = "task"
obstacle_spawn_cfg = sim_utils.CuboidCfg(
size=(2.0, 1.5, 0.01),
collision_props=sim_utils.CollisionPropertiesCfg(),
visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(1.0, 0.0, 0.0), opacity=0.1),
rigid_props=sim_utils.RigidBodyPropertiesCfg(kinematic_enabled=True),
activate_contact_sensors=True,
)
obstacle_spawn_cfg.func(
"/World/envs/env_.*/obstacle1",
obstacle_spawn_cfg,
translation=(target_hybrid_set_tilted[0, 0] + 0.085, 0.0, 0.3),
orientation=(0.9238795325, 0.0, -0.3826834324, 0.0),
)
contact_forces_cfg = ContactSensorCfg(
prim_path="/World/envs/env_.*/obstacle.*",
update_period=0.0,
history_length=2,
debug_vis=False,
force_threshold=0.1,
)
contact_forces = ContactSensor(contact_forces_cfg)
osc_cfg = OperationalSpaceControllerCfg(
target_types=["pose_abs", "wrench_abs"],
impedance_mode="fixed",
inertial_dynamics_decoupling=True,
partial_inertial_dynamics_decoupling=False,
gravity_compensation=False,
motion_stiffness_task=400.0,
motion_damping_ratio_task=1.0,
contact_wrench_stiffness_task=[0.0, 0.0, 0.1, 0.0, 0.0, 0.0],
motion_control_axes_task=[1, 1, 0, 1, 1, 1],
contact_wrench_control_axes_task=[0, 0, 1, 0, 0, 0],
)
osc = OperationalSpaceController(osc_cfg, num_envs=num_envs, device=sim_context.device)
_run_op_space_controller(
robot,
osc,
"panda_leftfinger",
["panda_joint.*"],
target_hybrid_set_tilted,
sim_context,
num_envs,
ee_marker,
goal_marker,
contact_forces,
frame,
)
@pytest.mark.isaacsim_ci
def test_franka_pose_abs_without_inertial_decoupling_with_nullspace_centering(sim):
"""Test absolute pose control with fixed impedance and nullspace centerin but without inertial decoupling."""
(
sim_context,
num_envs,
robot_cfg,
ee_marker,
goal_marker,
contact_forces,
_,
target_abs_pose_set_b,
_,
_,
_,
_,
_,
_,
_,
_,
frame,
) = sim
robot = Articulation(cfg=robot_cfg)
osc_cfg = OperationalSpaceControllerCfg(
target_types=["pose_abs"],
impedance_mode="fixed",
inertial_dynamics_decoupling=False,
gravity_compensation=False,
motion_stiffness_task=[400.0, 400.0, 400.0, 100.0, 100.0, 100.0],
motion_damping_ratio_task=[5.0, 5.0, 5.0, 0.001, 0.001, 0.001],
nullspace_control="position",
)
osc = OperationalSpaceController(osc_cfg, num_envs=num_envs, device=sim_context.device)
_run_op_space_controller(
robot,
osc,
"panda_hand",
["panda_joint.*"],
target_abs_pose_set_b,
sim_context,
num_envs,
ee_marker,
goal_marker,
contact_forces,
frame,
)
@pytest.mark.isaacsim_ci
def test_franka_pose_abs_with_partial_inertial_decoupling_nullspace_centering(sim):
"""Test absolute pose control with fixed impedance, partial inertial decoupling and nullspace centering."""
(
sim_context,
num_envs,
robot_cfg,
ee_marker,
goal_marker,
contact_forces,
_,
target_abs_pose_set_b,
_,
_,
_,
_,
_,
_,
_,
_,
frame,
) = sim
robot = Articulation(cfg=robot_cfg)
osc_cfg = OperationalSpaceControllerCfg(
target_types=["pose_abs"],
impedance_mode="fixed",
inertial_dynamics_decoupling=True,
partial_inertial_dynamics_decoupling=True,
gravity_compensation=False,
motion_stiffness_task=1000.0,
motion_damping_ratio_task=1.0,
nullspace_control="position",
)
osc = OperationalSpaceController(osc_cfg, num_envs=num_envs, device=sim_context.device)
_run_op_space_controller(
robot,
osc,
"panda_hand",
["panda_joint.*"],
target_abs_pose_set_b,
sim_context,
num_envs,
ee_marker,
goal_marker,
contact_forces,
frame,
)
@pytest.mark.isaacsim_ci
def test_franka_pose_abs_with_nullspace_centering(sim):
"""Test absolute pose control with fixed impedance, inertial decoupling and nullspace centering."""
(
sim_context,
num_envs,
robot_cfg,
ee_marker,
goal_marker,
contact_forces,
_,
target_abs_pose_set_b,
_,
_,
_,
_,
_,
_,
_,
_,
frame,
) = sim
robot = Articulation(cfg=robot_cfg)
osc_cfg = OperationalSpaceControllerCfg(
target_types=["pose_abs"],
impedance_mode="fixed",
inertial_dynamics_decoupling=True,
partial_inertial_dynamics_decoupling=False,
gravity_compensation=False,
motion_stiffness_task=500.0,
motion_damping_ratio_task=1.0,
nullspace_control="position",
)
osc = OperationalSpaceController(osc_cfg, num_envs=num_envs, device=sim_context.device)
_run_op_space_controller(
robot,
osc,
"panda_hand",
["panda_joint.*"],
target_abs_pose_set_b,
sim_context,
num_envs,
ee_marker,
goal_marker,
contact_forces,
frame,
)
@pytest.mark.isaacsim_ci
def test_franka_taskframe_hybrid_with_nullspace_centering(sim):
"""Test hybrid control in task frame with fixed impedance, inertial decoupling and nullspace centering."""
(
sim_context,
num_envs,
robot_cfg,
ee_marker,
goal_marker,
contact_forces,
_,
_,
_,
_,
_,
_,
_,
_,
_,
target_hybrid_set_tilted,
frame,
) = sim
robot = Articulation(cfg=robot_cfg)
frame = "task"
obstacle_spawn_cfg = sim_utils.CuboidCfg(
size=(2.0, 1.5, 0.01),
collision_props=sim_utils.CollisionPropertiesCfg(),
visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(1.0, 0.0, 0.0), opacity=0.1),
rigid_props=sim_utils.RigidBodyPropertiesCfg(kinematic_enabled=True),
activate_contact_sensors=True,
)
obstacle_spawn_cfg.func(
"/World/envs/env_.*/obstacle1",
obstacle_spawn_cfg,
translation=(target_hybrid_set_tilted[0, 0] + 0.085, 0.0, 0.3),
orientation=(0.9238795325, 0.0, -0.3826834324, 0.0),
)
contact_forces_cfg = ContactSensorCfg(
prim_path="/World/envs/env_.*/obstacle.*",
update_period=0.0,
history_length=2,
debug_vis=False,
force_threshold=0.1,
)
contact_forces = ContactSensor(contact_forces_cfg)
osc_cfg = OperationalSpaceControllerCfg(
target_types=["pose_abs", "wrench_abs"],
impedance_mode="fixed",
inertial_dynamics_decoupling=True,
partial_inertial_dynamics_decoupling=False,
gravity_compensation=False,
motion_stiffness_task=400.0,
motion_damping_ratio_task=1.0,
contact_wrench_stiffness_task=[0.0, 0.0, 0.1, 0.0, 0.0, 0.0],
motion_control_axes_task=[1, 1, 0, 1, 1, 1],
contact_wrench_control_axes_task=[0, 0, 1, 0, 0, 0],
nullspace_control="position",
)
osc = OperationalSpaceController(osc_cfg, num_envs=num_envs, device=sim_context.device)
_run_op_space_controller(
robot,
osc,
"panda_leftfinger",
["panda_joint.*"],
target_hybrid_set_tilted,
sim_context,
num_envs,
ee_marker,
goal_marker,
contact_forces,
frame,
)
def _run_op_space_controller(
robot: Articulation,
osc: OperationalSpaceController,
ee_frame_name: str,
arm_joint_names: list[str],
target_set: torch.tensor,
sim: sim_utils.SimulationContext,
num_envs: int,
ee_marker: VisualizationMarkers,
goal_marker: VisualizationMarkers,
contact_forces: ContactSensor | None,
frame: str,
):
"""Run the operational space controller with the given parameters.
Args:
robot (Articulation): The robot to control.
osc (OperationalSpaceController): The operational space controller.
ee_frame_name (str): The name of the end-effector frame.
arm_joint_names (list[str]): The names of the arm joints.
target_set (torch.tensor): The target set to track.
sim (sim_utils.SimulationContext): The simulation context.
num_envs (int): The number of environments.
ee_marker (VisualizationMarkers): The end-effector marker.
goal_marker (VisualizationMarkers): The goal marker.
contact_forces (ContactSensor | None): The contact forces sensor.
frame (str): The reference frame for targets.
"""
# Initialize the masks for evaluating target convergence according to selection matrices
pos_mask = torch.tensor(osc.cfg.motion_control_axes_task[:3], device=sim.device).view(1, 3)
rot_mask = torch.tensor(osc.cfg.motion_control_axes_task[3:], device=sim.device).view(1, 3)
wrench_mask = torch.tensor(osc.cfg.contact_wrench_control_axes_task, device=sim.device).view(1, 6)
force_mask = wrench_mask[:, 0:3] # Take only the force components as we can measure only these
# Define simulation stepping
sim_dt = sim.get_physics_dt()
# Play the simulator
sim.reset()
# Obtain the frame index of the end-effector
ee_frame_idx = robot.find_bodies(ee_frame_name)[0][0]
# Obtain joint indices
arm_joint_ids = robot.find_joints(arm_joint_names)[0]
# Update existing buffers
# Note: We need to update buffers before the first step for the controller.
robot.update(dt=sim_dt)
# Get the center of the robot soft joint limits
joint_centers = torch.mean(robot.data.soft_joint_pos_limits[:, arm_joint_ids, :], dim=-1)
# get the updated states
(
jacobian_b,
mass_matrix,
gravity,
ee_pose_b,
ee_vel_b,
root_pose_w,
ee_pose_w,
ee_force_b,
joint_pos,
joint_vel,
) = _update_states(robot, ee_frame_idx, arm_joint_ids, sim, contact_forces, num_envs)
# Track the given target command
current_goal_idx = 0 # Current goal index for the arm
command = torch.zeros(
num_envs, osc.action_dim, device=sim.device
) # Generic target command, which can be pose, position, force, etc.
ee_target_pose_b = torch.zeros(num_envs, 7, device=sim.device) # Target pose in the body frame
ee_target_pose_w = torch.zeros(num_envs, 7, device=sim.device) # Target pose in the world frame (for marker)
# Set joint efforts to zero
zero_joint_efforts = torch.zeros(num_envs, robot.num_joints, device=sim.device)
joint_efforts = torch.zeros(num_envs, len(arm_joint_ids), device=sim.device)
# Now we are ready!
for count in range(1501):
# reset every 500 steps
if count % 500 == 0:
# check that we converged to the goal
if count > 0:
_check_convergence(
osc, ee_pose_b, ee_target_pose_b, ee_force_b, command, pos_mask, rot_mask, force_mask, frame
)
# reset joint state to default
default_joint_pos = robot.data.default_joint_pos.clone()
default_joint_vel = robot.data.default_joint_vel.clone()
robot.write_joint_state_to_sim(default_joint_pos, default_joint_vel)
robot.set_joint_effort_target(zero_joint_efforts) # Set zero torques in the initial step
robot.write_data_to_sim()
robot.reset()
# reset contact sensor
if contact_forces is not None:
contact_forces.reset()
# reset target pose
robot.update(sim_dt)
_, _, _, ee_pose_b, _, _, _, _, _, _ = _update_states(
robot, ee_frame_idx, arm_joint_ids, sim, contact_forces, num_envs
) # at reset, the jacobians are not updated to the latest state
command, ee_target_pose_b, ee_target_pose_w, current_goal_idx = _update_target(
osc, root_pose_w, ee_pose_b, target_set, current_goal_idx
)
# set the osc command
osc.reset()
command, task_frame_pose_b = _convert_to_task_frame(
osc, command=command, ee_target_pose_b=ee_target_pose_b, frame=frame
)
osc.set_command(command=command, current_ee_pose_b=ee_pose_b, current_task_frame_pose_b=task_frame_pose_b)
else:
# get the updated states
(
jacobian_b,
mass_matrix,
gravity,
ee_pose_b,
ee_vel_b,
root_pose_w,
ee_pose_w,
ee_force_b,
joint_pos,
joint_vel,
) = _update_states(robot, ee_frame_idx, arm_joint_ids, sim, contact_forces, num_envs)
# compute the joint commands
joint_efforts = osc.compute(
jacobian_b=jacobian_b,
current_ee_pose_b=ee_pose_b,
current_ee_vel_b=ee_vel_b,
current_ee_force_b=ee_force_b,
mass_matrix=mass_matrix,
gravity=gravity,
current_joint_pos=joint_pos,
current_joint_vel=joint_vel,
nullspace_joint_pos_target=joint_centers,
)
robot.set_joint_effort_target(joint_efforts, joint_ids=arm_joint_ids)
robot.write_data_to_sim()
# update marker positions
ee_marker.visualize(ee_pose_w[:, 0:3], ee_pose_w[:, 3:7])
goal_marker.visualize(ee_target_pose_w[:, 0:3], ee_target_pose_w[:, 3:7])
# perform step
sim.step(render=False)
# update buffers
robot.update(sim_dt)
def _update_states(
robot: Articulation,
ee_frame_idx: int,
arm_joint_ids: list[int],
sim: sim_utils.SimulationContext,
contact_forces: ContactSensor | None,
num_envs: int,
):
"""Update the states of the robot and obtain the relevant quantities for the operational space controller.
Args:
robot (Articulation): The robot to control.
ee_frame_idx (int): The index of the end-effector frame.
arm_joint_ids (list[int]): The indices of the arm joints.
sim (sim_utils.SimulationContext): The simulation context.
contact_forces (ContactSensor | None): The contact forces sensor.
num_envs (int): Number of environments.
Returns:
jacobian_b (torch.tensor): The Jacobian in the root frame.
mass_matrix (torch.tensor): The mass matrix.
gravity (torch.tensor): The gravity vector.
ee_pose_b (torch.tensor): The end-effector pose in the root frame.
ee_vel_b (torch.tensor): The end-effector velocity in the root frame.
root_pose_w (torch.tensor): The root pose in the world frame.
ee_pose_w (torch.tensor): The end-effector pose in the world frame.
ee_force_b (torch.tensor): The end-effector force in the root frame.
joint_pos (torch.tensor): The joint positions.
joint_vel (torch.tensor): The joint velocities.
"""
# obtain dynamics related quantities from simulation
ee_jacobi_idx = ee_frame_idx - 1
jacobian_w = robot.root_physx_view.get_jacobians()[:, ee_jacobi_idx, :, arm_joint_ids]
mass_matrix = robot.root_physx_view.get_generalized_mass_matrices()[:, arm_joint_ids, :][:, :, arm_joint_ids]
gravity = robot.root_physx_view.get_gravity_compensation_forces()[:, arm_joint_ids]
# Convert the Jacobian from world to root frame
jacobian_b = jacobian_w.clone()
root_rot_matrix = matrix_from_quat(quat_inv(robot.data.root_quat_w))
jacobian_b[:, :3, :] = torch.bmm(root_rot_matrix, jacobian_b[:, :3, :])
jacobian_b[:, 3:, :] = torch.bmm(root_rot_matrix, jacobian_b[:, 3:, :])
# Compute current pose of the end-effector
root_pose_w = robot.data.root_pose_w
ee_pose_w = robot.data.body_pose_w[:, ee_frame_idx]
ee_pos_b, ee_quat_b = subtract_frame_transforms(
root_pose_w[:, 0:3], root_pose_w[:, 3:7], ee_pose_w[:, 0:3], ee_pose_w[:, 3:7]
)
ee_pose_b = torch.cat([ee_pos_b, ee_quat_b], dim=-1)
# Compute the current velocity of the end-effector
ee_vel_w = robot.data.body_vel_w[:, ee_frame_idx, :] # Extract end-effector velocity in the world frame
root_vel_w = robot.data.root_vel_w # Extract root velocity in the world frame
relative_vel_w = ee_vel_w - root_vel_w # Compute the relative velocity in the world frame
ee_lin_vel_b = quat_apply_inverse(robot.data.root_quat_w, relative_vel_w[:, 0:3]) # From world to root frame
ee_ang_vel_b = quat_apply_inverse(robot.data.root_quat_w, relative_vel_w[:, 3:6])
ee_vel_b = torch.cat([ee_lin_vel_b, ee_ang_vel_b], dim=-1)
# Calculate the contact force
ee_force_w = torch.zeros(num_envs, 3, device=sim.device)
if contact_forces is not None: # Only modify if it exist
sim_dt = sim.get_physics_dt()
contact_forces.update(sim_dt) # update contact sensor
# Calculate the contact force by averaging over last four time steps (i.e., to smoothen) and
# taking the max of three surfaces as only one should be the contact of interest
ee_force_w, _ = torch.max(torch.mean(contact_forces.data.net_forces_w_history, dim=1), dim=1)
# This is a simplification, only for the sake of testing.
ee_force_b = ee_force_w
# Get joint positions and velocities
joint_pos = robot.data.joint_pos[:, arm_joint_ids]
joint_vel = robot.data.joint_vel[:, arm_joint_ids]
return (
jacobian_b,
mass_matrix,
gravity,
ee_pose_b,
ee_vel_b,
root_pose_w,
ee_pose_w,
ee_force_b,
joint_pos,
joint_vel,
)
def _update_target(
osc: OperationalSpaceController,
root_pose_w: torch.tensor,
ee_pose_b: torch.tensor,
target_set: torch.tensor,
current_goal_idx: int,
):
"""Update the target for the operational space controller.
Args:
osc (OperationalSpaceController): The operational space controller.
root_pose_w (torch.tensor): The root pose in the world frame.
ee_pose_b (torch.tensor): The end-effector pose in the body frame.
target_set (torch.tensor): The target set to track.
current_goal_idx (int): The current goal index.
Returns:
command (torch.tensor): The target command.
ee_target_pose_b (torch.tensor): The end-effector target pose in the body frame.
ee_target_pose_w (torch.tensor): The end-effector target pose in the world frame.
next_goal_idx (int): The next goal index.
Raises:
ValueError: If the target type is undefined.
"""
# update the ee desired command
command = torch.zeros(osc.num_envs, osc.action_dim, device=osc._device)
command[:] = target_set[current_goal_idx]
# update the ee desired pose
ee_target_pose_b = torch.zeros(osc.num_envs, 7, device=osc._device)
for target_type in osc.cfg.target_types:
if target_type == "pose_abs":
ee_target_pose_b[:] = command[:, :7]
elif target_type == "pose_rel":
ee_target_pose_b[:, 0:3], ee_target_pose_b[:, 3:7] = apply_delta_pose(
ee_pose_b[:, :3], ee_pose_b[:, 3:], command[:, :7]
)
elif target_type == "wrench_abs":
pass # ee_target_pose_b could stay at the root frame for force control, what matters is ee_target_b
else:
raise ValueError("Undefined target_type within _update_target().")
# update the target desired pose in world frame (for marker)
ee_target_pos_w, ee_target_quat_w = combine_frame_transforms(
root_pose_w[:, 0:3], root_pose_w[:, 3:7], ee_target_pose_b[:, 0:3], ee_target_pose_b[:, 3:7]
)
ee_target_pose_w = torch.cat([ee_target_pos_w, ee_target_quat_w], dim=-1)
next_goal_idx = (current_goal_idx + 1) % len(target_set)
return command, ee_target_pose_b, ee_target_pose_w, next_goal_idx
def _convert_to_task_frame(
osc: OperationalSpaceController, command: torch.tensor, ee_target_pose_b: torch.tensor, frame: str
):
"""Convert the target command to the task frame if required.
Args:
osc (OperationalSpaceController): The operational space controller.
command (torch.tensor): The target command to convert.
ee_target_pose_b (torch.tensor): The end-effector target pose in the body frame.
frame (str): The reference frame for targets.
Returns:
command (torch.tensor): The converted target command.
task_frame_pose_b (torch.tensor): The task frame pose in the body frame.
Raises:
ValueError: If the frame is invalid.
"""
command = command.clone()
task_frame_pose_b = None
if frame == "root":
# No need to transform anything if they are already in root frame
pass
elif frame == "task":
# Convert target commands from base to the task frame
command = command.clone()
task_frame_pose_b = ee_target_pose_b.clone()
cmd_idx = 0
for target_type in osc.cfg.target_types:
if target_type == "pose_abs":
command[:, :3], command[:, 3:7] = subtract_frame_transforms(
task_frame_pose_b[:, :3], task_frame_pose_b[:, 3:], command[:, :3], command[:, 3:7]
)
cmd_idx += 7
elif target_type == "pose_rel":
# Compute rotation matrices
R_task_b = matrix_from_quat(task_frame_pose_b[:, 3:]) # Task frame to base frame
R_b_task = R_task_b.mT # Base frame to task frame
# Transform the delta position and orientation from base to task frame
command[:, :3] = (R_b_task @ command[:, :3].unsqueeze(-1)).squeeze(-1)
command[:, 3:7] = (R_b_task @ command[:, 3:7].unsqueeze(-1)).squeeze(-1)
cmd_idx += 6
elif target_type == "wrench_abs":
# These are already defined in target frame for ee_goal_wrench_set_tilted_task (since it is
# easier), so not transforming
cmd_idx += 6
else:
raise ValueError("Undefined target_type within _convert_to_task_frame().")
else:
# Raise error for invalid frame
raise ValueError("Invalid frame selection for target setting inside the test_operational_space.")
return command, task_frame_pose_b
def _check_convergence(
osc: OperationalSpaceController,
ee_pose_b: torch.tensor,
ee_target_pose_b: torch.tensor,
ee_force_b: torch.tensor,
ee_target_b: torch.tensor,
pos_mask: torch.tensor,
rot_mask: torch.tensor,
force_mask: torch.tensor,
frame: str,
):
"""Check the convergence to the target.
Args:
osc (OperationalSpaceController): The operational space controller.
ee_pose_b (torch.tensor): The end-effector pose in the body frame.
ee_target_pose_b (torch.tensor): The end-effector target pose in the body frame.
ee_force_b (torch.tensor): The end-effector force in the body frame.
ee_target_b (torch.tensor): The end-effector target in the body frame.
pos_mask (torch.tensor): The position mask.
rot_mask (torch.tensor): The rotation mask.
force_mask (torch.tensor): The force mask.
frame (str): The reference frame for targets.
Raises:
AssertionError: If the convergence is not achieved.
ValueError: If the target type is undefined.
"""
cmd_idx = 0
for target_type in osc.cfg.target_types:
if target_type == "pose_abs":
pos_error, rot_error = compute_pose_error(
ee_pose_b[:, 0:3], ee_pose_b[:, 3:7], ee_target_pose_b[:, 0:3], ee_target_pose_b[:, 3:7]
)
pos_error_norm = torch.norm(pos_error * pos_mask, dim=-1)
rot_error_norm = torch.norm(rot_error * rot_mask, dim=-1)
# desired error (zer)
des_error = torch.zeros_like(pos_error_norm)
# check convergence
torch.testing.assert_close(pos_error_norm, des_error, rtol=0.0, atol=0.1)
torch.testing.assert_close(rot_error_norm, des_error, rtol=0.0, atol=0.1)
cmd_idx += 7
elif target_type == "pose_rel":
pos_error, rot_error = compute_pose_error(
ee_pose_b[:, 0:3], ee_pose_b[:, 3:7], ee_target_pose_b[:, 0:3], ee_target_pose_b[:, 3:7]
)
pos_error_norm = torch.norm(pos_error * pos_mask, dim=-1)
rot_error_norm = torch.norm(rot_error * rot_mask, dim=-1)
# desired error (zer)
des_error = torch.zeros_like(pos_error_norm)
# check convergence
torch.testing.assert_close(pos_error_norm, des_error, rtol=0.0, atol=0.1)
torch.testing.assert_close(rot_error_norm, des_error, rtol=0.0, atol=0.1)
cmd_idx += 6
elif target_type == "wrench_abs":
force_target_b = ee_target_b[:, cmd_idx : cmd_idx + 3].clone()
# Convert to base frame if the target was defined in task frame
if frame == "task":
task_frame_pose_b = ee_target_pose_b.clone()
R_task_b = matrix_from_quat(task_frame_pose_b[:, 3:])
force_target_b[:] = (R_task_b @ force_target_b[:].unsqueeze(-1)).squeeze(-1)
force_error = ee_force_b - force_target_b
force_error_norm = torch.norm(
force_error * force_mask, dim=-1
) # ignore torque part as we cannot measure it
des_error = torch.zeros_like(force_error_norm)
# check convergence: big threshold here as the force control is not precise when the robot moves
torch.testing.assert_close(force_error_norm, des_error, rtol=0.0, atol=1.0)
cmd_idx += 6
else:
raise ValueError("Undefined target_type within _check_convergence().")
|