Skip to content

Commit 30f9521

Browse files
committed
docs(example): moved xarm examples to example folder
- moved xarm examples to example folder - fixed types in linting
1 parent 48fe542 commit 30f9521

8 files changed

Lines changed: 127 additions & 275 deletions

File tree

.gitignore

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -17,3 +17,4 @@ config.h
1717
wheels
1818
.env
1919
settings.json
20+
*.egg-info

examples/xarm7/xarm7_env_cartesian_control.py

Lines changed: 62 additions & 42 deletions
Original file line numberDiff line numberDiff line change
@@ -1,68 +1,88 @@
11
import logging
2+
from time import sleep
23

4+
from rcs._core.common import RobotPlatform
35
from rcs.envs.base import ControlMode, RelativeTo
46
from rcs.envs.creators import SimEnvCreator
7+
from rcs_xarm7.creators import RCSXArm7EnvCreator
58

69
import rcs
710
from rcs import sim
811

912
logger = logging.getLogger(__name__)
1013
logger.setLevel(logging.INFO)
1114

15+
"""
16+
The example shows how to create a xArm7 environment with Cartesian control
17+
and a relative action space. The example works both with a real robot and in
18+
simulation.
19+
20+
To test with a real robot, set ROBOT_INSTANCE to RobotPlatform.HARDWARE,
21+
install the rcs_xarm7 extension (`pip install extensions/rcs_xarm7`)
22+
and set the ROBOT_IP variable to the robot's IP address.
23+
"""
24+
25+
ROBOT_IP = "192.168.1.245"
26+
ROBOT_INSTANCE = RobotPlatform.SIMULATION
27+
# ROBOT_INSTANCE = RobotPlatform.HARDWARE
28+
1229

1330
def main():
1431

15-
robot_cfg = sim.SimRobotConfig()
16-
robot_cfg.actuators = [
17-
"act1",
18-
"act2",
19-
"act3",
20-
"act4",
21-
"act5",
22-
"act6",
23-
"act7",
24-
]
25-
robot_cfg.joints = [
26-
"joint1",
27-
"joint2",
28-
"joint3",
29-
"joint4",
30-
"joint5",
31-
"joint6",
32-
"joint7",
33-
]
34-
robot_cfg.base = "base"
35-
robot_cfg.robot_type = rcs.common.RobotType.XArm7
36-
robot_cfg.attachment_site = "attachment_site"
37-
robot_cfg.arm_collision_geoms = []
38-
robot_cfg.mjcf_scene_path = rcs.scenes["xarm7_empty_world"].mjb
39-
robot_cfg.kinematic_model_path = rcs.scenes["xarm7_empty_world"].mjcf_robot
40-
env_rel = SimEnvCreator()(
41-
robot_cfg=robot_cfg,
42-
control_mode=ControlMode.CARTESIAN_TQuat,
43-
gripper_cfg=None,
44-
# cameras=default_mujoco_cameraset_cfg(),
45-
max_relative_movement=0.5,
46-
relative_to=RelativeTo.LAST_STEP,
47-
)
48-
env_rel.get_wrapper_attr("sim").open_gui()
32+
if ROBOT_INSTANCE == RobotPlatform.HARDWARE:
33+
env_rel = RCSXArm7EnvCreator()(
34+
control_mode=ControlMode.CARTESIAN_TQuat,
35+
ip=ROBOT_IP,
36+
relative_to=RelativeTo.LAST_STEP,
37+
max_relative_movement=0.5,
38+
)
39+
else:
40+
robot_cfg = sim.SimRobotConfig()
41+
robot_cfg.actuators = [
42+
"act1",
43+
"act2",
44+
"act3",
45+
"act4",
46+
"act5",
47+
"act6",
48+
"act7",
49+
]
50+
robot_cfg.joints = [
51+
"joint1",
52+
"joint2",
53+
"joint3",
54+
"joint4",
55+
"joint5",
56+
"joint6",
57+
"joint7",
58+
]
59+
robot_cfg.base = "base"
60+
robot_cfg.robot_type = rcs.common.RobotType.XArm7
61+
robot_cfg.attachment_site = "attachment_site"
62+
robot_cfg.arm_collision_geoms = []
63+
robot_cfg.mjcf_scene_path = rcs.scenes["xarm7_empty_world"].mjb
64+
robot_cfg.kinematic_model_path = rcs.scenes["xarm7_empty_world"].mjcf_robot
65+
env_rel = SimEnvCreator()(
66+
robot_cfg=robot_cfg,
67+
control_mode=ControlMode.CARTESIAN_TQuat,
68+
gripper_cfg=None,
69+
# cameras=default_mujoco_cameraset_cfg(),
70+
max_relative_movement=0.5,
71+
relative_to=RelativeTo.LAST_STEP,
72+
)
73+
sleep(3) # wait for gui to open
74+
env_rel.get_wrapper_attr("sim").open_gui()
4975
obs, info = env_rel.reset()
5076

