## ## 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: "${ASSETS_DIR}/miscs/curobo/R5a/R5a/R5a.usd" usd_robot_root: "/robot" isaac_usd_path: "" usd_flip_joints: {} usd_flip_joint_limits: [] urdf_path: "${ASSETS_DIR}/miscs/curobo/R5a/R5a.urdf" asset_root_path: "robot" base_link: "base_link" ee_link: "link6" extra_links: {"attached_object":{"parent_link_name": "link6" , "link_name": "attached_object", "fixed_transform": [0,0,0,1,0,0,0], "joint_type":"FIXED", "joint_name": "attach_joint" }} collision_link_names: [ "base_link", "link1", "link2", "link3", "link4", "link5", "link6", "link7", "link8", "attached_object", ] collision_spheres: link1: - "center": [-0.002, 0.003, 0.037] "radius": 0.02 base_link: - "center": [-0.003, -0.0, 0.036] "radius": 0.02 link2: - "center": [-0.008, 0.0, -0.001] "radius": 0.02929 - "center": [-0.264, -0.001, 0.01] "radius": 0.02864 - "center": [-0.272, 0.003, -0.009] "radius": 0.02602 - "center": [-0.178, 0.002, -0.002] "radius": 0.02733 - "center": [-0.1, -0.003, -0.005] "radius": 0.0208 link3: - "center": [0.025, 0.001, -0.063] "radius": 0.02861 - "center": [0.085, -0.003, -0.062] "radius": 0.02274 - "center": [0.165, -0.008, -0.057] "radius": 0.02144 - "center": [-0.005, -0.019, -0.014] "radius": 0.02013 - "center": [0.091, -0.004, -0.072] "radius": 0.01883 - "center": [0.239, 0.012, -0.073] "radius": 0.01883 link4: - "center": [0.016, -0.001, 0.001] "radius": 0.02437 - "center": [0.071, 0.003, -0.052] "radius": 0.02302 link5: - "center": [-0.002, 0.006, 0.021] "radius": 0.02754 - "center": [0.003, 0.009, 0.08] "radius": 0.02697 link6: - "center": [0.055, 0.001, -0.001] "radius": 0.02822 - "center": [0.035, -0.001, -0.0] "radius": 0.02587 link7: - "center": [0.036, -0.015, -0.006] "radius": 0.0137 - "center": [-0.007, -0.003, -0.011] "radius": 0.0137 link8: - "center": [0.039, 0.016, -0.005] "radius": 0.0137 - "center": [-0.007, 0.002, -0.009] "radius": 0.0137 collision_sphere_buffer: 0.004 extra_collision_spheres: {"attached_object": 4} self_collision_ignore: { "base_link": ["link1", "link2", "link3", "link4", "link5", "link6", "link7", "link8", "attached_object"], "link1": ["link2", "link3", "link4", "link5", "link6", "link7", "link8", "attached_object"], "link2": ["link3", "link4", "link5", "link6", "link7", "link8", "attached_object"], "link3": ["link4", "link5", "link6", "link7", "link8", "attached_object"], "link4": ["link5", "link6", "link7", "link8", "attached_object"], "link5": ["link6", "link7", "link8", "attached_object"], "link6": ["link7", "link8", "attached_object"], "link7": ["link8", "attached_object"] } self_collision_buffer: { "base_link": 0.1, "link1": 0.05, "link2": 0.05, "link3": 0.05, "link4": 0.05, "link5": 0.05, "link6": 0.05, "link7": 0.02, "link8": 0.02, "attached_object": 0.0, } use_global_cumul: True mesh_link_names: [ "base_link", "link1", "link2", "link3", "link4", "link5", "link6", "link7", "link8" ] external_asset_path: null # Use this to add path for externally located assets/robot folder. lock_joints: {"joint7": 0.044, "joint8": 0.044} cspace: joint_names: ["joint1","joint2","joint3","joint4", "joint5", "joint6","joint7","joint8"] # retract_config: [0.0, 0.35, -0.35, 0.0, 0.0, 0.0, 0.0, 0.0] retract_config: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0] null_space_weight: [1,1,1,1,1,1,1,1] cspace_distance_weight: [1,1,1,1,1,1,1,1] max_acceleration: 15.0 max_jerk: 500.0