Isaac Sim 4.0 support, Kinematics API doc, Windows support

This commit is contained in:
Balakumar Sundaralingam
2024-07-20 14:51:43 -07:00
parent 2ae381f328
commit 3690d28c54
83 changed files with 2818 additions and 497 deletions

View File

@@ -19,6 +19,8 @@
<mesh filename="meshes/collision/link0.obj"/>
</geometry>
</collision>
</link>
<link name="panda_link1">
<visual>
@@ -31,6 +33,11 @@
<mesh filename="meshes/collision/link1.obj"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.00033 -0.02204 -0.04762"/>
<mass value="2.797"/>
<inertia ixx="0.0156" ixy="0.0" ixz="0.0" iyy="0.01439" iyz="-0.0024" izz="0.005"/>
</inertial>
</link>
<joint name="panda_joint1" type="revolute">
<safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-2.8973" soft_upper_limit="2.8973"/>
@@ -52,6 +59,11 @@
<mesh filename="meshes/collision/link2.obj"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.00038 -0.09211 0.01908"/>
<mass value="2.542"/>
<inertia ixx="0.0166" ixy="0.0" ixz="0.0" iyy="0.0046" iyz="0.0035" izz="0.015"/>
</inertial>
</link>
<joint name="panda_joint2" type="revolute">
<safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-1.7628" soft_upper_limit="1.7628"/>
@@ -73,6 +85,11 @@
<mesh filename="meshes/collision/link3.obj"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.05152 0.01696 -0.02971"/>
<mass value="2.2513"/>
<inertia ixx="0.006" ixy="0.009" ixz="0.003" iyy="0.0086" iyz="0.009" izz="0.0065"/>
</inertial>
</link>
<joint name="panda_joint3" type="revolute">
<safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-2.8973" soft_upper_limit="2.8973"/>
@@ -94,13 +111,18 @@
<mesh filename="meshes/collision/link4.obj"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.05113 0.05825 0.01698"/>
<mass value="2.2037"/>
<inertia ixx="0.0156" ixy="0.0" ixz="0.0" iyy="0.01439" iyz="-0.0024" izz="0.005"/>
</inertial>
</link>
<joint name="panda_joint4" type="revolute">
<safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-3.0718" soft_upper_limit="-0.0698"/>
<origin rpy="1.57079632679 0 0" xyz="0.0825 0 0"/>
<parent link="panda_link3"/>
<child link="panda_link4"/>
<axis xyz="0 0 1"/>
<axis xyz="0 0 1"/>
<dynamics damping="10.0"/>
<limit effort="87" lower="-3.0718" upper="-0.0698" velocity="2.1750"/>
<!-- something is weird with this joint limit config
@@ -118,6 +140,11 @@
<mesh filename="meshes/collision/link5.obj"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.00005 0.03730 -0.09280"/>
<mass value="2.2855"/>
<inertia ixx="0.02297014781" ixy="0.0" ixz="0.0" iyy="0.02095060919" iyz="0.00382345782" izz="0.00430606551"/>
</inertial>
</link>
<joint name="panda_joint5" type="revolute">
<safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-2.8973" soft_upper_limit="2.8973"/>
@@ -139,6 +166,11 @@
<mesh filename="meshes/collision/link6.obj"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.06572 -0.00371 0.00153"/>
<mass value="1.353"/>
<inertia ixx="0.00087964522" ixy="-0.00021487814" ixz="-0.00011911662" iyy="0.00277796968" iyz="0.00001274322" izz="0.00286701969"/>
</inertial>
</link>
<joint name="panda_joint6" type="revolute">
<safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-0.0175" soft_upper_limit="3.7525"/>
@@ -162,6 +194,11 @@
<mesh filename="meshes/collision/link7.obj"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.00089 -0.00044 0.05491"/>
<mass value="0.35973"/>
<inertia ixx="0.00019541063" ixy="0.00000165231" ixz="0.00000148826" iyy="0.00019210361" iyz="-0.00000131132" izz="0.00017936256"/>
</inertial>
</link>
<joint name="panda_joint7" type="revolute">
<safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-2.8973" soft_upper_limit="2.8973"/>
@@ -172,7 +209,7 @@
<dynamics damping="10.0"/>
<limit effort="12" lower="-2.8973" upper="2.8973" velocity="2.6100"/>
</joint>
<link name="panda_link8"/>
<joint name="panda_joint8" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0.107"/>
@@ -183,7 +220,7 @@
<joint name="panda_hand_joint" type="fixed">
<parent link="panda_link8"/>
<child link="panda_hand"/>
<origin rpy="0 0 -0.785398163397" xyz="0 0 0"/>
</joint>
<link name="panda_hand">
@@ -240,7 +277,7 @@
<dynamics damping="10.0"/>
<limit effort="20" lower="0.0" upper="0.04" velocity="0.2"/>
</joint>
<link name="ee_link"/>
<joint name="ee_fixed_joint" type="fixed">

