Skip to content

Commit 08805e6

Browse files
committed
lint: fixing linting errors
1 parent a652087 commit 08805e6

10 files changed

Lines changed: 98 additions & 105 deletions

File tree

examples/teleop/franka.py

Lines changed: 12 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -1,26 +1,17 @@
11
import logging
2-
import threading
3-
from time import sleep
2+
from typing import Any
43

54
import numpy as np
65
from rcs._core import common
7-
from rcs._core.common import RPY, Pose, RobotPlatform
6+
from rcs._core.common import RobotPlatform
87
from rcs._core.sim import SimConfig
98
from rcs.camera.hw import HardwareCameraSet
10-
from rcs.envs.base import (
11-
ControlMode,
12-
GripperDictType,
13-
LimitedTQuatRelDictType,
14-
RelativeActionSpace,
15-
RelativeTo,
16-
)
9+
from rcs.envs.base import ControlMode
1710
from rcs.envs.creators import SimMultiEnvCreator
18-
from rcs.envs.storage_wrapper import StorageWrapper
1911
from rcs.envs.utils import default_digit, default_sim_gripper_cfg, default_sim_robot_cfg
20-
from rcs.operator.gello import GelloArmConfig, GelloConfig, GelloOperator
12+
from rcs.operator.gello import GelloConfig, GelloOperator
2113
from rcs.operator.interface import TeleopLoop
2214
from rcs.operator.quest import QuestConfig, QuestOperator
23-
from rcs.utils import SimpleFrameRate
2415
from rcs_fr3.creators import RCSFR3MultiEnvCreator
2516
from rcs_fr3.utils import default_fr3_hw_gripper_cfg, default_fr3_hw_robot_cfg
2617
from rcs_realsense.utils import default_realsense
@@ -66,10 +57,15 @@
6657
INSTRUCTION = "build a tower with the blocks in front of you"
6758

6859
robot2world = {
69-
"right": rcs.common.Pose(translation=[0, 0, 0], rpy_vector=[0.89360858, -0.17453293, 0.46425758]),
70-
"left": rcs.common.Pose(translation=[0, 0, 0], rpy_vector=[-0.89360858, -0.17453293, -0.46425758]),
60+
"right": rcs.common.Pose(
61+
translation=np.array([0, 0, 0]), rpy_vector=np.array([0.89360858, -0.17453293, 0.46425758])
62+
),
63+
"left": rcs.common.Pose(
64+
translation=np.array([0, 0, 0]), rpy_vector=np.array([-0.89360858, -0.17453293, -0.46425758])
65+
),
7166
}
7267

68+
config: QuestConfig | GelloConfig
7369
config = QuestConfig(mq3_addr=MQ3_ADDR, simulation=ROBOT_INSTANCE == RobotPlatform.SIMULATION)
7470
# config = GelloConfig(
7571
# arms={
@@ -83,7 +79,7 @@
8379
def get_env():
8480
if ROBOT_INSTANCE == RobotPlatform.HARDWARE:
8581

86-
cams = []
82+
cams: list[Any] = []
8783
if CAMERA_DICT is not None:
8884
cams.append(default_realsense(CAMERA_DICT))
8985
if DIGIT_DICT is not None:

