Skip to content

Commit 63135c9

Browse files
authored
Merge pull request #791 from dimensionalOS/fix-mypy-errors
fix mypy errors and g1 detection blueprint merge errors
2 parents 76b4cc7 + f10b70b commit 63135c9

File tree

5 files changed

+43
-31
lines changed

5 files changed

+43
-31
lines changed

dimos/core/stream.py

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -35,6 +35,8 @@
3535
if TYPE_CHECKING:
3636
from collections.abc import Callable
3737

38+
from reactivex.observable import Observable
39+
3840
T = TypeVar("T")
3941

4042

@@ -57,7 +59,7 @@ def get_next(self, timeout: float = 10.0) -> T:
5759
def hot_latest(self) -> Callable[[], T]:
5860
return reactive.getter_streaming(self.observable()) # type: ignore[no-untyped-call]
5961

60-
def pure_observable(self): # type: ignore[no-untyped-def]
62+
def pure_observable(self) -> Observable[T]:
6163
def _subscribe(observer, scheduler=None): # type: ignore[no-untyped-def]
6264
unsubscribe = self.subscribe(observer.on_next) # type: ignore[attr-defined]
6365
return Disposable(unsubscribe)
@@ -67,7 +69,7 @@ def _subscribe(observer, scheduler=None): # type: ignore[no-untyped-def]
6769
# default return is backpressured because most
6870
# use cases will want this by default
6971
def observable(self): # type: ignore[no-untyped-def]
70-
return backpressure(self.pure_observable()) # type: ignore[no-untyped-call]
72+
return backpressure(self.pure_observable())
7173

7274

7375
class State(enum.Enum):

dimos/perception/detection/module2D.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -82,7 +82,7 @@ def process_image_frame(self, image: Image) -> ImageDetections2D:
8282
@simple_mcache
8383
def sharp_image_stream(self) -> Observable[Image]:
8484
return backpressure(
85-
self.image.pure_observable().pipe( # type: ignore[no-untyped-call]
85+
self.image.pure_observable().pipe(
8686
sharpness_barrier(self.config.max_freq),
8787
)
8888
)

dimos/perception/detection/person_tracker.py

Lines changed: 12 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,8 @@
1313
# limitations under the License.
1414

1515

16+
from typing import Any
17+
1618
from reactivex import operators as ops
1719
from reactivex.observable import Observable
1820

@@ -32,7 +34,7 @@ class PersonTracker(Module):
3234

3335
camera_info: CameraInfo
3436

35-
def __init__(self, cameraInfo: CameraInfo, **kwargs) -> None:
37+
def __init__(self, cameraInfo: CameraInfo, **kwargs: Any) -> None:
3638
super().__init__(**kwargs)
3739
self.camera_info = cameraInfo
3840

@@ -80,7 +82,13 @@ def detections_stream(self) -> Observable[ImageDetections2D]:
8082
),
8183
match_tolerance=0.0,
8284
buffer_size=2.0,
83-
).pipe(ops.map(lambda pair: ImageDetections2D.from_ros_detection2d_array(*pair)))
85+
).pipe(
86+
ops.map(
87+
lambda pair: ImageDetections2D.from_ros_detection2d_array(
88+
*pair # type: ignore[misc]
89+
)
90+
)
91+
)
8492
)
8593

8694
@rpc
@@ -95,8 +103,8 @@ def track(self, detections2D: ImageDetections2D) -> None:
95103
if len(detections2D) == 0:
96104
return
97105

98-
target = max(detections2D.detections, key=lambda det: det.bbox_2d_volume())
99-
vector = self.center_to_3d(target.center_bbox, self.camera_info, 2.0)
106+
target = max(detections2D.detections, key=lambda det: det.bbox_2d_volume()) # type: ignore[attr-defined]
107+
vector = self.center_to_3d(target.center_bbox, self.camera_info, 2.0) # type: ignore[attr-defined]
100108

