Skip to content
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
62 changes: 62 additions & 0 deletions .github/workflows/docker.yml
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@ jobs:
runs-on: [self-hosted, Linux]
outputs:
ros: ${{ steps.filter.outputs.ros }}
ros-jazzy: ${{ steps.filter.outputs.ros-jazzy }}
python: ${{ steps.filter.outputs.python }}
dev: ${{ steps.filter.outputs.dev }}
tests: ${{ steps.filter.outputs.tests }}
Expand All @@ -47,6 +48,11 @@ jobs:
- .github/workflows/docker.yml
- docker/ros/**

ros-jazzy:
- .github/workflows/_docker-build-template.yml
- .github/workflows/docker.yml
- docker/ros-jazzy/**

python:
- .github/workflows/_docker-build-template.yml
- .github/workflows/docker.yml
Expand Down Expand Up @@ -148,6 +154,46 @@ jobs:
to-image: ghcr.io/dimensionalos/ros-dev:${{ needs.check-changes.outputs.branch-tag }}
dockerfile: dev

# ROS Jazzy chain (Ubuntu 24.04 / Python 3.12)
ros-jazzy:
needs: [check-changes]
if: needs.check-changes.outputs.ros-jazzy == 'true'
uses: ./.github/workflows/_docker-build-template.yml
with:
should-run: true
from-image: ubuntu:24.04
to-image: ghcr.io/dimensionalos/ros-jazzy:${{ needs.check-changes.outputs.branch-tag }}
dockerfile: ros-jazzy

ros-python-jazzy:
needs: [check-changes, ros-jazzy]
if: always()
uses: ./.github/workflows/_docker-build-template.yml
with:
should-run: ${{
needs.check-changes.outputs.python == 'true' &&
needs.check-changes.result != 'error' &&
needs.ros-jazzy.result != 'error'
}}

from-image: ghcr.io/dimensionalos/ros-jazzy:${{ needs.ros-jazzy.result == 'success' && needs.check-changes.outputs.branch-tag || 'dev' }}
to-image: ghcr.io/dimensionalos/ros-python-jazzy:${{ needs.check-changes.outputs.branch-tag }}
dockerfile: python

ros-dev-jazzy:
needs: [check-changes, ros-python-jazzy]
if: always()
uses: ./.github/workflows/_docker-build-template.yml
with:
should-run: ${{
needs.check-changes.result == 'success' &&
(needs.check-changes.outputs.dev == 'true' ||
(needs.ros-python-jazzy.result == 'success' && (needs.check-changes.outputs.python == 'true' || needs.check-changes.outputs.ros-jazzy == 'true')))
}}
from-image: ghcr.io/dimensionalos/ros-python-jazzy:${{ needs.ros-python-jazzy.result == 'success' && needs.check-changes.outputs.branch-tag || 'dev' }}
to-image: ghcr.io/dimensionalos/ros-dev-jazzy:${{ needs.check-changes.outputs.branch-tag }}
dockerfile: dev

run-ros-tests:
needs: [check-changes, ros-dev]
if: always()
Expand Down Expand Up @@ -209,6 +255,22 @@ jobs:
cmd: "pytest -m lcm"
dev-image: dev:${{ (needs.check-changes.outputs.python == 'true' || needs.check-changes.outputs.dev == 'true') && needs.dev.result == 'success' && needs.check-changes.outputs.branch-tag || 'dev' }}

# Run mypy type checking with ROS types (uses Jazzy for Python 3.12)
run-mypy:
needs: [check-changes, ros-dev-jazzy]
if: always()
uses: ./.github/workflows/tests.yml
secrets: inherit
with:
should-run: ${{
needs.check-changes.result == 'success' &&
((needs.ros-dev-jazzy.result == 'success') ||
(needs.ros-dev-jazzy.result == 'skipped' &&
needs.check-changes.outputs.tests == 'true'))
}}
cmd: "MYPYPATH=/opt/ros/jazzy/lib/python3.12/site-packages mypy dimos"
dev-image: ros-dev-jazzy:${{ (needs.check-changes.outputs.python == 'true' || needs.check-changes.outputs.dev == 'true' || needs.check-changes.outputs.ros-jazzy == 'true') && needs.ros-dev-jazzy.result == 'success' && needs.check-changes.outputs.branch-tag || 'dev' }}

# Run module tests directly to avoid pytest forking issues
# run-module-tests:
# needs: [check-changes, dev]
Expand Down
2 changes: 1 addition & 1 deletion dimos/core/stream.py
Original file line number Diff line number Diff line change
Expand Up @@ -256,7 +256,7 @@ def transport(self) -> Transport[T]:
def publish(self, msg) -> None: # type: ignore[no-untyped-def]
self.transport.broadcast(self, msg) # type: ignore[arg-type]

@transport.setter # type: ignore[attr-defined, misc, no-redef]
@transport.setter # type: ignore[attr-defined, misc, no-redef, untyped-decorator]
def transport(self, value: Transport[T]) -> None:
self.owner.set_transport(self.name, value).result() # type: ignore[union-attr]
self._transport = value
2 changes: 1 addition & 1 deletion dimos/hardware/camera/zed/camera.py
Original file line number Diff line number Diff line change
Expand Up @@ -591,7 +591,7 @@ def __init__( # type: ignore[no-untyped-def]
self.tf = TF()

# Initialize storage for recording if path provided
self.storages = None
self.storages: dict[str, Any] | None = None
if self.recording_path:
from dimos.utils.testing import TimedSensorStorage

Expand Down
4 changes: 2 additions & 2 deletions dimos/hardware/gstreamer_camera.py
Original file line number Diff line number Diff line change
Expand Up @@ -29,11 +29,11 @@
if "/usr/lib/python3/dist-packages" not in sys.path:
sys.path.insert(0, "/usr/lib/python3/dist-packages")

import gi # type: ignore[import-not-found]
import gi # type: ignore[import-untyped,import-not-found]

gi.require_version("Gst", "1.0")
gi.require_version("GstApp", "1.0")
from gi.repository import GLib, Gst # type: ignore[import-not-found]
from gi.repository import GLib, Gst # type: ignore[import-untyped,import-not-found]

logger = setup_logger(level=logging.INFO)

Expand Down
4 changes: 2 additions & 2 deletions dimos/hardware/gstreamer_sender.py
Original file line number Diff line number Diff line change
Expand Up @@ -24,11 +24,11 @@
if "/usr/lib/python3/dist-packages" not in sys.path:
sys.path.insert(0, "/usr/lib/python3/dist-packages")

import gi # type: ignore[import-not-found]
import gi # type: ignore[import-untyped,import-not-found]

gi.require_version("Gst", "1.0")
gi.require_version("GstVideo", "1.0")
from gi.repository import GLib, Gst # type: ignore[import-not-found]
from gi.repository import GLib, Gst # type: ignore[import-untyped,import-not-found]

# Initialize GStreamer
Gst.init(None)
Expand Down
2 changes: 1 addition & 1 deletion dimos/hardware/piper_arm.py
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@
from piper_sdk import * # type: ignore[import-not-found] # from the official Piper SDK
import pytest
from reactivex.disposable import Disposable
from scipy.spatial.transform import Rotation as R
from scipy.spatial.transform import Rotation as R # type: ignore[import-untyped]

import dimos.core as core
from dimos.core import In, Module, rpc
Expand Down
2 changes: 1 addition & 1 deletion dimos/manipulation/visual_servoing/pbvs.py
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@

from dimos_lcm.vision_msgs import Detection3D # type: ignore[import-untyped]
import numpy as np
from scipy.spatial.transform import Rotation as R
from scipy.spatial.transform import Rotation as R # type: ignore[import-untyped]

from dimos.manipulation.visual_servoing.utils import (
create_pbvs_visualization,
Expand Down
2 changes: 1 addition & 1 deletion dimos/models/vl/base.py
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,7 @@ def warmup(self) -> None:
pass

# requery once if JSON parsing fails
@retry(max_retries=2, on_exception=json.JSONDecodeError, delay=0.0) # type: ignore[misc]
@retry(max_retries=2, on_exception=json.JSONDecodeError, delay=0.0) # type: ignore[misc, untyped-decorator]
def query_json(self, image: Image, query: str) -> dict: # type: ignore[type-arg]
response = self.query(image, query)
return extract_json(response) # type: ignore[return-value]
Expand Down
2 changes: 1 addition & 1 deletion dimos/msgs/geometry_msgs/Quaternion.py
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
from dimos_lcm.geometry_msgs import Quaternion as LCMQuaternion # type: ignore[import-untyped]
import numpy as np
from plum import dispatch
from scipy.spatial.transform import Rotation as R
from scipy.spatial.transform import Rotation as R # type: ignore[import-untyped]

from dimos.msgs.geometry_msgs.Vector3 import Vector3

Expand Down
2 changes: 1 addition & 1 deletion dimos/msgs/nav_msgs/OccupancyGrid.py
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@
)
from dimos_lcm.std_msgs import Time as LCMTime # type: ignore[import-untyped]
import numpy as np
from scipy import ndimage
from scipy import ndimage # type: ignore[import-untyped]

from dimos.msgs.geometry_msgs import Pose, Vector3, VectorLike
from dimos.types.timestamped import Timestamped
Expand Down
2 changes: 1 addition & 1 deletion dimos/navigation/bt_navigator/goal_validator.py
Original file line number Diff line number Diff line change
Expand Up @@ -227,7 +227,7 @@ def _find_safe_goal_voronoi(
- Requires scipy for efficient implementation
"""

from scipy import ndimage
from scipy import ndimage # type: ignore[import-untyped]
from skimage.morphology import skeletonize # type: ignore[import-not-found]

# Convert goal to grid coordinates
Expand Down
2 changes: 1 addition & 1 deletion dimos/navigation/frontier_exploration/utils.py
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ def costmap_to_pil_image(costmap: OccupancyGrid, scale_factor: int = 2) -> Image
# Scale up if requested
if scale_factor > 1:
new_size = (img.width * scale_factor, img.height * scale_factor)
img = img.resize(new_size, Image.NEAREST) # Use NEAREST to keep sharp pixels
img = img.resize(new_size, Image.NEAREST) # type: ignore[attr-defined] # Use NEAREST to keep sharp pixels

return img

Expand Down
4 changes: 2 additions & 2 deletions dimos/perception/common/export_tensorrt.py
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@

import argparse

from ultralytics import YOLO, FastSAM
from ultralytics import YOLO, FastSAM # type: ignore[attr-defined]


def parse_args(): # type: ignore[no-untyped-def]
Expand Down Expand Up @@ -46,7 +46,7 @@ def main() -> None:
int8 = args.precision == "int8"
# Load the appropriate model
if args.model_type == "yolo":
model = YOLO(args.model_path)
model: YOLO | FastSAM = YOLO(args.model_path)
else:
model = FastSAM(args.model_path)

Expand Down
2 changes: 1 addition & 1 deletion dimos/perception/detection/detectors/person/yolo.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
# See the License for the specific language governing permissions and
# limitations under the License.

from ultralytics import YOLO
from ultralytics import YOLO # type: ignore[attr-defined]

from dimos.msgs.sensor_msgs import Image
from dimos.perception.detection.detectors.types import Detector
Expand Down
2 changes: 1 addition & 1 deletion dimos/perception/detection/detectors/yolo.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
# See the License for the specific language governing permissions and
# limitations under the License.

from ultralytics import YOLO
from ultralytics import YOLO # type: ignore[attr-defined]

from dimos.msgs.sensor_msgs import Image
from dimos.perception.detection.detectors.types import Detector
Expand Down
2 changes: 1 addition & 1 deletion dimos/perception/pointcloud/utils.py
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
import cv2
import numpy as np
import open3d as o3d # type: ignore[import-untyped]
from scipy.spatial import cKDTree
from scipy.spatial import cKDTree # type: ignore[import-untyped]
import yaml

from dimos.perception.common.utils import project_3d_points_to_2d
Expand Down
2 changes: 1 addition & 1 deletion dimos/perception/segmentation/sam_2d_seg.py
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@

import cv2
import onnxruntime # type: ignore[import-untyped]
from ultralytics import FastSAM
from ultralytics import FastSAM # type: ignore[attr-defined]

from dimos.perception.common.detection2d_tracker import get_tracked_results, target2dTracker
from dimos.perception.segmentation.image_analyzer import ImageAnalyzer
Expand Down
28 changes: 15 additions & 13 deletions dimos/protocol/skill/test_coordinator.py
Original file line number Diff line number Diff line change
Expand Up @@ -47,51 +47,53 @@ def delayadd(self, x: int, y: int) -> int:
time.sleep(0.3)
return x + y

@skill(stream=Stream.call_agent, reducer=Reducer.all)
@skill(stream=Stream.call_agent, reducer=Reducer.all) # type: ignore[arg-type]
def counter(self, count_to: int, delay: float | None = 0.05) -> Generator[int, None, None]:
"""Counts from 1 to count_to, with an optional delay between counts."""
for i in range(1, count_to + 1):
if delay > 0:
if delay is not None and delay > 0:
time.sleep(delay)
yield i

@skill(stream=Stream.passive, reducer=Reducer.sum)
@skill(stream=Stream.passive, reducer=Reducer.sum) # type: ignore[arg-type]
def counter_passive_sum(
self, count_to: int, delay: float | None = 0.05
) -> Generator[int, None, None]:
"""Counts from 1 to count_to, with an optional delay between counts."""
for i in range(1, count_to + 1):
if delay > 0:
if delay is not None and delay > 0:
time.sleep(delay)
yield i

@skill(stream=Stream.passive, reducer=Reducer.latest)
@skill(stream=Stream.passive, reducer=Reducer.latest) # type: ignore[arg-type]
def current_time(self, frequency: float | None = 10) -> Generator[str, None, None]:
"""Provides current time."""
while True:
yield str(datetime.datetime.now())
time.sleep(1 / frequency)
if frequency is not None:
time.sleep(1 / frequency)

@skill(stream=Stream.passive, reducer=Reducer.latest)
@skill(stream=Stream.passive, reducer=Reducer.latest) # type: ignore[arg-type]
def uptime_seconds(self, frequency: float | None = 10) -> Generator[float, None, None]:
"""Provides current uptime."""
start_time = datetime.datetime.now()
while True:
yield (datetime.datetime.now() - start_time).total_seconds()
time.sleep(1 / frequency)
if frequency is not None:
time.sleep(1 / frequency)

@skill()
def current_date(self, frequency: float | None = 10) -> str:
"""Provides current date."""
return datetime.datetime.now()
return str(datetime.datetime.now())

@skill(output=Output.image)
def take_photo(self) -> str:
def take_photo(self) -> Image: # type: ignore[type-arg]
"""Takes a camera photo"""
print("Taking photo...")
img = Image.from_file(get_data("cafe-smol.jpg"))
img = Image.from_file(str(get_data("cafe-smol.jpg"))) # type: ignore[arg-type]
print("Photo taken.")
return img
return img # type: ignore[return-value]


@pytest.mark.asyncio
Expand All @@ -113,7 +115,7 @@ async def test_coordinator_parallel_calls() -> None:

skill_id = f"test-call-{cnt}"
tool_msg = skillstates[skill_id].agent_encode()
assert tool_msg.content == cnt + 2
assert tool_msg.content == cnt + 2 # type: ignore[union-attr]

cnt += 1
if cnt < 5:
Expand Down
2 changes: 1 addition & 1 deletion dimos/utils/transform_utils.py
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@


import numpy as np
from scipy.spatial.transform import Rotation as R
from scipy.spatial.transform import Rotation as R # type: ignore[import-untyped]

from dimos.msgs.geometry_msgs import Pose, Quaternion, Transform, Vector3

Expand Down
12 changes: 6 additions & 6 deletions dimos/web/websocket_vis/websocket_vis_module.py
Original file line number Diff line number Diff line change
Expand Up @@ -186,7 +186,7 @@ async def serve_index(request): # type: ignore[no-untyped-def]
self.app = socketio.ASGIApp(self.sio, starlette_app)

# Register SocketIO event handlers
@self.sio.event # type: ignore[misc]
@self.sio.event # type: ignore[misc, untyped-decorator]
async def connect(sid, environ) -> None: # type: ignore[no-untyped-def]
with self.state_lock:
current_state = dict(self.vis_state)
Expand All @@ -196,7 +196,7 @@ async def connect(sid, environ) -> None: # type: ignore[no-untyped-def]

await self.sio.emit("full_state", current_state, room=sid) # type: ignore[union-attr]

@self.sio.event # type: ignore[misc]
@self.sio.event # type: ignore[misc, untyped-decorator]
async def click(sid, position) -> None: # type: ignore[no-untyped-def]
goal = PoseStamped(
position=(position[0], position[1], 0),
Expand All @@ -206,22 +206,22 @@ async def click(sid, position) -> None: # type: ignore[no-untyped-def]
self.goal_request.publish(goal)
logger.info(f"Click goal published: ({goal.position.x:.2f}, {goal.position.y:.2f})")

@self.sio.event # type: ignore[misc]
@self.sio.event # type: ignore[misc, untyped-decorator]
async def gps_goal(sid, goal) -> None: # type: ignore[no-untyped-def]
logger.info(f"Set GPS goal: {goal}")
self.gps_goal.publish(LatLon(lat=goal["lat"], lon=goal["lon"]))

@self.sio.event # type: ignore[misc]
@self.sio.event # type: ignore[misc, untyped-decorator]
async def start_explore(sid) -> None: # type: ignore[no-untyped-def]
logger.info("Starting exploration")
self.explore_cmd.publish(Bool(data=True))

@self.sio.event # type: ignore[misc]
@self.sio.event # type: ignore[misc, untyped-decorator]
async def stop_explore(sid) -> None: # type: ignore[no-untyped-def]
logger.info("Stopping exploration")
self.stop_explore_cmd.publish(Bool(data=True))

@self.sio.event # type: ignore[misc]
@self.sio.event # type: ignore[misc, untyped-decorator]
async def move_command(sid, data) -> None: # type: ignore[no-untyped-def]
# Publish Twist if transport is configured
if self.cmd_vel and self.cmd_vel.transport:
Expand Down
Loading