python/rcs/envs/base.py

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -12,6 +12,7 @@
1212
from rcs.envs.space_utils import (
1313
ActObsInfoWrapper,
1414
RCSpaceType,
15+
Vec1Type,
1516
Vec6Type,
1617
Vec7Type,
1718
Vec18Type,
@@ -99,12 +100,12 @@ class LimitedJointsRelDictType(RCSpaceType):
99100

100101
class GripperDictType(RCSpaceType):
101102
# 0 for closed, 1 for open (>=0.5 for open)
102-
gripper: Annotated[float, gym.spaces.Box(low=0, high=1, dtype=np.float32)]
103+
gripper: Annotated[Vec1Type, gym.spaces.Box(low=0, high=1, shape=(1,), dtype=np.float32)]
103104

104105

105106
class HandBinDictType(RCSpaceType):
106107
# 0 for closed, 1 for open (>=0.5 for open)
107-
gripper: Annotated[float, gym.spaces.Box(low=0, high=1, dtype=np.float32)]
108+
gripper: Annotated[Vec1Type, gym.spaces.Box(low=0, high=1, shape=(1,), dtype=np.float32)]
108109

109110

110111
class HandVecDictType(RCSpaceType):

python/rcs/envs/creators.py

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -168,9 +168,9 @@ def __call__( # type: ignore
168168
for key, mid in name2id.items():
169169
env: gym.Env = RobotEnv(robots[key], control_mode)
170170
if gripper_cfg is not None:
171-
cfg = copy.copy(gripper_cfg)
172-
cfg.add_id(mid)
173-
gripper = rcs.sim.SimGripper(simulation, cfg)
171+
gripper_cfg_copy = copy.copy(gripper_cfg)
172+
gripper_cfg_copy.add_id(mid)
173+
gripper = rcs.sim.SimGripper(simulation, gripper_cfg_copy)
174174
env = GripperWrapper(env, gripper, binary=True)
175175

176176
if relative_to != RelativeTo.NONE:

python/rcs/envs/space_utils.py

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

1818
M = TypeVar("M", bound=int)
1919
VecType: TypeAlias = np.ndarray[M, np.dtype[np.float64]]
20+
Vec1Type: TypeAlias = np.ndarray[tuple[Literal[1]], np.dtype[np.float64]]
2021
Vec7Type: TypeAlias = np.ndarray[tuple[Literal[7]], np.dtype[np.float64]]
2122
Vec3Type: TypeAlias = np.ndarray[tuple[Literal[3]], np.dtype[np.float64]]
2223
Vec6Type: TypeAlias = np.ndarray[tuple[Literal[6]], np.dtype[np.float64]]

python/rcs/envs/utils.py

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -20,9 +20,9 @@ def default_sim_robot_cfg(scene: str = "fr3_empty_world", idx: str = "0") -> sim
2020
scene_cfg = rcs.scenes[scene]
2121
robot_cfg.robot_type = scene_cfg.robot_type
2222
robot_cfg.tcp_offset = common.Pose(common.FrankaHandTCPOffset())
23-
# robot_cfg.add_id(idx)
24-
if rcs.scenes[scene].mjb is not None:
25-
robot_cfg.mjcf_scene_path = rcs.scenes[scene].mjb
23+
robot_cfg.add_id(idx)
24+
if (mjb := rcs.scenes[scene].mjb) is not None:
25+
robot_cfg.mjcf_scene_path = mjb
2626
else:
2727
robot_cfg.mjcf_scene_path = scene_cfg.mjcf_scene
2828
robot_cfg.kinematic_model_path = scene_cfg.mjcf_robot
@@ -37,7 +37,7 @@ def default_tilburg_hw_hand_cfg(file: str | PathLike | None = None) -> THConfig:
3737
return hand_cfg
3838

3939

40-
def default_sim_gripper_cfg(idx: str = "0") -> sim.SimGripperConfig:
40+
def default_sim_gripper_cfg(_idx: str = "0") -> sim.SimGripperConfig:
4141
cfg = sim.SimGripperConfig()
4242
cfg.collision_geoms = []
4343
cfg.collision_geoms_fingers = []

python/rcs/operator/gello.py

Lines changed: 30 additions & 29 deletions
Original file line numberDiff line numberDiff line change
@@ -1,9 +1,10 @@
1+
import contextlib
12
import copy
23
import logging
34
import threading
45
import time
56
from dataclasses import dataclass, field
6-
from typing import Any, Dict, Iterator, List, Optional, Sequence, Tuple, TypedDict
7+
from typing import Any, ClassVar, Dict, Iterator, List, Sequence, Tuple
78

89
import numpy as np
910

@@ -25,13 +26,7 @@
2526
except ImportError:
2627
HAS_PYNPUT = False
2728

28-
from rcs.envs.base import (
29-
ArmWithGripper,
30-
ControlMode,
31-
GripperDictType,
32-
JointsDictType,
33-
RelativeTo,
34-
)
29+
from rcs.envs.base import ControlMode, RelativeTo
3530
from rcs.operator.interface import BaseOperator, BaseOperatorConfig, TeleopCommands
3631
from rcs.sim.sim import Sim
3732
from rcs.utils import SimpleFrameRate
@@ -64,14 +59,15 @@ def __init__(
6459
pulses_per_revolution: int = 4095,
6560
):
6661
if not HAS_DYNAMIXEL_SDK:
67-
raise ImportError("dynamixel_sdk is not installed. Please install it to use GelloOperator.")
62+
msg = "dynamixel_sdk is not installed. Please install it to use GelloOperator."
63+
raise ImportError(msg)
6864

6965
self._ids = ids
7066
self._port = port
7167
self._baudrate = baudrate
7268
self._pulses_per_revolution = pulses_per_revolution
7369
self._lock = threading.Lock()
74-
self._buffered_joint_positions = None
70+
self._buffered_joint_positions: np.ndarray | None = None
7571

7672
self._portHandler = PortHandler(self._port)
7773
self._packetHandler = PacketHandler(2.0)
@@ -86,29 +82,32 @@ def __init__(
8682
for dxl_id in self._ids:
8783
self._groupSyncReadHandlers[key].addParam(dxl_id)
8884

89-
if key != "model_number" and key != "present_position":
85+
if key not in {"model_number", "present_position"}:
9086
self._groupSyncWriteHandlers[key] = GroupSyncWrite(
9187
self._portHandler, self._packetHandler, entry["addr"], entry["len"]
9288
)
9389

9490
if not self._portHandler.openPort():
95-
raise ConnectionError(f"Failed to open port {self._port}")
91+
msg = f"Failed to open port {self._port}"
92+
raise ConnectionError(msg)
9693
if not self._portHandler.setBaudRate(self._baudrate):
97-
raise ConnectionError(f"Failed to set baudrate {self._baudrate}")
94+
msg = f"Failed to set baudrate {self._baudrate}"
95+
raise ConnectionError(msg)
9896

9997
self._stop_thread = threading.Event()
100-
self._polling_thread = None
98+
self._polling_thread: threading.Thread | None = None
10199
self._is_polling = False
102100

103101
def write_value_by_name(self, name: str, values: Sequence[int | None]):
104102
if len(values) != len(self._ids):
105-
raise ValueError(f"The length of {name} must match the number of servos")
103+
msg = f"The length of {name} must match the number of servos"
104+
raise ValueError(msg)
106105

107106
handler = self._groupSyncWriteHandlers[name]
108107
value_len = XL330_CONTROL_TABLE[name]["len"]
109108

110109
with self._lock:
111-
for dxl_id, value in zip(self._ids, values):
110+
for dxl_id, value in zip(self._ids, values, strict=False):
112111
if value is None:
113112
continue
114113
param = [(value >> (8 * i)) & 0xFF for i in range(value_len)]
@@ -117,7 +116,8 @@ def write_value_by_name(self, name: str, values: Sequence[int | None]):
117116
comm_result = handler.txPacket()
118117
if comm_result != COMM_SUCCESS:
119118
handler.clearParam()
120-
raise RuntimeError(f"Failed to syncwrite {name}: {self._packetHandler.getTxRxResult(comm_result)}")
119+
msg = f"Failed to syncwrite {name}: {self._packetHandler.getTxRxResult(comm_result)}"
120+
raise RuntimeError(msg)
121121
handler.clearParam()
122122

123123
def read_value_by_name(self, name: str) -> List[int]:
@@ -128,7 +128,8 @@ def read_value_by_name(self, name: str) -> List[int]:
128128
with self._lock:
129129
comm_result = handler.txRxPacket()
130130
if comm_result != COMM_SUCCESS:
131-
raise RuntimeError(f"Failed to sync read {name}: {self._packetHandler.getTxRxResult(comm_result)}")
131+
msg = f"Failed to sync read {name}: {self._packetHandler.getTxRxResult(comm_result)}"
132+
raise RuntimeError(msg)
132133

133134
values = []
134135
for dxl_id in self._ids:
@@ -137,7 +138,8 @@ def read_value_by_name(self, name: str) -> List[int]:
137138
value = int(np.int32(np.uint32(value)))
138139
values.append(value)
139140
else:
140-
raise RuntimeError(f"Failed to get {name} for ID {dxl_id}")
141+
msg = f"Failed to get {name} for ID {dxl_id}"
142+
raise RuntimeError(msg)
141143
return values
142144

143145
def start_joint_polling(self):
@@ -213,7 +215,7 @@ class DynamixelControlConfig:
213215
goal_current: List[int] = field(default_factory=list)
214216
operating_mode: List[int] = field(default_factory=list)
215217

216-
_UPDATE_ORDER = [
218+
_UPDATE_ORDER: ClassVar[list[str]] = [
217219
"operating_mode",
218220
"goal_current",
219221
"kp_p",
@@ -329,10 +331,8 @@ def _goal_position_to_pulses(self, goals):
329331
return [self._driver._rad_to_pulses(rad) for rad in goals_raw]
330332

331333
def close(self):
332-
try:
334+
with contextlib.suppress(Exception):
333335
self._driver.write_value_by_name("torque_enable", [0] * self._num_total_joints)
334-
except:
335-
pass
336336
self._driver.close()
337337

338338

@@ -342,7 +342,7 @@ def close(self):
342342
class GelloOperator(BaseOperator):
343343
control_mode = (ControlMode.JOINTS, RelativeTo.NONE)
344344

345-
def __init__(self, config: GelloConfig, sim: Sim | None = None):
345+
def __init__(self, config: "GelloConfig", sim: Sim | None = None):
346346
super().__init__(config, sim)
347347
self.config: GelloConfig
348348
self._resource_lock = threading.Lock()
@@ -353,7 +353,7 @@ def __init__(self, config: GelloConfig, sim: Sim | None = None):
353353

354354
self.controller_names = list(self.config.arms.keys())
355355

356-
self._last_joints = {name: None for name in self.controller_names}
356+
self._last_joints: Dict[str, np.ndarray | None] = {name: None for name in self.controller_names}
357357
self._last_gripper = {name: 1.0 for name in self.controller_names}
358358
self._hws: Dict[str, GelloHardware] = {}
359359

@@ -386,12 +386,13 @@ def reset_operator_state(self):
386386
pass
387387

388388
def consume_action(self) -> Dict[str, Any]:
389-
actions = {}
389+
actions: Dict[str, Any] = {}
390390
with self._resource_lock:
391391
for name in self.controller_names:
392-
if self._last_joints[name] is not None:
392+
joints = self._last_joints[name]
393+
if joints is not None:
393394
actions[name] = {
394-
"joints": self._last_joints[name].copy(),
395+
"joints": joints.copy(),
395396
"gripper": np.array([self._last_gripper[name]]),
396397
}
397398
return actions
@@ -434,6 +435,6 @@ def close(self):
434435

435436
@dataclass(kw_only=True)
436437
class GelloConfig(BaseOperatorConfig):
437-
operator_class = GelloOperator
438+
operator_class: type[BaseOperator] = field(default=GelloOperator)
438439
# Dictionary for multi-arm setups: {"left": GelloArmConfig(...), "right": GelloArmConfig(...)}
439440
arms: Dict[str, GelloArmConfig] = field(default_factory=lambda: {"right": GelloArmConfig()})

python/rcs/operator/interface.py

Lines changed: 11 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -27,9 +27,9 @@ class TeleopCommands:
2727

2828
class BaseOperator(ABC, threading.Thread):
2929
control_mode: tuple[ControlMode, RelativeTo]
30-
controller_names: list[str] = field(default=["left", "right"])
30+
controller_names: list[str]
3131

32-
def __init__(self, config: BaseOperatorConfig, sim: Sim | None = None):
32+
def __init__(self, config: "BaseOperatorConfig", sim: Sim | None = None):
3333
threading.Thread.__init__(self)
3434
self.config = config
3535
self.sim = sim
@@ -55,7 +55,7 @@ def close(self):
5555

5656
@dataclass(kw_only=True)
5757
class BaseOperatorConfig:
58-
operator_class: BaseOperator
58+
operator_class: type[BaseOperator]
5959
read_frequency: int = 30
6060
simulation: bool = True
6161

@@ -105,13 +105,12 @@ def _translate_keys(self, actions):
105105
# Fill in missing robots with "hold" actions from last observation
106106
# This is necessary because absolute environments (like MultiRobotWrapper)
107107
# require actions for all configured robots in every step.
108-
for robot_name in self.env.get_wrapper_attr("envs").keys():
109-
if robot_name not in translated:
110-
if robot_name in self._last_obs:
111-
translated[robot_name] = {
112-
"joints": self._last_obs[robot_name]["joints"].copy(),
113-
"gripper": self._last_obs[robot_name].get("gripper", 1.0),
114-
}
108+
for robot_name in self.env.get_wrapper_attr("envs"):
109+
if robot_name not in translated and robot_name in self._last_obs:
110+
translated[robot_name] = {
111+
"joints": self._last_obs[robot_name]["joints"].copy(),
112+
"gripper": self._last_obs[robot_name].get("gripper", 1.0),
113+
}
115114
return translated
116115

117116
def environment_step_loop(self):
@@ -141,7 +140,7 @@ def environment_step_loop(self):
141140
# consume new commands because of potential origin reset
142141
continue
143142

144-
elif cmds.failure:
143+
if cmds.failure:
145144
print("Command: Failure! Resetting env...")
146145
self._last_obs, _ = self.env.reset()
147146
self.operator.reset_operator_state()
@@ -160,7 +159,7 @@ def environment_step_loop(self):
160159
print("Waiting for sync... (Press 's' on GELLO/Keyboard to sync)")
161160

162161
hold_actions = {}
163-
for robot_name in self.env.get_wrapper_attr("envs").keys():
162+
for robot_name in self.env.get_wrapper_attr("envs"):
164163
if robot_name in self._last_obs and "joints" in self._last_obs[robot_name]:
165164
hold_actions[robot_name] = {
166165
"joints": self._last_obs[robot_name]["joints"].copy(),

python/rcs/operator/pedals.py

Lines changed: 12 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -11,7 +11,8 @@ def __init__(self, device_name_substring="Foot Switch"):
1111
self.device_path = self._find_device(device_name_substring)
1212

1313
if not self.device_path:
14-
raise FileNotFoundError(f"Could not find a device matching '{device_name_substring}'")
14+
msg = f"Could not find a device matching '{device_name_substring}'"
15+
raise FileNotFoundError(msg)
1516

1617
self.device = evdev.InputDevice(self.device_path)
1718
self.device.grab() # Prevent events from leaking into the OS/terminal
@@ -45,17 +46,18 @@ def _read_events(self):
4546
if event.type == ecodes.EV_KEY:
4647
key_event = evdev.categorize(event)
4748

48-
with self._lock:
49-
# keystate: 1 is DOWN, 2 is HOLD, 0 is UP
50-
is_pressed = key_event.keystate in [1, 2]
49+
if isinstance(key_event, evdev.KeyEvent):
50+
with self._lock:
51+
# keystate: 1 is DOWN, 2 is HOLD, 0 is UP
52+
is_pressed = key_event.keystate in [1, 2]
5153

52-
# Store state using the string name of the key (e.g., 'KEY_A')
53-
# If a key resolves to a list (rare, but happens in evdev), take the first one
54-
key_name = key_event.keycode
55-
if isinstance(key_name, list):
56-
key_name = key_name[0]
54+
# Store state using the string name of the key (e.g., 'KEY_A')
55+
# If a key resolves to a list (rare, but happens in evdev), take the first one
56+
key_name = key_event.keycode
57+
if isinstance(key_name, list):
58+
key_name = key_name[0]
5759

58-
self._key_states[key_name] = is_pressed
60+
self._key_states[key_name] = is_pressed
5961

6062
except OSError:
6163
pass # Device disconnected or closed

0 commit comments

Comments
 (0)