Skip to content

Commit 68689c3

Browse files
committed
fix: linting errors in examples and tests
1 parent 6103f8e commit 68689c3

7 files changed

Lines changed: 55 additions & 36 deletions

File tree

pyproject.toml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -101,6 +101,7 @@ ignore = [
101101
"PLR5501", # elif to reduce indentation
102102
"PT018", # assertion should be broken down into multiple parts
103103
"NPY002",
104+
"G004", # Logging format string does not contain any placeholders
104105
]
105106

106107
[tool.pylint.format]

python/examples/env_cartesian_control.py

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -44,6 +44,7 @@
4444

4545

4646
def main():
47+
resource_manger: FCI | DummyResourceManager
4748
if ROBOT_INSTANCE == RobotInstance.HARDWARE:
4849
user, pw = load_creds_fr3_desk()
4950
resource_manger = FCI(Desk(ROBOT_IP, user, pw), unlock=False, lock_when_done=False)
@@ -59,7 +60,7 @@ def main():
5960
collision_guard="lab",
6061
gripper_cfg=default_fr3_hw_gripper_cfg(),
6162
max_relative_movement=0.5,
62-
relative_to=RelativeTo.LAST_STEP
63+
relative_to=RelativeTo.LAST_STEP,
6364
)
6465
else:
6566
env_rel = fr3_sim_env(
@@ -69,12 +70,12 @@ def main():
6970
gripper_cfg=default_fr3_sim_gripper_cfg(),
7071
camera_set_cfg=default_mujoco_cameraset_cfg(),
7172
max_relative_movement=0.5,
72-
relative_to=RelativeTo.LAST_STEP
73+
relative_to=RelativeTo.LAST_STEP,
7374
)
7475
env_rel.get_wrapper_attr("sim").open_gui()
7576

7677
env_rel.reset()
77-
print(env_rel.unwrapped.robot.get_cartesian_position())
78+
print(env_rel.unwrapped.robot.get_cartesian_position()) # type: ignore
7879

7980
for _ in range(10):
8081
for _ in range(10):

python/examples/env_joint_control.py

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -45,6 +45,7 @@
4545

4646

4747
def main():
48+
resource_manger: FCI | DummyResourceManager
4849
if ROBOT_INSTANCE == RobotInstance.HARDWARE:
4950
user, pw = load_creds_fr3_desk()
5051
resource_manger = FCI(Desk(ROBOT_IP, user, pw), unlock=False, lock_when_done=False)

python/examples/fr3.py

Lines changed: 20 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -55,49 +55,54 @@ def main():
5555
if "lab" not in rcsss.scenes:
5656
logger.error("This pip package was not built with the UTN lab models, aborting.")
5757
sys.exit()
58+
resource_manger: FCI | DummyResourceManager
5859
if ROBOT_INSTANCE == RobotInstance.HARDWARE:
5960
user, pw = load_creds_fr3_desk()
6061
resource_manger = FCI(Desk(ROBOT_IP, user, pw), unlock=False, lock_when_done=False)
6162
else:
6263
resource_manger = DummyResourceManager()
6364

6465
with resource_manger:
66+
robot: rcsss.common.Robot
67+
gripper: rcsss.common.Gripper
6568
if ROBOT_INSTANCE == RobotInstance.SIMULATION:
6669
simulation = sim.Sim(rcsss.scenes["fr3_empty_world"])
6770
urdf_path = get_urdf_path(URDF_PATH, allow_none_if_not_found=False)
71+
assert urdf_path is not None
6872
ik = rcsss.common.IK(urdf_path)
6973
robot = rcsss.sim.FR3(simulation, "0", ik)
7074
cfg = sim.FR3Config()
7175
cfg.tcp_offset = rcsss.common.Pose(rcsss.common.FrankaHandTCPOffset())
7276
cfg.realtime = False
7377
robot.set_parameters(cfg)
7478

75-
gripper_cfg = sim.FHConfig()
76-
gripper = sim.FrankaHand(simulation, "0", gripper_cfg)
79+
gripper_cfg_sim = sim.FHConfig()
80+
gripper = sim.FrankaHand(simulation, "0", gripper_cfg_sim)
7781

