Skip to content

Commit

Permalink
Merge pull request #59 from zauberzeug/timelapse
Browse files Browse the repository at this point in the history
Resurrect and enhance time lapse functionality
  • Loading branch information
falkoschindler authored Dec 18, 2023
2 parents 5d6efd6 + 6b2970e commit 074df2f
Show file tree
Hide file tree
Showing 3 changed files with 119 additions and 43 deletions.
119 changes: 91 additions & 28 deletions rosys/analysis/timelapse_recorder.py
Original file line number Diff line number Diff line change
Expand Up @@ -11,13 +11,14 @@
from PIL import Image, ImageDraw, ImageFont

from .. import rosys
from ..vision import Camera

STORAGE_PATH = Path('~/.rosys/timelapse').expanduser()
VIDEO_PATH = STORAGE_PATH / 'videos'
FONT = str(Path(__file__).parent / 'assets' / 'RobotoMono-Medium.ttf')
IMAGE_FONT = ImageFont.truetype(FONT, 12)
BIG_COVER_FONT = ImageFont.truetype(FONT, 100)
SMALL_COVER_FONT = ImageFont.truetype(FONT, 60)
IMAGE_FONT = ImageFont.truetype(FONT, 16)
BIG_COVER_FONT = ImageFont.truetype(FONT, 50)
SMALL_COVER_FONT = ImageFont.truetype(FONT, 30)


class RosysImage(Protocol):
Expand All @@ -28,66 +29,128 @@ class RosysImage(Protocol):

class TimelapseRecorder:

def __init__(self) -> None:
self.log = logging.getLogger('rosys.timelapse_recorder')
def __init__(self, *, width: int = 800, height: int = 600, capture_rate: float = 1) -> None:
"""Creates a time lapse recorder to capture images from a camera and creates a video of the sequence afterwards.
param: width: width of the images to capture (default: 800)
param: height: height of the images to capture (default: 600)
param: capture_rate: images per second to capture (default: 1)
"""
self.log = logging.getLogger('rosys.timelapse_recorder')
self.width = width
self.height = height
self.avoid_broken_images = True
self.capture_rate = capture_rate
self.last_capture_time = rosys.time()
self._notifications: list[list[str]] = []
self.camera: Optional[Camera] = None
VIDEO_PATH.mkdir(parents=True, exist_ok=True)
rosys.on_repeat(self._capture, 0.01)

async def _capture(self) -> None:
if self.camera is None:
return
if rosys.time() - self.last_capture_time < 1 / self.capture_rate:
return
images = self.camera.get_recent_images(timespan=2)
if self.avoid_broken_images:
images = [i for i in images if not i.is_broken and i.time < rosys.time() - 0.1]
if images:
self.last_capture_time = rosys.time()
await self.save(images[-1])

async def save(self, image: RosysImage) -> None:
await rosys.run.cpu_bound(save_image, image, STORAGE_PATH)
"""Captures an image to be used in video."""
await rosys.run.cpu_bound(_save_image,
image,
STORAGE_PATH,
(self.width, self.height),
self._notifications.pop(0) if self._notifications else [])