101109
pose_in_camera = PoseStamped(
102110
ts=detections2D.ts,

dimos/perception/detection/reid/module.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -59,8 +59,8 @@ def __init__(self, idsystem: IDSystem | None = None, **kwargs) -> None: # type:
5959
def detections_stream(self) -> Observable[ImageDetections2D]:
6060
return backpressure(
6161
align_timestamped(
62-
self.image.pure_observable(), # type: ignore[no-untyped-call]
63-
self.detections.pure_observable().pipe( # type: ignore[no-untyped-call]
62+
self.image.pure_observable(),
63+
self.detections.pure_observable().pipe(
6464
ops.filter(lambda d: d.detections_length > 0) # type: ignore[attr-defined]
6565
),
6666
match_tolerance=0.0,

dimos/robot/unitree_webrtc/unitree_g1_blueprints.py

Lines changed: 24 additions & 22 deletions
Original file line numberDiff line numberDiff line change
@@ -19,8 +19,10 @@
1919
from basic teleoperation to full autonomous agent configurations.
2020
"""
2121

22-
from dimos_lcm.foxglove_msgs import SceneUpdate
23-
from dimos_lcm.foxglove_msgs.ImageAnnotations import ImageAnnotations
22+
from dimos_lcm.foxglove_msgs import SceneUpdate # type: ignore[import-untyped]
23+
from dimos_lcm.foxglove_msgs.ImageAnnotations import (
24+
ImageAnnotations,
25+
)
2426
from dimos_lcm.sensor_msgs import CameraInfo # type: ignore[import-untyped]
2527

2628
from dimos.agents2.agent import llm_agent
@@ -192,7 +194,7 @@
192194
# Detection configuration with person tracking and 3D detection
193195
detection = (
194196
autoconnect(
195-
basic,
197+
basic_ros,
196198
# Person detection modules with YOLO
197199
detection3d_module(
198200
camera_info=zed.CameraInfo.SingleWebcam,
@@ -221,49 +223,49 @@
221223
.transports(
222224
{
223225
# Detection 3D module outputs
224-
(Detection3DModule, "detections"): LCMTransport(
226+
("detections", Detection3DModule): LCMTransport(
225227
"/detector3d/detections", Detection2DArray
226228
),
227-
(Detection3DModule, "annotations"): LCMTransport(
229+
("annotations", Detection3DModule): LCMTransport(
228230
"/detector3d/annotations", ImageAnnotations
229231
),
230-
(Detection3DModule, "scene_update"): LCMTransport(
232+
("scene_update", Detection3DModule): LCMTransport(
231233
"/detector3d/scene_update", SceneUpdate
232234
),
233-
(Detection3DModule, "detected_pointcloud_0"): LCMTransport(
235+
("detected_pointcloud_0", Detection3DModule): LCMTransport(
234236
"/detector3d/pointcloud/0", PointCloud2
235237
),
236-
(Detection3DModule, "detected_pointcloud_1"): LCMTransport(
238+
("detected_pointcloud_1", Detection3DModule): LCMTransport(
237239
"/detector3d/pointcloud/1", PointCloud2
238240
),
239-
(Detection3DModule, "detected_pointcloud_2"): LCMTransport(
241+
("detected_pointcloud_2", Detection3DModule): LCMTransport(
240242
"/detector3d/pointcloud/2", PointCloud2
241243
),
242-
(Detection3DModule, "detected_image_0"): LCMTransport("/detector3d/image/0", Image),
243-
(Detection3DModule, "detected_image_1"): LCMTransport("/detector3d/image/1", Image),
244-
(Detection3DModule, "detected_image_2"): LCMTransport("/detector3d/image/2", Image),
244+
("detected_image_0", Detection3DModule): LCMTransport("/detector3d/image/0", Image),
245+
("detected_image_1", Detection3DModule): LCMTransport("/detector3d/image/1", Image),
246+
("detected_image_2", Detection3DModule): LCMTransport("/detector3d/image/2", Image),
245247
# Detection DB module outputs
246-
(ObjectDBModule, "detections"): LCMTransport(
248+
("detections", ObjectDBModule): LCMTransport(
247249
"/detectorDB/detections", Detection2DArray
248250
),
249-
(ObjectDBModule, "annotations"): LCMTransport(
251+
("annotations", ObjectDBModule): LCMTransport(
250252
"/detectorDB/annotations", ImageAnnotations
251253
),
252-
(ObjectDBModule, "scene_update"): LCMTransport("/detectorDB/scene_update", SceneUpdate),
253-
(ObjectDBModule, "detected_pointcloud_0"): LCMTransport(
254+
("scene_update", ObjectDBModule): LCMTransport("/detectorDB/scene_update", SceneUpdate),
255+
("detected_pointcloud_0", ObjectDBModule): LCMTransport(
254256
"/detectorDB/pointcloud/0", PointCloud2
255257
),
256-
(ObjectDBModule, "detected_pointcloud_1"): LCMTransport(
258+
("detected_pointcloud_1", ObjectDBModule): LCMTransport(
257259
"/detectorDB/pointcloud/1", PointCloud2
258260
),
259-
(ObjectDBModule, "detected_pointcloud_2"): LCMTransport(
261+
("detected_pointcloud_2", ObjectDBModule): LCMTransport(
260262
"/detectorDB/pointcloud/2", PointCloud2
261263
),
262-
(ObjectDBModule, "detected_image_0"): LCMTransport("/detectorDB/image/0", Image),
263-
(ObjectDBModule, "detected_image_1"): LCMTransport("/detectorDB/image/1", Image),
264-
(ObjectDBModule, "detected_image_2"): LCMTransport("/detectorDB/image/2", Image),
264+
("detected_image_0", ObjectDBModule): LCMTransport("/detectorDB/image/0", Image),
265+
("detected_image_1", ObjectDBModule): LCMTransport("/detectorDB/image/1", Image),
266+
("detected_image_2", ObjectDBModule): LCMTransport("/detectorDB/image/2", Image),
265267
# Person tracker outputs
266-
(PersonTracker, "target"): LCMTransport("/person_tracker/target", PoseStamped),
268+
("target", PersonTracker): LCMTransport("/person_tracker/target", PoseStamped),
267269
}
268270
)
269271
)

0 commit comments

Comments
 (0)