Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add support for rtsp camera streams #17

Merged
merged 58 commits into from
Jul 15, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
58 commits
Select commit Hold shift + click to select a range
4042ffe
first experiment with opencv based on usb provider
rodja Jan 7, 2023
f6b9f83
using ffmpeg instead of opencv
rodja Jan 7, 2023
1e5f8e9
debugging
rodja Jan 9, 2023
26216ff
Merge remote-tracking branch 'origin/main' into camera_streams
rodja Jan 18, 2023
f95195d
scan for cameras and activate/deactivate them
rodja Jan 18, 2023
14babc9
debugging
rodja Jan 20, 2023
12bc6fd
experimenting with multiple cameras
rodja Jan 22, 2023
9b6067b
made example work again with one cam
rodja Jan 22, 2023
3d893c5
performant reading from multiple ip cam streams
rodja Jan 23, 2023
29ad1b2
cleanup
rodja Jan 23, 2023
3c78763
cleanup
rodja Jan 23, 2023
bf89b8e
update rtsp url
rodja Jan 23, 2023
60bf924
minimal speed improvements
rodja Jan 24, 2023
f25de29
allow setting a name for cams
rodja Jan 24, 2023
0cbac60
try to improve quality
rodja Jan 24, 2023
7cab3d1
handle rotation of rtsp cameras
pglah Mar 16, 2023
192e2b2
allow rtsp_cams on mac
rodja Mar 17, 2023
f48fe8f
fixed activating available cameras
rodja Mar 27, 2023
15de468
working on camera rotation
rodja Mar 29, 2023
1843d2f
fixed rotation of jpeg images
rodja Mar 29, 2023
e0ac6e2
fixed adding new camera and providing arp-scan package
rodja Apr 4, 2023
9aaf40a
using gstreamer
rodja Apr 5, 2023
2a5ca07
fine tuning
rodja Apr 5, 2023
405810b
fixed reloading
rodja Apr 5, 2023
1c3c11b
adding function to request backup
rodja Apr 5, 2023
5a8321e
camera resolution
rodja Apr 6, 2023
37a26e9
cleanup
rodja Apr 6, 2023
b0f0042
show warning if arp scan fails due to missing permission
rodja Apr 14, 2023
ddfb0d7
ensure timeout really works in all cases
rodja Apr 14, 2023
c447718
further enhancing timeout for run.sh
rodja Apr 14, 2023
d15ec0b
reducing timeout for arp scan for quicker results
rodja Apr 14, 2023
32c8753
use 6 fps for camera streams by default
rodja Apr 14, 2023
2bf82ac
increase timeout again
pglah Apr 17, 2023
022c085
added tags to detect in detector_simulation
angelom93 Apr 27, 2023
476b447
made confidence configurable for simulated objects
rodja Apr 28, 2023
39c9246
request_backup method for all camera_providers
rodja May 19, 2023
25a4b85
deactivate non-reachable cams (from persistance)
rodja May 20, 2023
ff743d1
fixed docker build
rodja May 21, 2023
7e9963a
adding support for dahua cameras
rodja May 21, 2023
9570afe
determine camera resolution from rtsp stream
rodja May 21, 2023
e71a2bc
Merge commit 'fd069b1605ed3c46324ebdd250a976281fcf3887' into camera_s…
rodja May 21, 2023
6ddcad6
cleanup
rodja May 21, 2023
3657703
fixed dependency defenition
rodja May 21, 2023
ef82168
extracted vendor mac to url matching
rodja May 21, 2023
8fcbde9
catch errors with image size determination
rodja May 21, 2023
29d2fcc
only set active-flag after cam has been activated
rodja May 22, 2023
260f208
code review
falkoschindler May 22, 2023
be93f20
convert detections from and to dict (for rest interface)
rodja Jun 3, 2023
49372d3
handle unauthorized rtsp cameras
rodja Jun 4, 2023
b9ec0e5
introduce combining camera provider
rodja Jun 4, 2023
8af7991
get smaller images for 4k cameras
pglah Jun 7, 2023
4061414
get image snapshot
pglah Jun 7, 2023
63487ac
fixed get_image _snapshot
angelom93 Jun 20, 2023
d9108c0
fixed camera size for image snapshot
angelom93 Jul 3, 2023
4bafccd
cleanup
falkoschindler Jul 5, 2023
a87d852
provide RtspCamera in vision module
falkoschindler Jul 5, 2023
72ef0a3
fixed return type annotation
angelom93 Jul 5, 2023
ca8dabd
small logging changes
angelom93 Jul 11, 2023
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
3 changes: 1 addition & 2 deletions Dockerfile
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
FROM python:3.11-buster