async def compress_video(self) -> None:
"""Creates a video from the captured images"""
jpgs = sorted(STORAGE_PATH.glob('*.jpg'))
if len(jpgs) < 20:
self.log.info(f'very few images ({len(jpgs)}); not creating video')
self.discard_video()
return
start_unix = int(jpgs[0].stem[:-4])
start = datetime.fromtimestamp(start_unix)
end = datetime.fromtimestamp(int(Path(jpgs[-1]).stem[:-4]))
start = datetime.fromtimestamp(float(jpgs[0].stem))
end = datetime.fromtimestamp(float(jpgs[-1].stem))
self.log.info(f'creating video from {start} to {end}')
duration = humanize.naturaldelta(end-start)
await self.create_info(start.strftime('%d.%m.%Y %H:%M:%S'), duration, time=start_unix - 1)
duration = humanize.naturaldelta(end - start)
await self.create_info(start.strftime(r'%d.%m.%Y %H:%M:%S'), duration, time=start.timestamp() - 1)
id_ = start.strftime(r'%Y%m%d_%H-%M-%S_' + duration.replace(' ', '_'))
target_dir = STORAGE_PATH / id_
target_dir.mkdir(parents=True, exist_ok=True)
self.log.info(await rosys.run.sh(f'mv {STORAGE_PATH}/*.jpg {target_dir}', shell=True))
# it seems that niceness of subprocess is relative to own niceness, but we want an absolute niceness
await rosys.run.sh(f'mv {STORAGE_PATH}/*.jpg {target_dir}', shell=True)
source_file = target_dir / 'source.txt'
with source_file.open('w') as f:
for jpg in sorted(target_dir.glob('*.jpg')):
f.write(f"file '{jpg}'\n")
absolute_niceness = 10 - os.nice(0)
cmd = f'nice -n {absolute_niceness} ffmpeg -hide_banner -threads 1 -r 10 -pattern_type glob -i "{target_dir}/*.jpg" -s 1600x1200 -vcodec libx264 -crf 18 -preset slow -pix_fmt yuv420p -y {target_dir}/{id_}.mp4; mv {target_dir}/*mp4 {STORAGE_PATH}/videos; rm -r {target_dir};'
cmd = (
f'nice -n {absolute_niceness} ffmpeg -hide_banner -threads 1 -f concat -safe 0 -i "{source_file}" '
f'-s {self.width}x{self.height} -vcodec libx264 -crf 18 -preset slow -pix_fmt yuv420p -y {target_dir}/{id_}.mp4;'
f'mv {target_dir}/*mp4 {STORAGE_PATH}/videos;'
f'rm -r {target_dir};'
)
self.log.info(f'starting {cmd}')
rosys.background_tasks.create(rosys.run.sh(cmd, timeout=None, shell=True), name='timelapse ffmpeg')

def clear_jpegs(self) -> None:
for jpg in STORAGE_PATH.glob('**/*.jpg'):
def discard_video(self) -> None:
"""Drop the currently recorded video data."""
for jpg in STORAGE_PATH.glob('*.jpg'):
jpg.unlink()

async def create_info(self, title: str, subtitle: str, frames: int = 20, time: Optional[float] = None) -> None:
await rosys.run.cpu_bound(save_info, title, subtitle, rosys.time() if time is None else time, frames)
"""Shows info on black screen with title and subtitle"""
await rosys.run.cpu_bound(_save_info, title, subtitle, rosys.time() if time is None else time, frames)

def notify(self, message: str, frames: int = 10) -> None:
"""Place message in the next n frames"""
while len(self._notifications) < frames:
self._notifications.append([])
for i in range(frames):
self._notifications[i].append(message)


def save_image(image: RosysImage, path: Path) -> None:
def _save_image(image: RosysImage, path: Path, size: tuple[int, int], notifications: list[str]) -> None:
assert image.data is not None
img = Image.open(io.BytesIO(image.data))
img = img.resize(size)
draw = ImageDraw.Draw(img)
x = img.width - 300
y = img.height - 18
text = f'{datetime.fromtimestamp(image.time).strftime(r"%Y-%m-%d %H:%M:%S")}, cam {image.camera_id}'
x = y = 20
_write(f'{datetime.fromtimestamp(image.time):%Y-%m-%d %H:%M:%S}, cam {image.camera_id}', draw, x, y)
for message in notifications:
y += 30
_write(message, draw, x, y)
img.save(path / f'{image.time:.3f}.jpg', 'JPEG')


def _write(text: str, draw: ImageDraw.Draw, x: int, y: int) -> None:
# shadow
draw.text((x - 1, y - 1), text, font=IMAGE_FONT, fill=(0, 0, 0))
draw.text((x + 1, y - 1), text, font=IMAGE_FONT, fill=(0, 0, 0))
draw.text((x - 1, y + 1), text, font=IMAGE_FONT, fill=(0, 0, 0))
draw.text((x + 1, y + 1), text, font=IMAGE_FONT, fill=(0, 0, 0))
# actual text
draw.text((x, y), text, font=IMAGE_FONT, fill=(255, 255, 255))
img.save(path / f'{int(image.time)}0000.jpg', 'JPEG')


