Skip to content

Commit 74341e0

Browse files
authored
Inheritance and abstract class fixes for DepthCamera (#963)
* make inheritance and abstract class fixes * CI code cleanup * renamed stereo to depth camera since most depth cameras are not stereo cameras * bug fix * fix mypy Former-commit-id: 35ea42c [formerly 888999f] Former-commit-id: 528c6d6
1 parent a3e5d4c commit 74341e0

9 files changed

Lines changed: 48 additions & 36 deletions

File tree

dimos/agents/temp/webcam_agent.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -115,7 +115,7 @@ def main() -> None:
115115
),
116116
hardware=lambda: Webcam(
117117
camera_index=0,
118-
frequency=15,
118+
fps=15,
119119
stereo_slice="left",
120120
camera_info=zed.CameraInfo.SingleWebcam,
121121
),

dimos/hardware/sensors/camera/realsense/camera.py

Lines changed: 5 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -28,14 +28,15 @@
2828
from dimos.core.transport import LCMTransport
2929
from dimos.hardware.sensors.camera.spec import (
3030
OPTICAL_ROTATION,
31-
StereoCamera,
32-
StereoCameraConfig,
31+
DepthCameraConfig,
32+
DepthCameraHardware,
3333
)
3434
from dimos.msgs.geometry_msgs import Quaternion, Transform, Vector3
3535
from dimos.msgs.sensor_msgs import CameraInfo
3636
from dimos.msgs.sensor_msgs.Image import Image, ImageFormat
3737
from dimos.msgs.sensor_msgs.PointCloud2 import PointCloud2
3838
from dimos.robot.foxglove_bridge import FoxgloveBridge
39+
from dimos.spec import perception
3940
from dimos.utils.reactive import backpressure
4041

4142

@@ -48,7 +49,7 @@ def default_base_transform() -> Transform:
4849

4950

5051
@dataclass
51-
class RealSenseCameraConfig(ModuleConfig, StereoCameraConfig):
52+
class RealSenseCameraConfig(ModuleConfig, DepthCameraConfig):
5253
width: int = 848
5354
height: int = 480
5455
fps: int = 15
@@ -63,7 +64,7 @@ class RealSenseCameraConfig(ModuleConfig, StereoCameraConfig):
6364
serial_number: str | None = None
6465

6566

66-
class RealSenseCamera(StereoCamera, Module):
67+
class RealSenseCamera(DepthCameraHardware, Module, perception.DepthCamera):
6768
color_image: Out[Image]
6869
depth_image: Out[Image]
6970
pointcloud: Out[PointCloud2]

dimos/hardware/sensors/camera/spec.py

Lines changed: 9 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -27,6 +27,9 @@
2727

2828
class CameraConfig(Protocol):
2929
frame_id_prefix: str | None
30+
width: int
31+
height: int
32+
fps: int | float
3033

3134

3235
CameraConfigT = TypeVar("CameraConfigT", bound=CameraConfig)
@@ -43,12 +46,9 @@ def camera_info(self) -> CameraInfo:
4346
pass
4447

4548

46-
class StereoCameraConfig(Protocol):
47-
"""Protocol for stereo camera configuration."""
49+
class DepthCameraConfig(CameraConfig):
50+
"""Protocol for depth camera configuration."""
4851

49-
width: int
50-
height: int
51-
fps: int
5252
camera_name: str
5353
base_frame_id: str
5454
base_transform: Transform | None
@@ -59,8 +59,10 @@ class StereoCameraConfig(Protocol):
5959
camera_info_fps: float
6060

6161

62-
class StereoCamera(ABC):
63-
"""Abstract class for stereo camera modules (RealSense, ZED, etc.)."""
62+
class DepthCameraHardware(ABC):
63+
"""Abstract class for depth camera modules (RealSense, ZED, etc.)."""
64+
65+
config: DepthCameraConfig
6466

6567
@abstractmethod
6668
def get_color_camera_info(self) -> CameraInfo | None:

dimos/hardware/sensors/camera/test_webcam.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -43,7 +43,7 @@ def test_streaming_single(dimos) -> None:
4343
),
4444
hardware=lambda: Webcam(
4545
camera_index=0,
46-
frequency=0.0, # full speed but set something to test sharpness barrier
46+
fps=0.0, # full speed but set something to test sharpness barrier
4747
camera_info=zed.CameraInfo.SingleWebcam,
4848
),
4949
)