RUN apt update && apt install -y \
sudo vim less ack-grep rsync wget curl cmake iproute2 iw python3-pip python3-autopep8 libgeos-dev graphviz graphviz-dev v4l-utils psmisc sysstat \
sudo vim less ack-grep rsync wget curl cmake arp-scan iproute2 iw python3-pip python3-autopep8 libgeos-dev graphviz graphviz-dev v4l-utils psmisc sysstat \
libgl1-mesa-glx ffmpeg libsm6 libxext6 \
avahi-utils iputils-ping \
jq \
Expand All @@ -19,7 +19,6 @@ RUN curl -sSL https://install.python-poetry.org | python3 - && \
# only copy poetry package specs to minimize rebuilding of image layers
WORKDIR /rosys
COPY pyproject.toml ./
RUN poetry config experimental.new-installer false

# Allow installing dev dependencies to run tests
ARG INSTALL_DEV=true
Expand Down
23 changes: 23 additions & 0 deletions docs/src/example_camera_streams.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
#!/usr/bin/env python3
from nicegui import ui

import rosys

camera_provider = rosys.vision.RtspCameraProviderHardware()


def refresh() -> None:
for uid, camera in camera_provider.cameras.items():
if uid not in streams:
with camera_grid:
with ui.card().tight():
streams[uid] = ui.interactive_image()
ui.label(uid).classes('m-2')
streams[uid].set_source(camera_provider.get_latest_image_url(camera))


streams: dict[str, ui.interactive_image] = {}
camera_grid = ui.row()
ui.timer(0.01, refresh)

ui.run(title='RoSys')
4 changes: 2 additions & 2 deletions docs/src/example_cameras_images.py
Original file line number Diff line number Diff line change
Expand Up @@ -10,11 +10,11 @@
def refresh() -> None:
for uid, camera in camera_provider.cameras.items():
if uid not in feeds:
feeds[uid] = ui.image()
feeds[uid] = ui.interactive_image()
feeds[uid].set_source(camera_provider.get_latest_image_url(camera))


feeds = {}
feeds: dict[str, ui.interactive_image] = {}
ui.timer(0.3, refresh)

ui.run(title='RoSys')
1,259 changes: 584 additions & 675 deletions poetry.lock

Large diffs are not rendered by default.

6 changes: 4 additions & 2 deletions pyproject.toml
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@ keywords = ["robot", "framework", "automation", "control", "steer"]

[tool.poetry.dependencies]
python = ">=3.10, <3.12"
nicegui = "1.2.10"
nicegui = ">=1.2.14"
asyncio = "^3.4.3"
retry = "^0.9.2"
aenum = "^3.1.5"
Expand All @@ -37,10 +37,12 @@ uvloop = "^0.17.0"
dataclasses-json = "^0.5.7"
executing = "^1.0.0"
suntime = "^1.2.5"
line-profiler = "^4.0.2"
line-profiler = "^4.0.3"
yappi = "^1.4"
pyloot = "^0.1.0"
objgraph = "^3.5.0"
imgsize = "^2.1"
netifaces = "^0.11.0"
httpx = "^0.24.0"

[tool.poetry.dev-dependencies]
Expand Down
3 changes: 3 additions & 0 deletions rosys/config.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,3 +18,6 @@ def backup(self) -> dict[str, Any]:

def restore(self, data: dict[str, Any]) -> None:
self.simulation_speed = data.get('simulation_speed', 1.0)

def invalidate(self) -> None:
self.needs_backup = True
15 changes: 15 additions & 0 deletions rosys/helpers.py
Original file line number Diff line number Diff line change
Expand Up @@ -69,3 +69,18 @@ def set(self, **kwargs) -> Generator[None, None, None]:
finally:
for key, value in backup.items():
setattr(self, key, value)


