diff --git a/.github/workflows/pants.yaml b/.github/workflows/pants.yaml index fd1417b14..1664ac33b 100644 --- a/.github/workflows/pants.yaml +++ b/.github/workflows/pants.yaml @@ -56,7 +56,6 @@ jobs: pants --changed-since=HEAD update-build-files --check - name: install system dependencies run: | # cargo is required to build fastuuid (no wheels for Python 3.11) - sudo ./build-support/install_kinect_prerequisites.sh sudo apt install jq cargo - name: Lint run: | @@ -69,7 +68,7 @@ jobs: pants --changed-since=origin/master --changed-dependees=transitive test - name: Build Docker images run: | # filter out non-essential docker images (there was a problem with full storage on github) - pants filter --target-type=docker_image --changed-since=origin/master --changed-dependees=transitive | grep -v arcor2_3d_mouse | grep -v arcor2_kinect_azure | grep -v arcor2_fanuc arcor2_fanuc_upload_object_types | xargs pants package + pants filter --target-type=docker_image --changed-since=origin/master --changed-dependees=transitive | grep -v arcor2_3d_mouse | grep -v arcor2_fanuc arcor2_fanuc_upload_object_types | xargs pants package - name: Build Python packages run: | pants filter --target-type=python_distribution :: | xargs pants package diff --git a/3rdparty/requirements.txt b/3rdparty/requirements.txt index 3ff0f2820..9ab939ad7 100644 --- a/3rdparty/requirements.txt +++ b/3rdparty/requirements.txt @@ -28,7 +28,6 @@ orjson~=3.10.3 packaging~=24.0 pydub~=0.25.1 pyhumps==3.8.0 -pyk4a@ git+https://github.com/Jakub-Dv/pyk4a.git@feature/body-tracking pyserial~=3.5 pyspacemouse~=1.1.3 pytest-asyncio~=0.23.7 diff --git a/README.md b/README.md index ec03cdfcd..6cfbd11a1 100644 --- a/README.md +++ b/README.md @@ -109,19 +109,6 @@ The following video by [Kinali](https://www.kinali.cz/en/) shows the use case (o [README](src/python/arcor2_fit_demo/README.md) | [CHANGELOG](src/python/arcor2_fit_demo/CHANGELOG.md) - 2024-04-11: [1.5.0](https://github.com/robofit/arcor2/releases/tag/arcor2_fit_demo%2F1.5.0) ([docker](https://hub.docker.com/r/arcor2/arcor2_upload_fit_demo/tags?page=1&ordering=last_updated&name=1.5.0), [pypi](https://pypi.org/project/arcor2-fit-demo/1.5.0/)). - -### arcor2_kinect_azure - -[README](src/python/arcor2_kinect_azure/README.md) | [CHANGELOG](src/python/arcor2_kinect_azure/CHANGELOG.md) - - - 2024-04-11: [0.8.0](https://github.com/robofit/arcor2/releases/tag/arcor2_kinect_azure%2F0.8.0) ([docker](https://hub.docker.com/r/arcor2/arcor2_kinect_azure/tags?page=1&ordering=last_updated&name=0.8.0), [pypi](https://pypi.org/project/arcor2_kinect_azure/0.8.0/)). - -### arcor2_kinect_azure_data - -[README](src/python/arcor2_kinect_azure_data/README.md) | [CHANGELOG](src/python/arcor2_kinect_azure_data/CHANGELOG.md) - - - 2024-04-11: [0.2.0](https://github.com/robofit/arcor2/releases/tag/arcor2_kinect_azure_data%2F0.2.0) ([pypi](https://pypi.org/project/arcor2_kinect_azure_data/0.2.0/)). - ### arcor2_logger diff --git a/build-support/BUILD b/build-support/BUILD deleted file mode 100644 index 979bb5a85..000000000 --- a/build-support/BUILD +++ /dev/null @@ -1 +0,0 @@ -shell_source(name="install_kinect_prerequisites.sh", source="install_kinect_prerequisites.sh") \ No newline at end of file diff --git a/build-support/install_kinect_prerequisites.sh b/build-support/install_kinect_prerequisites.sh deleted file mode 100755 index cee07f5ce..000000000 --- a/build-support/install_kinect_prerequisites.sh +++ /dev/null @@ -1,13 +0,0 @@ -#!/usr/bin/env bash - -set -e # stop script when error occurs -apt-get update -apt-get install -y gnupg2 libgl1-mesa-glx libglib2.0-0 -curl -sSL https://packages.microsoft.com/keys/microsoft.asc | apt-key add - -echo "deb [arch=amd64] https://packages.microsoft.com/ubuntu/18.04/prod bionic main" >>/etc/apt/sources.list # 20.04 is not officially supported but it works like this -apt-get update -export DEBIAN_FRONTEND="noninteractive" -echo 'libk4a1.4 libk4a1.4/accepted-eula-hash string 0f5d5c5de396e4fee4c0753a21fee0c1ed726cf0316204edda484f08cb266d76' | debconf-set-selections -echo 'libk4a1.4 libk4a1.4/accept-eula boolean true' | debconf-set-selections -echo 'libk4abt1.1 libk4abt1.1/accepted-eula-hash string 03a13b63730639eeb6626d24fd45cf25131ee8e8e0df3f1b63f552269b176e38' | debconf-set-selections -apt-get install -y libk4a1.4=1.4.1 libk4a1.4-dev=1.4.1 libk4abt1.1 libk4abt1.1-dev diff --git a/compose-files/fit-demo/docker-compose.yml b/compose-files/fit-demo/docker-compose.yml index e80765e68..0a3eb2224 100644 --- a/compose-files/fit-demo/docker-compose.yml +++ b/compose-files/fit-demo/docker-compose.yml @@ -11,8 +11,6 @@ services: condition: service_healthy fit-demo-execution: condition: service_started - fit-demo-kinect: - condition: service_healthy fit-demo-scene: condition: service_healthy fit-demo-calibration: @@ -27,7 +25,6 @@ services: - "6789:6789" - "6799:6799" networks: - - fit-demo-kinect-network - fit-demo-scene-network - fit-demo-project-network - fit-demo-asset-network @@ -42,7 +39,6 @@ services: - ARCOR2_EXECUTION_URL=ws://fit-demo-execution:6790 - ARCOR2_BUILD_URL=http://fit-demo-build:5008 - ARCOR2_CALIBRATION_URL=http://fit-demo-calibration:5014 - - ARCOR2_KINECT_AZURE_URL=http://192.168.104.100:5017 # Run kinect using pants fit-demo-build: image: arcor2/arcor2_build:1.6.0 @@ -91,16 +87,6 @@ services: ports: - "5009:5009" - fit-demo-kinect: - image: arcor2/arcor2_kinect_azure:0.8.0 - container_name: fit-demo-kinect - networks: - - fit-demo-kinect-network - ports: - - "5016:5016" - environment: - - ARCOR2_KINECT_AZURE_MOCK=true - fit-demo-calibration: image: arcor2/arcor2_calibration:1.2.0 networks: @@ -265,7 +251,6 @@ networks: fit-demo-execution-network: fit-demo-project-network: fit-demo-asset-network: - fit-demo-kinect-network: fit-demo-dobot-magician-network: fit-demo-dobot-magician2-network: fit-demo-dobot-m1-network: diff --git a/src/docker/arcor2_kinect_azure/BUILD b/src/docker/arcor2_kinect_azure/BUILD deleted file mode 100644 index 16066948d..000000000 --- a/src/docker/arcor2_kinect_azure/BUILD +++ /dev/null @@ -1,7 +0,0 @@ -# Note that container from this docker image can only handle running kinect in MOCK! -docker_image( - name="arcor2_kinect_azure", - repository="arcor2/arcor2_kinect_azure", - dependencies=["build-support:install_kinect_prerequisites.sh"], - image_tags=["0.8.0"], -) diff --git a/src/docker/arcor2_kinect_azure/Dockerfile b/src/docker/arcor2_kinect_azure/Dockerfile deleted file mode 100644 index d5f2f6df2..000000000 --- a/src/docker/arcor2_kinect_azure/Dockerfile +++ /dev/null @@ -1,25 +0,0 @@ -FROM python:3.11.9-bookworm as deps -COPY src.python.arcor2_kinect_azure.scripts/kinect_azure.pex /binary.pex -RUN PEX_TOOLS=1 PYTHONOPTIMIZE=1 /usr/local/bin/python /binary.pex venv --scope=deps --compile /bin/app - -FROM python:3.11.9-bookworm as srcs -COPY src.python.arcor2_kinect_azure.scripts/kinect_azure.pex /binary.pex -RUN PEX_TOOLS=1 PYTHONOPTIMIZE=1 /usr/local/bin/python /binary.pex venv --scope=srcs --compile /bin/app - -FROM python:3.11.9-bookworm - -COPY build-support/install_kinect_prerequisites.sh /root/install_kinect_prerequisites.sh - -# curl is for healthcheck -RUN apt-get update \ - && apt-get install -y -q --no-install-recommends libgl1-mesa-glx=22.3.6-1+deb12u1 libglib2.0-0=2.74.6-2+deb12u2 gnupg2=2.2.40-1.1 curl=7.88.1-10+deb12u5 \ - && /root/install_kinect_prerequisites.sh \ - && apt-get clean \ - && rm -rf /var/lib/apt/lists/* - -ENTRYPOINT ["/bin/app/pex"] -COPY --from=deps /bin/app /bin/app -COPY --from=srcs /bin/app /bin/app - -EXPOSE 5016 -HEALTHCHECK --interval=5s --start-period=60s CMD curl -f http://localhost:5016/healthz/ready || exit 1 diff --git a/src/python/arcor2_fit_demo/scripts/BUILD b/src/python/arcor2_fit_demo/scripts/BUILD index bfe8dc756..ce0a88106 100644 --- a/src/python/arcor2_fit_demo/scripts/BUILD +++ b/src/python/arcor2_fit_demo/scripts/BUILD @@ -5,7 +5,6 @@ arcor2_pex_binary( dependencies=[ "src/python/arcor2_fit_demo/data/dobot-m1", "src/python/arcor2_fit_demo/data/dobot-magician", - "src/python/arcor2_fit_demo/data:kinect_azure.dae", "src/python/arcor2_fit_demo/data:conveyor_belt.fbx", ], ) diff --git a/src/python/arcor2_fit_demo/scripts/kinect_calibration.py b/src/python/arcor2_fit_demo/scripts/kinect_calibration.py deleted file mode 100644 index 8ea354b8f..000000000 --- a/src/python/arcor2_fit_demo/scripts/kinect_calibration.py +++ /dev/null @@ -1,23 +0,0 @@ -import time - -from arcor2.data.common import Pose -from arcor2.data.object_type import Box -from arcor2_calibration_data import client as calib_client -from arcor2_kinect_azure_data.object_types.kinect_azure import KinectAzure, UrlSettings - - -def main() -> None: - kinect = KinectAzure("", "", Pose(), Box("", 0.1, 0.1, 0.1), UrlSettings("http://localhost:5016")) - # print(kinect.color_camera_params) - assert kinect.color_camera_params - ci_start = time.monotonic() - color_image = kinect.color_image() - print(f"Time to get color_image: {time.monotonic()-ci_start}") - - calib_start = time.monotonic() - print(calib_client.estimate_camera_pose(kinect.color_camera_params, color_image)) - print(f"Time to get calibration: {time.monotonic()-calib_start}") - - -if __name__ == "__main__": - main() diff --git a/src/python/arcor2_fit_demo/scripts/upload_objects.py b/src/python/arcor2_fit_demo/scripts/upload_objects.py index b8d3b6e24..e5f9611c5 100755 --- a/src/python/arcor2_fit_demo/scripts/upload_objects.py +++ b/src/python/arcor2_fit_demo/scripts/upload_objects.py @@ -11,18 +11,13 @@ from arcor2_fit_demo.object_types.fit_common_mixin import FitCommonMixin from arcor2_fit_demo.object_types.milling_machine import MillingMachine from arcor2_fit_demo.object_types.optical_quality_control import OpticalQualityControl -from arcor2_kinect_azure_data.object_types.kinect_azure import KinectAzure def main() -> None: upload_def(AbstractDobot) upload_def(DobotMagician, urdf=Urdf(get_data("dobot-magician"), DobotMagician.urdf_package_name)) upload_def(DobotM1, urdf=Urdf(get_data("dobot-m1"), DobotM1.urdf_package_name)) - upload_def( - KinectAzure, - Mesh(KinectAzure.__name__, KinectAzure.mesh_filename), - file_to_upload=get_data(KinectAzure.mesh_filename), - ) + upload_def( ConveyorBelt, Mesh(ConveyorBelt.__name__, ConveyorBelt.mesh_filename), diff --git a/src/python/arcor2_kinect_azure/BUILD b/src/python/arcor2_kinect_azure/BUILD deleted file mode 100644 index f7441ed8c..000000000 --- a/src/python/arcor2_kinect_azure/BUILD +++ /dev/null @@ -1,5 +0,0 @@ -arcor2_python_distribution( - name="arcor2_kinect_azure", - description="REST API for Kinect Azure.", - binaries={"arcor2_kinect_azure": "src/python/arcor2_kinect_azure/scripts:kinect_azure"}, -) diff --git a/src/python/arcor2_kinect_azure/CHANGELOG.md b/src/python/arcor2_kinect_azure/CHANGELOG.md deleted file mode 100644 index f1d4275b8..000000000 --- a/src/python/arcor2_kinect_azure/CHANGELOG.md +++ /dev/null @@ -1,72 +0,0 @@ -# Changelog - -The format is based on [Keep a Changelog](https://keepachangelog.com/en/1.0.0/), - -## [0.8.0] - 2024-04-11 - -### Changed - -- Updated dependencies, switched to Python 3.11. - -## [0.7.0] - 2023-07-20 - -### Changed - -- App is refactored and adds endpoints for tracking user using body-tracking api -- App can track user in numerous ways: - - Get user positions - - Get user velocity and direction - - Check how many users are in frame - - Get RGB, depth and rgb with skeleton image - - Show what camera sees in browser - - Check if user is nearby some point -- **Breaking**: App runs in Docker only in MOCK mode. - -## [0.6.0] - 2023-03-07 - -### Changed - -- Health check end-point at `/healthz/ready`. -- Requires `pose` in the body of `GET /state/start`. - -### Added - -- New endpoint `GET /state/pose`. - -## [0.5.0] - 2022-10-28 - -### Changed - -- **BREAKING**: Implement new error handling flow. Error codes of **every** endpoint were replaced with error - types as described in swagger documentation. -- Changed service name. -- Switched to Python 3.10, updated dependencies. - -## [0.4.0] - 2021-10-25 - -### Changed - -- New environment variable `ARCOR2_KINECT_AZURE_MOCK`. - -### Fixed - -- Depth file was not packaged (used in mock mode). - -## [0.3.0] - 2021-05-21 - -### Changed - -- Lazy import of `pyk4a` - mock can run without it. - -## [0.2.0] - 2021-02-08 - -### Changed - -- Mock now sends real images. -- Part of the code refactored into `arcor2/flask.py`. - -## [0.1.0] - 2020-12-14 - -### Changed - -- Initial release of the package. \ No newline at end of file diff --git a/src/python/arcor2_kinect_azure/README.md b/src/python/arcor2_kinect_azure/README.md deleted file mode 100644 index ab68a5a62..000000000 --- a/src/python/arcor2_kinect_azure/README.md +++ /dev/null @@ -1,25 +0,0 @@ -# Kinect Azure Service - -## Usage Instructions - -- By default, the service runs on port 5016. - - This can be changed by setting `ARCOR2_KINECT_AZURE_URL`. -- Kinect SDK has to be installed beforehand (`sudo ./build-support/install_kinect_prerequisites.sh`). -- You may need to run following commands when using the real sensor to set permissions: - -```bash -sudo wget https://raw.githubusercontent.com/microsoft/Azure-Kinect-Sensor-SDK/develop/scripts/99-k4a.rules -P /etc/udev/rules.d/ -sudo udevadm control --reload-rules && udevadm trigger -``` - -- The real kinect needs display. Insert any dummy HDMI plug to graphics card or plug in real monitor. -- When all of the above is done, execute `./pants run src/python/arcor2_kinect_azure/scripts/kinect_azure.py` and the app should run without any problem - -#### Note that the app cannot run in docker when using real kinect device. Follow steps above to run in production - -## Environment variables - -- `ARCOR2_KINECT_AZURE_URL=http://0.0.0.0:5016` - by default, the service listens on port 5016. -- `ARCOR2_KINECT_AZURE_MOCK=1` - the service will start in a mock (simulator) mode. -- `ARCOR2_REST_API_DEBUG=1` - turns on Flask debugging (logs each endpoint call). -- `ARCOR2_KINECT_AZURE_DEBUG=1` - turns on additional debugging \ No newline at end of file diff --git a/src/python/arcor2_kinect_azure/VERSION b/src/python/arcor2_kinect_azure/VERSION deleted file mode 100644 index 8adc70fdd..000000000 --- a/src/python/arcor2_kinect_azure/VERSION +++ /dev/null @@ -1 +0,0 @@ -0.8.0 \ No newline at end of file diff --git a/src/python/arcor2_kinect_azure/__init__.py b/src/python/arcor2_kinect_azure/__init__.py deleted file mode 100644 index 05cfbe1e4..000000000 --- a/src/python/arcor2_kinect_azure/__init__.py +++ /dev/null @@ -1,16 +0,0 @@ -import logging -import os - -from arcor2 import env, package_version - -_ROOT = os.path.abspath(os.path.dirname(__file__)) - -ARCOR2_KINECT_AZURE_LOG_LEVEL = logging.DEBUG if env.get_bool("ARCOR2_KINECT_AZURE_DEBUG") else logging.INFO - - -def version() -> str: - return package_version(__name__) - - -def get_data(path: str) -> str: - return os.path.join(_ROOT, "data", path) diff --git a/src/python/arcor2_kinect_azure/app.py b/src/python/arcor2_kinect_azure/app.py deleted file mode 100644 index a145d2efd..000000000 --- a/src/python/arcor2_kinect_azure/app.py +++ /dev/null @@ -1,67 +0,0 @@ -import argparse -import os -from typing import TYPE_CHECKING - -from arcor2 import env -from arcor2.data.camera import CameraParameters -from arcor2.data.common import Pose, Position -from arcor2.flask import create_app, run_app -from arcor2.helpers import port_from_url -from arcor2.logging import get_logger -from arcor2_kinect_azure import ARCOR2_KINECT_AZURE_LOG_LEVEL, version -from arcor2_kinect_azure.exceptions import WebApiError -from arcor2_kinect_azure.routes import ( - aggregation, - body, - color, - debug_request, - depth, - position, - skeleton, - state, - synchronized, - video, -) - -logger = get_logger(__name__, ARCOR2_KINECT_AZURE_LOG_LEVEL) - -URL = os.getenv("ARCOR2_KINECT_AZURE_URL", "http://localhost:5016") -SERVICE_NAME = "Kinect Azure Web API" - -app = create_app(__name__) - -if TYPE_CHECKING: - from arcor2_kinect_azure.kinect import KinectAzure - -KINECT: "None | KinectAzure" = None -MOCK: bool = False -MOCK_STARTED: bool = False - -POSITION: Position = Position() - - -def main() -> None: - parser = argparse.ArgumentParser(description=SERVICE_NAME) - parser.add_argument("-s", "--swagger", action="store_true", default=False) - parser.add_argument("-m", "--mock", action="store_true", default=env.get_bool("ARCOR2_KINECT_AZURE_MOCK")) - args = parser.parse_args() - - global MOCK - MOCK = args.mock - if MOCK: - logger.info("Starting as a mock!") - - app.register_blueprint(aggregation.blueprint) - app.register_blueprint(body.blueprint) - app.register_blueprint(color.blueprint) - app.register_blueprint(depth.blueprint) - app.register_blueprint(position.blueprint) - app.register_blueprint(skeleton.blueprint) - app.register_blueprint(state.blueprint) - app.register_blueprint(synchronized.blueprint) - app.register_blueprint(video.blueprint) - app.before_request(debug_request) - run_app(app, SERVICE_NAME, version(), port_from_url(URL), [CameraParameters, WebApiError, Pose], args.swagger) - - if KINECT is not None: - KINECT.cleanup() diff --git a/src/python/arcor2_kinect_azure/data/BUILD b/src/python/arcor2_kinect_azure/data/BUILD deleted file mode 100644 index ee6b4d1af..000000000 --- a/src/python/arcor2_kinect_azure/data/BUILD +++ /dev/null @@ -1 +0,0 @@ -resources(sources=["*.jpg", "*.png"]) diff --git a/src/python/arcor2_kinect_azure/data/depth.png b/src/python/arcor2_kinect_azure/data/depth.png deleted file mode 100644 index 51dc2bde7..000000000 --- a/src/python/arcor2_kinect_azure/data/depth.png +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:603959e4a649bb994be23e04a0719bd45484df09bb6c074b31ec19c15b47ae28 -size 422866 diff --git a/src/python/arcor2_kinect_azure/data/rgb.jpg b/src/python/arcor2_kinect_azure/data/rgb.jpg deleted file mode 100644 index e7fe20903..000000000 --- a/src/python/arcor2_kinect_azure/data/rgb.jpg +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:cbfc128023afba5a5d9a61255535cb89d1467bed55c39521804acc502269f23b -size 180896 diff --git a/src/python/arcor2_kinect_azure/exceptions.py b/src/python/arcor2_kinect_azure/exceptions.py deleted file mode 100644 index 1d5f2d622..000000000 --- a/src/python/arcor2_kinect_azure/exceptions.py +++ /dev/null @@ -1,21 +0,0 @@ -from arcor2.flask import FlaskException, WebApiErrorFactory -from arcor2_kinect_azure import __name__ as package_name - - -class KinectAzureException(FlaskException): - service = package_name - - -class NotFound(KinectAzureException): - description = "Occurs when something is not found." - - -class StartError(KinectAzureException): - description = "Occurs when start condition is not met." - - -class InvalidDirection(KinectAzureException): - description = "Cannot determine direction" - - -WebApiError = WebApiErrorFactory.get_class(StartError, NotFound) diff --git a/src/python/arcor2_kinect_azure/kinect/BUILD b/src/python/arcor2_kinect_azure/kinect/BUILD deleted file mode 100644 index db46e8d6c..000000000 --- a/src/python/arcor2_kinect_azure/kinect/BUILD +++ /dev/null @@ -1 +0,0 @@ -python_sources() diff --git a/src/python/arcor2_kinect_azure/kinect/__init__.py b/src/python/arcor2_kinect_azure/kinect/__init__.py deleted file mode 100644 index bf86c178a..000000000 --- a/src/python/arcor2_kinect_azure/kinect/__init__.py +++ /dev/null @@ -1,344 +0,0 @@ -import json -import logging -import threading -import time -from collections import deque -from threading import Lock -from typing import Generator, NamedTuple - -import cv2 -import numpy as np -import pyk4a -from PIL import Image -from pyk4a import Config, ImageFormat, K4AException, PyK4A, PyK4ACapture - -from arcor2.data.camera import CameraParameters -from arcor2.data.common import Orientation, Pose, Position -from arcor2.exceptions import Arcor2Exception -from arcor2.logging import get_logger -from arcor2.transformations import make_pose_abs, make_pose_rel -from arcor2_kinect_azure import ARCOR2_KINECT_AZURE_LOG_LEVEL -from arcor2_kinect_azure.kinect.common import parse_skeleton - - -class KinectAzureException(Arcor2Exception): - pass - - -class ColorAndDepthImage(NamedTuple): - color: Image.Image - depth: Image.Image - - -class KinectAzure: - CAPTURE_BUFFER_CAP = 30 - - def __init__(self) -> None: - self._lock = Lock() - - self._config = Config( - color_resolution=pyk4a.ColorResolution.RES_1536P, - camera_fps=pyk4a.FPS.FPS_30, - depth_mode=pyk4a.DepthMode.NFOV_UNBINNED, - synchronized_images_only=True, - color_format=ImageFormat.COLOR_BGRA32, - ) - self._k4a = PyK4A(self._config) - self._k4a.start() - self._k4a.exposure_mode_auto = True - - self._camera_pose = Pose(Position(), Orientation()) - - self._kinect_logger = get_logger("kinect_logger", ARCOR2_KINECT_AZURE_LOG_LEVEL) - # Keep 1 second of images - self._capture_buffer: deque[PyK4ACapture] = deque(maxlen=self.CAPTURE_BUFFER_CAP) - self._running_capture_thread: bool = False - self._capture_thread: threading.Thread | None = None - - if self.color_camera_params is None: - raise KinectAzureException("Failed to get camera calibration.") - - def get_camera_pose(self) -> Pose: - return self._camera_pose - - def set_camera_pose(self, pose: Pose) -> None: - self._camera_pose = pose - - def get_camera_relative_pos(self, position: Position) -> Position: - abs_pose = Pose(position, Orientation()) - return make_pose_rel(self._camera_pose, abs_pose).position - - def get_camera_absolute_pos(self, position: Position) -> Position: - rel_pose = Pose(position, Orientation()) - return make_pose_abs(self._camera_pose, rel_pose).position - - @staticmethod - def adjust_depth_position_to_rgb(position: Position) -> Position: - # Depth camera is rotated by 1.3° down by x-axis - # https://learn.microsoft.com/en-us/azure/kinect-dk/coordinate-systems - # - # Rotate upward 1.3° to match rgb camera axis - adjuster = Pose(Position(-0.025, 0.0, 0.0), Orientation(-0.000383, 0.0, 0.0, 0.999997)) - return position.rotated(adjuster.orientation) + adjuster.position - - @property - def log(self) -> logging.Logger: - return self._kinect_logger - - @property - def color_camera_params(self) -> CameraParameters | None: - # https://github.com/microsoft/Azure-Kinect-Sensor-SDK/blob/develop/examples/opencv_compatibility/main.cpp - # https://github.com/etiennedub/pyk4a/issues/69#issuecomment-698756626 - - # order of parameters in JSON hopefully corresponds to order of parameters in this struct - # https://microsoft.github.io/Azure-Kinect-Sensor-SDK/master/structk4a__calibration__intrinsic__parameters__t_1_1__param.html - - # for mode related offsets see this - # https://github.com/microsoft/Azure-Kinect-Sensor-SDK/blob/90f77529f5ad19efd1e8f155a240c329e3bcbbdf/src/transformation/mode_specific_calibration.c#L95 - - # "CALIBRATION_LensDistortionModelBrownConrady" - - img = self.color_image() - - # no need to handle depth camera parameters as we will always provide transformed depth image - - c = json.loads(self._k4a.calibration_raw) - try: - for camera in c["CalibrationInformation"]["Cameras"]: - params = camera["Intrinsics"]["ModelParameters"] - - cx = params[0] - cy = params[1] - - fx = params[2] - fy = params[3] - - k1 = params[4] - k2 = params[5] - k3 = params[6] - k4 = params[7] - k5 = params[8] - k6 = params[9] - - p2 = params[12] - p1 = params[13] - - cp = CameraParameters(fx, fy, cx, cy, [k1, k2, p1, p2, k3, k4, k5, k6]) - - if camera["Location"] == "CALIBRATION_CameraLocationPV0": - h = img.width / 4 * 3 - - # un-normalize values - cp.cx *= img.width - cp.cy *= h - cp.fx *= img.width - cp.fy *= h - - # apply crop offset - cp.cy -= (img.width / 4 * 3 - img.width / 16 * 9) / 2 - return cp - - except (KeyError, IndexError) as e: - raise KinectAzureException("Failed to parse calibration.") from e - - return None - - def config(self) -> Config: - return self._config - - def capture_buffer(self) -> deque[PyK4ACapture]: - return self._capture_buffer - - def stable_buffer(self) -> deque[PyK4ACapture]: - return self._capture_buffer.copy() - - def get_n_non_empty_captures(self, n: int) -> list[PyK4ACapture] | None: - buffer: list[PyK4ACapture] = list() - total_captures = 0 - if self._capture_thread is None: - while len(buffer) < n: - capture = self.__capture_from_device() - skeleton = parse_skeleton(capture) - if skeleton is not None: - buffer.append(capture) - if total_captures > self.CAPTURE_BUFFER_CAP: - return None - total_captures += 1 - return buffer - else: - stable_buffer = list(self.stable_buffer()) - for capture in stable_buffer[::-1]: - skeleton = parse_skeleton(capture) - if skeleton is not None: - buffer.append(capture) - if len(buffer) == n: - return buffer[::-1] - return None - - def get_non_empty_capture(self, tries: int = 5) -> PyK4ACapture | None: - if self._capture_thread is None: - for _ in range(tries): - capture = self.__capture_from_device() - skeleton = parse_skeleton(capture) - if skeleton is not None: - return capture - else: - stable_buffer = list(self.stable_buffer()) - for capture in stable_buffer[::-1]: - skeleton = parse_skeleton(capture) - if skeleton is not None: - return capture - return None - - def stable_buffer_len(self) -> int: - return len(self._capture_buffer) - - def start_capturing(self): - self._running_capture_thread = True - - def capture_forever() -> None: - """Periodically capture frames from kinect.""" - - counter = 0 - fps = 30 - while self._running_capture_thread: - counter += 1 - start = time.time() - capture = self.__capture_from_device() - try: - _ = capture.body_skeleton - except Exception as e: - self.log.exception(e) - continue - - end = time.time() - self._capture_buffer.append(capture) - if counter % fps == 0: - self.log.debug(f"{counter}: capturing took: {end - start}, captured: {fps} frames") - time.sleep(0.005) - - self._capture_thread = threading.Thread(target=capture_forever) - self._capture_thread.start() - - def __capture_from_device(self) -> PyK4ACapture: - with self._lock: - try: - return self._k4a.get_capture(timeout=1000) - except K4AException as e: - self._kinect_logger.exception(e) - raise KinectAzureException("Failed to get capture.") from e - - def capture(self) -> PyK4ACapture: - if self._capture_thread is None: - return self.__capture_from_device() - else: - if len(self._capture_buffer) == 0: - time.sleep(0.2) - return self._capture_buffer[-1] - - @staticmethod - def convert_bgra_to_rgba(arr: np.ndarray) -> None: - arr[:, :, [0, 1, 2, 3]] = arr[:, :, [2, 1, 0, 3]] - - def color_image(self) -> Image.Image: - capture = self.capture() - - if capture.color is None: - raise KinectAzureException("Color image not available.") - else: - color = capture.color - self.convert_bgra_to_rgba(color) - - return Image.fromarray(color, mode="RGBA") - - def _depth_image(self) -> np.ndarray: - capture = self.capture() - - if capture.transformed_depth is None: - raise KinectAzureException("Depth image not available.") - - return capture.transformed_depth - - def depth_image(self, num_frames: int = 1) -> Image.Image: - assert num_frames > 0 - - img = self._depth_image() - array = img.astype(np.float32) - - for _ in range(num_frames - 1): - array += self._depth_image().astype(np.float32) - - return Image.fromarray((array / num_frames).astype(img.dtype)) - - def sync_images(self) -> ColorAndDepthImage: - capture = self.capture() - - if capture.color is None or capture.depth is None: - raise KinectAzureException("Color/depth image not available.") - else: - color = capture.color - self.convert_bgra_to_rgba(color) - - return ColorAndDepthImage(Image.fromarray(color).convert("RGB"), Image.fromarray(capture.transformed_depth)) - - def cleanup(self) -> None: - if self._capture_thread is not None: - self._running_capture_thread = False - self._capture_thread.join(2) - - self._k4a.stop() - - def get_skeleton(self, body_id: int = 0) -> np.ndarray | None: - capture = self.capture() - return parse_skeleton(capture, body_id) - - def skeleton_image(self, raw: bool = False) -> Image.Image | np.ndarray: - capture = self.capture() - - if capture.color is None: - raise KinectAzureException("Color image not available.") - - frame = capture.color - - body_skeleton = capture.body_skeleton - if body_skeleton is not None: - for body_index in range(body_skeleton.shape[0]): - skeleton = body_skeleton[body_index, :, :] - for joint_index in range(skeleton.shape[0]): - if skeleton[joint_index, -1] != 1: - continue - - x, y = skeleton[joint_index, (-3, -2)].astype(int) - cv2.circle(frame, (x, y), 12, (50, 50, 50), thickness=-1, lineType=cv2.FILLED) - cv2.putText(frame, str(joint_index), (x, y), cv2.FONT_HERSHEY_SIMPLEX, 1, (0, 0, 0), 2, cv2.LINE_AA) - if skeleton.shape[0] > 0: - # Display body id - cv2.putText( - frame, - f"Body id: {body_index}", - skeleton[1, (-3, -2)].astype(int), - cv2.FONT_HERSHEY_SIMPLEX, - 1, - (0, 255, 0), - 2, - cv2.LINE_AA, - ) # type: ignore - - if raw: - return frame - else: - return Image.fromarray(frame, mode="RGBA") - - def get_bodies(self) -> np.ndarray | None: - return self.capture().body_skeleton - - def get_video_feed(self) -> Generator[bytes, None, None]: - """Get video feed that will be shown in browser.""" - while True: - frame = self.skeleton_image(raw=True) - # lower quality for smooth network transfer - encode_param = [int(cv2.IMWRITE_JPEG_QUALITY), 30] - buffer = cv2.imencode(".jpg", frame, encode_param)[1] # type: ignore # TODO solve it - buffer_encode = np.array(buffer) - frame = buffer_encode.tobytes() # type: ignore # TODO solve it - yield b"--frame\r\nContent-Type: image/jpeg\r\n\r\n" + frame + b"\r\n" # type: ignore # TODO solve it diff --git a/src/python/arcor2_kinect_azure/kinect/aggregation.py b/src/python/arcor2_kinect_azure/kinect/aggregation.py deleted file mode 100644 index fe8047ea1..000000000 --- a/src/python/arcor2_kinect_azure/kinect/aggregation.py +++ /dev/null @@ -1,206 +0,0 @@ -import math -from math import radians, tan -from typing import Tuple - -import pyk4a -from flask import Request -from pyk4a import ColorResolution, PyK4ACapture - -from arcor2.data.common import BodyJointId, Direction, Position -from arcor2.exceptions import Arcor2Exception -from arcor2.logging import get_logger -from arcor2_kinect_azure import ARCOR2_KINECT_AZURE_LOG_LEVEL -from arcor2_kinect_azure.exceptions import InvalidDirection -from arcor2_kinect_azure.kinect.common import parse_skeleton -from arcor2_kinect_azure_data.aggregation import MovingDirection -from arcor2_kinect_azure_data.joint import BodyJoint, JointValid - -log = get_logger(__name__, ARCOR2_KINECT_AZURE_LOG_LEVEL) - - -def get_distance_coeffs(distance: float) -> Tuple[float, float]: - """We need to account for the camera curvature. - - :return: Horizontal coefficient, vertical coefficient - """ - - def map_resolution_to_radians(resolution: ColorResolution) -> Tuple[float, float]: - assert resolution in (r.value for r in ColorResolution) - assert resolution != 0 - return { - ColorResolution.RES_2160P: (radians(90), radians(59)), - ColorResolution.RES_1440P: (radians(90), radians(59)), - ColorResolution.RES_1080P: (radians(90), radians(59)), - ColorResolution.RES_720P: (radians(90), radians(59)), - ColorResolution.RES_3072P: (radians(90), radians(74.3)), - ColorResolution.RES_1536P: (radians(90), radians(74.3)), - }[resolution] - - from arcor2_kinect_azure import app - - kinect = app.KINECT - assert kinect is not None - config = kinect.config() - horizontal_radians, vertical_radians = map_resolution_to_radians(config.color_resolution) - - def compute_coef(rads: float) -> float: - return tan(rads / 2) * 2 * (distance / 1000 + 1) - - return compute_coef(horizontal_radians), compute_coef(vertical_radians) - - -class FailedToComputeError(Arcor2Exception): - pass - - -class Moving(MovingDirection): - """Class for computing moving direction from captures.""" - - def __init__( - self, - compute_buffer: list[PyK4ACapture], - body_index: int = 0, - joint_index: int = BodyJointId.SPINE_CHEST, - num_samples: int | None = None, - best_effort: bool = False, - camera_fps: pyk4a.FPS = pyk4a.FPS.FPS_30, - ) -> None: - fps = 30 if camera_fps is pyk4a.FPS.FPS_30 else 15 if camera_fps is pyk4a.FPS.FPS_15 else 5 - - self._compute_buffer = compute_buffer - - self.body_index: int = body_index - self.joint_index: int = joint_index - self.num_samples: int = num_samples or 5 - - self._best_effort: bool = best_effort - - self._camera_fps = fps - - def compute(self) -> None: - log.debug(f"Computing for {self.body_index=}, {self.joint_index=}") - if self.num_samples < 2: - raise FailedToComputeError("Not enough data") - - relevant_buffer: list[BodyJoint] = [] - skip_counter: int = 0 - - for capture in self._compute_buffer[::-1]: - skeleton = parse_skeleton(capture, self.body_index) - if skeleton is None: - if self._best_effort is False and skip_counter > 4: - log.error("Multiple captures in sequence are missing bodies") - raise FailedToComputeError("No body in frame") - skip_counter += 1 - continue - skip_counter = 0 - - joint: BodyJoint = BodyJoint.from_joint(skeleton[self.joint_index]) - if joint.valid != JointValid.VALID: - log.error(f"{joint} is invalid") - continue - - relevant_buffer.append(joint) - - if len(relevant_buffer) == self.num_samples: - break - - if len(relevant_buffer) != self.num_samples and self._best_effort is False: - return - - if len(relevant_buffer) < 2: - log.error(f"{len(relevant_buffer)=}, unable to compute direction") - return - - pos = relevant_buffer[0].position - self.position = pos - - def get_speed(buffer: list[float], coef: float = 1) -> float: - _sum: float = 0 - for i in range(len(buffer) - 1): - _sum += buffer[i] - buffer[i + 1] - return _sum / len(buffer) * coef - - _horizontal_coef, _vertical_coef = get_distance_coeffs(pos.z) - - x_speed = get_speed([b.position.x for b in relevant_buffer], _horizontal_coef) - y_speed = get_speed([b.position.y for b in relevant_buffer], _vertical_coef) - z_speed = get_speed([b.position.z for b in relevant_buffer]) - - speed_coef = self._camera_fps / self.num_samples - - self.speed = Position(x=x_speed * speed_coef, y=y_speed * speed_coef, z=z_speed * speed_coef) - - -class DirectionWithSpeed: - def __init__(self, direction: Direction, speed: float) -> None: - self.direction = direction - # Speed in m/s - self.speed = speed - - @classmethod - def from_moving(cls, moving: Moving) -> "DirectionWithSpeed": - speed = math.sqrt(moving.speed.x**2 + moving.speed.y**2 + moving.speed.z**2) - return cls(Direction(moving.speed.x, moving.speed.y, moving.speed.z), speed) - - @classmethod - def from_request(cls, request: Request) -> "DirectionWithSpeed": - speed = float(request.args.get("speed") or 0.1) - direction = Direction.from_json(request.data) - - return cls(direction, speed) - - def is_zero(self) -> bool: - if self.direction.x == 0.0 and self.direction.y == 0.0 and self.direction.z == 0.0: - return True - else: - return False - - def is_faster_than(self, other: "DirectionWithSpeed", deviation: float = 0.1) -> bool: - if not 0.0 <= deviation <= 1.0: - raise ValueError("Invalid deviation passed") - - def check_matching_directions() -> bool: - for s, o in [ - (self.direction.x, other.direction.x), - (self.direction.y, other.direction.y), - (self.direction.z, other.direction.z), - ]: - if s < 0 < o: - return False - elif o < 0 < s: - return False - return True - - if not check_matching_directions(): - return False - - def get_hypotenuse(d: Direction) -> float: - # c side of right triangle - return math.sqrt(d.x**2 + d.y**2 + d.z**2) - - # Scale direction based on x - self_scale = 1.0 - if self.direction.x != 0.0: - other_scale = other.direction.x / self.direction.x - elif self.direction.y != 0.0: - other_scale = other.direction.y / self.direction.y - elif self.direction.z != 0.0: - other_scale = other.direction.z / self.direction.z - else: - raise InvalidDirection(f"{self.direction}") - - def get_normalized_direction_by_scale(d: Direction, scale: float) -> Direction: - return Direction(d.x / scale, d.y / scale, d.z / scale) - - self_n_d = get_normalized_direction_by_scale(self.direction, self_scale) - other_n_d = get_normalized_direction_by_scale(other.direction, other_scale) - - self_c = get_hypotenuse(self_n_d) - other_c = get_hypotenuse(other_n_d) - - # check if same direction - if other_c * (1.0 - deviation) < self_c < other_c / (1.0 - deviation): - if self.speed > other.speed: - return True - return False diff --git a/src/python/arcor2_kinect_azure/kinect/common.py b/src/python/arcor2_kinect_azure/kinect/common.py deleted file mode 100644 index 35b94a0a7..000000000 --- a/src/python/arcor2_kinect_azure/kinect/common.py +++ /dev/null @@ -1,21 +0,0 @@ -import numpy as np -from pyk4a import PyK4ACapture - -from arcor2_kinect_azure_data.joint import BodyJoint - - -def parse_skeleton(capture: PyK4ACapture, body_id: int = 0) -> np.ndarray | None: - skeleton = capture.body_skeleton - if skeleton is None or skeleton.shape[0] == 0: - return None - try: - return skeleton[body_id, :, :] - except KeyError: - return None - - -def get_body_joint(capture: PyK4ACapture, index: int, body_id: int = 0) -> BodyJoint | None: - body_skeleton = parse_skeleton(capture, body_id) - if body_skeleton is None: - return None - return BodyJoint.from_joint(body_skeleton[index]) diff --git a/src/python/arcor2_kinect_azure/py.typed b/src/python/arcor2_kinect_azure/py.typed deleted file mode 100644 index e69de29bb..000000000 diff --git a/src/python/arcor2_kinect_azure/routes/BUILD b/src/python/arcor2_kinect_azure/routes/BUILD deleted file mode 100644 index db46e8d6c..000000000 --- a/src/python/arcor2_kinect_azure/routes/BUILD +++ /dev/null @@ -1 +0,0 @@ -python_sources() diff --git a/src/python/arcor2_kinect_azure/routes/__init__.py b/src/python/arcor2_kinect_azure/routes/__init__.py deleted file mode 100644 index 6b404622e..000000000 --- a/src/python/arcor2_kinect_azure/routes/__init__.py +++ /dev/null @@ -1,40 +0,0 @@ -import logging -from functools import wraps -from typing import Callable, ParamSpec, TypeVar - -from flask import request - -from arcor2_kinect_azure import app -from arcor2_kinect_azure.exceptions import StartError - - -def started() -> bool: - if app.MOCK: - return app.MOCK_STARTED - - return app.KINECT is not None - - -P = ParamSpec("P") -R = TypeVar("R") -F = Callable[P, R] - - -def requires_started(f: F) -> Callable[P, R]: - @wraps(f) - def wrapped(*args: P.args, **kwargs: P.kwargs): - if not started(): - raise StartError("Not started") - return f(*args, **kwargs) - - return wrapped - - -def debug_request() -> None: - flask_logger = logging.getLogger("werkzeug") - - flask_logger.debug(f"Request query params: {request.args}") - flask_logger.debug(f"Request raw data: {request.data!r}") - - -__all__ = [requires_started.__name__, started.__name__] diff --git a/src/python/arcor2_kinect_azure/routes/aggregation.py b/src/python/arcor2_kinect_azure/routes/aggregation.py deleted file mode 100644 index fcdea6154..000000000 --- a/src/python/arcor2_kinect_azure/routes/aggregation.py +++ /dev/null @@ -1,128 +0,0 @@ -import json -from http import HTTPStatus - -from flask import Blueprint, Response, request - -from arcor2.data.common import BodyJointId -from arcor2.logging import get_logger -from arcor2_kinect_azure import ARCOR2_KINECT_AZURE_LOG_LEVEL, app -from arcor2_kinect_azure.kinect.aggregation import DirectionWithSpeed, FailedToComputeError, Moving -from arcor2_kinect_azure.routes import requires_started - -log = get_logger(__name__, ARCOR2_KINECT_AZURE_LOG_LEVEL) - -blueprint = Blueprint("aggregation", __name__, url_prefix="/aggregation") - - -@blueprint.route("/is-moving", methods=["GET"]) -@requires_started -def is_moving() -> Response: - """See if a body part is moving in certain direction at certain speed - --- - get: - description: Get true if body part is moving - tags: - - Kinect Azure - parameters: - - in: query - name: body_id - schema: - type: integer - default: 0 - - in: query - name: joint_id - schema: - type: integer - default: 2 - minimum: 0 - maximum: 31 - - in: query - name: num_samples - schema: - type: integer - default: 5 - - in: query - name: best_effort - schema: - type: boolean - default: false - - in: query - name: speed - description: Minimum speed - schema: - type: number - format: float - default: 0.1 - minimum: 0.0 - - in: query - name: deviation - description: How precise should the measurement be - schema: - type: number - format: float - default: 0.1 - minimum: 0.0 - maximum: 1.0 - requestBody: - content: - application/json: - schema: - $ref: Orientation - responses: - 200: - description: Ok - content: - application/json: - schema: - type: boolean - 500: - description: "Error types: **General**, **StartError**." - content: - application/json: - schema: - $ref: WebApiError - """ - body_id = int(request.args.get("body_id") or 0) - joint_id = BodyJointId.from_str_or_default(request.args.get("joint_id")) - num_samples = int(request.args.get("num_samples") or 5) - deviation = float(request.args.get("deviation") or 0.1) - if not (1 < num_samples < 30): - return Response( - response='"Wrong number of samples provided"', - status=HTTPStatus.FORBIDDEN, - ) - best_effort = bool(request.args.get("best_effort") or False) - if best_effort: - log.debug(f'"Computing with {best_effort=}"') - try: - direction_w_speed = DirectionWithSpeed.from_request(request) - except (TypeError, ValueError) as e: - log.exception(e) - return Response(response='"Cannot build DirectionWitSpeed from request"', status=HTTPStatus.FORBIDDEN) - - assert app.KINECT is not None - buffer = app.KINECT.get_n_non_empty_captures(num_samples) - if buffer is None: - return Response('"No user in frame"', status=HTTPStatus.INTERNAL_SERVER_ERROR) - - moving_direction = Moving( - compute_buffer=buffer, - body_index=body_id, - joint_index=joint_id, - num_samples=num_samples, - best_effort=best_effort, - camera_fps=app.KINECT.config().camera_fps, - ) - - try: - moving_direction.compute() - except FailedToComputeError: - return Response(response='"Failed to compute speed"', status=HTTPStatus.INTERNAL_SERVER_ERROR) - - moving_direction_w_speed = DirectionWithSpeed.from_moving(moving_direction) - if moving_direction_w_speed.is_zero(): - is_faster = False - else: - is_faster = moving_direction_w_speed.is_faster_than(direction_w_speed, deviation) - - return Response(response=json.dumps(is_faster)) diff --git a/src/python/arcor2_kinect_azure/routes/body.py b/src/python/arcor2_kinect_azure/routes/body.py deleted file mode 100644 index 17c053728..000000000 --- a/src/python/arcor2_kinect_azure/routes/body.py +++ /dev/null @@ -1,84 +0,0 @@ -import json -import time - -from flask import Blueprint, Response, request - -from arcor2.flask import RespT -from arcor2_kinect_azure import app -from arcor2_kinect_azure.routes import requires_started - -blueprint = Blueprint("body", __name__, url_prefix="/body") - - -@blueprint.route("/count", methods=["GET"]) -@requires_started -def get_body_count() -> RespT: - """Get body count - --- - get: - description: Get body count - tags: - - Kinect Azure - responses: - 200: - description: Ok - content: - application/json: - schema: - type: integer - 500: - description: "Error types: **General**, **StartError**." - content: - application/json: - schema: - $ref: WebApiError - """ - kinect = app.KINECT - assert kinect is not None - - bodies = kinect.get_bodies() - count = 0 if bodies is None else bodies.shape[0] - return Response(response=str(count)) - - -@blueprint.route("/present", methods=["GET"]) -@requires_started -def is_user_present() -> RespT: - """Get body count - --- - get: - description: Returns true is someone is present - tags: - - Kinect Azure - parameters: - - in: query - name: wait - schema: - type: boolean - default: false - responses: - 200: - description: Ok - content: - application/json: - schema: - type: integer - 500: - description: "Error types: **General**, **StartError**." - content: - application/json: - schema: - $ref: WebApiError - """ - kinect = app.KINECT - assert kinect is not None - - wait = json.loads(request.args.get("wait", "false")) - - while True: - bodies = kinect.get_bodies() - is_present = False if bodies is None else bodies.shape[0] > 0 - if wait and not is_present: - time.sleep(0.1) - continue - return Response(response=json.dumps(is_present)) diff --git a/src/python/arcor2_kinect_azure/routes/color.py b/src/python/arcor2_kinect_azure/routes/color.py deleted file mode 100644 index 4ebead875..000000000 --- a/src/python/arcor2_kinect_azure/routes/color.py +++ /dev/null @@ -1,91 +0,0 @@ -from flask import Blueprint, jsonify, send_file -from PIL import Image - -from arcor2.data.camera import CameraParameters -from arcor2.flask import RespT -from arcor2.image import image_to_bytes_io -from arcor2_kinect_azure import app, get_data -from arcor2_kinect_azure.exceptions import StartError -from arcor2_kinect_azure.routes import requires_started - -blueprint = Blueprint("color", __name__, url_prefix="/color") - - -def color_image() -> Image.Image: - return Image.open(get_data("rgb.jpg")) - - -@blueprint.route("/image", methods=["GET"]) -@requires_started -def get_image_color() -> RespT: - """Get the color image. - --- - get: - description: Get the color image. - tags: - - Color camera - responses: - 200: - description: Ok - content: - image/jpeg: - schema: - type: string - 500: - description: "Error types: **General**, **StartError**." - content: - application/json: - schema: - $ref: WebApiError - """ - - if app.MOCK: - img = color_image() - else: - assert app.KINECT is not None - img = app.KINECT.color_image() - - return send_file( - image_to_bytes_io(img, target_format="JPEG", target_mode="RGB"), - mimetype="image/jpeg", - max_age=0, - ) - - -@blueprint.route("/parameters", methods=["GET"]) -@requires_started -def get_color_camera_parameters() -> RespT: - """Get the color camera parameters. - --- - get: - description: Get the color camera parameters. - tags: - - Color camera - responses: - 200: - description: Ok - content: - application/json: - schema: - $ref: CameraParameters - 500: - description: "Error types: **General**, **StartError**." - content: - application/json: - schema: - $ref: WebApiError - """ - - if app.MOCK: - params = CameraParameters( - 915.575, 915.425, 957.69, 556.35, [0.447, -2.5, 0.00094, -0.00053, 1.432, 0.329, -2.332, 1.363] - ) - else: - assert app.KINECT is not None - - if not app.KINECT.color_camera_params: - raise StartError("Failed to get camera parameters") - - params = app.KINECT.color_camera_params - - return jsonify(params.to_dict()), 200 diff --git a/src/python/arcor2_kinect_azure/routes/depth.py b/src/python/arcor2_kinect_azure/routes/depth.py deleted file mode 100644 index d18b5321e..000000000 --- a/src/python/arcor2_kinect_azure/routes/depth.py +++ /dev/null @@ -1,54 +0,0 @@ -from flask import Blueprint, request, send_file -from PIL import Image - -from arcor2.flask import RespT -from arcor2.image import image_to_bytes_io -from arcor2_kinect_azure import app, get_data -from arcor2_kinect_azure.routes import requires_started - -blueprint = Blueprint("depth", __name__, url_prefix="/depth") - - -def depth_image() -> Image.Image: - return Image.open(get_data("depth.png")) - - -@blueprint.route("/image", methods=["GET"]) -@requires_started -def get_image_depth() -> RespT: - """Get the depth image. - --- - get: - description: Get the depth image. - tags: - - Depth camera - parameters: - - in: query - name: averagedFrames - schema: - type: integer - default: 1 - required: false - description: Package name - responses: - 200: - description: Ok - content: - image/png: - schema: - type: string - 500: - description: "Error types: **General**, **StartError**." - content: - application/json: - schema: - $ref: WebApiError - """ - - if app.MOCK: - img = depth_image() - else: - assert app.KINECT is not None - img = app.KINECT.depth_image(num_frames=int(request.args.get("num_frames", default=1))) - - return send_file(image_to_bytes_io(img, target_format="PNG"), mimetype="image/png", max_age=0) diff --git a/src/python/arcor2_kinect_azure/routes/position.py b/src/python/arcor2_kinect_azure/routes/position.py deleted file mode 100644 index 31a729430..000000000 --- a/src/python/arcor2_kinect_azure/routes/position.py +++ /dev/null @@ -1,231 +0,0 @@ -import json -import math -import time - -from flask import Blueprint, Response, request - -from arcor2.data.common import BodyJointId, Pose, Position -from arcor2.flask import DataclassResponse, RespT -from arcor2.logging import get_logger -from arcor2_kinect_azure import ARCOR2_KINECT_AZURE_LOG_LEVEL, app -from arcor2_kinect_azure.exceptions import NotFound -from arcor2_kinect_azure.kinect.common import get_body_joint, parse_skeleton -from arcor2_kinect_azure.routes import requires_started -from arcor2_kinect_azure_data.joint import BodyJoint, JointValid - -blueprint = Blueprint("position", __name__, url_prefix="/position") - -log = get_logger(__name__, ARCOR2_KINECT_AZURE_LOG_LEVEL) - - -def get_distance(p1: Position, p2: Position) -> float: - p = p1 - p2 - return math.sqrt(p.x**2 + p.y**2 + p.z**2) - - -@blueprint.route("/is-nearby", methods=["GET"]) -@requires_started -def is_nearby() -> RespT: - """Get true if body part is nearby specified position - --- - get: - description: Get true if body part is nearby specified position - tags: - - Kinect Azure - requestBody: - content: - application/json: - schema: - $ref: Position - parameters: - - in: query - name: body_id - description: Default value points to the chest - schema: - type: integer - default: 2 - minimum: 0 - maximum: 31 - - in: query - name: radius - schema: - type: number - format: float - default: 1.0 - minimum: 0.0 - - in: query - name: wait - schema: - type: boolean - default: false - responses: - 200: - description: Ok - content: - application/json: - schema: - type: boolean - 500: - description: "Error types: **General**, **StartError**." - content: - application/json: - schema: - $ref: WebApiError - """ - if not isinstance(request.json, dict): - raise NotFound("Position was not found") - - kinect = app.KINECT - assert kinect is not None - - scene_abs_position = Position.from_dict(request.json) - log.debug(f"Position from request: {scene_abs_position}") - position = kinect.get_camera_relative_pos(scene_abs_position) - log.debug(f"Camera absolute position: {position}") - body_id = int(request.args.get("body_id") or 0) - joint_id = BodyJointId.from_str_or_default(request.args.get("joint_id")) - radius = float(request.args.get("radius") or 1.0) - wait = json.loads(request.args.get("wait", "false")) - - while True: - joint = get_body_joint(kinect.capture(), joint_id, body_id) - if not joint: - if wait: - time.sleep(0.1) - continue - return Response(response=json.dumps(False)) - - log.debug(f"Raw joint position: {joint.position}") - adjusted_joint_position = kinect.adjust_depth_position_to_rgb(joint.position) - log.debug(f"Adjusted joint position: {adjusted_joint_position}") - - point_distance = get_distance(position, adjusted_joint_position) - if point_distance > radius: - if wait: - time.sleep(0.1) - continue - return Response(response=json.dumps(False)) - - return Response(response=json.dumps(True)) - - -@blueprint.route("/is-colliding", methods=["GET"]) -@requires_started -def is_colliding() -> RespT: - """Get true if body is going to collide with provided position - --- - get: - description: Get true if body is going to collide with provided position - tags: - - Kinect Azure - requestBody: - content: - application/json: - schema: - $ref: Position - parameters: - - in: query - name: radius - schema: - type: number - format: float - default: 0.03 - minimum: 0.0 - responses: - 200: - description: Ok - content: - application/json: - schema: - type: boolean - 500: - description: "Error types: **General**, **StartError**." - content: - application/json: - schema: - $ref: WebApiError - """ - if not isinstance(request.json, dict): - raise NotFound("Position was not found") - - kinect = app.KINECT - assert kinect is not None - - scene_abs_position = Position.from_dict(request.json) - log.debug(f"Position from request: {scene_abs_position}") - position = kinect.get_camera_relative_pos(scene_abs_position) - log.debug(f"Camera absolute position: {position}") - threshold = float(request.args.get("radius") or 0.1) - - capture = kinect.get_non_empty_capture() - if capture is None: - return Response(response=json.dumps(False)) - - skeleton = parse_skeleton(capture) - if skeleton is None: - log.warning("No skeleton was found") - return Response(response=json.dumps(False)) - - log.debug(f"{threshold=}") - for joint_id in BodyJointId.set(): - body_joint = BodyJoint.from_joint(skeleton[joint_id]) - if body_joint.valid != JointValid.VALID or body_joint.position is None: - continue - - distance = position - body_joint.position - log.debug(f"{joint_id}: {distance=}") - if abs(distance.x) < threshold and abs(distance.y) < threshold and abs(distance.z) < threshold: - return Response(response=json.dumps(True)) - - return Response(response=json.dumps(False)) - - -@blueprint.route("/get", methods=["GET"]) -@requires_started -def get_position() -> RespT: - """Return position of specified body part - --- - get: - description: Return position of specified body part - tags: - - Kinect Azure - parameters: - - in: query - name: body_id - schema: - type: integer - default: 0 - - in: query - name: joint_id - schema: - type: integer - default: 2 - minimum: 0 - maximum: 31 - responses: - 200: - description: Ok - content: - application/json: - schema: - $ref: Pose - 500: - description: "Error types: **General**, **StartError**." - content: - application/json: - schema: - $ref: WebApiError - """ - kinect = app.KINECT - assert kinect is not None - - body_id = int(request.args.get("body_id") or 0) - joint_id = BodyJointId.from_str_or_default(request.args.get("joint_id")) - - capture = kinect.capture() - joint = get_body_joint(capture, joint_id, body_id) - assert joint is not None - - abs_position = kinect.get_camera_relative_pos(joint.position) - - return DataclassResponse(Pose(abs_position)) diff --git a/src/python/arcor2_kinect_azure/routes/skeleton.py b/src/python/arcor2_kinect_azure/routes/skeleton.py deleted file mode 100644 index de62e6a1d..000000000 --- a/src/python/arcor2_kinect_azure/routes/skeleton.py +++ /dev/null @@ -1,45 +0,0 @@ -from flask import Blueprint, send_file - -from arcor2.flask import RespT -from arcor2.image import image_to_bytes_io -from arcor2_kinect_azure import app -from arcor2_kinect_azure.routes import requires_started -from arcor2_kinect_azure.routes.color import color_image - -blueprint = Blueprint("skeleton", __name__, url_prefix="/skeleton") - - -@blueprint.route("/image", methods=["GET"]) -@requires_started -def get_skeleton_image() -> RespT: - """Get the color image with visualized skeleton. - --- - get: - description: Get the color image with visualized skeleton. - tags: - - Color camera - responses: - 200: - description: Ok - content: - image/jpeg: - schema: - type: string - 500: - description: "Error types: **General**, **StartError**." - content: - application/json: - schema: - $ref: WebApiError - """ - if app.MOCK: - img = color_image() - else: - assert app.KINECT is not None - img = app.KINECT.skeleton_image() # type: ignore # TODO solve it - - return send_file( - image_to_bytes_io(img, target_format="JPEG", target_mode="RGB"), - mimetype="image/jpeg", - max_age=0, - ) diff --git a/src/python/arcor2_kinect_azure/routes/state.py b/src/python/arcor2_kinect_azure/routes/state.py deleted file mode 100644 index 57da41a81..000000000 --- a/src/python/arcor2_kinect_azure/routes/state.py +++ /dev/null @@ -1,262 +0,0 @@ -import json -from http import HTTPStatus - -from flask import Blueprint, Response, request - -from arcor2.data.common import Pose -from arcor2.flask import RespT -from arcor2.logging import get_logger -from arcor2_kinect_azure import ARCOR2_KINECT_AZURE_LOG_LEVEL, app -from arcor2_kinect_azure.exceptions import StartError -from arcor2_kinect_azure.routes import requires_started, started - -log = get_logger(__name__, ARCOR2_KINECT_AZURE_LOG_LEVEL) - -blueprint = Blueprint("state", __name__, url_prefix="/state") - - -@blueprint.route("/start", methods=["PUT"]) -def put_start() -> RespT: - """Start the sensor. - --- - put: - description: Start the robot. - tags: - - State - requestBody: - content: - application/json: - schema: - $ref: Pose - responses: - 204: - description: Ok - 500: - description: "Error types: **General**, **DobotGeneral**, **StartError**." - content: - application/json: - schema: - $ref: WebApiError - """ - - if started(): - raise StartError("Already started.") - - if app.MOCK: - app.MOCK_STARTED = True - else: - if not isinstance(request.json, dict): - StartError("Body should be a JSON dict containing Pose.") - camera_pose = Pose.from_json(request.data) - - # lazy import so mock mode can work without pyk4a installed - from arcor2_kinect_azure.kinect import KinectAzure - - assert app.KINECT is None - app.KINECT = KinectAzure() - - app.KINECT.set_camera_pose(camera_pose) - - log.info("Started") - return Response(response="ok", status=HTTPStatus.OK) - - -@blueprint.route("/full-start", methods=["PUT"]) -def put_full_start() -> RespT: - """Start the sensor. - --- - put: - description: Start the sensor and start capturing all frames. - tags: - - State - requestBody: - content: - application/json: - schema: - $ref: Pose - responses: - 200: - description: Ok - 405: - description: Already running - 500: - description: "Error types: **General**, **StartError**." - content: - application/json: - schema: - $ref: WebApiError - """ - if started(): - return Response(response="Already running.", status=HTTPStatus.METHOD_NOT_ALLOWED) - - if app.MOCK: - app.MOCK_STARTED = True - else: - if not isinstance(request.json, dict): - StartError("Body should be a JSON dict containing Pose.") - camera_pose = Pose.from_json(request.data) - - # lazy import so mock mode can work without pyk4a installed - from arcor2_kinect_azure.kinect import KinectAzure - - assert app.KINECT is None - app.KINECT = KinectAzure() - - app.KINECT.set_camera_pose(camera_pose) - - app.KINECT.start_capturing() - - log.info("Started and capturing") - return Response(response="ok", status=HTTPStatus.OK) - - -@blueprint.route("/start-capturing", methods=["PUT"]) -@requires_started -def put_capture() -> RespT: - """Start the capturing. - --- - put: - description: Start capturing all frames. - tags: - - State - responses: - 200: - description: Ok - 500: - description: "Error types: **General**, **StartError**." - content: - application/json: - schema: - $ref: WebApiError - """ - - if not app.MOCK: - assert app.KINECT is not None - app.KINECT.start_capturing() - - log.info("Capturing") - return Response(response="ok", status=HTTPStatus.OK) - - -@blueprint.route("/stop", methods=["PUT"]) -@requires_started -def put_stop() -> RespT: - """Stop the sensor. - --- - put: - description: Stop the sensor. - tags: - - State - responses: - 200: - description: Ok - 500: - description: "Error types: **General**, **StartError**." - content: - application/json: - schema: - $ref: WebApiError - """ - - if app.MOCK: - app.MOCK_STARTED = False - else: - assert app.KINECT is not None - app.KINECT.cleanup() - app.KINECT = None - log.info("Stopped") - return Response(response="ok", status=HTTPStatus.OK) - - -@blueprint.route("/started", methods=["GET"]) -def get_started() -> RespT: - """Get the current state. - --- - get: - description: Get the current state. - tags: - - State - responses: - 200: - description: Ok - content: - application/json: - schema: - type: boolean - 500: - description: "Error types: **General**, **StartError**." - content: - application/json: - schema: - $ref: WebApiError - """ - return Response(response=json.dumps(started()), status=HTTPStatus.OK) - - -@blueprint.route("/pose", methods=["GET"]) -@requires_started -def get_pose() -> RespT: - """Returns the pose configured during startup. - --- - get: - description: Returns the pose configured during startup. - tags: - - State - responses: - 200: - description: Ok - content: - application/json: - schema: - $ref: Pose - 500: - description: "Error types: **General**, **StartError**." - content: - application/json: - schema: - $ref: WebApiError - """ - kinect = app.KINECT - assert kinect is not None - - pose = kinect.get_camera_pose() - - return Response(response=pose.to_json(), status=HTTPStatus.OK) - - -@blueprint.route("/pose", methods=["PUT"]) -@requires_started -def put_pose() -> RespT: - """Sets sensor pose in runtime. - --- - put: - description: Sets sensor pose in runtime. - tags: - - State - requestBody: - content: - application/json: - schema: - $ref: Pose - responses: - 204: - description: Ok - 500: - description: "Error types: **General**, **StartError**." - content: - application/json: - schema: - $ref: WebApiError - """ - - if not isinstance(request.json, dict): - raise StartError("Body should be a JSON dict containing Pose.") - - kinect = app.KINECT - assert kinect is not None - - pose = Pose.from_dict(request.json) - - kinect.set_camera_pose(pose) - - return Response(response="ok", status=HTTPStatus.OK) diff --git a/src/python/arcor2_kinect_azure/routes/synchronized.py b/src/python/arcor2_kinect_azure/routes/synchronized.py deleted file mode 100644 index 0c4c6cc4d..000000000 --- a/src/python/arcor2_kinect_azure/routes/synchronized.py +++ /dev/null @@ -1,59 +0,0 @@ -import io -import zipfile - -from flask import Blueprint, send_file - -from arcor2.flask import RespT -from arcor2.image import image_to_bytes_io -from arcor2_kinect_azure import app -from arcor2_kinect_azure.routes import requires_started -from arcor2_kinect_azure.routes.color import color_image -from arcor2_kinect_azure.routes.depth import depth_image - -blueprint = Blueprint("synchronized", __name__, url_prefix="/synchronized") - - -@blueprint.route("/image", methods=["GET"]) -@requires_started -def get_image_both() -> RespT: - """Get the both color/depth image. - --- - get: - description: Get the depth image. - tags: - - Synchronized - responses: - 200: - description: Ok - content: - application/zip: - schema: - type: string - format: binary - 500: - description: "Error types: **General**, **StartError**." - content: - application/json: - schema: - $ref: WebApiError - """ - - if app.MOCK: - color = color_image() - depth = depth_image() - else: - assert app.KINECT is not None - both = app.KINECT.sync_images() - color = both.color - depth = both.depth - - mem_zip = io.BytesIO() - - with zipfile.ZipFile(mem_zip, mode="w", compression=zipfile.ZIP_STORED) as zf: - zf.writestr("color.jpg", image_to_bytes_io(color).getvalue()) - zf.writestr("depth.png", image_to_bytes_io(depth, target_format="PNG").getvalue()) - - mem_zip.seek(0) - return send_file( - mem_zip, mimetype="application/zip", max_age=0, as_attachment=True, download_name="synchronized.zip" - ) diff --git a/src/python/arcor2_kinect_azure/routes/video.py b/src/python/arcor2_kinect_azure/routes/video.py deleted file mode 100644 index 011d85b4e..000000000 --- a/src/python/arcor2_kinect_azure/routes/video.py +++ /dev/null @@ -1,58 +0,0 @@ -from flask import Blueprint, Response, render_template_string - -from arcor2.flask import RespT -from arcor2_kinect_azure import app -from arcor2_kinect_azure.routes import requires_started - -blueprint = Blueprint("video", __name__, url_prefix="/video") - - -@blueprint.route("/show", methods=["GET"]) -@requires_started -def show() -> RespT: - """Show live feed from the camera in browser - --- - get: - description: Show live feed from camera in browser - tags: - - Color camera - responses: - 200: - description: Ok - content: - image/jpeg: - schema: - type: string - 500: - description: "Error types: **General**, **StartError**." - content: - application/json: - schema: - $ref: WebApiError - """ - assert app.KINECT - - return ( - render_template_string( - """ - - -
-