Hello! So, I am following along with tutorial 5.7: 5.7. Adding a New Manipulator — Omniverse IsaacSim latest documentation
My issue comes at section 5.7.5. I am having issues with setting SingleManipulator(prim_path=…) on line 41. I have a custom URDF
(dumped below)
<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from gen3_robotiq_2f_85.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot name="gen3_robotiq_2f_85">
<!-- Run the macros -->
<!-- For gazebo and DART -->
<link name="world"/>
<joint name="world_to_root" type="fixed">
<child link="base_link"/>
<parent link="world"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
</joint>
<link name="base_link">
<inertial>
<origin rpy="0 0 0" xyz="-0.000648 -0.000166 0.084487"/>
<mass value="1.697"/>
<inertia ixx="0.004622" ixy="9E-06" ixz="6E-05" iyy="0.004495" iyz="9E-06" izz="0.002079"/>
</inertial>
<visual>
<origin rpy="0 0 -1.5708" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kortex_description/arms/gen3/6dof/meshes/base_link.STL"/>
</geometry>
<material name="">
<color rgba="0.75294 0.75294 0.75294 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 -1.5708" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kortex_description/arms/gen3/6dof/meshes/base_link.STL"/>
</geometry>
</collision>
</link>
<link name="shoulder_link">
<inertial>
<origin rpy="0 0 0" xyz="-2.3E-05 -0.010364 -0.07336"/>
<mass value="1.377"/>
<inertia ixx="0.00457" ixy="1E-06" ixz="2E-06" iyy="0.004831" iyz="0.000448" izz="0.001409"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kortex_description/arms/gen3/6dof/meshes/shoulder_link.STL"/>
</geometry>
<material name="">
<color rgba="0.75294 0.75294 0.75294 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kortex_description/arms/gen3/6dof/meshes/shoulder_link.STL"/>
</geometry>
</collision>
</link>
<joint name="joint_1" type="continuous">
<origin rpy="-3.1416 0.0 -1.5708" xyz="0 0 0.15643"/>
<parent link="base_link"/>
<child link="shoulder_link"/>
<axis xyz="0 0 1"/>
<limit effort="39" velocity="1.3963"/>
</joint>
<link name="bicep_link">
<inertial>
<origin rpy="0 0 0" xyz="3.5E-05 -0.208207 -0.01889"/>
<mass value="1.262"/>
<inertia ixx="0.046752" ixy="-9E-06" ixz="0" iyy="0.00085" iyz="-9.8E-05" izz="0.047188"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kortex_description/arms/gen3/6dof/meshes/bicep_link.STL"/>
</geometry>
<material name="">
<color rgba="0.75294 0.75294 0.75294 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kortex_description/arms/gen3/6dof/meshes/bicep_link.STL"/>
</geometry>
</collision>
</link>
<joint name="joint_2" type="revolute">
<origin rpy="1.5708 0.0 0.0" xyz="0 0.005375 -0.12838"/>
<parent link="shoulder_link"/>
<child link="bicep_link"/>
<axis xyz="0 0 1"/>
<limit effort="39" lower="-2.41" upper="2.41" velocity="1.3963"/>
</joint>
<link name="forearm_link">
<inertial>
<origin rpy="0 0 0" xyz="1.8E-05 0.076168 -0.01397"/>
<mass value="0.93"/>
<inertia ixx="0.008292" ixy="-1E-06" ixz="0" iyy="0.000628" iyz="0.000432" izz="0.008464"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kortex_description/arms/gen3/6dof/meshes/forearm_link.STL"/>
</geometry>
<material name="">
<color rgba="0.75294 0.75294 0.75294 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kortex_description/arms/gen3/6dof/meshes/forearm_link.STL"/>
</geometry>
</collision>
</link>
<joint name="joint_3" type="revolute">
<origin rpy="3.1416 0 0" xyz="0 -0.41 0"/>
<parent link="bicep_link"/>
<child link="forearm_link"/>
<axis xyz="0 0 1"/>
<limit effort="39" lower="-2.66" upper="2.66" velocity="1.3963"/>
</joint>
<link name="spherical_wrist_1_link">
<inertial>
<origin rpy="0 0 0" xyz="-1E-06 0.008486 -0.062937"/>
<mass value="0.678"/>
<inertia ixx="0.001645" ixy="0" ixz="0" iyy="0.001666" iyz="-0.000234" izz="0.000389"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kortex_description/arms/gen3/6dof/meshes/spherical_wrist_1_link.STL"/>
</geometry>
<material name="">
<color rgba="0.75294 0.75294 0.75294 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kortex_description/arms/gen3/6dof/meshes/spherical_wrist_1_link.STL"/>
</geometry>
</collision>
</link>
<joint name="joint_4" type="continuous">
<origin rpy="1.5708 0.0 0.0" xyz="0 0.20843 -0.006375"/>
<parent link="forearm_link"/>
<child link="spherical_wrist_1_link"/>
<axis xyz="0 0 1"/>
<limit effort="9" velocity="1.2218"/>
</joint>
<link name="spherical_wrist_2_link">
<inertial>
<origin rpy="0 0 0" xyz="-1E-06 0.046429 -0.008704"/>
<mass value="0.678"/>
<inertia ixx="0.001685" ixy="0" ixz="0" iyy="0.0004" iyz="0.000255" izz="0.001696"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kortex_description/arms/gen3/6dof/meshes/spherical_wrist_2_link.STL"/>
</geometry>
<material name="">
<color rgba="0.75294 0.75294 0.75294 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kortex_description/arms/gen3/6dof/meshes/spherical_wrist_2_link.STL"/>
</geometry>
</collision>
</link>
<joint name="joint_5" type="revolute">
<origin rpy="-1.5708 0.0 0.0" xyz="0 -0.00017505 -0.10593"/>
<parent link="spherical_wrist_1_link"/>
<child link="spherical_wrist_2_link"/>
<axis xyz="0 0 1"/>
<limit effort="9" lower="-2.23" upper="2.23" velocity="1.2218"/>
</joint>
<link name="bracelet_link">
<inertial>
<origin rpy="0 0 0" xyz="0.000281 0.011402 -0.029798"/>
<mass value="0.5"/>
<inertia ixx="0.000587" ixy="3E-06" ixz="3E-06" iyy="0.000369" iyz="-0.000118" izz="0.000609"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kortex_description/arms/gen3/6dof/meshes/bracelet_with_vision_link.STL"/>
</geometry>
<material name="">
<color rgba="0.75294 0.75294 0.75294 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kortex_description/arms/gen3/6dof/meshes/bracelet_with_vision_link.STL"/>
</geometry>
</collision>
</link>
<joint name="joint_6" type="continuous">
<origin rpy="1.5708 0.0 0.0" xyz="0 0.10593 -0.00017505"/>
<parent link="spherical_wrist_2_link"/>
<child link="bracelet_link"/>
<axis xyz="0 0 1"/>
<limit effort="9" velocity="1.2218"/>
</joint>
<link name="end_effector_link">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
</link>
<joint name="end_effector" type="fixed">
<origin rpy="3.14159265358979 1.09937075168372E-32 3.14159265358979" xyz="0 0 -0.0615250000000001"/>
<parent link="bracelet_link"/>
<child link="end_effector_link"/>
<axis xyz="0 0 0"/>
</joint>
<link name="camera_link">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.001 0.001 0.001"/>
</geometry>
</visual>
</link>
<link name="depth_camera_link">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.001 0.001 0.001"/>
</geometry>
</visual>
</link>
<joint name="camera_color_joint" type="fixed">
<origin rpy="0 0 3.14" xyz="0 0.05639 -0.00305"/>
<parent link="end_effector_link"/>
<child link="camera_link"/>
<axis xyz="0.001 0.001 0.001"/>
</joint>
<joint name="camera_depth_joint" type="fixed">
<origin rpy="0 0 3.14" xyz="0.0275 0.06600 -0.00305"/>
<parent link="end_effector_link"/>
<child link="depth_camera_link"/>
<axis xyz="0.001 0.001 0.001"/>
</joint>
<!-- This line was removed by Kinova because we replaced the transmission file with our own
<xacro:include filename="$(find robotiq_2f_85_gripper_visualization)/urdf/robotiq_arg2f_transmission.xacro" /> -->
<!-- Tool frame used by the arm -->
<link name="tool_frame">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
</link>
<joint name="tool_frame_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0.120"/>
<parent link="end_effector_link"/>
<child link="tool_frame"/>
<axis xyz="0 0 0"/>
</joint>
<!-- This joint was added by Kinova -->
<joint name="gripper_base_joint" type="fixed">
<parent link="end_effector_link"/>
<child link="robotiq_arg2f_base_link"/>
<origin rpy="0.0 0.0 1.57" xyz="0.0 0.0 0.0"/>
</joint>
<link name="robotiq_arg2f_base_link">
<!-- <inertial>
<origin xyz="8.625E-08 -4.6583E-06 0.03145" rpy="0 0 0" />
<mass value="0.22652" />
<inertia ixx="0.00020005" ixy="-4.2442E-10" ixz="-2.9069E-10" iyy="0.00017832" iyz="-3.4402E-08" izz="0.00013478" />
</inertial> -->
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<!-- The DAE file doesn't show well in Gazebo so we're using the STL instead -->
<!-- <mesh filename="package://kortex_description/grippers/robotiq_2f_85/meshes/visual/robotiq_arg2f_85_base_link.dae" scale="0.001 0.001 0.001"/> -->
<mesh filename="package://kortex_description/grippers/robotiq_2f_85/meshes/collision/robotiq_arg2f_base_link.stl"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kortex_description/grippers/robotiq_2f_85/meshes/collision/robotiq_arg2f_base_link.stl"/>
</geometry>
</collision>
</link>
<joint name="gripper_inertia_base_joint" type="fixed">
<parent link="end_effector_link"/>
<child link="inertia_link"/>
<origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/>
</joint>
<link name="inertia_link">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0.058"/>
<mass value="0.925"/>
<inertia ixx="0.000000" ixy="0.000000" ixz="0.000000" iyy="0.000000" iyz="0.000000" izz="0.000000"/>
</inertial>
</link>
<gazebo reference="robotiq_arg2f_base_link">
<material>Gazebo/Black</material>
</gazebo>
<link name="left_outer_knuckle">
<!-- <inertial>
<origin xyz="-0.000200000000003065 0.0199435877845359 0.0292245259211331" rpy="0 0 0" />
<mass value="0.00853198276973456" />
<inertia ixx="2.89328108496468E-06" ixy="-1.57935047237397E-19" ixz="-1.93980378593255E-19" iyy="1.86719750325683E-06" iyz="-1.21858577871576E-06" izz="1.21905238907251E-06" />
</inertial> -->
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kortex_description/grippers/robotiq_2f_85/meshes/visual/robotiq_arg2f_85_outer_knuckle.dae" scale="0.001 0.001 0.001"/>
</geometry>
<material name="">
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kortex_description/grippers/robotiq_2f_85/meshes/collision/robotiq_arg2f_85_outer_knuckle.dae" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="left_outer_finger">
<!-- <inertial>
<origin xyz="0.00030115855001899 0.0373907951953854 -0.0208027427000385" rpy="0 0 0" />
<mass value="0.022614240507152" />
<inertia ixx="1.52518312458174E-05" ixy="9.76583423954399E-10" ixz="-5.43838577022588E-10" iyy="6.17694243867776E-06" iyz="6.78636130740228E-06" izz="1.16494917907219E-05" />
</inertial> -->
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kortex_description/grippers/robotiq_2f_85/meshes/visual/robotiq_arg2f_85_outer_finger.dae" scale="0.001 0.001 0.001"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kortex_description/grippers/robotiq_2f_85/meshes/collision/robotiq_arg2f_85_outer_finger.dae" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="left_inner_finger">
<!-- <inertial>
<origin xyz="0.000299999999999317 0.0160078233491243 -0.0136945669206257" rpy="0 0 0" />
<mass value="0.0104003125914103" />
<inertia ixx="2.71909453810972E-06" ixy="1.35402465472579E-21" ixz="-7.1817349065269E-22" iyy="7.69100314106116E-07" iyz="6.74715432769696E-07" izz="2.30315190420171E-06" />
</inertial> -->
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kortex_description/grippers/robotiq_2f_85/meshes/visual/robotiq_arg2f_85_inner_finger.dae" scale="0.001 0.001 0.001"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kortex_description/grippers/robotiq_2f_85/meshes/collision/robotiq_arg2f_85_inner_finger.dae" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="left_inner_finger_pad">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.022 0.00635 0.0375"/>
</geometry>
<material name="">
<color rgba="0.9 0.9 0.9 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.022 0.00635 0.0375"/>
</geometry>
<material name="">
<color rgba="0.9 0.0 0.0 1"/>
</material>
</collision>
</link>
<link name="left_inner_knuckle">
<!-- <inertial>
<origin xyz="0.000123011831763771 0.0507850843201817 0.00103968640075166" rpy="0 0 0" />
<mass value="0.0271177346495152" />
<inertia ixx="2.61910379223783E-05" ixy="-2.43616858946494E-07" ixz="-6.37789906117123E-09" iyy="2.8270243746167E-06" iyz="-5.37200748039765E-07" izz="2.83695868220296E-05" />
</inertial> -->
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kortex_description/grippers/robotiq_2f_85/meshes/visual/robotiq_arg2f_85_inner_knuckle.dae" scale="0.001 0.001 0.001"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kortex_description/grippers/robotiq_2f_85/meshes/collision/robotiq_arg2f_85_inner_knuckle.dae" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="right_outer_knuckle">
<!-- <inertial>
<origin xyz="-0.000200000000003065 0.0199435877845359 0.0292245259211331" rpy="0 0 0" />
<mass value="0.00853198276973456" />
<inertia ixx="2.89328108496468E-06" ixy="-1.57935047237397E-19" ixz="-1.93980378593255E-19" iyy="1.86719750325683E-06" iyz="-1.21858577871576E-06" izz="1.21905238907251E-06" />
</inertial> -->
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kortex_description/grippers/robotiq_2f_85/meshes/visual/robotiq_arg2f_85_outer_knuckle.dae" scale="0.001 0.001 0.001"/>
</geometry>
<material name="">
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kortex_description/grippers/robotiq_2f_85/meshes/collision/robotiq_arg2f_85_outer_knuckle.dae" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="right_outer_finger">
<!-- <inertial>
<origin xyz="0.00030115855001899 0.0373907951953854 -0.0208027427000385" rpy="0 0 0" />
<mass value="0.022614240507152" />
<inertia ixx="1.52518312458174E-05" ixy="9.76583423954399E-10" ixz="-5.43838577022588E-10" iyy="6.17694243867776E-06" iyz="6.78636130740228E-06" izz="1.16494917907219E-05" />
</inertial> -->
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kortex_description/grippers/robotiq_2f_85/meshes/visual/robotiq_arg2f_85_outer_finger.dae" scale="0.001 0.001 0.001"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kortex_description/grippers/robotiq_2f_85/meshes/collision/robotiq_arg2f_85_outer_finger.dae" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="right_inner_finger">
<!-- <inertial>
<origin xyz="0.000299999999999317 0.0160078233491243 -0.0136945669206257" rpy="0 0 0" />
<mass value="0.0104003125914103" />
<inertia ixx="2.71909453810972E-06" ixy="1.35402465472579E-21" ixz="-7.1817349065269E-22" iyy="7.69100314106116E-07" iyz="6.74715432769696E-07" izz="2.30315190420171E-06" />
</inertial> -->
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kortex_description/grippers/robotiq_2f_85/meshes/visual/robotiq_arg2f_85_inner_finger.dae" scale="0.001 0.001 0.001"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kortex_description/grippers/robotiq_2f_85/meshes/collision/robotiq_arg2f_85_inner_finger.dae" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="right_inner_finger_pad">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.022 0.00635 0.0375"/>
</geometry>
<material name="">
<color rgba="0.9 0.9 0.9 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.022 0.00635 0.0375"/>
</geometry>
<material name="">
<color rgba="0.9 0.0 0.0 1"/>
</material>
</collision>
</link>
<link name="right_inner_knuckle">
<!-- <inertial>
<origin xyz="0.000123011831763771 0.0507850843201817 0.00103968640075166" rpy="0 0 0" />
<mass value="0.0271177346495152" />
<inertia ixx="2.61910379223783E-05" ixy="-2.43616858946494E-07" ixz="-6.37789906117123E-09" iyy="2.8270243746167E-06" iyz="-5.37200748039765E-07" izz="2.83695868220296E-05" />
</inertial> -->
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kortex_description/grippers/robotiq_2f_85/meshes/visual/robotiq_arg2f_85_inner_knuckle.dae" scale="0.001 0.001 0.001"/>
</geometry>
<material name="">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kortex_description/grippers/robotiq_2f_85/meshes/collision/robotiq_arg2f_85_inner_knuckle.dae" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<joint name="finger_joint" type="fixed">
<origin rpy="0 0 3.141592653589793" xyz="0 -0.0306011 0.054904"/>
<parent link="robotiq_arg2f_base_link"/>
<child link="left_outer_knuckle"/>
<axis xyz="1 0 0"/>
<limit effort="1000" lower="0" upper="0.8" velocity="2.0"/>
</joint>
<joint name="left_outer_finger_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0.0315 -0.0041"/>
<parent link="left_outer_knuckle"/>
<child link="left_outer_finger"/>
<axis xyz="1 0 0"/>
</joint>
<joint name="left_inner_knuckle_joint" type="fixed">
<!-- <origin xyz="0 ${reflect * -0.0127} 0.06142" rpy="${pi / 2 + .725} 0 ${(reflect - 1) * pi / 2}" /> -->
<origin rpy="0 0 3.141592653589793" xyz="0 -0.0127 0.06142"/>
<parent link="robotiq_arg2f_base_link"/>
<child link="left_inner_knuckle"/>
<axis xyz="1 0 0"/>
<limit effort="1000" lower="0" upper="0.8757" velocity="2.0"/>
<mimic joint="finger_joint" multiplier="1" offset="0"/>
</joint>
<joint name="left_inner_finger_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0.0061 0.0471"/>
<parent link="left_outer_finger"/>
<child link="left_inner_finger"/>
<axis xyz="1 0 0"/>
<limit effort="1000" lower="-0.8757" upper="0.8757" velocity="2.0"/>
<mimic joint="finger_joint" multiplier="-1" offset="0"/>
</joint>
<joint name="left_inner_finger_pad_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 -0.0220203446692936 0.03242"/>
<parent link="left_inner_finger"/>
<child link="left_inner_finger_pad"/>
<axis xyz="0 0 1"/>
</joint>
<joint name="right_outer_knuckle_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0.0306011 0.054904"/>
<parent link="robotiq_arg2f_base_link"/>
<child link="right_outer_knuckle"/>
<axis xyz="1 0 0"/>
<limit effort="1000" lower="0" upper="0.81" velocity="2.0"/>
<mimic joint="finger_joint" multiplier="1" offset="0"/>
</joint>
<joint name="right_outer_finger_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0.0315 -0.0041"/>
<parent link="right_outer_knuckle"/>
<child link="right_outer_finger"/>
<axis xyz="1 0 0"/>
</joint>
<joint name="right_inner_knuckle_joint" type="fixed">
<!-- <origin xyz="0 ${reflect * -0.0127} 0.06142" rpy="${pi / 2 + .725} 0 ${(reflect - 1) * pi / 2}" /> -->
<origin rpy="0 0 0.0" xyz="0 0.0127 0.06142"/>
<parent link="robotiq_arg2f_base_link"/>
<child link="right_inner_knuckle"/>
<axis xyz="1 0 0"/>
<limit effort="1000" lower="0" upper="0.8757" velocity="2.0"/>
<mimic joint="finger_joint" multiplier="1" offset="0"/>
</joint>
<joint name="right_inner_finger_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0.0061 0.0471"/>
<parent link="right_outer_finger"/>
<child link="right_inner_finger"/>
<axis xyz="1 0 0"/>
<limit effort="1000" lower="-0.8757" upper="0.8757" velocity="2.0"/>
<mimic joint="finger_joint" multiplier="-1" offset="0"/>
</joint>
<joint name="right_inner_finger_pad_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 -0.0220203446692936 0.03242"/>
<parent link="right_inner_finger"/>
<child link="right_inner_finger_pad"/>
<axis xyz="0 0 1"/>
</joint>
<!-- Transmissions are loaded in the generic kortex xacro when simulation is enabled -->
<!-- <xacro:robotiq_arg2f_transmission prefix="${prefix}"/> -->
<joint name="forque_joint" type="fixed">
<parent link="end_effector_link"/>
<child link="forque"/>
<origin rpy="0.0 0.0 0" xyz="0.0 0.0 0.11"/>
</joint>
<link name="forque">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0.091"/>
<mass value="0.113"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kortex_description/tools/forque/forque.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="carbon_fiber">
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kortex_description/tools/forque/forque.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<gazebo reference="forque">
<material>Gazebo/Black</material>
</gazebo>
<link name="forque_end_effector">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
</link>
<joint name="joint_forque_end_effector" type="fixed">
<parent link="forque"/>
<child link="forque_end_effector"/>
<axis xyz="0 0 0"/>
<limit effort="2000" lower="0" upper="0" velocity="1"/>
<origin rpy="0 0 0" xyz="0 0.007 0.18"/>
</joint>
<link name="forque_tip">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
</link>
<joint name="joint_forque_tip" type="fixed">
<parent link="forque"/>
<child link="forque_tip"/>
<axis xyz="0 0 0"/>
<limit effort="2000" lower="0" upper="0" velocity="1"/>
<!-- Rotation consistent with pointers of forque: -->
<origin rpy="-0.5 0 0" xyz="0.0 0.007 0.18"/>
</joint>
</robot>
that I want to import into IsaacSim using the IsaacSim URDF Importer. I have checked Fix Base Link and Create Physics Scene checked, as well as unchecked Parse Mimic Joint tag, as shown in the picture:
I hit the Import button, and then when I open up the saved USD, this is the file structure of the prim:
The articulation root is set to world. However, I want it to be set to the top level gen3_robotiq_2f_85 prim.
The reason is because in my actual code:
zip_to_be.zip (3.2 KB)
under tasks/follow_target.py, for the Single Manipulator prim_path parameter, I have to set the path to the articulation root, which exists at /World/Kinova/world. However, my end effector exists at /World/Kinova, and thus, when I set end_effector_prim_path to “end_effector_link”, the link I want to get, it looks for a link at “/World/Kinova/world/end_effector_link”, which doesn’t exist. I’ve tried setting the prim_path to /World/Kinova, which gives me the error
Pattern ‘/World/Kinova’ did not match any articulations
I tried doing …/end_effector_link, which has failed as well, saying this file doesn’t exist.
Normally, I should be able to resolve this by changing the articulation root to World/Kinova. However, when I go into the file structure, and go through Add > Physics, the only option I see is Colliders Preset. I can disable articulation root for the World/Kinova/world prim, but even then, I can only set the articulation root another prim within World/Kinova, like to World/Kinova/shoulder_link. How do I set the articulation root to World/Kinova? I know in version 2023.1.0, they set the articulation root api to the top level, a.k.a World/Kinova, while the actual root was located at something like World/Kinova/base_link. Would downgrading help here? Any guidance is greatly appreciated.