Vì sao URDF chưa đủ?
URDF mô tả kinematic tree, joint limits, visual mesh và collision mesh, nhưng cuRobo cần thêm hai lớp dữ liệu để chạy nhanh trên GPU: collision spheres cho từng link và self-collision ignore matrix. Tài liệu cuRobo gọi RobotBuilder để fit spheres, tính cặp link nào có thể bỏ qua, rồi xuất YAML hoặc XRDF cho các module FK, IK, motion planning và MPC.
Chuẩn bị URDF
Trước khi chạy builder, kiểm tra ba thứ:
- Joint axis đúng chiều.
- Mesh path không phụ thuộc workspace ROS 2 local.
- Collision mesh đủ đơn giản, hoặc visual mesh có thể fit sphere ổn.
Một cấu trúc sạch:
my_arm_description/
urdf/my_arm.urdf
meshes/base.stl
meshes/link1.stl
meshes/link2.stl
Nếu URDF dùng package://my_arm_description/meshes/link1.stl, đặt --asset-path vào thư mục cha chứa my_arm_description.
Chạy 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
Viewer Viser mặc định ở http://localhost:8080. Trên Jetson headless, forward port qua SSH:
ssh -L 8080:localhost:8080 robot@jetson
Đọc metric sphere fitting
Đừng chỉ nhìn "created successfully". Hãy đọc bảng per-link:
| Metric | Ý nghĩa | Hành động |
|---|---|---|
cover% |
Mesh được spheres phủ bao nhiêu | Thấp quá thì tăng sphere density |
protr% |
Spheres lồi ra ngoài mesh | Cao quá thì tăng protrusion weight |
gap_mm |
Khoảng hở lớn nhất | Gap lớn ở gripper/finger rất nguy hiểm |
vol_ratio |
Thể tích spheres so với mesh | Quá lớn gây false collision |
Với robot arm công nghiệp, false collision ở base và wrist là lỗi thường gặp. Dùng clipping nếu base spheres chạm mặt bàn:
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
Self-collision matrix không phải giấy phép bỏ qua safety
Self-collision ignore matrix giúp planner không kiểm tra các cặp link luôn liền kề hoặc không thể va chạm trong không gian joint hợp lệ. Nhưng nếu URDF sai limit, matrix sẽ sai. Trước khi tin matrix, random sample joint positions và render link pairs ở các posture cực trị: elbow folded, wrist rotated, gripper near forearm.
Tiêu chí pass/fail
Một config arm nên pass các check sau:
- FK của cuRobo trùng với TF/URDF viewer trong sai số nhỏ.
- IK về home pose, pre-grasp pose và 5 pose biên workspace đều thành công.
- Self-collision checker phát hiện posture gập tay có va chạm thật.
- Base/table không gây false positive khi robot ở home.
- Config YAML được commit cùng URDF version hoặc artifact hash.
Kết luận
Robot model là nền móng của toàn bộ stack cuRobo. Nếu sphere fitting sai, mọi planner phía sau sẽ hoặc quá bảo thủ, hoặc nguy hiểm. Bài tiếp theo sẽ dùng config này để kiểm tra FK/IK và chuẩn hóa convention quaternion, frame, joint order.

