VnRobo
AboutPricingBlogContact
🇻🇳VISign InStart Free Trial
🇻🇳VI
VnRobo logo

AI infrastructure for next-generation industrial robots.

Product

  • Features
  • Pricing
  • Knowledge Base
  • Services

Company

  • About Us
  • Blog
  • Contact

Legal

  • Privacy Policy
  • Terms of Service

© 2026 VnRobo. All rights reserved.

Made with♥in Vietnam
VnRobo
AboutPricingBlogContact
🇻🇳VISign InStart Free Trial
🇻🇳VI
  1. Home
  2. Blog
  3. Building a cuRobo robot model: URDF, collision spheres, and self-collision
manipulationcurobourdfcollisionrobot-armtutorial

Building a cuRobo robot model: URDF, collision spheres, and self-collision

How to convert a robot arm URDF into a usable cuRobo config with mesh paths, sphere fitting, self-collision ignores, clipping, and pass/fail criteria.

Nguyen Anh TuanMay 24, 20263 min readUpdated: Jun 19, 2026
Building a cuRobo robot model: URDF, collision spheres, and self-collision

Why URDF is not enough

URDF gives you the kinematic tree, joint limits, visual meshes, and collision meshes. cuRobo needs two extra layers for fast GPU planning: collision spheres fitted to each link and a self-collision ignore matrix. The official RobotBuilder pipeline generates both and exports a YAML or XRDF config consumed by FK, IK, motion planning, and MPC.

Prepare the URDF

Before running the builder, inspect three things:

  1. Joint axes point in the expected direction.
  2. Mesh paths do not depend on a local ROS 2 workspace.
  3. Collision meshes are simple enough, or visual meshes can be approximated with spheres.

A clean layout:

my_arm_description/
  urdf/my_arm.urdf
  meshes/base.stl
  meshes/link1.stl
  meshes/link2.stl

If the URDF uses package://my_arm_description/meshes/link1.stl, point --asset-path to the parent directory that contains my_arm_description.

Run the builder

python -m curobo.examples.getting_started.build_robot_model \
  --urdf /workspace/my_arm_description/urdf/my_arm.urdf \
  --asset-path /workspace \
  --output /workspace/curobo_configs/my_arm.yml \
  --compute-metrics \
  --visualize

The Viser viewer runs at http://localhost:8080 by default. On a headless Jetson:

ssh -L 8080:localhost:8080 robot@jetson

Read sphere-fitting metrics

Do not stop at "created successfully". Inspect per-link metrics:

Metric Meaning Action
cover% How much of the mesh is covered Increase sphere density if low
protr% Sphere volume outside the mesh Increase protrusion weight if high
gap_mm Largest uncovered gap Dangerous around grippers and fingers
vol_ratio Sphere volume versus mesh volume Too high causes false collisions

False collision near the base and wrist is common. Clip base spheres if they intersect the table:

python -m curobo.examples.getting_started.build_robot_model \
  --urdf /workspace/my_arm_description/urdf/my_arm.urdf \
  --asset-path /workspace \
  --output /workspace/curobo_configs/my_arm.yml \
  --clip-link base_link z 0.0 \
  --sphere-density 1.5 \
  --compute-metrics

The self-collision matrix is not a safety waiver

The ignore matrix skips link pairs that are adjacent or unreachable under valid joint limits. If the URDF limits are wrong, the matrix is wrong. Before trusting it, random-sample joint positions and visualize extreme postures: folded elbow, rotated wrist, and gripper near forearm.

Pass/fail criteria

A robot arm config should pass:

  • cuRobo FK matches TF/URDF visualization within a small tolerance.
  • IK succeeds for home, pre-grasp, and five boundary workspace poses.
  • Self-collision detects truly folded postures.
  • Base/table contact does not create false positives at home.
  • The YAML config is versioned with the URDF revision or artifact hash.

Conclusion

Robot modeling is the foundation. Bad sphere fitting makes every downstream planner either too conservative or unsafe. Next we will validate FK, IK, quaternion convention, frame names, and joint order.

NT

Nguyễn Anh Tuấn

Robotics & AI Engineer. Building VnRobo — sharing knowledge about robot learning, VLA models, and automation.

Khám phá VnRobo

Fleet MonitoringROS 2 IntegrationAMR Solutions

Related Posts

Tutorial
FK và IK trong cuRobo: kiểm tra frame, quaternion và joint order
curoboikfk
manipulation

FK và IK trong cuRobo: kiểm tra frame, quaternion và joint order

Bài thực hành kiểm tra forward kinematics, inverse kinematics, quaternion wxyz, joint order và lỗi frame thường gặp trước khi chạy planner trên robot thật.

5/28/20263 min read
NT
NEWTutorial
Mô hình cánh tay robot: joints, links, URDF, DH, SE(3)
robot-armkinematicsurdfPart 3
manipulation

Mô hình cánh tay robot: joints, links, URDF, DH, SE(3)

Tự điền bảng DH UR5, dựng robot model bằng NumPy/C++ Eigen, rồi đối chiếu với Robotics Toolbox và Pinocchio URDF.

6/13/202616 min read
NT
NEWTutorial
Inverse Kinematics: analytical vs numerical IK
robot-arminverse-kinematicsur5Part 5
manipulation

Inverse Kinematics: analytical vs numerical IK

Tự giải IK UR5 bằng tay, rồi viết solver numerical IK Python/C++ với Jacobian pseudo-inverse, DLS và tránh joint-limit.

6/13/202614 min read
NT
VnRobo logo

AI infrastructure for next-generation industrial robots.

Product

  • Features
  • Pricing
  • Knowledge Base
  • Services

Company

  • About Us
  • Blog
  • Contact

Legal

  • Privacy Policy
  • Terms of Service

© 2026 VnRobo. All rights reserved.

Made with♥in Vietnam