dimos/hardware/sensors/camera/webcam.py

Lines changed: 10 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -32,9 +32,9 @@
3232
@dataclass
3333
class WebcamConfig(CameraConfig):
3434
camera_index: int = 0 # /dev/videoN
35-
frame_width: int = 640
36-
frame_height: int = 480
37-
frequency: int = 15
35+
width: int = 640
36+
height: int = 480
37+
fps: float = 15.0
3838
camera_info: CameraInfo = field(default_factory=CameraInfo)
3939
frame_id_prefix: str | None = None
4040
stereo_slice: Literal["left", "right"] | None = None # For stereo cameras
@@ -84,8 +84,8 @@ def start(self): # type: ignore[no-untyped-def]
8484
raise RuntimeError(f"Failed to open camera {self.config.camera_index}")
8585

8686
# Set camera properties
87-
self._capture.set(cv2.CAP_PROP_FRAME_WIDTH, self.config.frame_width) # type: ignore[attr-defined]
88-
self._capture.set(cv2.CAP_PROP_FRAME_HEIGHT, self.config.frame_height) # type: ignore[attr-defined]
87+
self._capture.set(cv2.CAP_PROP_FRAME_WIDTH, self.config.width) # type: ignore[attr-defined]
88+
self._capture.set(cv2.CAP_PROP_FRAME_HEIGHT, self.config.height) # type: ignore[attr-defined]
8989

9090
# Clear stop event and start the capture thread
9191
self._stop_event.clear()
@@ -99,7 +99,8 @@ def stop(self) -> None:
9999

100100
# Wait for thread to finish
101101
if self._capture_thread and self._capture_thread.is_alive():
102-
self._capture_thread.join(timeout=(1.0 / self.config.frequency) + 0.1)
102+
timeout = 0.1 if self.config.fps <= 0 else (1.0 / self.config.fps) + 0.1
103+
self._capture_thread.join(timeout=timeout)
103104

104105
# Release the capture
105106
if self._capture:
@@ -142,7 +143,7 @@ def capture_frame(self) -> Image:
142143

143144
def _capture_loop(self) -> None:
144145
"""Capture frames at the configured frequency"""
145-
frame_interval = 1.0 / self.config.frequency
146+
frame_interval = 0.0 if self.config.fps <= 0 else 1.0 / self.config.fps
146147
next_frame_time = time.time()
147148

148149
while self._capture and not self._stop_event.is_set():
@@ -153,6 +154,8 @@ def _capture_loop(self) -> None:
153154
self._observer.on_next(image)
154155

155156
# Wait for next frame time or until stopped
157+
if frame_interval <= 0:
158+
continue
156159
next_frame_time += frame_interval
157160
sleep_time = next_frame_time - time.time()
158161
if sleep_time > 0:

dimos/hardware/sensors/camera/zed/camera.py

Lines changed: 15 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -28,14 +28,15 @@
2828
from dimos.core.transport import LCMTransport
2929
from dimos.hardware.sensors.camera.spec import (
3030
OPTICAL_ROTATION,
31-
StereoCamera,
32-
StereoCameraConfig,
31+
DepthCameraConfig,
32+
DepthCameraHardware,
3333
)
3434
from dimos.msgs.geometry_msgs import Quaternion, Transform, Vector3
3535
from dimos.msgs.sensor_msgs import CameraInfo
3636
from dimos.msgs.sensor_msgs.Image import Image, ImageFormat
3737
from dimos.msgs.sensor_msgs.PointCloud2 import PointCloud2
3838
from dimos.robot.foxglove_bridge import FoxgloveBridge
39+
from dimos.spec import perception
3940
from dimos.utils.reactive import backpressure
4041

4142

@@ -48,7 +49,7 @@ def default_base_transform() -> Transform:
4849

4950

5051
@dataclass
51-
class ZEDCameraConfig(ModuleConfig, StereoCameraConfig):
52+
class ZEDCameraConfig(ModuleConfig, DepthCameraConfig):
5253
width: int = 1280
5354
height: int = 720
5455
fps: int = 15
@@ -73,7 +74,7 @@ class ZEDCameraConfig(ModuleConfig, StereoCameraConfig):
7374
world_frame: str = "world"
7475