7882
# add camera to have a rendering gui
7983
cameras = {
8084
"default_free": SimCameraConfig(identifier="", type=int(CameraType.default_free)),
8185
"wrist": SimCameraConfig(identifier="eye-in-hand_0", type=int(CameraType.fixed)),
8286
}
8387
cam_cfg = SimCameraSetConfig(cameras=cameras, resolution_width=1280, resolution_height=720, frame_rate=20)
84-
camera_set = SimCameraSet(simulation, cam_cfg) # noqa: F841
88+
camera_set = SimCameraSet(simulation, cam_cfg) # noqa: F841
8589
simulation.open_gui()
8690

8791
else:
8892
urdf_path = get_urdf_path(URDF_PATH, allow_none_if_not_found=False)
93+
assert urdf_path is not None
8994
ik = rcsss.common.IK(urdf_path)
90-
robot = rcsss.hw.FR3(ROBOT_IP, str(rcsss.scenes["lab"].parent / "fr3.urdf"), ik)
95+
robot = rcsss.hw.FR3(ROBOT_IP, ik)
9196
robot_cfg = FR3Config()
9297
robot_cfg.tcp_offset = rcsss.common.Pose(rcsss.common.FrankaHandTCPOffset())
9398
robot_cfg.controller = IKController.robotics_library
9499
robot.set_parameters(robot_cfg)
95100

96-
gripper_cfg = rcsss.hw.FHConfig()
97-
gripper_cfg.epsilon_inner = gripper_cfg.epsilon_outer = 0.1
98-
gripper_cfg.speed = 0.1
99-
gripper_cfg.force = 30
100-
gripper = rcsss.hw.FrankaHand(ROBOT_IP, gripper_cfg)
101+
gripper_cfg_hw = rcsss.hw.FHConfig()
102+
gripper_cfg_hw.epsilon_inner = gripper_cfg_hw.epsilon_outer = 0.1
103+
gripper_cfg_hw.speed = 0.1
104+
gripper_cfg_hw.force = 30
105+
gripper = rcsss.hw.FrankaHand(ROBOT_IP, gripper_cfg_hw)
101106
input("the robot is going to move, press enter whenever you are ready")
102107

103108
# move to home position and open gripper
@@ -113,7 +118,7 @@ def main():
113118
)
114119
if ROBOT_INSTANCE == RobotInstance.SIMULATION:
115120
simulation.step_until_convergence()
116-
logger.debug(f"IK success: {robot.get_state().ik_success}")
121+
logger.debug(f"IK success: {robot.get_state().ik_success}") # type: ignore
117122
logger.debug(f"sim converged: {simulation.is_converged()}")
118123

119124
# 5cm in y direction
@@ -122,7 +127,7 @@ def main():
122127
)
123128
if ROBOT_INSTANCE == RobotInstance.SIMULATION:
124129
simulation.step_until_convergence()
125-
logger.debug(f"IK success: {robot.get_state().ik_success}")
130+
logger.debug(f"IK success: {robot.get_state().ik_success}") # type: ignore
126131
logger.debug(f"sim converged: {simulation.is_converged()}")
127132

128133
# 5cm in z direction
@@ -131,7 +136,7 @@ def main():
131136
)
132137
if ROBOT_INSTANCE == RobotInstance.SIMULATION:
133138
simulation.step_until_convergence()
134-
logger.debug(f"IK success: {robot.get_state().ik_success}")
139+
logger.debug(f"IK success: {robot.get_state().ik_success}") # type: ignore
135140
logger.debug(f"sim converged: {simulation.is_converged()}")
136141

137142
# rotate the arm 90 degrees around the inverted y and z axis
@@ -141,7 +146,7 @@ def main():
141146
robot.set_cartesian_position(new_pose)
142147
if ROBOT_INSTANCE == RobotInstance.SIMULATION:
143148
simulation.step_until_convergence()
144-
logger.debug(f"IK success: {robot.get_state().ik_success}")
149+
logger.debug(f"IK success: {robot.get_state().ik_success}") # type: ignore
145150
logger.debug(f"sim converged: {simulation.is_converged()}")
146151

147152
if ROBOT_INSTANCE == RobotInstance.HARDWARE:
@@ -155,7 +160,7 @@ def main():
155160
)
156161
if ROBOT_INSTANCE == RobotInstance.SIMULATION:
157162
simulation.step_until_convergence()
158-
logger.debug(f"IK success: {robot.get_state().ik_success}")
163+
logger.debug(f"IK success: {robot.get_state().ik_success}") # type: ignore
159164
logger.debug(f"sim converged: {simulation.is_converged()}")
160165