View File

@@ -60,7 +60,15 @@ robot_cfg:
}
urdf_path: robot/kinova/kinova_gen3_7dof.urdf
asset_root_path: robot/kinova
mesh_link_names:
- base_link
- shoulder_link
- half_arm_1_link
- half_arm_2_link
- forearm_link
- spherical_wrist_1_link
- spherical_wrist_2_link
- bracelet_link
cspace:
joint_names: ['joint_1', 'joint_2', 'joint_3', 'joint_4', 'joint_5', 'joint_6', 'joint_7']
cspace_distance_weight:
@@ -71,7 +79,7 @@ robot_cfg:
- 1.0
- 1.0
- 1.0
null_space_weight:
- 1.0
- 1.0

View File

@@ -0,0 +1,100 @@
format: xrdf
format_version: 1.0
modifiers:
- set_base_frame: "base_link"
default_joint_positions:
shoulder_pan_joint: 0.0
shoulder_lift_joint: -2.2
elbow_joint: 1.9
wrist_1_joint: -1.383
wrist_2_joint: -1.57
wrist_3_joint: 0.0
cspace:
joint_names:
- "shoulder_pan_joint"
- "shoulder_lift_joint"
- "elbow_joint"
- "wrist_1_joint"
- "wrist_2_joint"
- "wrist_3_joint"
acceleration_limits: [12.0, 12.0, 12.0, 12.0, 12.0, 12.0]
jerk_limits: [500.0, 500.0, 500.0, 500.0, 500.0, 500.0]
tool_frames: ["tool0"]
collision:
geometry: "ur10e_collision_spheres"
buffer_distance:
shoulder_link: 0.01
upper_arm_link: 0.01
forearm_link: 0.01
wrist_1_link: 0.01
wrist_2_link: 0.01
wrist_3_link: 0.01
tool0: 0.01
self_collision:
geometry: "ur10e_collision_spheres"
buffer_distance:
shoulder_link: 0.07
tool0: 0.05
ignore:
upper_arm_link: ["forearm_link", "shoulder_link"]
forearm_link: ["wrist_1_link"]
wrist_1_link: ["wrist_2_link","wrist_3_link"]
wrist_2_link: ["wrist_3_link", "tool0"]
wrist_3_link: ["tool0"]
geometry:
ur10e_collision_spheres:
spheres:
shoulder_link:
- center: [0, 0, 0]
radius: 0.05
upper_arm_link:
- center: [-0, -0, 0.18]
radius: 0.09
- center: [-0.102167, 0, 0.18]
radius: 0.05
- center: [-0.204333, 0, 0.18]
radius: 0.05
- center: [-0.3065, 0, 0.18]
radius: 0.05
- center: [-0.408667, 0, 0.18]
radius: 0.05
- center: [-0.510833, 0, 0.18]
radius: 0.05
- center: [-0.613, 0,0.18]
radius: 0.07
forearm_link:
- center: [-0, 0, 0.03]
radius: 0.05
- center: [-0.0951667, 0, 0.03]
radius: 0.05
- center: [-0.190333, 0, 0.03]
radius: 0.05
- center: [-0.2855, 0, 0.03]
radius: 0.05
- center: [-0.380667, 0,0.03]
radius: 0.05
- center: [-0.475833, 0,0.03]
radius: 0.05
- center: [-0.571, -1.19904e-17, 0.03]
radius: 0.05
wrist_1_link:
- center: [0, 0, 0]
radius: 0.05
wrist_2_link:
- center: [0, 0, 0]
radius: 0.05
wrist_3_link:
- center: [0, 0, 0]
radius: 0.05
- center: [0, 0, 0.06]
radius: 0.07
tool0:
- center: [0, 0, 0.12]
radius: -0.01