Skip to content

Commit 1cc87c5

Browse files
committed
docs: added hw to fr3 examples
1 parent c0d554f commit 1cc87c5

3 files changed

Lines changed: 80 additions & 30 deletions

File tree

examples/__init__.py

Whitespace-only changes.

examples/fr3/fr3_env_cartesian_control.py

Lines changed: 39 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,6 @@
11
import logging
22

3+
from rcs._core.common import RobotPlatform
34
from rcs.envs.base import ControlMode, RelativeTo
45
from rcs.envs.creators import SimEnvCreator
56
from rcs.envs.utils import (
@@ -11,38 +12,59 @@
1112
logger = logging.getLogger(__name__)
1213
logger.setLevel(logging.INFO)
1314

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.
1419
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"
1628

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")
2753

2854
env_rel.reset()
55+
56+
# access low level robot api to get current cartesian position
2957
print(env_rel.unwrapped.robot.get_cartesian_position()) # type: ignore
3058

3159
for _ in range(100):
3260
for _ in range(10):
3361
# move 1cm in x direction (forward) and close gripper
3462
act = {"tquat": [0.01, 0, 0, 0, 0, 0, 1], "gripper": 0}
3563
obs, reward, terminated, truncated, info = env_rel.step(act)
36-
if truncated or terminated:
37-
logger.info("Truncated or terminated!")
38-
return
3964
for _ in range(10):
4065
# move 1cm in negative x direction (backward) and open gripper
4166
act = {"tquat": [-0.01, 0, 0, 0, 0, 0, 1], "gripper": 1}
4267
obs, reward, terminated, truncated, info = env_rel.step(act)
43-
if truncated or terminated:
44-
logger.info("Truncated or terminated!")
45-
return
4668

4769

4870
if __name__ == "__main__":

examples/fr3/fr3_env_joint_control.py

Lines changed: 41 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,7 @@
11
import logging
22

33
import numpy as np
4+
from rcs._core.common import RobotPlatform
45
from rcs.envs.base import ControlMode, RelativeTo
56
from rcs.envs.creators import SimEnvCreator
67
from rcs.envs.utils import (
@@ -12,28 +13,55 @@
1213
logger = logging.getLogger(__name__)
1314
logger.setLevel(logging.INFO)
1415

16+
"""
17+
This script demonstrates how to control the FR3 robot in joint position control mode
18+
using relative movements. The robot (or its simulation) samples random relative joint movements
19+
in a loop.
20+
21+
To control a real FR3 robot, install the rcs_fr3 extension (`pip install extensions/rcs_fr3`),
22+
change the ROBOT_INSTANCE variable to RobotPlatform.HARDWARE
23+
and set the FR3_IP variable to the robot's IP address. Make sure to unlock the robot's joints and
24+
put it into FCI mode before running this script. For a scripted way of unlocking and guiding mode see the
25+
fr3_direct_control.py example which uses the FCI context manager.
26+
"""
27+
28+
ROBOT_INSTANCE = RobotPlatform.SIMULATION
29+
FR3_IP = "192.168.101.1"
1530

1631
def main():
17-
env_rel = SimEnvCreator()(
18-
control_mode=ControlMode.JOINTS,
19-
collision_guard=False,
20-
robot_cfg=default_sim_robot_cfg("fr3_empty_world"),
21-
gripper_cfg=default_sim_gripper_cfg(),
22-
cameras=default_mujoco_cameraset_cfg(),
23-
max_relative_movement=np.deg2rad(5),
24-
relative_to=RelativeTo.LAST_STEP,
25-
)
26-
env_rel.get_wrapper_attr("sim").open_gui()
32+
if ROBOT_INSTANCE == RobotPlatform.SIMULATION:
33+
env_rel = SimEnvCreator()(
34+
control_mode=ControlMode.JOINTS,
35+
robot_cfg=default_sim_robot_cfg("fr3_empty_world"),
36+
gripper_cfg=default_sim_gripper_cfg(),
37+
cameras=default_mujoco_cameraset_cfg(),
38+
max_relative_movement=np.deg2rad(5),
39+
relative_to=RelativeTo.LAST_STEP,
40+
)
41+
env_rel.get_wrapper_attr("sim").open_gui()
42+
else:
43+
from rcs_fr3.creators import RCSFR3EnvCreator
44+
from rcs_fr3.utils import default_fr3_hw_gripper_cfg, default_fr3_hw_robot_cfg
45+
env_rel = RCSFR3EnvCreator()(
46+
ip=FR3_IP,
47+
control_mode=ControlMode.JOINTS,
48+
robot_cfg=default_fr3_hw_robot_cfg(),
49+
gripper_cfg=default_fr3_hw_gripper_cfg(),
50+
camera_set=None,
51+
max_relative_movement=np.deg2rad(5),
52+
relative_to=RelativeTo.LAST_STEP,
53+
)
54+
input("the robot is going to move, press enter whenever you are ready")
55+
56+
# access low level robot api to get current cartesian position
57+
print(env_rel.unwrapped.robot.get_joint_position()) # type: ignore
2758

2859
for _ in range(100):
2960
obs, info = env_rel.reset()
3061
for _ in range(10):
3162
# sample random relative action and execute it
3263
act = env_rel.action_space.sample()
3364
obs, reward, terminated, truncated, info = env_rel.step(act)
34-
if truncated or terminated:
35-
logger.info("Truncated or terminated!")
36-
return
3765

3866

3967
if __name__ == "__main__":

0 commit comments

Comments
 (0)