Skip to content

Commit 188bae6

Browse files
committed
style: formatting and linting
1 parent 5ee5473 commit 188bae6

File tree

9 files changed

+58
-38
lines changed

9 files changed

+58
-38
lines changed

examples/so101_env_cartesian_control.py

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,4 @@
11
import logging
2-
from time import sleep
32

43
from rcs.envs.base import ControlMode, RelativeTo
54
from rcs.envs.creators import SimEnvCreator

examples/so101_env_joint_control.py

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,4 @@
11
import logging
2-
from time import sleep
32

43
import numpy as np
54
from rcs.envs.base import ControlMode, RelativeTo

extensions/rcs_realsense/src/rcs_realsense/calibration.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -154,4 +154,4 @@ def get_marker_pose(calib_tag_id, detector, intrinsics, frame):
154154
tag_size=0.1,
155155
)
156156

157-
return marker_det, pose
157+
return marker_det, pose

extensions/rcs_realsense/src/rcs_realsense/utils.py

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@ def default_realsense(name2id: dict[str, str] | None) -> RealSenseCameraSet | No
1717
calibration_strategy = {name: typing.cast(CalibrationStrategy, FR3BaseArucoCalibration(name)) for name in name2id}
1818
return RealSenseCameraSet(cameras=cameras, calibration_strategy=calibration_strategy)
1919

20+
2021
def default_realsense_dummy_calibration(name2id: dict[str, str] | None) -> RealSenseCameraSet | None:
2122
if name2id is None:
2223
return None

extensions/rcs_so101/src/rcs_so101/env_cartesian_control.py

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

1919
def main():
2020

21+
robot_cfg: rcs._core.common.RobotConfig
2122
if ROBOT_INSTANCE == RobotPlatform.HARDWARE:
2223
robot_cfg = SO101Config()
2324
robot_cfg.id = "jobi_follower"

extensions/rcs_so101/src/rcs_so101/env_joint_control.py

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

2020
def main():
2121

22+
robot_cfg: rcs._core.common.RobotConfig
2223
if ROBOT_INSTANCE == RobotPlatform.HARDWARE:
2324
robot_cfg = SO101Config()
2425
robot_cfg.id = "jobi_follower"

extensions/rcs_so101/src/rcs_so101/hw.py

Lines changed: 7 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -1,11 +1,9 @@
11
import threading
2-
import time
32
import typing
43
from pathlib import Path
54

65
import numpy as np
7-
from attr import dataclass
8-
from lerobot.robots import make_robot_from_config # noqa: F401
6+
from lerobot.robots import make_robot_from_config
97
from lerobot.robots.so101_follower.config_so101_follower import SO101FollowerConfig
108
from lerobot.robots.so101_follower.so101_follower import SO101Follower
119
from rcs.utils import SimpleFrameRate
@@ -19,14 +17,14 @@ class SO101Config(common.RobotConfig):
1917
calibration_dir: str = "."
2018

2119

22-
class SO101:
20+
class SO101(common.Robot):
2321
def __init__(self, robot_cfg: SO101Config, ik: common.IK):
2422
super().__init__()
2523
self.ik = ik
2624
cfg = SO101FollowerConfig(id=robot_cfg.id, calibration_dir=Path(robot_cfg.calibration_dir), port=robot_cfg.port)
2725
self.hf_robot = make_robot_from_config(cfg)
2826
self.hf_robot.connect()
29-
self._thread = None
27+
self._thread: threading.Thread | None = None
3028
self._running = False
3129
self._goal = None
3230
self._goal_lock = threading.Lock()
@@ -87,8 +85,8 @@ def move_home(self) -> None:
8785
# np.ndarray[tuple[typing.Literal[5]], np.dtype[np.float64]],
8886
# common.robots_meta_config(common.RobotType.SO101).q_home,
8987
# )
90-
home = np.array([-0.01914898, -1.90521916, 1.56476701, 1.04783839, -1.40323926])
91-
self.set_joint_position(home)
88+
home = np.array([-0.01914898, -1.90521916, 1.56476701, 1.04783839, -1.40323926])
89+
self.set_joint_position(home) # type: ignore
9290

