Files
gen_data_curobo/src/curobo/content/configs/robot/ur5e.yml
Balakumar Sundaralingam 58958bbcce update to 0.6.2
2023-12-15 02:01:33 -08:00

126 lines
4.1 KiB
YAML

##
## Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
##
## NVIDIA CORPORATION, its affiliates and licensors retain all intellectual
## property and proprietary rights in and to this material, related
## documentation and any modifications thereto. Any use, reproduction,
## disclosure or distribution of this material and related documentation
## without an express license agreement from NVIDIA CORPORATION or
## its affiliates is strictly prohibited.
##
robot_cfg:
kinematics:
usd_path: "robot/ur_description/ur5e.usd"
usd_robot_root: "/robot"
isaac_usd_path: ""
usd_flip_joints: {}
usd_flip_joint_limits: []
urdf_path: "robot/ur_description/ur5e.urdf"
asset_root_path: "robot/ur_description"
base_link: "base_link"
ee_link: "tool0"
link_names: null
lock_joints: null
extra_links: null
collision_link_names: ['shoulder_link','upper_arm_link', 'forearm_link', 'wrist_1_link',
'wrist_2_link' ,'wrist_3_link', 'tool0'] # List[str]
collision_spheres:
shoulder_link:
- "center": [0.0, 0.0, 0.0]
"radius": 0.1
upper_arm_link:
- "center": [-0.416, -0.0, 0.143]
"radius": 0.078
- "center": [-0.015, 0.0, 0.134]
"radius": 0.077
- "center": [-0.14, 0.0, 0.138]
"radius": 0.062
- "center": [-0.285, -0.001, 0.139]
"radius": 0.061
- "center": [-0.376, 0.001, 0.138]
"radius": 0.077
- "center": [-0.222, 0.001, 0.139]
"radius": 0.061
- "center": [-0.055, 0.008, 0.14]
"radius": 0.07
- "center": [-0.001, -0.002, 0.143]
"radius": 0.076
forearm_link:
- "center": [-0.01, 0.002, 0.031]
"radius": 0.072
- "center": [-0.387, 0.0, 0.014]
"radius": 0.057
- "center": [-0.121, -0.0, 0.006]
"radius": 0.057
- "center": [-0.206, 0.001, 0.007]
"radius": 0.057
- "center": [-0.312, -0.001, 0.006]
"radius": 0.056
- "center": [-0.057, 0.003, 0.008]
"radius": 0.065
- "center": [-0.266, 0.0, 0.006]
"radius": 0.057
- "center": [-0.397, -0.001, -0.018]
"radius": 0.052
- "center": [-0.164, -0.0, 0.007]
"radius": 0.057
wrist_1_link:
- "center": [-0.0, 0.0, -0.009]
"radius": 0.047
- "center": [-0.0, 0.0, -0.052]
"radius": 0.047
- "center": [-0.002, 0.027, -0.001]
"radius": 0.045
- "center": [0.001, -0.01, 0.0]
"radius": 0.046
wrist_2_link:
- "center": [0.0, -0.01, -0.001]
"radius": 0.047
- "center": [0.0, 0.008, -0.001]
"radius": 0.047
- "center": [0.001, -0.001, -0.036]
"radius": 0.047
- "center": [0.001, -0.03, -0.0]
"radius": 0.047
wrist_3_link:
- "center": [0.001, 0.001, -0.029]
"radius": 0.043
tool0:
- "center": [0.001, 0.001, 0.05]
"radius": 0.05
collision_sphere_buffer: 0.005
extra_collision_spheres: {}
self_collision_ignore: {
"upper_arm_link": ["forearm_link", "shoulder_link"],
"forearm_link": ["wrist_1_link", "wrist_2_link", "wrist_3_link"],
"wrist_1_link": ["wrist_2_link","wrist_3_link","tool0"],
"wrist_2_link": ["wrist_3_link", "tool0"],
"wrist_3_link": ["tool0"],
}
self_collision_buffer: {'upper_arm_link': 0,
'forearm_link': 0,
'wrist_1_link': 0,
'wrist_2_link': 0,
'wrist_3_link' : 0,
}
use_global_cumul: True
mesh_link_names: ['shoulder_link','upper_arm_link', 'forearm_link', 'wrist_1_link',
'wrist_2_link' ,'wrist_3_link'] # List[str]
cspace:
joint_names: ['shoulder_pan_joint', 'shoulder_lift_joint', 'elbow_joint', 'wrist_1_joint', 'wrist_2_joint', 'wrist_3_joint']
retract_config: [0.0, -2.2, 1.9, -1.383, -1.57, 0.00]
null_space_weight: [1.0, 1.0, 1.0, 1.0, 1.0, 1.0]
cspace_distance_weight: [1.0, 1.0, 1.0, 1.0, 1.0, 1.0]
max_jerk: 500.0
max_acceleration: 12.0
position_limit_clip: 0.1