5177
for _ in range(100):
5278
for _ in range(10):
5379
# move 1cm in x direction (forward) and close gripper
54-
act = {"tquat": [0.01, 0, 0, 0, 0, 0, 1], "gripper": 0}
80+
act = {"tquat": [0.01, 0, 0, 0, 0, 0, 1]}
5581
obs, reward, terminated, truncated, info = env_rel.step(act)
56-
if truncated or terminated:
57-
logger.info("Truncated or terminated!")
58-
return
5982
for _ in range(10):
6083
# move 1cm in negative x direction (backward) and open gripper
61-
act = {"tquat": [-0.01, 0, 0, 0, 0, 0, 1], "gripper": 1}
84+
act = {"tquat": [-0.01, 0, 0, 0, 0, 0, 1]}
6285
obs, reward, terminated, truncated, info = env_rel.step(act)
63-
if truncated or terminated:
64-
logger.info("Truncated or terminated!")
65-
return
6686

6787

6888
if __name__ == "__main__":

examples/xarm7/xarm7_env_joint_control.py

Lines changed: 60 additions & 37 deletions
Original file line numberDiff line numberDiff line change
@@ -1,61 +1,84 @@
11
import logging
2+
from time import sleep
23

34
import numpy as np
5+
from rcs._core.common import RobotPlatform
46
from rcs.envs.base import ControlMode, RelativeTo
57
from rcs.envs.creators import SimEnvCreator
8+
from rcs_xarm7.creators import RCSXArm7EnvCreator
69

710
import rcs
811
from rcs import sim
912

1013
logger = logging.getLogger(__name__)
1114
logger.setLevel(logging.INFO)
1215

16+
"""
17+
The example shows how to create a xArm7 environment with joint control
18+
and a relative action space. The example works both with a real robot and in
19+
simulation.
20+
21+
To test with a real robot, set ROBOT_INSTANCE to RobotPlatform.HARDWARE,
22+
install the rcs_xarm7 extension (`pip install extensions/rcs_xarm7`)
23+
and set the ROBOT_IP variable to the robot's IP address.
24+
"""
25+
26+
ROBOT_IP = "192.168.1.245"
27+
ROBOT_INSTANCE = RobotPlatform.SIMULATION
28+
# ROBOT_INSTANCE = RobotPlatform.HARDWARE
29+
1330

