2828from dimos .core .transport import LCMTransport
2929from dimos .hardware .sensors .camera .spec import (
3030 OPTICAL_ROTATION ,
31- StereoCamera ,
32- StereoCameraConfig ,
31+ DepthCameraConfig ,
32+ DepthCameraHardware ,
3333)
3434from dimos .msgs .geometry_msgs import Quaternion , Transform , Vector3
3535from dimos .msgs .sensor_msgs import CameraInfo
3636from dimos .msgs .sensor_msgs .Image import Image , ImageFormat
3737from dimos .msgs .sensor_msgs .PointCloud2 import PointCloud2
3838from dimos .robot .foxglove_bridge import FoxgloveBridge
39+ from dimos .spec import perception
3940from 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
0 commit comments