|
1 | 1 | import logging |
| 2 | +from time import sleep |
2 | 3 |
|
| 4 | +from rcs._core.common import RobotPlatform |
3 | 5 | from rcs.envs.base import ControlMode, RelativeTo |
4 | 6 | from rcs.envs.creators import SimEnvCreator |
| 7 | +from rcs_xarm7.creators import RCSXArm7EnvCreator |
5 | 8 |
|
6 | 9 | import rcs |
7 | 10 | from rcs import sim |
8 | 11 |
|
9 | 12 | logger = logging.getLogger(__name__) |
10 | 13 | logger.setLevel(logging.INFO) |
11 | 14 |
|
| 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 | + |
12 | 29 |
|
13 | 30 | def main(): |
14 | 31 |
|
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() |
49 | 75 | obs, info = env_rel.reset() |
50 | 76 |
|
51 | 77 | for _ in range(100): |
52 | 78 | for _ in range(10): |
53 | 79 | # 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]} |
55 | 81 | obs, reward, terminated, truncated, info = env_rel.step(act) |
56 | | - if truncated or terminated: |
57 | | - logger.info("Truncated or terminated!") |
58 | | - return |
59 | 82 | for _ in range(10): |
60 | 83 | # 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]} |
62 | 85 | obs, reward, terminated, truncated, info = env_rel.step(act) |
63 | | - if truncated or terminated: |
64 | | - logger.info("Truncated or terminated!") |
65 | | - return |
66 | 86 |
|
67 | 87 |
|
68 | 88 | if __name__ == "__main__": |
|
0 commit comments