diff --git a/examples/fr3/fr3_direct_control.py b/examples/fr3/fr3_direct_control.py index 2ce8b7d5..ae3683f3 100644 --- a/examples/fr3/fr3_direct_control.py +++ b/examples/fr3/fr3_direct_control.py @@ -60,7 +60,8 @@ def main(): robot: rcs.common.Robot gripper: rcs.common.Gripper if ROBOT_INSTANCE == RobotPlatform.SIMULATION: - simulation = sim.Sim(rcs.scenes["fr3_empty_world"].mjb) + scene = rcs.scenes["fr3_empty_world"] + simulation = sim.Sim(scene.mjb or scene.mjcf_scene) robot_cfg = sim.SimRobotConfig() robot_cfg.add_id("0") robot_cfg.tcp_offset = rcs.common.Pose(rcs.common.FrankaHandTCPOffset()) diff --git a/examples/so101/so101_env_cartesian_control.py b/examples/so101/so101_env_cartesian_control.py index 19c9e4e7..051cc540 100644 --- a/examples/so101/so101_env_cartesian_control.py +++ b/examples/so101/so101_env_cartesian_control.py @@ -25,7 +25,8 @@ def main(): robot_cfg.robot_type = rcs.common.RobotType.SO101 robot_cfg.attachment_site = "gripper" robot_cfg.arm_collision_geoms = [] - robot_cfg.mjcf_scene_path = rcs.scenes["so101_empty_world"].mjb + scene = rcs.scenes["so101_empty_world"] + robot_cfg.mjcf_scene_path = scene.mjb or scene.mjcf_scene robot_cfg.kinematic_model_path = rcs.scenes["so101_empty_world"].mjcf_robot gripper_cfg = sim.SimGripperConfig() diff --git a/examples/so101/so101_env_joint_control.py b/examples/so101/so101_env_joint_control.py index 2b3b1956..580fd5be 100644 --- a/examples/so101/so101_env_joint_control.py +++ b/examples/so101/so101_env_joint_control.py @@ -26,7 +26,8 @@ def main(): robot_cfg.robot_type = rcs.common.RobotType.SO101 robot_cfg.attachment_site = "gripper" robot_cfg.arm_collision_geoms = [] - robot_cfg.mjcf_scene_path = rcs.scenes["so101_empty_world"].mjb + scene = rcs.scenes["so101_empty_world"] + robot_cfg.mjcf_scene_path = scene.mjb or scene.mjcf_scene robot_cfg.kinematic_model_path = rcs.scenes["so101_empty_world"].mjcf_robot gripper_cfg = sim.SimGripperConfig() diff --git a/examples/ur5e/ur5e_env_cartesian_control.py b/examples/ur5e/ur5e_env_cartesian_control.py index f0a3eefb..97cc9edb 100644 --- a/examples/ur5e/ur5e_env_cartesian_control.py +++ b/examples/ur5e/ur5e_env_cartesian_control.py @@ -44,7 +44,8 @@ def main(): robot_sim_cfg.robot_type = rcs.common.RobotType.UR5e robot_sim_cfg.attachment_site = "attachment_site" robot_sim_cfg.arm_collision_geoms = [] - robot_sim_cfg.mjcf_scene_path = rcs.scenes["ur5e_empty_world"].mjb + scene = rcs.scenes["ur5e_empty_world"] + robot_sim_cfg.mjcf_scene_path = scene.mjb or scene.mjcf_scene robot_sim_cfg.kinematic_model_path = rcs.scenes["ur5e_empty_world"].mjcf_robot robot_sim_cfg.base = "base" robot_sim_cfg.tcp_offset = rcs.common.Pose() diff --git a/examples/ur5e/ur5e_env_joint_control.py b/examples/ur5e/ur5e_env_joint_control.py index 5177d380..7caee7e2 100644 --- a/examples/ur5e/ur5e_env_joint_control.py +++ b/examples/ur5e/ur5e_env_joint_control.py @@ -45,7 +45,8 @@ def main(): robot_sim_cfg.robot_type = rcs.common.RobotType.UR5e robot_sim_cfg.attachment_site = "attachment_site" robot_sim_cfg.arm_collision_geoms = [] - robot_sim_cfg.mjcf_scene_path = rcs.scenes["ur5e_empty_world"].mjb + scene = rcs.scenes["ur5e_empty_world"] + robot_sim_cfg.mjcf_scene_path = scene.mjb or scene.mjcf_scene robot_sim_cfg.kinematic_model_path = rcs.scenes["ur5e_empty_world"].mjcf_robot robot_sim_cfg.base = "base" diff --git a/examples/xarm7/xarm7_env_cartesian_control.py b/examples/xarm7/xarm7_env_cartesian_control.py index 9bf3e50c..91cce45a 100644 --- a/examples/xarm7/xarm7_env_cartesian_control.py +++ b/examples/xarm7/xarm7_env_cartesian_control.py @@ -60,7 +60,8 @@ def main(): robot_cfg.robot_type = rcs.common.RobotType.XArm7 robot_cfg.attachment_site = "attachment_site" robot_cfg.arm_collision_geoms = [] - robot_cfg.mjcf_scene_path = rcs.scenes["xarm7_empty_world"].mjb + scene = rcs.scenes["xarm7_empty_world"] + robot_cfg.mjcf_scene_path = scene.mjb or scene.mjcf_scene robot_cfg.kinematic_model_path = rcs.scenes["xarm7_empty_world"].mjcf_robot env_rel = SimEnvCreator()( robot_cfg=robot_cfg, diff --git a/examples/xarm7/xarm7_env_joint_control.py b/examples/xarm7/xarm7_env_joint_control.py index 5b98abdd..9cfcc17b 100644 --- a/examples/xarm7/xarm7_env_joint_control.py +++ b/examples/xarm7/xarm7_env_joint_control.py @@ -60,7 +60,8 @@ def main(): robot_cfg.robot_type = rcs.common.RobotType.XArm7 robot_cfg.attachment_site = "attachment_site" robot_cfg.arm_collision_geoms = [] - robot_cfg.mjcf_scene_path = rcs.scenes["xarm7_empty_world"].mjb + scene = rcs.scenes["xarm7_empty_world"] + robot_cfg.mjcf_scene_path = scene.mjb or scene.mjcf_scene robot_cfg.kinematic_model_path = rcs.scenes["xarm7_empty_world"].mjcf_robot env_rel = SimEnvCreator()( robot_cfg=robot_cfg, diff --git a/python/rcs/envs/utils.py b/python/rcs/envs/utils.py index 1d440098..f756670f 100644 --- a/python/rcs/envs/utils.py +++ b/python/rcs/envs/utils.py @@ -17,15 +17,16 @@ def default_sim_robot_cfg(scene: str = "fr3_empty_world", idx: str = "0") -> sim.SimRobotConfig: robot_cfg = rcs.sim.SimRobotConfig() - robot_cfg.robot_type = rcs.scenes[scene].robot_type + scene_cfg = rcs.scenes[scene] + robot_cfg.robot_type = scene_cfg.robot_type robot_cfg.tcp_offset = common.Pose(common.FrankaHandTCPOffset()) robot_cfg.add_id(idx) - if rcs.scenes[scene].mjb is not None: - robot_cfg.mjcf_scene_path = rcs.scenes[scene].mjb + if scene_cfg.mjb is not None: + robot_cfg.mjcf_scene_path = scene_cfg.mjb else: - robot_cfg.mjcf_scene_path = rcs.scenes[scene].mjcf_scene - robot_cfg.kinematic_model_path = rcs.scenes[scene].mjcf_robot - # robot_cfg.kinematic_model_path = rcs.scenes[scene].urdf + robot_cfg.mjcf_scene_path = scene_cfg.mjcf_scene + robot_cfg.kinematic_model_path = scene_cfg.mjcf_robot + # robot_cfg.kinematic_model_path = scene_cfg.urdf return robot_cfg