NVlabs / curobo

CUDA Accelerated Robot Library
https://curobo.org
Other
732 stars 109 forks source link

Unknown joint type prismatic #95

Closed Hermanye996 closed 8 months ago

Hermanye996 commented 9 months ago
  1. cuRobo installation mode (choose from [isaac sim]):
  2. python version: python 3.10.13
  3. Isaac Sim version (if using): 2023.1.0-hotfix

Unknown joint type prismatic, error occurred at cuda_robot_generator.py/CudaRobotGenerator._build_kinematics_tensors(), it could not recognize my prismatic gripper, but prismatic are in the JointType.

class JointType(Enum):
    FIXED = -1
    X_PRISM = 0
    Y_PRISM = 1
    Z_PRISM = 2
    X_ROT = 3
    Y_ROT = 4
    Z_ROT = 5
    X_PRISM_NEG = 6
    Y_PRISM_NEG = 7
    Z_PRISM_NEG = 8
    X_ROT_NEG = 9
    Y_ROT_NEG = 10
    Z_ROT_NEG = 11
GET JOINT TYPE: JointType.FIXED
JOINT TYPE VALUE: -1
GET JOINT TYPE: JointType.FIXED
JOINT TYPE VALUE: -1
GET JOINT TYPE: prismatic
Traceback (most recent call last):
  File "/home/hermanye20/new_curobo_ws/curobo/examples/isaac_sim/motion_gen_reacher.py", line 376, in <module>
    main()
  File "/home/hermanye20/new_curobo_ws/curobo/examples/isaac_sim/motion_gen_reacher.py", line 180, in main
    motion_gen_config = MotionGenConfig.load_from_robot_config(
  File "/home/hermanye20/.local/share/ov/pkg/isaac_sim-2023.1.0-hotfix.1/kit/python/lib/python3.10/contextlib.py", line 79, in inner
    return func(*args, **kwds)
  File "/home/hermanye20/new_curobo_ws/curobo/src/curobo/wrap/reacher/motion_gen.py", line 345, in load_from_robot_config
    robot_cfg = RobotConfig.from_dict(robot_cfg, tensor_args)
  File "/home/hermanye20/new_curobo_ws/curobo/src/curobo/types/robot.py", line 48, in from_dict
    data_dict["kinematics"] = CudaRobotModelConfig.from_config(
  File "/home/hermanye20/new_curobo_ws/curobo/src/curobo/cuda_robot_model/cuda_robot_model.py", line 129, in from_config
    generator = CudaRobotGenerator(config)
  File "/home/hermanye20/new_curobo_ws/curobo/src/curobo/cuda_robot_model/cuda_robot_generator.py", line 222, in __init__
    self.initialize_tensors()
  File "/home/hermanye20/.local/share/ov/pkg/isaac_sim-2023.1.0-hotfix.1/kit/python/lib/python3.10/contextlib.py", line 79, in inner
    return func(*args, **kwds)
  File "/home/hermanye20/new_curobo_ws/curobo/src/curobo/cuda_robot_model/cuda_robot_generator.py", line 290, in initialize_tensors
    self._build_kinematics(self.base_link, self.ee_link, other_links, self.link_names)
  File "/home/hermanye20/.local/share/ov/pkg/isaac_sim-2023.1.0-hotfix.1/kit/python/lib/python3.10/contextlib.py", line 79, in inner
    return func(*args, **kwds)
  File "/home/hermanye20/new_curobo_ws/curobo/src/curobo/cuda_robot_model/cuda_robot_generator.py", line 467, in _build_kinematics
    self._build_kinematics_tensors(base_link, ee_link, link_names, chain_link_names)
  File "/home/hermanye20/.local/share/ov/pkg/isaac_sim-2023.1.0-hotfix.1/kit/python/lib/python3.10/contextlib.py", line 79, in inner
    return func(*args, **kwds)
  File "/home/hermanye20/new_curobo_ws/curobo/src/curobo/cuda_robot_model/cuda_robot_generator.py", line 421, in _build_kinematics_tensors
    print(f"JOINT TYPE VALUE: {self._bodies[i].joint_type.value}")
AttributeError: 'str' object has no attribute 'value'
 <joint name="gripper_inspire_left_joint_1" type="prismatic">
    <origin rpy="3.141592653589793 -1.5707963267948966 0" xyz="-0.034907 -0.009 0.12953"/>
    <parent link="gripper_inspire_body_link"/>
    <child link="gripper_inspire_left_link_1"/>
    <axis xyz="-0.00597 0 -0.99998"/>
    <limit effort="0" lower="-0.035" upper="0" velocity="0"/>
  </joint>
  <link name="gripper_inspire_right_link_1">
    <inertial>
      <origin rpy="0 0 0" xyz="-0.018807 0.0089979 -0.0046901"/>
      <mass value="0.010721"/>
      <inertia ixx="5.1508E-07" ixy="1.2231E-10" ixz="2.8973E-07" iyy="1.5709E-06" iyz="7.2401E-11" izz="1.6904E-06"/>
    </inertial>
    <visual>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="meshes/gripper/gripper_inspire_right_link_1.stl"/>
      </geometry>
      <material name="">
        <color rgba="0.79216 0.81961 0.93333 1"/>
      </material>
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="meshes/gripper/gripper_inspire_right_link_1.stl"/>
      </geometry>
    </collision>
  </link>
  <joint name="gripper_inspire_right_joint_1" type="prismatic">
    <origin rpy="3.141592653589793 -1.5707963267948966 3.141592653589793" xyz="0.034907 -0.009 0.12953"/>
    <parent link="gripper_inspire_body_link"/>
    <child link="gripper_inspire_right_link_1"/>
    <axis xyz="0.00597 0 0.99998"/>
    <limit effort="0" lower="0" upper="0.035" velocity="0"/>
    <!-- mimic not supported in isaac sim 2023.1.0-hotfix  -->
    <!-- <mimic joint="${name}_left_joint_1" multiplier="-1" offset="0" /> -->
  </joint>
Hermanye996 commented 9 months ago
<axis xyz="0.00597 0 0.99998"/>

urdf_kinematics_parser.py

        elif joint_type == "prismatic":
            if joint_axis[0] == 1:
                joint_type = JointType.X_PRISM
            if joint_axis[1] == 1:
                joint_type = JointType.Y_PRISM
            if joint_axis[2] == 1:
                joint_type = JointType.Z_PRISM
            if joint_axis[0] == -1:
                joint_type = JointType.X_PRISM_NEG
            if joint_axis[1] == -1:
                joint_type = JointType.Y_PRISM_NEG
            if joint_axis[2] == -1:
                joint_type = JointType.Z_PRISM_NEG

my axis is not 1 or -1, that's it.

balakumar-s commented 8 months ago

cuRobo does not support arbitrary axis. It should be 1 or -1.

Hermanye996 commented 8 months ago

Thanks for the helpful advice. @balakumar-s

balakumar-s commented 8 months ago

From the urdf, it looks like you could approximate the axis to 1 since it's very close numerically.

Hermanye996 commented 8 months ago

Yeah, that's what I have done, thanks a lot.

GuoPingPan commented 1 month ago

@balakumar-s Dear Bro. How can I deal with the situation that the axis must be arbitrary?