NVlabs / curobo

CUDA Accelerated Robot Library
https://curobo.org
Other
798 stars 125 forks source link

Bug: Error when loading URDF for mobile robot #341

Open brennand opened 4 months ago

brennand commented 4 months ago
  1. cuRobo installation mode: docker via isaac_ros_common/docker/Dockerfile.ros2_humble - branch: 855d408
  2. python version: 3.10.12
  3. curobo: isaac_ros_cumotion via branch: 3bfed9d
  4. start via: ros2 run isaac_ros_cumotion cumotion_planner_node --ros-args -p robot:=kr1.xrdf -p urdf_path:=kr1.urdf

There is an error in the _build_kinematics_with_lock_joints() function when you load a robot with joints that are not fixed and also not in the robot arm.

  File "/home/bren/ws_humanoid/build/curobo_core/curobo/src/curobo/cuda_robot_model/cuda_robot_generator.py", line 527, in _build_kinematics_with_lock_joints
    if "mimic" in joint_data[k]:
KeyError: 'left_wheel_joint'

I can solve this with this modified code:

        for k in lock_joint_names:
            if k in joint_data:
                    mimic_link_names = [[x["parent"], x["child"]] for x in joint_data[k]["mimic"]]
                    mimic_link_names = [x for xs in mimic_link_names for x in xs]
                    lock_links += mimic_link_names

This then leads to some other problem that I managed to solve, but as I don't 100% know what this code is doing I haven't created a pull request.

With a print statement this is the joints in the 2 dicts:

self.joint_names:  ['arm_joint_1', 'arm_joint_2', 'arm_joint_3', 'arm_joint_4', 'arm_joint_5', 'arm_joint_6', 'arm_joint_7']
joint_data: {}
lock_joint_names:  ['left_wheel_joint', 'right_wheel_joint', 'torso_joint_1', 'torso_joint_2', 'gripper_motor_joint']

My kr1.xrdf file:

format: xrdf
format_version: 1.0

modifiers:
  - set_base_frame: "right_arm_base_link"

default_joint_positions:
  arm_joint_1: 0.8508
  arm_joint_2: -1.0055
  arm_joint_3: -1.4077
  arm_joint_4: -2.1193
  arm_joint_5: 2.8
  arm_joint_6: 0.8199
  arm_joint_7: 0.0

cspace:
  joint_names:
    - "arm_joint_1"
    - "arm_joint_2"
    - "arm_joint_3"
    - "arm_joint_4"
    - "arm_joint_5"
    - "arm_joint_6"
    - "arm_joint_7"
  acceleration_limits: [12.0, 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, 500.0]

tool_frames: ["arm_link_7"]
balakumar-s commented 3 months ago

Is it possible for you to share the urdf?

brennand commented 3 months ago

Hello @balakumar-s, I got it working by making a very simple URDF for just the arm. But I have attached the full robot urdf.

kr1.zip