161166
# grasp the object
@@ -170,7 +175,7 @@ def main():
170175
)
171176
if ROBOT_INSTANCE == RobotInstance.SIMULATION:
172177
simulation.step_until_convergence()
173-
logger.debug(f"IK success: {robot.get_state().ik_success}")
178+
logger.debug(f"IK success: {robot.get_state().ik_success}") # type: ignore
174179
logger.debug(f"sim converged: {simulation.is_converged()}")
175180

176181
if ROBOT_INSTANCE == RobotInstance.HARDWARE:

python/examples/grasp_demo.py

Lines changed: 9 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -1,10 +1,11 @@
11
import logging
2+
from typing import Any, cast
23

34
import gymnasium as gym
45
import mujoco
56
import numpy as np
67
from rcsss._core.common import Pose
7-
from rcsss.envs.base import GripperWrapper
8+
from rcsss.envs.base import FR3Env, GripperWrapper
89

910
logger = logging.getLogger(__name__)
1011
logger.setLevel(logging.INFO)
@@ -13,9 +14,10 @@
1314
class PickUpDemo:
1415
def __init__(self, env: gym.Env):
1516
self.env = env
16-
self.home_pose = self.env.unwrapped.robot.get_cartesian_position()
17+
self.unwrapped: FR3Env = cast(FR3Env, self.env.unwrapped)
18+
self.home_pose = self.unwrapped.robot.get_cartesian_position()
1719

18-
def _action(self, pose: Pose, gripper: float) -> np.ndarray:
20+
def _action(self, pose: Pose, gripper: float) -> dict[str, Any]:
1921
return {"xyzrpy": pose.xyzrpy(), "gripper": gripper}
2022

