robot_cfg: kinematics: use_usd_kinematics: False usd_path: null usd_robot_root: null isaac_usd_path: null usd_flip_joints: {} usd_flip_joint_limits: {} urdf_path: ${ASSETS_PATH}/assets/embodiments/piper/piper.urdf asset_root_path: null base_link: "base_link" ee_link: "link6" collision_link_names: [ "base_link", "link1", "link2", "link3", "link4", "link5", "link6", "link7", "link8" ] collision_spheres: ${ASSETS_PATH}/assets/embodiments/piper/collision_piper.yml collision_sphere_buffer: 0.004 # 0.0025 extra_collision_spheres: null use_global_cumul: True self_collision_ignore: { "base_link": ["link1", "link2", "link3"], "link1": ["link2", "link3"], "link2": ["link3", "link4"], "link3": ["link4", "link5", "link6", "link7", "link8"], "link4": ["link5", "link6", "link7", "link8"], "link5": ["link6", "link7", "link8"], "link6": ["link7", "link8"], "link7": ["link8"] } self_collision_buffer: { "base_link": 0.0, "link1": 0.0, "link2": 0.0, "link3": 0.0, "link4": 0.0, "link5": 0.0, "link6": 0.0, "link7": 0.0, "link8": 0.0 } #link_names: ["panda_link4"] mesh_link_names: [ "base_link", "link1", "link2", "link3", "link4", "link5", "link6", "link7", "link8" ] lock_joints: {"joint7": 0.0, "joint8": 0.0} extra_links: null cspace: joint_names: ["joint1","joint2","joint3","joint4", "joint5", "joint6","joint7","joint8"] retract_config: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00, 0.0] null_space_weight: [1,1,1,1,1,1,1,1,1] cspace_distance_weight: [1,1,1,1,1,1,1,1,1] max_acceleration: 15.0 max_jerk: 500.0 planner: frame_bias: [0., 0., 0.]