Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 2 additions & 1 deletion examples/fr3/fr3_direct_control.py
Original file line number Diff line number Diff line change
Expand Up @@ -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())
Expand Down
3 changes: 2 additions & 1 deletion examples/so101/so101_env_cartesian_control.py
Original file line number Diff line number Diff line change
Expand Up @@ -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()
Expand Down
3 changes: 2 additions & 1 deletion examples/so101/so101_env_joint_control.py
Original file line number Diff line number Diff line change
Expand Up @@ -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()
Expand Down
3 changes: 2 additions & 1 deletion examples/ur5e/ur5e_env_cartesian_control.py
Original file line number Diff line number Diff line change
Expand Up @@ -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()
Expand Down
3 changes: 2 additions & 1 deletion examples/ur5e/ur5e_env_joint_control.py
Original file line number Diff line number Diff line change
Expand Up @@ -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"

Expand Down
3 changes: 2 additions & 1 deletion examples/xarm7/xarm7_env_cartesian_control.py
Original file line number Diff line number Diff line change
Expand Up @@ -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,
Expand Down
3 changes: 2 additions & 1 deletion examples/xarm7/xarm7_env_joint_control.py
Original file line number Diff line number Diff line change
Expand Up @@ -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,
Expand Down
13 changes: 7 additions & 6 deletions python/rcs/envs/utils.py
Original file line number Diff line number Diff line change
Expand Up @@ -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


Expand Down
Loading