1431
def main():
15-
robot_cfg = sim.SimRobotConfig()
16-
robot_cfg.actuators = [
17-
"act1",
18-
"act2",
19-
"act3",
20-
"act4",
21-
"act5",
22-
"act6",
23-
"act7",
24-
]
25-
robot_cfg.joints = [
26-
"joint1",
27-
"joint2",
28-
"joint3",
29-
"joint4",
30-
"joint5",
31-
"joint6",
32-
"joint7",
33-
]
34-
robot_cfg.base = "base"
35-
robot_cfg.robot_type = rcs.common.RobotType.XArm7
36-
robot_cfg.attachment_site = "attachment_site"
37-
robot_cfg.arm_collision_geoms = []
38-
robot_cfg.mjcf_scene_path = rcs.scenes["xarm7_empty_world"].mjb
39-
robot_cfg.kinematic_model_path = rcs.scenes["xarm7_empty_world"].mjcf_robot
40-
env_rel = SimEnvCreator()(
41-
robot_cfg=robot_cfg,
42-
control_mode=ControlMode.JOINTS,
43-
gripper_cfg=None,
44-
# cameras=default_mujoco_cameraset_cfg(),
45-
max_relative_movement=np.deg2rad(5),
46-
relative_to=RelativeTo.LAST_STEP,
47-
)
48-
env_rel.get_wrapper_attr("sim").open_gui()
32+
if ROBOT_INSTANCE == RobotPlatform.HARDWARE:
33+
env_rel = RCSXArm7EnvCreator()(
34+
control_mode=ControlMode.JOINTS,
35+
ip=ROBOT_IP,
36+
relative_to=RelativeTo.LAST_STEP,
37+
max_relative_movement=np.deg2rad(5),
38+
)
39+
else:
40+
robot_cfg = sim.SimRobotConfig()
41+
robot_cfg.actuators = [
42+
"act1",
43+
"act2",
44+
"act3",
45+
"act4",
46+
"act5",
47+
"act6",
48+
"act7",
49+
]
50+
robot_cfg.joints = [
51+
"joint1",
52+
"joint2",
53+
"joint3",
54+
"joint4",
55+
"joint5",
56+
"joint6",
57+
"joint7",
58+
]
59+
robot_cfg.base = "base"
60+
robot_cfg.robot_type = rcs.common.RobotType.XArm7
61+
robot_cfg.attachment_site = "attachment_site"
62+
robot_cfg.arm_collision_geoms = []
63+
robot_cfg.mjcf_scene_path = rcs.scenes["xarm7_empty_world"].mjb
64+
robot_cfg.kinematic_model_path = rcs.scenes["xarm7_empty_world"].mjcf_robot
65+
env_rel = SimEnvCreator()(
66+
robot_cfg=robot_cfg,
67+
control_mode=ControlMode.JOINTS,
68+
gripper_cfg=None,
69+
# cameras=default_mujoco_cameraset_cfg(),
70+
max_relative_movement=np.deg2rad(5),
71+
relative_to=RelativeTo.LAST_STEP,
72+
)
73+
env_rel.get_wrapper_attr("sim").open_gui()
74+
sleep(3) # wait for gui to open
4975

5076
for _ in range(100):
5177
obs, info = env_rel.reset()
5278
for _ in range(10):
5379
# sample random relative action and execute it
5480
act = env_rel.action_space.sample()
5581
obs, reward, terminated, truncated, info = env_rel.step(act)
56-
if truncated or terminated:
57-
logger.info("Truncated or terminated!")
58-
return
5982

6083

6184
if __name__ == "__main__":

extensions/rcs_xarm7/src/rcs_xarm7/creators.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -19,13 +19,13 @@
1919
RobotEnv,
2020
)
2121
from rcs.envs.creators import RCSHardwareEnvCreator
22-
from rcs.envs.sim import CollisionGuard, GripperWrapperSim, RobotSimWrapper, SimWrapper
22+
from rcs.envs.sim import GripperWrapperSim, RobotSimWrapper, SimWrapper
2323
from rcs.hand.tilburg_hand import THConfig, TilburgHand
2424
from rcs.sim import SimCameraConfig, SimGripperConfig, SimRobotConfig
2525
from rcs_xarm7.hw import XArm7
2626

2727
import rcs
28-
from rcs import common, sim
28+
from rcs import sim
2929

3030
logger = logging.getLogger(__name__)
3131
logger.setLevel(logging.INFO)

extensions/rcs_xarm7/src/rcs_xarm7/env_cartesian_control.py

Lines changed: 0 additions & 107 deletions
This file was deleted.

0 commit comments

Comments
 (0)