|
1 | 1 | import logging |
2 | 2 |
|
| 3 | +from rcs._core.common import RobotPlatform |
3 | 4 | from rcs.envs.base import ControlMode, RelativeTo |
4 | 5 | from rcs.envs.creators import SimEnvCreator |
5 | 6 | from rcs.envs.utils import ( |
|
11 | 12 | logger = logging.getLogger(__name__) |
12 | 13 | logger.setLevel(logging.INFO) |
13 | 14 |
|
| 15 | +""" |
| 16 | +This script demonstrates how to control the FR3 robot in Cartesian position control mode |
| 17 | +using relative movements. The robot (or its simulation) moves 1cm forward and then 1cm backward |
| 18 | +in a loop while opening and closing the gripper. |
14 | 19 |
|
15 | | -def main(): |
| 20 | +To control a real FR3 robot, install the rcs_fr3 extension (`pip install extensions/rcs_fr3`), |
| 21 | +and set the FR3_IP variable to the robot's IP address. Make sure to unlock the robot's joints and |
| 22 | +put it into FCI mode before running this script. For a scripted way of unlocking and guiding mode see the |
| 23 | +fr3_direct_control.py example which uses the FCI context manager. |
| 24 | +""" |
| 25 | + |
| 26 | +ROBOT_INSTANCE = RobotPlatform.SIMULATION |
| 27 | +FR3_IP = "192.168.101.1" |
16 | 28 |
|
17 | | - env_rel = SimEnvCreator()( |
18 | | - control_mode=ControlMode.CARTESIAN_TQuat, |
19 | | - robot_cfg=default_sim_robot_cfg(scene="fr3_empty_world"), |
20 | | - collision_guard=False, |
21 | | - gripper_cfg=default_sim_gripper_cfg(), |
22 | | - cameras=default_mujoco_cameraset_cfg(), |
23 | | - max_relative_movement=0.5, |
24 | | - relative_to=RelativeTo.LAST_STEP, |
25 | | - ) |
26 | | - env_rel.get_wrapper_attr("sim").open_gui() |
| 29 | +def main(): |
| 30 | + if ROBOT_INSTANCE == RobotPlatform.SIMULATION: |
| 31 | + env_rel = SimEnvCreator()( |
| 32 | + control_mode=ControlMode.CARTESIAN_TQuat, |
| 33 | + robot_cfg=default_sim_robot_cfg(scene="fr3_empty_world"), |
| 34 | + gripper_cfg=default_sim_gripper_cfg(), |
| 35 | + cameras=default_mujoco_cameraset_cfg(), |
| 36 | + max_relative_movement=0.5, |
| 37 | + relative_to=RelativeTo.LAST_STEP, |
| 38 | + ) |
| 39 | + env_rel.get_wrapper_attr("sim").open_gui() |
| 40 | + else: |
| 41 | + from rcs_fr3.creators import RCSFR3EnvCreator |
| 42 | + from rcs_fr3.utils import default_fr3_hw_gripper_cfg, default_fr3_hw_robot_cfg |
| 43 | + env_rel = RCSFR3EnvCreator()( |
| 44 | + ip=FR3_IP, |
| 45 | + control_mode=ControlMode.CARTESIAN_TQuat, |
| 46 | + robot_cfg=default_fr3_hw_robot_cfg(), |
| 47 | + gripper_cfg=default_fr3_hw_gripper_cfg(), |
| 48 | + camera_set=None, |
| 49 | + max_relative_movement=0.5, |
| 50 | + relative_to=RelativeTo.LAST_STEP, |
| 51 | + ) |
| 52 | + input("the robot is going to move, press enter whenever you are ready") |
27 | 53 |
|
28 | 54 | env_rel.reset() |
| 55 | + |
| 56 | + # access low level robot api to get current cartesian position |
29 | 57 | print(env_rel.unwrapped.robot.get_cartesian_position()) # type: ignore |
30 | 58 |
|
31 | 59 | for _ in range(100): |
32 | 60 | for _ in range(10): |
33 | 61 | # move 1cm in x direction (forward) and close gripper |
34 | 62 | act = {"tquat": [0.01, 0, 0, 0, 0, 0, 1], "gripper": 0} |
35 | 63 | obs, reward, terminated, truncated, info = env_rel.step(act) |
36 | | - if truncated or terminated: |
37 | | - logger.info("Truncated or terminated!") |
38 | | - return |
39 | 64 | for _ in range(10): |
40 | 65 | # move 1cm in negative x direction (backward) and open gripper |
41 | 66 | act = {"tquat": [-0.01, 0, 0, 0, 0, 0, 1], "gripper": 1} |
42 | 67 | obs, reward, terminated, truncated, info = env_rel.step(act) |
43 | | - if truncated or terminated: |
44 | | - logger.info("Truncated or terminated!") |
45 | | - return |
46 | 68 |
|
47 | 69 |
|
48 | 70 | if __name__ == "__main__": |
|
0 commit comments