def from_dict(data_class_type, data):
if data is None:
return None
elif hasattr(data_class_type, '__dataclass_fields__'): # It's a DataClass
field_types = {f: t for f, t in data_class_type.__annotations__.items()}
return data_class_type(**{f: from_dict(field_types[f], data[f]) for f in data})
elif hasattr(data_class_type, '__origin__'): # It's a generic
if data_class_type.__origin__ is list: # It's a List
return [from_dict(data_class_type.__args__[0], d) for d in data]
if data_class_type.__origin__ is dict: # It's a Dict
return {k: from_dict(data_class_type.__args__[1], v) for k, v in data.items()}
else: # It's a regular type
return data_class_type(data)
15 changes: 10 additions & 5 deletions rosys/run.py
Original file line number Diff line number Diff line change
Expand Up @@ -87,15 +87,15 @@ def popen() -> str:
cmd = shlex.split(command) if isinstance(command, str) else command
if timeout is not None:
if shell:
cmd = f'timeout {timeout} {cmd}'
cmd = f'timeout --signal=SIGKILL {timeout} {cmd}'
else:
cmd = ['timeout', str(timeout)] + cmd
cmd = ['timeout', '--signal=SIGKILL', str(timeout)] + cmd
# log.info(f'running sh: "{cmd}"')
proc = subprocess.Popen(
cmd,
cwd=working_dir,
stdout=asyncio.subprocess.PIPE,
stderr=asyncio.subprocess.STDOUT,
stdout=subprocess.PIPE,
stderr=subprocess.PIPE,
shell=shell,
start_new_session=True,
)
Expand All @@ -104,9 +104,14 @@ def popen() -> str:
_kill(proc)
running_sh_processes.remove(proc)
return stdout.decode('utf-8')

if rosys.is_stopping():
return
return await io_bound(popen)
try:
return await asyncio.wait_for(io_bound(popen), timeout)
except asyncio.TimeoutError:
log.warning(f'Command "{command}" timed out after {timeout} seconds.')
return ''


def _kill(proc: Popen) -> None:
Expand Down
5 changes: 1 addition & 4 deletions rosys/simulation_ui.py
Original file line number Diff line number Diff line change
Expand Up @@ -9,14 +9,11 @@ class simulation_ui:

def __init__(self) -> None:
ui.label('Simulation speed')
ui.slider(min=0, max=10, value=1, step=0.1, on_change=self.request_backup) \
ui.slider(min=0, max=10, value=1, step=0.1, on_change=rosys.config.invalidate) \
.bind_value(rosys.config, 'simulation_speed').props('label-always')
self.simulation_time = ui.label()
self.startup_time = rosys.time()
ui.timer(0.1, self.update_simulation_time)

def request_backup(self) -> None:
rosys.config.needs_backup = True

def update_simulation_time(self) -> None:
self.simulation_time.set_text(f'Running for {timedelta(seconds=int(rosys.time() - self.startup_time))}')
3 changes: 3 additions & 0 deletions rosys/vision/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,12 +3,15 @@
from .camera_objects_ import CameraObjects as camera_objects
from .camera_projector import CameraProjector
from .camera_provider import CameraProvider
from .combining_camera_provider import CombiningCameraProvider
from .detections import BoxDetection, Detection, Detections, PointDetection
from .detector import Detector
from .detector_hardware import DetectorHardware
from .detector_simulation import DetectorSimulation, SimulatedObject
from .image import Image, ImageSize
from .multi_camera_provider import MultiCameraProvider
from .rtsp_camera import RtspCamera
from .rtsp_camera_provider_hardware import RtspCameraProviderHardware
from .usb_camera import UsbCamera
from .usb_camera_provider_hardware import UsbCameraProviderHardware
from .usb_camera_provider_simulation import UsbCameraProviderSimulation
6 changes: 6 additions & 0 deletions rosys/vision/camera.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
from typing import Optional

import numpy as np

from rosys import persistence

from ..geometry import Rotation
Expand All @@ -18,6 +19,11 @@ class Camera(abc.ABC):
calibration: Optional[Calibration] = None
images: list[Image] = field(default_factory=list, metadata=persistence.exclude)
focal_length: Optional[float] = None
name: Optional[str] = None

def __post_init__(self) -> None:
if self.name is None:
self.name = self.id

@property
def captured_images(self) -> list[Image]:
Expand Down
3 changes: 3 additions & 0 deletions rosys/vision/camera_provider.py
Original file line number Diff line number Diff line change
Expand Up @@ -81,3 +81,6 @@ def prune_images(self, max_age_seconds: Optional[float] = None):
else:
while camera.images and camera.images[0].time < rosys.time() - max_age_seconds:
del camera.images[0]

def invalidate(self) -> None:
self.needs_backup = True
13 changes: 13 additions & 0 deletions rosys/vision/combining_camera_provider.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
from .camera import Camera
from .camera_provider import CameraProvider


class CombiningCameraProvider(CameraProvider):