def save_info(title: str, subtitle: str, time: float, frames: int) -> None:
def _save_info(title: str, subtitle: str, time: float, frames: int) -> None:
for i in range(frames):
img = Image.new('RGB', (1600, 1200), 'black')
draw = ImageDraw.Draw(img)
font = BIG_COVER_FONT if len(subtitle) < 25 and len(title) < 25 else SMALL_COVER_FONT
w, h = draw.textsize(title, font=font)
draw.text((img.width / 2 - w / 2, img.height / 2 - h / 2 - 200), title, font=font, fill='white')
w, h = draw.textsize(subtitle, font=font)
draw.text((img.width / 2 - w / 2, img.height / 2 - h / 2 + 100), subtitle, font=font, fill='white')
img.save(STORAGE_PATH / f'{time:.0f}{i:04}.jpg')

title_box = draw.textbbox((0, 0), title, font=font)
title_x = (img.width - title_box[2]) / 2
title_y = (img.height / 2) - 200 - (title_box[3] / 2)
draw.text((title_x, title_y), title, font=font, fill='white')

subtitle_box = draw.textbbox((0, 0), subtitle, font=font)
subtitle_x = (img.width - subtitle_box[2]) / 2
subtitle_y = (img.height / 2) + 100 - (subtitle_box[3] / 2)
draw.text((subtitle_x, subtitle_y), subtitle, font=font, fill='white')

img.save(STORAGE_PATH / f'{time:.3f}{i:03}.jpg')
34 changes: 20 additions & 14 deletions rosys/analysis/videos_page_.py
Original file line number Diff line number Diff line change
@@ -1,24 +1,30 @@
from pathlib import Path

from nicegui import app, ui
from starlette import responses
import watchfiles
from nicegui import background_tasks, ui

PATH = Path('~/.rosys/timelapse/videos').expanduser()
VIDEO_FILES = Path('~/.rosys/timelapse/videos').expanduser()


class VideosPage:

def __init__(self) -> None:
@ui.page('/videos', title='Videos')
def page():
def update_list() -> None:
video_list.clear()
with video_list:
for mp4 in sorted(PATH.glob('*.mp4'), reverse=True):
ui.link(mp4.stem.replace('_', ' ').replace('-', ':'), f'/timelapse/{mp4.name}')
video_list = ui.column()
ui.timer(5, update_list)

@app.get('/timelapse/{filename}')
def get_timelapse(filename: str) -> responses.FileResponse:
return responses.FileResponse(PATH / filename)

@ui.refreshable
def videos():
for mp4 in sorted(VIDEO_FILES.glob('*.mp4'), reverse=True):
with ui.row():
with ui.card().tight():
ui.video(mp4).classes('w-[800px]')
with ui.column():
ui.button(on_click=lambda mp4=mp4: mp4.unlink()).props('icon=delete flat')
ui.button(on_click=lambda mp4=mp4: ui.download(mp4)).props('icon=download flat')

async def watch_videos():
async for _ in watchfiles.awatch(VIDEO_FILES):
videos.refresh()

videos()
background_tasks.create(watch_videos(), name='watch videos files')
9 changes: 8 additions & 1 deletion rosys/vision/camera/camera.py
Original file line number Diff line number Diff line change
Expand Up @@ -101,7 +101,14 @@ def latest_captured_image(self) -> Optional[Image]:
def latest_detected_image(self) -> Optional[Image]:
return next((i for i in reversed(self.captured_images) if i.detections), None)

def get_recent_images(self, current_time: float, timespan: float = 10.0) -> list[Image]:
def get_recent_images(self, *, current_time: Optional[float] = None, timespan: float = 10.0) -> list[Image]:
"""Returns all images that were captured. Latest images are at the end of the list.
:param current_time: the starting time for the search; defaults to the current time
:param timespan: the timespan to search back in seconds
"""
if current_time is None:
current_time = rosys.time()
return [i for i in self.captured_images if i.time > current_time - timespan]

def _add_image(self, image: Image) -> None:
Expand Down

0 comments on commit 074df2f

Please sign in to comment.