9391
def reset(self) -> None:
9492
pass
@@ -119,7 +117,6 @@ def _set_joint_position(self, q: np.ndarray[tuple[typing.Literal[5]], np.dtype[n
119117

120118
def set_joint_position(self, q: np.ndarray[tuple[typing.Literal[5]], np.dtype[np.float64]]) -> None: # type: ignore
121119
self._set_joint_position(q)
122-
123120

124121
def _controller(self):
125122
print("Controller thread started")
@@ -187,6 +184,8 @@ def __init__(self, hf_robot: SO101Follower, robot: SO101):
187184
def get_normalized_width(self) -> float:
188185
# obs = self.hf_robot.get_observation()
189186
obs = self.robot.obs
187+
if obs is None:
188+
return 0.0
190189
return obs["gripper.pos"] / 100.0
191190

192191
# def get_parameters(self) -> GripperConfig: ...

extensions/rcs_usb_cam/src/rcs_usb_cam/camera.py

Lines changed: 40 additions & 24 deletions
Original file line numberDiff line numberDiff line change
@@ -1,38 +1,44 @@
11
import copy
2+
import datetime
23
import logging
34
import threading
45
import typing
5-
from dataclasses import dataclass
66

7+
import cv2
78
import numpy as np
89
from rcs.camera.hw import CalibrationStrategy, DummyCalibrationStrategy, HardwareCamera
9-
from rcs.camera.interface import BaseCameraSet, DataFrame, CameraFrame, Frame
10-
import cv2
10+
from rcs.camera.interface import CameraFrame, DataFrame, Frame
11+
1112
from rcs import common
12-
import datetime
13-
'''
13+
14+
"""
1415
A generic extension class for handling USB-connected cameras.
1516
Uses OpenCV to interface with the camera hardware, specifically using cv2.VideoCapture(id).
1617
The ID can be both a single integer passed as a string, i.e. str(0), str(1), or the full /dev/ path, like /dev/video0.
1718
18-
'''
19+
"""
20+
21+
1922
class USBCameraConfig(common.BaseCameraConfig):
2023
color_intrinsics: np.ndarray[tuple[typing.Literal[3], typing.Literal[4]], np.dtype[np.float64]] | None = None
2124
distortion_coeffs: np.ndarray[tuple[typing.Literal[5]], np.dtype[np.float64]] | None = None
2225

26+
2327
class USBCameraSet(HardwareCamera):
24-
def __init__(self,
25-
cameras: dict[str, USBCameraConfig],
26-
calibration_strategy: dict[str, CalibrationStrategy] | None = None,):
28+
def __init__(
29+
self,
30+
cameras: dict[str, USBCameraConfig],
31+
calibration_strategy: dict[str, CalibrationStrategy] | None = None,
32+
):
2733
self.cameras = cameras
2834
self.CALIBRATION_FRAME_SIZE = 30
2935
if calibration_strategy is None:
3036
calibration_strategy = {camera_name: DummyCalibrationStrategy() for camera_name in cameras}
31-
for name, cam in self.cameras.items():
37+
for cam in self.cameras.values():
3238
if cam.color_intrinsics is None:
33-
cam.color_intrinsics = np.zeros((3, 4), dtype=np.float64)
39+
cam.color_intrinsics = np.zeros((3, 4), dtype=np.float64) # type: ignore
3440
if cam.distortion_coeffs is None:
35-
cam.distortion_coeffs = np.zeros((5,), dtype=np.float64)
41+
cam.distortion_coeffs = np.zeros((5,), dtype=np.float64) # type: ignore
3642
if cam.resolution_height is None:
3743
cam.resolution_height = 480
3844
if cam.resolution_width is None:
@@ -44,7 +50,9 @@ def __init__(self,
4450
self._captures: dict[str, cv2.VideoCapture] = {}
4551
self._logger = logging.getLogger(__name__)
4652
self._logger.info("USBCamera initialized with cameras: %s", self._camera_names)
47-
self._logger.info("If the camera streams are not correct, try v4l2-ctl --list-devices to see the available cameras.")
53+
self._logger.info(
54+
"If the camera streams are not correct, try v4l2-ctl --list-devices to see the available cameras."
55+
)
4856
self._frame_buffer_lock: dict[str, threading.Lock] = {}
4957
self._frame_buffer: dict[str, list] = {}
5058

@@ -58,7 +66,8 @@ def open(self):
5866
cap.set(cv2.CAP_PROP_FPS, camera.frame_rate)
5967

6068
if not cap.isOpened():
61-
raise RuntimeError(f"Could not open camera {name} with id {camera.identifier}")
69+
msg = f"Could not open camera {name} with id {camera.identifier}"
70+
raise RuntimeError(msg)
6271
self._captures[name] = cap
6372

6473
@property
@@ -70,20 +79,27 @@ def poll_frame(self, camera_name: str) -> Frame:
7079
timestamp = datetime.datetime.now().timestamp()
7180
ret, color_frame = cap.read()
7281
if not ret:
73-
raise RuntimeError(f"Failed to read frame from camera {camera_name}")
82+
msg = f"Failed to read frame from camera {camera_name}"
83+
raise RuntimeError(msg)
7484
with self._frame_buffer_lock[camera_name]:
7585
if len(self._frame_buffer[camera_name]) >= self.CALIBRATION_FRAME_SIZE:
7686
self._frame_buffer[camera_name].pop(0)
7787
self._frame_buffer[camera_name].append(copy.deepcopy(color_frame))
78-
color = DataFrame(data=color_frame,
79-
timestamp=timestamp,
80-
intrinsics=self.cameras[camera_name].color_intrinsics,
81-
extrinsics=self.calibration_strategy[camera_name].get_extrinsics())
82-
depth_frame = np.zeros((self.cameras[camera_name].resolution_height, self.cameras[camera_name].resolution_width), dtype=np.uint16)
83-
depth = DataFrame(data=depth_frame,
84-
timestamp=timestamp,
85-
intrinsics=self.cameras[camera_name].color_intrinsics,
86-
extrinsics=self.calibration_strategy[camera_name].get_extrinsics())
88+
color = DataFrame(
89+
data=color_frame,
90+
timestamp=timestamp,
91+
intrinsics=self.cameras[camera_name].color_intrinsics,
92+
extrinsics=self.calibration_strategy[camera_name].get_extrinsics(),
93+
)
94+
depth_frame = np.zeros(
95+
(self.cameras[camera_name].resolution_height, self.cameras[camera_name].resolution_width), dtype=np.uint16
96+
)
97+
depth = DataFrame(
98+
data=depth_frame,
99+
timestamp=timestamp,
100+
intrinsics=self.cameras[camera_name].color_intrinsics,
101+
extrinsics=self.calibration_strategy[camera_name].get_extrinsics(),
102+
)
87103
cf = CameraFrame(color=color, depth=depth)
88104
return Frame(camera=cf, avg_timestamp=timestamp)
89105

extensions/rcs_usb_cam/src/rcs_usb_cam/webcam.py

Lines changed: 7 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,10 @@
11
import cv2
2-
'''
2+
3+
"""
34
Simple script for opening a webcam using OpenCV and displaying the video feed.
4-
'''
5+
"""
6+
7+
58
def open_webcam():
69
# Open the default webcam (0).
710
# If you have multiple cameras, you can try 1, 2, etc.
@@ -26,12 +29,13 @@ def open_webcam():
2629
cv2.imshow("Webcam", frame)
2730

2831
# Press 'q' to quit
29-
if cv2.waitKey(1) & 0xFF == ord('q'):
32+
if cv2.waitKey(1) & 0xFF == ord("q"):
3033
break
3134

3235
# Release the camera and close windows
3336
cap.release()
3437
cv2.destroyAllWindows()
3538

39+
3640
if __name__ == "__main__":
3741
open_webcam()

0 commit comments

Comments
 (0)