def __init__(self, camera_providers: list[CameraProvider] = []):
super().__init__()
self.camera_providers = camera_providers

@property
def cameras(self) -> dict[str, Camera]:
return {camera.id: camera for provider in self.camera_providers for camera in provider.cameras.values()}
5 changes: 4 additions & 1 deletion rosys/vision/detections.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
from __future__ import annotations

from dataclasses import dataclass, field
from dataclasses import asdict, dataclass, field

from ..geometry import Point

Expand Down Expand Up @@ -125,3 +125,6 @@ def to_svg(self, shrink: int = 1) -> str:
b.to_svg(shrink) for b in self.boxes) + '\n' + '\n'.join(
p.to_svg(shrink) for p in self.points) + '\n' + '\n'.join(
s.to_svg(shrink) for s in self.segmentations)

def to_dict(self) -> dict:
return asdict(self)
5 changes: 3 additions & 2 deletions rosys/vision/detector_simulation.py
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@ class SimulatedObject:
position: Point3d
size: Optional[tuple[float]] = None
uuid: str = field(init=False)
confidence: float = 1.0

def __post_init__(self) -> None:
self.uuid = str(uuid4())
Expand Down Expand Up @@ -87,7 +88,7 @@ def detect_from_simulated_objects(self, image: Image) -> None:
image.detections.points.append(PointDetection(
category_name=object.category_name,
model_name='simulation',
confidence=1.0,
confidence=object.confidence,
x=image_point.x + self.noise * np.random.randn(),
y=image_point.y + self.noise * np.random.randn(),
uuid=object.uuid,
Expand All @@ -103,7 +104,7 @@ def detect_from_simulated_objects(self, image: Image) -> None:
image.detections.boxes.append(BoxDetection(
category_name=object.category_name,
model_name='simulation',
confidence=1.0,
confidence=object.confidence,
x=image_points[:, 0].min() + self.noise * np.random.randn(),
y=image_points[:, 1].min() + self.noise * np.random.randn(),
width=image_points[:, 0].max() - image_points[:, 0].min() + self.noise * np.random.randn(),
Expand Down
78 changes: 78 additions & 0 deletions rosys/vision/rtsp_camera.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,78 @@
from dataclasses import dataclass
from enum import Enum
from typing import Optional, Self

import rosys

from ..geometry import Rectangle
from .camera import Camera
from .image import ImageSize


class ImageRotation(str, Enum):
NONE: int = 0
RIGHT: int = 90
UPSIDE_DOWN: int = 180
LEFT: int = 270

@classmethod
def from_degrees(cls, degrees: int) -> Self:
for rotation in cls:
if int(rotation.value) == degrees % 360:
return rotation
raise ValueError(f'invalid rotation angle: {degrees}')


@dataclass(slots=True, kw_only=True)
class RtspCamera(Camera):
active: bool = True
detect: bool = False
url: Optional[str] = None
authorized: bool = True

color: Optional[str] = None
"""a color code to identify the camera"""

resolution: Optional[ImageSize] = None
"""physical resolution currently configured in the camera"""

rotation: ImageRotation = ImageRotation.NONE
"""rotation which should be applied after grabbing and cropping"""

fps: Optional[int] = None
"""current frames per second (read only)"""

crop: Optional[Rectangle] = None
"""region to crop on the original resolution before rotation"""

@property
def image_resolution(self) -> Optional[ImageSize]:
if self.resolution is None:
return None
width = self.crop.width if self.crop else self.resolution.width
height = self.crop.height if self.crop else self.resolution.height
if self.rotation == ImageRotation.LEFT or self.rotation == ImageRotation.RIGHT:
return ImageSize(width=height, height=width)
else:
return ImageSize(width=self.resolution.width, height=self.resolution.height)

@property
def rotation_angle(self) -> int:
"""Rotation angle in degrees."""
return int(self.rotation)

@rotation_angle.setter
def rotation_angle(self, value: int) -> None:
self.rotation = ImageRotation.from_degrees(value)

def rotate_clockwise(self) -> None:
"""Rotate the image clockwise by 90 degrees."""
self.rotation_angle += 90

def rotate_counter_clockwise(self) -> None:
"""Rotate the image counter clockwise by 90 degrees."""
self.rotation_angle -= 90

def __repr__(self) -> dict:
last_image = f'{rosys.time() - self.latest_captured_image.time:.0f} s ago' if self.latest_captured_image else 'never'
return {'name': self.name, 'url': self.url, 'active': self.active, 'last_image': last_image}
Loading