2123
def get_object_pose(self, geom_name) -> Pose:
@@ -32,17 +34,17 @@ def generate_waypoints(self, start_pose: Pose, end_pose: Pose, num_waypoints: in
3234
waypoints.append(start_pose.interpolate(end_pose, t))
3335
return waypoints
3436

35-
def step(self, action: np.ndarray) -> dict:
37+
def step(self, action: dict) -> dict:
3638
return self.env.step(action)[0]
3739

3840
def plan_linear_motion(self, geom_name: str, delta_up: float, num_waypoints: int = 20) -> list[Pose]:
39-
end_eff_pose = self.env.unwrapped.robot.get_cartesian_position()
41+
end_eff_pose = self.unwrapped.robot.get_cartesian_position()
4042

4143
goal_pose = self.get_object_pose(geom_name=geom_name)
4244
# goal pose is above the object and gripper coordinate must flip z-axis (end effector base rotation is [1, 0, 0, 0])
4345
# be careful we define identity quaternion as as [0, 0, 0, 1]
4446
# this does not work if the object is flipped
45-
goal_pose *= Pose(translation=[0, 0, delta_up], quaternion=[1, 0, 0, 0])
47+
goal_pose *= Pose(translation=np.array([0, 0, delta_up]), quaternion=np.array([1, 0, 0, 0]))
4648

4749
return self.generate_waypoints(end_eff_pose, goal_pose, num_waypoints=num_waypoints)
4850

@@ -68,7 +70,7 @@ def grasp(self, geom_name: str):
6870
self.execute_motion(waypoints=waypoints, gripper=GripperWrapper.BINARY_GRIPPER_CLOSED)
6971

7072
def move_home(self):
71-
end_eff_pose = self.env.unwrapped.robot.get_cartesian_position()
73+
end_eff_pose = self.unwrapped.robot.get_cartesian_position()
7274
waypoints = self.generate_waypoints(end_eff_pose, self.home_pose, num_waypoints=10)
7375
self.execute_motion(waypoints=waypoints, gripper=GripperWrapper.BINARY_GRIPPER_CLOSED)
7476

python/rcsss/envs/factories.py

Lines changed: 1 addition & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -18,8 +18,6 @@
1818
ControlMode,
1919
FR3Env,
2020
GripperWrapper,
21-
LimitedJointsRelDictType,
22-
ObsArmsGrCam,
2321
RelativeActionSpace,
2422
RelativeTo,
2523
)
@@ -186,7 +184,7 @@ def fr3_sim_env(
186184
urdf_path: str | PathLike | None = None,
187185
mjcf: str | PathLike = "fr3_empty_world",
188186
sim_wrapper: Type[SimWrapper] | None = None,
189-
) -> gym.Env[ObsArmsGrCam, LimitedJointsRelDictType]:
187+
) -> gym.Env:
190188
"""
191189
Creates a simulation environment for the FR3 robot.
192190

python/tests/test_sim_envs.py

Lines changed: 19 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -1,15 +1,23 @@
1+
from typing import cast
2+
13
import numpy as np
24
import pytest
35
import rcsss
6+
from rcsss.envs.base import (
7+
ControlMode,
8+
FR3Env,
9+
GripperDictType,
10+
JointsDictType,
11+
TQuartDictType,
12+
TRPYDictType,
13+
)
414
from rcsss.envs.factories import (
515
default_fr3_sim_gripper_cfg,
616
default_fr3_sim_robot_cfg,
717
default_mujoco_cameraset_cfg,
818
fr3_sim_env,
919
)
1020

11-
from rcsss.envs.base import ControlMode, TRPYDictType, GripperDictType, TQuartDictType, JointsDictType
12-
1321

1422
@pytest.fixture()
1523
def cfg():
@@ -144,14 +152,15 @@ def test_collision_guard_trpy(self, cfg, gripper_cfg, cam_cfg):
144152
max_relative_movement=0.5,
145153
)
146154
obs, _ = env.reset()
147-
p1 = env.unwrapped.robot.get_joint_position()
155+
unwrapped = cast(FR3Env, env.unwrapped)
156+
p1 = unwrapped.robot.get_joint_position()
148157
# an obvious below ground collision action
149158
obs["xyzrpy"][0] = 0.3
150159
obs["xyzrpy"][2] = -0.2
151160
collision_action = TRPYDictType(xyzrpy=obs["xyzrpy"])
152161
collision_action.update(GripperDictType(gripper=0))
153162
_, _, _, _, info = env.step(collision_action)
154-
p2 = env.unwrapped.robot.get_joint_position()
163+
p2 = unwrapped.robot.get_joint_position()
155164
self.assert_collision(info)
156165
# assure that the robot did not move
157166
assert np.allclose(p1, p2)
@@ -245,14 +254,15 @@ def test_collision_guard_tquart(self, cfg, gripper_cfg, cam_cfg):
245254
max_relative_movement=None,
246255
)
247256
obs, _ = env.reset()
248-
p1 = env.unwrapped.robot.get_joint_position()
257+
unwrapped = cast(FR3Env, env.unwrapped)
258+
p1 = unwrapped.robot.get_joint_position()
249259
# an obvious below ground collision action
250260
obs["tquart"][0] = 0.3
251261
obs["tquart"][2] = -0.2
252262
collision_action = TQuartDictType(tquart=obs["tquart"])
253263
collision_action.update(GripperDictType(gripper=0))
254264
_, _, _, _, info = env.step(collision_action)
255-
p2 = env.unwrapped.robot.get_joint_position()
265+
p2 = unwrapped.robot.get_joint_position()
256266
self.assert_collision(info)
257267
# assure that the robot did not move
258268
assert np.allclose(p1, p2)
@@ -319,12 +329,13 @@ def test_collision_guard_joints(self, cfg, gripper_cfg, cam_cfg):
319329
max_relative_movement=None,
320330
)
321331
env.reset()
322-
p1 = env.unwrapped.robot.get_joint_position()
332+
unwrapped = cast(FR3Env, env.unwrapped)
333+
p1 = unwrapped.robot.get_joint_position()
323334
# the below action is a test_case where there is an obvious collision regardless of the gripper action
324335
collision_act = JointsDictType(joints=np.array([0, 1.78, 0, -1.45, 0, 0, 0], dtype=np.float32))
325336
collision_act.update(GripperDictType(gripper=1))
326337
_, _, _, _, info = env.step(collision_act)
327-
p2 = env.unwrapped.robot.get_joint_position()
338+
p2 = unwrapped.robot.get_joint_position()
328339

329340
self.assert_collision(info)
330341
# assure that the robot did not move

0 commit comments

Comments
 (0)