7576

76-
class ZEDCamera(StereoCamera, Module):
77+
class ZEDCamera(DepthCameraHardware, Module, perception.DepthCamera):
7778
color_image: Out[Image]
7879
depth_image: Out[Image]
7980
pointcloud: Out[PointCloud2]
@@ -123,7 +124,7 @@ def __init__(self, *args, **kwargs) -> None: # type: ignore[no-untyped-def]
123124
self._tracking_enabled = False
124125
self._stream_width = self.config.width
125126
self._stream_height = self.config.height
126-
self._camera_info: sl.CameraInformation | None = None
127+
self._sl_camera_info: sl.CameraInformation | None = None
127128

128129
def _publish_camera_info(self) -> None:
129130
ts = time.time()
@@ -165,10 +166,10 @@ def start(self) -> None:
165166
self._depth_map = sl.Mat()
166167
self._pose = sl.Pose()
167168

168-
self._camera_info = self._zed.get_camera_information()
169-
if self._camera_info is not None:
170-
self._stream_width = self._camera_info.camera_configuration.resolution.width
171-
self._stream_height = self._camera_info.camera_configuration.resolution.height
169+
self._sl_camera_info = self._zed.get_camera_information()
170+
if self._sl_camera_info is not None:
171+
self._stream_width = self._sl_camera_info.camera_configuration.resolution.width
172+
self._stream_height = self._sl_camera_info.camera_configuration.resolution.height
172173

173174
self._build_camera_info()
174175
self._get_extrinsics()
@@ -198,9 +199,9 @@ def start(self) -> None:
198199
)
199200

200201
def _build_camera_info(self) -> None:
201-
if self._camera_info is None:
202+
if self._sl_camera_info is None:
202203
return
203-
calib = self._camera_info.camera_configuration.calibration_parameters
204+
calib = self._sl_camera_info.camera_configuration.calibration_parameters
204205
left_cam = calib.left_cam
205206

206207
self._color_camera_info = self._intrinsics_to_camera_info(
@@ -236,9 +237,9 @@ def _intrinsics_to_camera_info(
236237
)
237238

238239
def _get_extrinsics(self) -> None:
239-
if self._camera_info is None:
240+
if self._sl_camera_info is None:
240241
return
241-
sensors_config = self._camera_info.sensors_configuration
242+
sensors_config = self._sl_camera_info.sensors_configuration
242243
# camera_imu_transform gives the transform from IMU (body center) to left camera
243244
self._camera_link_to_color_extrinsics = sensors_config.camera_imu_transform
244245

@@ -470,7 +471,7 @@ def stop(self) -> None:
470471
self._image_left = None
471472
self._depth_map = None
472473
self._pose = None
473-
self._camera_info = None
474+
self._sl_camera_info = None
474475
self._tracking_enabled = False
475476
super().stop()
476477

dimos/robot/unitree/g1/g1zed.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -56,7 +56,7 @@ def deploy_g1_monozed(dimos: DimosCluster) -> CameraModule:
5656
),
5757
hardware=lambda: Webcam(
5858
camera_index=0,
59-
frequency=5,
59+
fps=5,
6060
stereo_slice="left",
6161
camera_info=zed.CameraInfo.SingleWebcam,
6262
),

dimos/robot/unitree_webrtc/unitree_g1_blueprints.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -75,7 +75,7 @@
7575
),
7676
hardware=lambda: Webcam(
7777
camera_index=0,
78-
frequency=15,
78+
fps=15,
7979
stereo_slice="left",
8080
camera_info=zed.CameraInfo.SingleWebcam,
8181
),

dimos/spec/perception.py

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -27,5 +27,10 @@ class Camera(Image):
2727
_camera_info: CameraInfo
2828

2929

30+
class DepthCamera(Camera):
31+
depth_image: Out[ImageMsg]
32+
depth_camera_info: Out[CameraInfo]
33+
34+
3035
class Pointcloud(Protocol):
3136
pointcloud: Out[PointCloud2]

0 commit comments

Comments
 (0)