Showing preview only (418K chars total). Download the full file or copy to clipboard to get everything.
Repository: bdtinc/maskcam
Branch: main
Commit: 4841c2c49235
Files: 106
Total size: 388.6 KB
Directory structure:
gitextract_82ysmahp/
├── .gitignore
├── Dockerfile
├── LICENSE.md
├── README.md
├── deepstream_plugin_yolov4/
│ ├── Makefile
│ ├── README.md
│ ├── kernels.cu
│ ├── nvdsinfer_yolo_engine.cpp
│ ├── nvdsparsebbox_Yolo.cpp
│ ├── trt_utils.cpp
│ ├── trt_utils.h
│ ├── yolo.cpp
│ ├── yolo.h
│ ├── yoloPlugins.cpp
│ └── yoloPlugins.h
├── docker/
│ ├── constraints.docker
│ ├── opencv_python-3.2.0.egg-info
│ ├── scikit-learn-0.19.1.egg-info
│ └── start.sh
├── docker-compose.yml
├── docs/
│ ├── BalenaOS-DevKit-Nano-Setup.md
│ ├── BalenaOS-Photon-Nano-Setup.md
│ ├── Custom-Container-Development.md
│ ├── Manual-Dependencies-Installation.md
│ └── Useful-Development-Scripts.md
├── maskcam/
│ ├── common.py
│ ├── config.py
│ ├── maskcam_filesave.py
│ ├── maskcam_fileserver.py
│ ├── maskcam_inference.py
│ ├── maskcam_streaming.py
│ ├── mqtt_commander.py
│ ├── mqtt_common.py
│ ├── prints.py
│ └── utils.py
├── maskcam_config.txt
├── maskcam_run.py
├── requirements-dev.in
├── requirements.in
├── requirements.txt
├── server/
│ ├── backend/
│ │ ├── Dockerfile
│ │ ├── alembic.ini
│ │ ├── app/
│ │ │ ├── api/
│ │ │ │ ├── __init__.py
│ │ │ │ ├── exceptions.py
│ │ │ │ └── routes/
│ │ │ │ ├── device_routes.py
│ │ │ │ └── statistic_routes.py
│ │ │ ├── core/
│ │ │ │ └── config.py
│ │ │ ├── db/
│ │ │ │ ├── cruds/
│ │ │ │ │ ├── __init__.py
│ │ │ │ │ ├── crud_device.py
│ │ │ │ │ ├── crud_statistic.py
│ │ │ │ │ └── crud_video_file.py
│ │ │ │ ├── migrations/
│ │ │ │ │ ├── env.py
│ │ │ │ │ ├── script.py.mako
│ │ │ │ │ └── versions/
│ │ │ │ │ ├── 6a4d853aabce_added_database.py
│ │ │ │ │ ├── 6d5c250f098c_added_device_file_server_address.py
│ │ │ │ │ ├── 8f58cd776eda_added_database.py
│ │ │ │ │ └── fb245977373f_added_video_file_table.py
│ │ │ │ ├── schema/
│ │ │ │ │ ├── __init__.py
│ │ │ │ │ ├── base.py
│ │ │ │ │ ├── models.py
│ │ │ │ │ └── schemas.py
│ │ │ │ └── utils/
│ │ │ │ ├── __init__.py
│ │ │ │ ├── enums.py
│ │ │ │ └── utils.py
│ │ │ ├── main.py
│ │ │ └── mqtt/
│ │ │ ├── broker.py
│ │ │ ├── publisher.py
│ │ │ └── subscriber.py
│ │ ├── prestart.sh
│ │ ├── requirements.txt
│ │ └── test_crud.py
│ ├── backend.env.template
│ ├── build_docker.sh
│ ├── database.env.template
│ ├── docker-compose.yml
│ ├── frontend/
│ │ ├── Dockerfile
│ │ ├── main.py
│ │ ├── requirements.txt
│ │ ├── session_manager.py
│ │ └── utils/
│ │ ├── api_utils.py
│ │ └── format_utils.py
│ ├── frontend.env.template
│ ├── mosquitto.conf
│ ├── server_setup.sh
│ └── stop_docker.sh
├── utils/
│ ├── combine_coco.py
│ ├── gst_capabilities.sh
│ ├── mqtt-test/
│ │ ├── broker.py
│ │ ├── publisher.py
│ │ └── suscriber.py
│ ├── onnx_fix_mobilenet.py
│ ├── remove_images_coco.py
│ ├── tf1_trt_inference.py
│ ├── tf2_trt_convert.py
│ └── tf_trt_convert.py
└── yolo/
├── config.py
├── config_images.yml
├── data/
│ ├── obj.data
│ └── obj.names
├── facemask-yolov4-tiny.cfg
├── facemask-yolov4.cfg
├── integrations/
│ └── yolo/
│ ├── detector_trt.py
│ ├── utils_pytorch.py
│ └── yolo_adaptor.py
├── run_yolo_images.py
└── train_cu90.sh
================================================
FILE CONTENTS
================================================
================================================
FILE: .gitignore
================================================
# Project particular ignores
backup/
videos/inputs/*
videos/outputs/*
images*/
*.mp4
.DS_Store
.vscode/
# Intermediate files to convert MobileNetV2 from TF->TF-TRT
utils/*.png
mobilenetv2/inference_graph_*/
mobilenetv2/converted_trt_*.pb
# Avoid weights, or engines
*.weights
*.trt
*.engine
*.onnx
# Environment files (not templates)
server/*.env
# Byte-compiled / optimized / DLL files
__pycache__/
*.py[cod]
*$py.class
# C extensions
*.so
*.o
# Distribution / packaging
.Python
build/
develop-eggs/
dist/
downloads/
eggs/
.eggs/
lib/
lib64/
parts/
sdist/
var/
wheels/
pip-wheel-metadata/
share/python-wheels/
*.egg-info/
.installed.cfg
*.egg
MANIFEST
# PyInstaller
# Usually these files are written by a python script from a template
# before PyInstaller builds the exe, so as to inject date/other infos into it.
*.manifest
*.spec
# Installer logs
pip-log.txt
pip-delete-this-directory.txt
# Unit test / coverage reports
htmlcov/
.tox/
.nox/
.coverage
.coverage.*
.cache
nosetests.xml
coverage.xml
*.cover
*.py,cover
.hypothesis/
.pytest_cache/
# Translations
*.mo
*.pot
# Django stuff:
*.log
local_settings.py
db.sqlite3
db.sqlite3-journal
# Flask stuff:
instance/
.webassets-cache
# Scrapy stuff:
.scrapy
# Sphinx documentation
docs/_build/
# PyBuilder
target/
# Jupyter Notebook
.ipynb_checkpoints
# IPython
profile_default/
ipython_config.py
# pyenv
.python-version
# pipenv
# According to pypa/pipenv#598, it is recommended to include Pipfile.lock in version control.
# However, in case of collaboration, if having platform-specific dependencies or dependencies
# having no cross-platform support, pipenv may install dependencies that don't work, or not
# install all needed dependencies.
#Pipfile.lock
# PEP 582; used by e.g. github.com/David-OConnor/pyflow
__pypackages__/
# Celery stuff
celerybeat-schedule
celerybeat.pid
# SageMath parsed files
*.sage.py
# Environments
.env
.venv
env/
venv/
ENV/
env.bak/
venv.bak/
# Spyder project settings
.spyderproject
.spyproject
# Rope project settings
.ropeproject
# mkdocs documentation
/site
# mypy
.mypy_cache/
.dmypy.json
dmypy.json
# Pyre type checker
.pyre/
================================================
FILE: Dockerfile
================================================
# Installs maskcam on a BalenaOS container (devkit or Photon)
FROM balenalib/jetson-nano-ubuntu:20210201
# Don't prompt with any configuration questions
ENV DEBIAN_FRONTEND noninteractive
# Switch the nvidia apt source repos and
# install some utilities
RUN \
apt-get update && apt-get install -y \
lbzip2 wget tar python3 git
ENV UDEV=1
# Download and install BSP binaries for L4T 32.4.2
# This is mostly from Balena's Alan Boris at:
# https://github.com/balena-io-playground/jetson-nano-sample-new/blob/master/CUDA/Dockerfile
RUN apt-get update && apt-get install -y wget tar python3 libegl1 && \
wget https://developer.nvidia.com/embedded/L4T/r32_Release_v4.2/t210ref_release_aarch64/Tegra210_Linux_R32.4.2_aarch64.tbz2 && \
tar xf Tegra210_Linux_R32.4.2_aarch64.tbz2 && \
cd Linux_for_Tegra && \
sed -i 's/config.tbz2\"/config.tbz2\" --exclude=etc\/hosts --exclude=etc\/hostname/g' apply_binaries.sh && \
sed -i 's/install --owner=root --group=root \"${QEMU_BIN}\" \"${L4T_ROOTFS_DIR}\/usr\/bin\/\"/#install --owner=root --group=root \"${QEMU_BIN}\" \"${L4T_ROOTFS_DIR}\/usr\/bin\/\"/g' nv_tegra/nv-apply-debs.sh && \
sed -i 's/LC_ALL=C chroot . mount -t proc none \/proc/ /g' nv_tegra/nv-apply-debs.sh && \
sed -i 's/umount ${L4T_ROOTFS_DIR}\/proc/ /g' nv_tegra/nv-apply-debs.sh && \
sed -i 's/chroot . \// /g' nv_tegra/nv-apply-debs.sh && \
./apply_binaries.sh -r / --target-overlay && cd .. && \
rm -rf Tegra210_Linux_R32.4.2_aarch64.tbz2 && \
rm -rf Linux_for_Tegra && \
echo "/usr/lib/aarch64-linux-gnu/tegra" > /etc/ld.so.conf.d/nvidia-tegra.conf && \
echo "/usr/lib/aarch64-linux-gnu/tegra-egl" > /etc/ld.so.conf.d/nvidia-tegra-egl.conf && ldconfig
# Install GStreamer and remove unnecessary files
RUN apt-get install -y \
libssl1.0.0 \
libgstreamer1.0-0 \
gstreamer1.0-tools \
gstreamer1.0-plugins-good \
gstreamer1.0-plugins-bad \
gstreamer1.0-plugins-ugly \
gstreamer1.0-libav \
libgstrtspserver-1.0-0 \
libjansson4=2.11-1 \
cuda-toolkit-10-2 && \
ldconfig
RUN \
rm -rf /usr/src/nvidia/graphics_demos \
/usr/local/cuda-10.2/samples \
/usr/local/cuda-10.2/doc
# Install DeepStream
RUN apt-get install -y deepstream-5.0 && \
rm -rf /opt/nvidia/deepstream/deepstream-5.0/samples \
/usr/lib/aarch64-linux-gnu/libcudnn_static_v8.a \
/usr/lib/aarch64-linux-gnu/libcudnn_cnn_infer_static_v8.a \
/usr/lib/aarch64-linux-gnu/libnvinfer_static.a \
/usr/lib/aarch64-linux-gnu/libcudnn_adv_infer_static_v8.a \
/usr/lib/aarch64-linux-gnu/libcublas_static.a \
/usr/lib/aarch64-linux-gnu/libcudnn_adv_train_static_v8.a \
/usr/lib/aarch64-linux-gnu/libcudnn_ops_infer_static_v8.a \
/usr/lib/aarch64-linux-gnu/libcublasLt_static.a \
/usr/lib/aarch64-linux-gnu/libcudnn_cnn_train_static_v8.a \
/usr/lib/aarch64-linux-gnu/libcudnn_ops_train_static_v8.a \
/usr/lib/aarch64-linux-gnu/libmyelin_compiler_static.a \
/usr/lib/aarch64-linux-gnu/libmyelin_executor_static.a \
/usr/lib/aarch64-linux-gnu/libnvinfer_plugin_static.a && \
ldconfig
# Install system-level python3 packages
RUN apt-get update && apt-get install -y \
gir1.2-gst-rtsp-server-1.0 \
python3-pip \
python3-opencv \
python3-libnvinfer \
python3-scipy \
cython3 \
python3-sklearn \
python-gi-dev \
unzip && ldconfig
# These system-level packages don't provide egg-info files, add them manually so that pip knows
COPY docker/opencv_python-3.2.0.egg-info /usr/lib/python3/dist-packages/
COPY docker/scikit-learn-0.19.1.egg-info /usr/lib/python3/dist-packages/
# Install gst-python (python bindings for GStreamer)
RUN \
export GST_CFLAGS="-pthread -I/usr/include/gstreamer-1.0 -I/usr/include/glib-2.0 -I/usr/lib/x86_64-linux-gnu/glib-2.0/include" && \
export GST_LIBS="-lgstreamer-1.0 -lgobject-2.0 -lglib-2.0" && \
git clone https://github.com/GStreamer/gst-python.git && \
cd gst-python && git checkout 1a8f48a && \
./autogen.sh PYTHON=python3 && \
./configure PYTHON=python3 && \
make && make install
# Install pyds (python bindings for DeepStream)
RUN cd /opt/nvidia/deepstream/deepstream-5.0/lib && python3 setup.py install
# Upgrade here to avoid re-running on code changes
RUN pip3 install --upgrade pip
# ---- Below steps are run before copying full maskcam code to allow layer caching ----
# Compile YOLOv4 plugin for DeepStream
COPY deepstream_plugin_yolov4 /deepstream_plugin_yolov4
ENV CUDA_VER=10.2
RUN cd /deepstream_plugin_yolov4 && make
# Get TensorRT engine (pretrained YOLOv4-tiny)
# Model trained on smaller dataset
# RUN wget -P / https://maskcam.s3.us-east-2.amazonaws.com/facemask_y4tiny_1024_608_fp16.trt
# Model trained on bigger dataset, merged with MAFA, WiderFace, Kaggle Medical Masks and FDDB
RUN wget -P / https://maskcam.s3.us-east-2.amazonaws.com/maskcam_y4t_1024_608_fp16.trt
# RUN wget -P / https://maskcam.s3.us-east-2.amazonaws.com/maskcam_y4t_1120_640_fp16.trt
# Install requirements with pinned versions
COPY requirements.txt /maskcam_requirements.txt
RUN pip3 install -r /maskcam_requirements.txt
# ---- Note: all layers below this will be re-generated each time code changes ----
# Copy full maskcam code
COPY . /opt/maskcam_1.0/
WORKDIR /opt/maskcam_1.0
# Move pre-copied files to their maskcam location
# NOTE: Ignoring errors with `exit 0` to avoid breaking on balena livepush
RUN rm -r deepstream_plugin_yolov4 && mv /deepstream_plugin_yolov4 . ; exit 0
RUN mv /*.trt yolo/ ; exit 0
# Preload library to avoids Gst errors "cannot allocate memory in static TLS block"
ENV LD_PRELOAD=/usr/lib/aarch64-linux-gnu/libgomp.so.1
# Un-pinned versions of maskcam requirements (comment pip3 install above before this)
# RUN pip3 install -r requirements.in -c docker/constraints.docker
RUN chmod +x docker/start.sh
RUN chmod +x maskcam_run.py
CMD ["docker/start.sh"]
================================================
FILE: LICENSE.md
================================================
MIT License
Copyright (c) 2020, 2021 Berkeley Design Technology, Inc.. All rights reserved.
Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the “Software”), to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED “AS IS”, WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
================================================
FILE: README.md
================================================
# MaskCam <!-- omit in toc -->
<p align="center">
<img src="/docs/imgs/MaskCam-Demo1.gif">
</p>
MaskCam is a prototype reference design for a Jetson Nano-based smart camera system that measures crowd face mask usage in real-time, with all AI computation performed at the edge. MaskCam detects and tracks people in its field of view and determines whether they are wearing a mask via an object detection, tracking, and voting algorithm. It uploads statistics (not videos) to the cloud, where a web GUI can be used to monitor face mask compliance in the field of view. It saves interesting video snippets to local disk (e.g., a sudden influx of lots of people not wearing masks) and can optionally stream video via RTSP.
MaskCam can be run on a Jetson Nano Developer Kit, or on a Jetson Nano module (SOM) with the ConnectTech Photon carrier board. It was designed to use the Raspberry Pi High Quality Camera but will also work with pretty much any USB webcam that is supported on Linux.
The on-device software stack is mostly written in Python and runs under JetPack 4.4.1 or 4.5. Edge AI processing is handled by NVIDIA’s DeepStream video analytics framework, YOLOv4-tiny, and Tryolabs' [Norfair](https://github.com/tryolabs/norfair) tracker. MaskCam reports statistics to and receives commands from the cloud using MQTT and a web-based GUI. The software is containerized and for evaluation can be easily installed on a Jetson Nano DevKit using docker with just a couple of commands. For production, MaskCam can run under balenaOS, which makes it easy to manage and deploy multiple devices.
We urge you to try it out! It’s easy to install on a Jetson Nano Developer Kit and requires only a web cam. (The cloud-based statistics server and web GUI are optional, but are also dockerized and easy to install on any reasonable Linux system.) [See below for installation instructions.](#running-maskcam-from-a-container-on-a-jetson-nano-developer-kit)
MaskCam was developed by Berkeley Design Technology, Inc. (BDTI) and Tryolabs S.A., with development funded by NVIDIA. MaskCam is offered under the MIT License. For more information about MaskCam, please see the [report from BDTI](https://www.bdti.com/maskcam). If you have questions, please email us at maskcam@bdti.com. Thanks!
## Table of contents <!-- omit in toc -->
- [Start Here!](#start-here)
- [Running MaskCam from a Container on a Jetson Nano Developer Kit](#running-maskcam-from-a-container-on-a-jetson-nano-developer-kit)
- [Viewing the Live Video Stream](#viewing-the-live-video-stream)
- [Setting Device Configuration Parameters](#setting-device-configuration-parameters)
- [MQTT Server Setup](#mqtt-and-web-server-setup)
- [Running the MQTT Broker and Web Server](#running-the-mqtt-broker-and-web-server)
- [Setup a Device with Your Server](#setup-a-device-with-your-server)
- [Checking MQTT Connection](#checking-mqtt-connection)
- [Working With the MaskCam Container](#working-with-the-maskcam-container)
- [Development Mode: Manually Running MaskCam](#development-mode-manually-running-maskcam)
- [Debugging: Running MaskCam Modules as Standalone Processes](#debugging-running-maskcam-modules-as-standalone-processes)
- [Additional Information](#additional-information)
- [Running on Jetson Nano Developer Kit Using BalenaOS](#running-on-jetson-nano-developer-kit-using-balenaos)
- [Custom Container Development](#custom-container-development)
- [Building From Source on Jetson Nano Developer Kit](#building-from-source-on-jetson-nano-developer-kit)
- [Using Your Own Detection Model](#using-your-own-detection-model)
- [Installing MaskCam Manually (Without a Container)](#installing-maskcam-manually-without-a-container)
- [Running on Jetson Nano with Photon Carrier Board](#running-on-jetson-nano-with-photon-carrier-board)
- [Useful Development Scripts](#useful-development-scripts)
- [Troubleshooting Common Errors](#troubleshooting-common-errors)
## Start Here!
### Running MaskCam from a Container on a Jetson Nano Developer Kit
The easiest and fastest way to get MaskCam running on your Jetson Nano Dev Kit is using our pre-built containers. You will need:
1. A Jetson Nano Dev Kit running JetPack 4.4.1 or 4.5
2. An external DC 5 volt, 4 amp power supply connected through the Dev Kit's barrel jack connector (J25). (See [these instructions](https://www.jetsonhacks.com/2019/04/10/jetson-nano-use-more-power/) on how to enable barrel jack power.) This software makes full use of the GPU, so it will not run with USB power.
3. A USB webcam attached to your Nano
4. Another computer with a program that can display RTSP streams -- we suggest [VLC](https://www.videolan.org/vlc/index.html) or [QuickTime](https://www.apple.com/quicktime/download/).
First, the MaskCam container needs to be downloaded from Docker Hub. On your Nano, run:
```
# This will take 10 minutes or more to download
sudo docker pull maskcam/maskcam-beta
```
Find your local Jetson Nano IP address using `ifconfig`. This address will be used later to view a live video stream from the camera and to interact with the Nano from a web server.
Make sure a USB camera is connected to the Nano, and then start MaskCam by running the following command. Make sure to substitute `<your-jetson-ip>` with your Nano's IP address.
```
# Connect USB camera before running this!
sudo docker run --runtime nvidia --privileged --rm -it --env MASKCAM_DEVICE_ADDRESS=<your-jetson-ip> -p 1883:1883 -p 8080:8080 -p 8554:8554 maskcam/maskcam-beta
```
The MaskCam container should start running the `maskcam_run.py` script, using the USB camera as the default input device (`/dev/video0`). It will produce various status output messages (and error messages, if it encounters problems). If there are errors, the process will automatically end after several seconds. Check the [Troubleshooting](#troubleshooting-common-errors) section for tips on resolving errors.
Otherwise, after 30 seconds or so, it should continually generate status messages (such as `Processed 100 frames...`). Leave it running (don't press `Ctrl+C`, but be aware that the device will start heating up) and continue to the next section to visualize the video!
### Viewing the Live Video Stream
If you scroll through the logs and don't see any errors, you should find a message like:
```Streaming at rtsp://aaa.bbb.ccc.ddd:8554/maskcam```
where `aaa.bbb.ccc.ddd` is the address that you provided in `MASKCAM_DEVICE_ADDRESS` previously. If you didn't provide an address, you'll see some unknown address label there, but the streaming will still work.
You can copy-paste that URL into your RSTP streaming viewer ([see how](https://user-images.githubusercontent.com/12506292/111346333-e14d8800-865c-11eb-9242-0ffa4f50547f.mp4) to do it with VLC) on another computer. If all goes well, you should be rewarded with streaming video of your Nano, with green boxes around faces wearing masks and red boxes around faces not wearing masks. An example video of the live streaming in action is shown below.
<p align="center">
<img src="/docs/imgs/MaskCam-Live1.gif">
</p>
This video stream gives a general demonstration of how MaskCam works. However, MaskCam also has other features, such as the ability to send mask detection statistics to the cloud and view them through a web browser. If you'd like to see these features in action, you'll need to set up an MQTT server, which is covered in the [MQTT Server Setup section](#mqtt-and-web-server-setup).
If you encounter any errors running the live stream, check the [Troubleshooting](#troubleshooting-common-errors) section for tips on resolving errors.
### Setting Device Configuration Parameters
MaskCam uses environment variables to configure parameters without having to rebuild the container or manually change the configuration file each time the program is run. For example, in the previous section we set the `MASKCAM_DEVICE_ADDRESS` variable to indicate our Nano's IP address. A list of configurable parameters is shown in [maskcam_config.txt](maskcam_config.txt). The mapping between environment variable names and configuration parameters is defined in [maskcam/config.py](maskcam/config.py).
This section shows how to set environment variables to change configuration parameters. For example, if you want to use the `/dev/video1` camera device rather than `/dev/video0`, you can define `MASKCAM_INPUT` when running the container:
```
# Run with MASKCAM_INPUT and MASKCAM_DEVICE_ADDRESS
sudo docker run --runtime nvidia --privileged --rm -it --env MASKCAM_INPUT=v4l2:///dev/video1 --env MASKCAM_DEVICE_ADDRESS=<your-jetson-ip> -p 1883:1883 -p 8080:8080 -p 8554:8554 maskcam/maskcam-beta
```
Another useful input device that you might want to use is a CSI camera (like the Raspberry Pi camera), and in that case you need to set `MASKCAM_INPUT=argus://0` instead of the value shown above.
As another example, if you have an already set up our MQTT and web server (as shown in [MQTT Server Setup section](#mqtt-and-web-server-setup)), you need to define
two addtional environment variables, `MQTT_BROKER_IP` and `MQTT_DEVICE_NAME`. This allows your device to find the MQTT server and identify itself:
```
# Run with MQTT_BROKER_IP, MQTT_DEVICE_NAME, and MASKCAM_DEVICE_ADDRESS
sudo docker run --runtime nvidia --privileged --rm -it --env MQTT_BROKER_IP=<server IP> --env MQTT_DEVICE_NAME=<a-unique-string-you-like> --env MASKCAM_DEVICE_ADDRESS=<your-jetson-ip> -p 1883:1883 -p 8080:8080 -p 8554:8554 maskcam/maskcam-beta
```
*If you have too many `--env` variables to add, it might be easier to create a [.env file](https://docs.docker.com/compose/env-file/) and point to it using the `--env-file` flag instead.*
## MQTT and Web Server Setup
### Running the MQTT Broker and Web Server
MaskCam is intended to be set up with a web server that stores mask detection statistics and allows users to remotely interact with the device. We wrote code for instantiating a [server](server/) that receives statistics from the device, stores them in a database, and has a web-based GUI frontend to display them. A screenshot of the frontend for an example device is shown below.
<p align="center">
<img src="/docs/imgs/maskcam-frontend.PNG">
</p>
You can test out and explore this functionality by starting the server on a PC on your local network and pointing your Jetson Nano MaskCam device to it. This section gives instructions on how to do so. The MQTT broker and web server can be built and run on a Linux or OSX machine; we've tested it on Ubuntu 18.04LTS and OSX Big Sur. It can also be set up in an online AWS EC2 instance if you want to access it from outside of your local network.
The server consists of several docker containers that run together using [docker-compose](https://docs.docker.com/compose/install/). Install docker-compose on your machine by following the [installation instructions for your platform](https://docs.docker.com/compose/install/) before continuing. All other necessary packages and libraries will be automatically installed when you set up the containers in the next steps.
After installing docker-compose, clone this repo:
```
git clone https://github.com/bdtinc/maskcam.git
```
Go to the `server/` folder, which has all the needed components implemented on four containers: the Mosquitto broker, backend API, database, and Streamlit frontend.
These containers are configured using environment variables, so create the `.env` files by copying the default templates:
```
cd server
cp database.env.template database.env
cp frontend.env.template frontend.env
cp backend.env.template backend.env
```
The only file that needs to be changed is `database.env`. Open it with a text editor and replace the `<DATABASE_USER>`, `<DATABASE_PASSWORD>`, and `<DATABASE_NAME>` fields with your own values. Here are some example values, but you better be more creative for security reasons:
```
POSTGRES_USER=postgres
POSTGRES_PASSWORD=some_password
POSTGRES_DB=maskcam
```
*NOTE:* If you want to change any of the `database.env` values after building the containers, the easiest thing to do is to delete the `pgdata` volume by running `docker volume rm pgdata`. It will also delete all stored database information and statistics.
After editing the database environment file, you're ready to build all the containers and run them with a single command:
```
sudo docker-compose up -d
```
Wait a couple minutes after issuing the command to make sure that all containers are built and running. Then, check the local IP of your computer by running the `ifconfig` command. (It should be an address that starts with `192.168...`, `10...` or `172...`.) This is the server IP that will be used for connecting to the server (since the server is hosted on this computer).
Next, open a web browser and enter the server IP to visit the frontend webpage:
```
http://<server IP>:8501/
```
If you see a `ConnectionError` in the frontend, wait a couple more seconds and reload the page. The backend container can take some time to finish the database setup.
*NOTE:* If you're setting the server up on a remote instance like an AWS EC2, make sure you have ports `1883` (MQTT) and `8501` (web frontend) open for inbound and outbound traffic.
### Setup a Device With Your Server
Once you've got the server set up on a local machine (or in a AWS EC2 instance with a public IP), switch back to the Jetson Nano device. Run the MaskCam container using the following command, where `MQTT_BROKER_IP` is set to the IP of your server. (If you're using an AWS EC2 server, make sure to configure port `1883` for inbound and outbound traffic before running this command.)
```
# Run with MQTT_BROKER_IP, MQTT_DEVICE_NAME, and MASKCAM_DEVICE_ADDRESS
sudo docker run --runtime nvidia --privileged --rm -it --env MQTT_BROKER_IP=<server IP> --env MQTT_DEVICE_NAME=my-jetson-1 --env MASKCAM_DEVICE_ADDRESS=<your-jetson-ip> -p 1883:1883 -p 8080:8080 -p 8554:8554 maskcam/maskcam-beta
```
And that's it. If the device has access to the server's IP, then you should see in the output logs some successful connection messages and then see your device listed in the drop-down menu of the frontend (reload the page if you don't see it). In the frontend, select `Group data by: Second` and hit `Refresh status` to see how the plot changes when new data arrives.
Check the next section if the MQTT connection is not established from the device to the server.
### Checking MQTT Connection
If you're running the MQTT broker on a machine in your local network, make sure its IP is accessible from the Jetson device:
```
ping <local server IP>
```
*NOTE:* Remember to use the network address of the computer you set up the server on, which you can check using the `ifconfig` command and looking for an address that should start with `192.168...`, `10...` or `172...`
If you're setting up a remote server and using its public IP to connect
from your device, chances are you're not setting properly the port `1883` to be opened for inbound and outbound traffic.
If you want to check the port is correctly configured, use `nc` from a local machine or your jetson:
```
nc -vz <server IP> 1883
```
Remember you also need to open port `8501` to access the web server frontend from a web browser, as explained in the [server configuration section](#running-the-mqtt-broker-and-web-server) (but that's not relevant for the MQTT communication with the device).
## Working With the MaskCam Container
### Development Mode: Manually Running MaskCam
If you want to play around with the code, you probably don't want the container to automatically start running the `maskcam_run.py` script.
The easiest way to achieve that, is by defining the environment variable `DEV_MODE=1`:
```
docker run --runtime nvidia --privileged --rm -it --env DEV_MODE=1 -p 1883:1883 -p 8080:8080 -p 8554:8554 maskcam/maskcam-beta
```
This will cause the container to start a `/bin/bash` prompt (see [docker/start.sh](docker/start.sh) for details), from which you could run the script manually, or any
of its sub-modules as standalone processes:
```
# e.g: Run with a different input instead of default `/dev/video0`
./maskcam_run.py v4l2:///dev/video1
# e.g: Disable tracker to visualize raw detections and scores
MASKCAM_DISABLE_TRACKER=1 ./maskcam_run.py
```
### Debugging: Running MaskCam Modules as Standalone Processes
The script `maskcam_run.py`, which is the main entrypoint for the MaskCam software, has two roles:
- Handles all the MQTT communication (send stats and receive commands)
- Orchestrates all other processes that live under `maskcam/maskcam_*.py`.
But you can actually run any of those modules as standalone processes, which can be easier for debugging.
You need to set `DEV_MODE=1` as explained in the previous section to access the container prompt, and then you can run the python modules:
```
# e.g: Run only the static file server process
python3 -m maskcam.maskcam_fileserver
# e.g: Serve another directory to test
python3 -m maskcam.maskcam_fileserver /tmp
# e.g: Run only the inference and streaming processes
python3 -m maskcam.maskcam_streaming &
# Hit enter until you get a prompt and then:
python3 -m maskcam.maskcam_inference
```
**Note:** In the last example, `maskcam_streaming` is running on background,
so it will not terminate if you press `Ctrl+C` (only `maskcam_inference` will,
since it's running on the foreground).
To check that the streaming is still running and then bring it to foreground to terminate it, run:
```
jobs
fg %1
# Now you can hit Ctrl+C to terminate streaming
```
## Additional Information
Further information about working with and customizing MaskCam is provided on separate pages in the [docs](docs) folder. This section gives a brief description and link to each page.
### Running on Jetson Nano Developer Kit Using BalenaOS
[BalenaOS](https://www.balena.io/os/) is a lightweight operating system designed for running containers on embedded devices. It provides several advantages for fleet deployment and management, especially when combined with balena's balenaCloud mangament system. If you'd like to try running MaskCam with balenaOS instead of JetPack OS on your Jetson Nano, please follow the instructions at [BalenaOS-DevKit-Nano-Setup.md](docs/BalenaOS-DevKit-Nano-Setup.md).
### Custom Container Development
MaskCam is intended to be a reference design for any connected smart camera application. You can create your own application by starting from our pre-built container, modifying it to add the code files and packages needed for your program, and then re-building the container. The [Custom-Container-Development.md](docs/Custom-Container-Development.md) gives instructions on how to build your own container based off MaskCam.
#### Building From Source on Jetson Nano Developer Kit
Please see [How to Build your Own Container from Source on the Jetson Nano](https://github.com/bdtinc/maskcam/blob/main/docs/Custom-Container-Development.md#how-to-build-your-own-container-from-source-on-the-jetson-nano) for instructions on how to build a custom MaskCam container on your Jetson Nano Developer Kit.
#### Using Your Own Detection Model
Please see [How to Use Your Own Detection Model](https://github.com/bdtinc/maskcam/blob/main/docs/Custom-Container-Development.md#how-to-use-your-own-detection-model) for instructions on how to use your own detection model rather than our mask detection model.
### Installing MaskCam Manually (Without a Container)
MaskCam can also be installed manually, rather than by downloading our pre-built container. Using a manual installation of MaskCam can help with development if you'd prefer not to work with containers. If you'd like to install MaskCam without using containers, please see [docs/Manual-Dependencies-Installation.md](docs/Manual-Dependencies-Installation.md).
### Running on Jetson Nano with Photon Carrier Board
For our hardware prototype of MaskCam, we used a Jetson Nano module and a [Connect Tech Photon carrier board](https://connecttech.com/product/photon-jetson-nano-ai-camera-platform/), rather than the Jetson Nano Developer Kit. We used the Photon because the Developer Kit is not sold or warrantied for production use. Using the Photon allowed us to quickly create a production-ready prototype using off-the-shelf hardware. If you have a Photon carrier board and Jetson Nano module, you can install MaskCam on them by using the setup instructions at [docs/Photon-Nano-Setup.md](docs/Photon-Nano-Setup.md).
### Useful Development Scripts
During development, some scripts were produced which might be useful for other developers to debug or update the software. These include an MQTT sniffer, a script to run the TensorRT model on images, and to convert a model trained with the original YOLO Darknet implementation to TensorRT format. Basic usage for all these tools is covered on [docs/Useful-Development-Scripts.md](docs/Useful-Development-Scripts.md).
## Troubleshooting Common Errors
If you run into any errors or issues while working with MaskCam, this section gives common errors and their solutions.
MaskCam consists of many different processes running in parallel. As a consequence, when there's an error on a particular process, all of them will be sent termination signals and finish gracefully. This means that you need to scroll up through the output to find out the original error that caused a failure. It should be very notorious, flagged as a red **ERROR** log entry, followed by the name of the process that failed and a message.
#### Error: camera not connected/not recognized
If you see an error containing the message `Cannot identify device '/dev/video0'`, among other Gst and v4l messages, it means the program couldn't find the camera device. Make sure your camera is connected to the Nano and recognized by the host Ubuntu OS by issuing `ls /dev` and checking if `/dev/video0` is present in the output.
#### Error: not running in privileged mode
In this case, you'll see a bunch of annoying messages like:
```
Error: Can't initialize nvrm channel
Couldn't create ddkvic Session: Cannot allocate memory
nvbuf_utils: Could not create Default NvBufferSession
```
You'll probably see multiple failures in other MaskCam processes as well. To resolve these errors, make sure you're running docker with the `--privileged` flag, as described in the [first section](#running-maskcam-from-a-container-on-a-jetson-nano-developer-kit).
#### Error: reason not negotiated/camera capabilities
If you get an error that looks like: `v4l-camera-source / reason not-negotiated`
Then the problem is that the USB camera you're using doesn't support the default `camera-framerate=30` (frames per second). If you don't have another camera, try running the script under utils/gst_capabilities.sh and find the lines with type `video/x-raw ...`
Find any suitable `framerate=X/1` (with `X` being an integer like 24, 15, etc.) and set the corresponding configuration parameter with `--env MASKCAM_CAMERA_FRAMERATE=X` (see [previous section](#setting-device-configuration-parameters)).
#### Error: Streaming or file server are not accessible (nothing else seems to fail)
Make sure you're mapping the right ports from the container, with the `-p container_port:host_port` parameters indicated in the previous sections. The default port numbers, that should be exposed by the container, are configured in [maskcam_config.txt](maskcam_config.txt) as:
```
fileserver-port=8080
streaming-port=8554
mqtt-broker-port=1883
```
These port mappings are why we use `docker run ... -p 1883:1883 -p 8080:8080 -p 8554:8554 ...` with the run command. Remember that all the ports can be overriden using environment variables, as described in the [previous section](#setting-device-configuration-parameters). Other ports like `udp-port-*` are not intended to be accessible from outside the container, they are used for communication between the inference process and the streaming and file-saving processes.
#### Other Errors
Sometimes after restarting the process or the whole docker container many times, some GPU resources can get stuck and cause unexpected errors. If that's the case, try rebooting the device and running the container again. If you find that the container fails systematically after running some sequence, please don't hesitate to [report an Issue](https://github.com/bdtinc/maskcam/issues) with the relevant context and we'll try to reproduce and fix it.
## Questions? Need Help?
Email us at maskcam@bdti.com, and be sure to check out our [independent report on the development of MaskCam](https://bdti.com/maskcam)!
================================================
FILE: deepstream_plugin_yolov4/Makefile
================================================
################################################################################
# Copyright (c) 2019, NVIDIA CORPORATION. All rights reserved.
#
# Permission is hereby granted, free of charge, to any person obtaining a
# copy of this software and associated documentation files (the "Software"),
# to deal in the Software without restriction, including without limitation
# the rights to use, copy, modify, merge, publish, distribute, sublicense,
# and/or sell copies of the Software, and to permit persons to whom the
# Software is furnished to do so, subject to the following conditions:
#
# The above copyright notice and this permission notice shall be included in
# all copies or substantial portions of the Software.
#
# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL
# THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
# FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
# DEALINGS IN THE SOFTWARE.
################################################################################
CUDA_VER?=
ifeq ($(CUDA_VER),)
$(error "CUDA_VER is not set")
endif
CC:= g++
NVCC:=/usr/local/cuda-$(CUDA_VER)/bin/nvcc
CFLAGS:= -Wall -std=c++11 -shared -fPIC -Wno-error=deprecated-declarations
CFLAGS+= -I../../includes -I/usr/local/cuda-$(CUDA_VER)/include -I/opt/nvidia/deepstream/deepstream-5.0/sources/includes
LIBS:= -lnvinfer_plugin -lnvinfer -lnvparsers -L/usr/local/cuda-$(CUDA_VER)/lib64 -lcudart -lcublas -lstdc++fs -L/opt/nvidia/deepstream/deepstream-5.0/lib
LFLAGS:= -shared -Wl,--start-group $(LIBS) -Wl,--end-group
INCS:= $(wildcard *.h)
SRCFILES:= nvdsinfer_yolo_engine.cpp \
nvdsparsebbox_Yolo.cpp \
yoloPlugins.cpp \
trt_utils.cpp \
yolo.cpp \
kernels.cu
TARGET_LIB:= libnvdsinfer_custom_impl_Yolo.so
TARGET_OBJS:= $(SRCFILES:.cpp=.o)
TARGET_OBJS:= $(TARGET_OBJS:.cu=.o)
all: $(TARGET_LIB)
%.o: %.cpp $(INCS) Makefile
$(CC) -c -o $@ $(CFLAGS) $<
%.o: %.cu $(INCS) Makefile
$(NVCC) -c -o $@ --compiler-options '-fPIC' $<
$(TARGET_LIB) : $(TARGET_OBJS)
$(CC) -o $@ $(TARGET_OBJS) $(LFLAGS)
clean:
rm -rf $(TARGET_LIB)
================================================
FILE: deepstream_plugin_yolov4/README.md
================================================
## YOLOv4 plugin for DeepStream
This plugin was obtained from: https://github.com/Tianxiaomo/pytorch-YOLOv4/tree/master/DeepStream
It must be compiled locally on the jetson device:
```
export CUDA_VER=10.2
make
```
================================================
FILE: deepstream_plugin_yolov4/kernels.cu
================================================
/*
* Copyright (c) 2018-2019 NVIDIA Corporation. All rights reserved.
*
* NVIDIA Corporation and its licensors retain all intellectual property
* and proprietary rights in and to this software, related documentation
* and any modifications thereto. Any use, reproduction, disclosure or
* distribution of this software and related documentation without an express
* license agreement from NVIDIA Corporation is strictly prohibited.
*
*/
#include <cuda.h>
#include <cuda_runtime.h>
#include <stdint.h>
#include <stdio.h>
#include <string.h>
inline __device__ float sigmoidGPU(const float& x) { return 1.0f / (1.0f + __expf(-x)); }
__global__ void gpuYoloLayerV3(const float* input, float* output, const uint gridSize, const uint numOutputClasses,
const uint numBBoxes)
{
uint x_id = blockIdx.x * blockDim.x + threadIdx.x;
uint y_id = blockIdx.y * blockDim.y + threadIdx.y;
uint z_id = blockIdx.z * blockDim.z + threadIdx.z;
if ((x_id >= gridSize) || (y_id >= gridSize) || (z_id >= numBBoxes))
{
return;
}
const int numGridCells = gridSize * gridSize;
const int bbindex = y_id * gridSize + x_id;
output[bbindex + numGridCells * (z_id * (5 + numOutputClasses) + 0)]
= sigmoidGPU(input[bbindex + numGridCells * (z_id * (5 + numOutputClasses) + 0)]);
output[bbindex + numGridCells * (z_id * (5 + numOutputClasses) + 1)]
= sigmoidGPU(input[bbindex + numGridCells * (z_id * (5 + numOutputClasses) + 1)]);
output[bbindex + numGridCells * (z_id * (5 + numOutputClasses) + 2)]
= __expf(input[bbindex + numGridCells * (z_id * (5 + numOutputClasses) + 2)]);
output[bbindex + numGridCells * (z_id * (5 + numOutputClasses) + 3)]
= __expf(input[bbindex + numGridCells * (z_id * (5 + numOutputClasses) + 3)]);
output[bbindex + numGridCells * (z_id * (5 + numOutputClasses) + 4)]
= sigmoidGPU(input[bbindex + numGridCells * (z_id * (5 + numOutputClasses) + 4)]);
for (uint i = 0; i < numOutputClasses; ++i)
{
output[bbindex + numGridCells * (z_id * (5 + numOutputClasses) + (5 + i))]
= sigmoidGPU(input[bbindex + numGridCells * (z_id * (5 + numOutputClasses) + (5 + i))]);
}
}
cudaError_t cudaYoloLayerV3(const void* input, void* output, const uint& batchSize, const uint& gridSize,
const uint& numOutputClasses, const uint& numBBoxes,
uint64_t outputSize, cudaStream_t stream);
cudaError_t cudaYoloLayerV3(const void* input, void* output, const uint& batchSize, const uint& gridSize,
const uint& numOutputClasses, const uint& numBBoxes,
uint64_t outputSize, cudaStream_t stream)
{
dim3 threads_per_block(16, 16, 4);
dim3 number_of_blocks((gridSize / threads_per_block.x) + 1,
(gridSize / threads_per_block.y) + 1,
(numBBoxes / threads_per_block.z) + 1);
for (unsigned int batch = 0; batch < batchSize; ++batch)
{
gpuYoloLayerV3<<<number_of_blocks, threads_per_block, 0, stream>>>(
reinterpret_cast<const float*>(input) + (batch * outputSize),
reinterpret_cast<float*>(output) + (batch * outputSize), gridSize, numOutputClasses,
numBBoxes);
}
return cudaGetLastError();
}
================================================
FILE: deepstream_plugin_yolov4/nvdsinfer_yolo_engine.cpp
================================================
/*
* Copyright (c) 2019-2020, NVIDIA CORPORATION. All rights reserved.
*
* Permission is hereby granted, free of charge, to any person obtaining a
* copy of this software and associated documentation files (the "Software"),
* to deal in the Software without restriction, including without limitation
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
* and/or sell copies of the Software, and to permit persons to whom the
* Software is furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL
* THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
* DEALINGS IN THE SOFTWARE.
*/
#include "nvdsinfer_custom_impl.h"
#include "nvdsinfer_context.h"
#include "yoloPlugins.h"
#include "yolo.h"
#include <algorithm>
#define USE_CUDA_ENGINE_GET_API 1
static bool getYoloNetworkInfo (NetworkInfo &networkInfo, const NvDsInferContextInitParams* initParams)
{
std::string yoloCfg = initParams->customNetworkConfigFilePath;
std::string yoloType;
std::transform (yoloCfg.begin(), yoloCfg.end(), yoloCfg.begin(), [] (uint8_t c) {
return std::tolower (c);});
if (yoloCfg.find("yolov2") != std::string::npos) {
if (yoloCfg.find("yolov2-tiny") != std::string::npos)
yoloType = "yolov2-tiny";
else
yoloType = "yolov2";
} else if (yoloCfg.find("yolov3") != std::string::npos) {
if (yoloCfg.find("yolov3-tiny") != std::string::npos)
yoloType = "yolov3-tiny";
else
yoloType = "yolov3";
} else {
std::cerr << "Yolo type is not defined from config file name:"
<< yoloCfg << std::endl;
return false;
}
networkInfo.networkType = yoloType;
networkInfo.configFilePath = initParams->customNetworkConfigFilePath;
networkInfo.wtsFilePath = initParams->modelFilePath;
networkInfo.deviceType = (initParams->useDLA ? "kDLA" : "kGPU");
networkInfo.inputBlobName = "data";
if (networkInfo.configFilePath.empty() ||
networkInfo.wtsFilePath.empty()) {
std::cerr << "Yolo config file or weights file is NOT specified."
<< std::endl;
return false;
}
if (!fileExists(networkInfo.configFilePath) ||
!fileExists(networkInfo.wtsFilePath)) {
std::cerr << "Yolo config file or weights file is NOT exist."
<< std::endl;
return false;
}
return true;
}
#if !USE_CUDA_ENGINE_GET_API
IModelParser* NvDsInferCreateModelParser(
const NvDsInferContextInitParams* initParams) {
NetworkInfo networkInfo;
if (!getYoloNetworkInfo(networkInfo, initParams)) {
return nullptr;
}
return new Yolo(networkInfo);
}
#else
extern "C"
bool NvDsInferYoloCudaEngineGet(nvinfer1::IBuilder * const builder,
const NvDsInferContextInitParams * const initParams,
nvinfer1::DataType dataType,
nvinfer1::ICudaEngine *& cudaEngine);
extern "C"
bool NvDsInferYoloCudaEngineGet(nvinfer1::IBuilder * const builder,
const NvDsInferContextInitParams * const initParams,
nvinfer1::DataType dataType,
nvinfer1::ICudaEngine *& cudaEngine)
{
NetworkInfo networkInfo;
if (!getYoloNetworkInfo(networkInfo, initParams)) {
return false;
}
Yolo yolo(networkInfo);
cudaEngine = yolo.createEngine (builder);
if (cudaEngine == nullptr)
{
std::cerr << "Failed to build cuda engine on "
<< networkInfo.configFilePath << std::endl;
return false;
}
return true;
}
#endif
================================================
FILE: deepstream_plugin_yolov4/nvdsparsebbox_Yolo.cpp
================================================
/*
* Copyright (c) 2019, NVIDIA CORPORATION. All rights reserved.
*
* Permission is hereby granted, free of charge, to any person obtaining a
* copy of this software and associated documentation files (the "Software"),
* to deal in the Software without restriction, including without limitation
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
* and/or sell copies of the Software, and to permit persons to whom the
* Software is furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL
* THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
* DEALINGS IN THE SOFTWARE.
*/
#include <algorithm>
#include <cassert>
#include <cmath>
#include <cstring>
#include <fstream>
#include <iostream>
#include <unordered_map>
#include "nvdsinfer_custom_impl.h"
#include "trt_utils.h"
static const int NUM_CLASSES_YOLO = 4; // This is just for checkings, keep updated by hand
extern "C" bool NvDsInferParseCustomYoloV3(
std::vector<NvDsInferLayerInfo> const &outputLayersInfo,
NvDsInferNetworkInfo const &networkInfo,
NvDsInferParseDetectionParams const &detectionParams,
std::vector<NvDsInferParseObjectInfo> &objectList);
extern "C" bool NvDsInferParseCustomYoloV3Tiny(
std::vector<NvDsInferLayerInfo> const &outputLayersInfo,
NvDsInferNetworkInfo const &networkInfo,
NvDsInferParseDetectionParams const &detectionParams,
std::vector<NvDsInferParseObjectInfo> &objectList);
extern "C" bool NvDsInferParseCustomYoloV2(
std::vector<NvDsInferLayerInfo> const &outputLayersInfo,
NvDsInferNetworkInfo const &networkInfo,
NvDsInferParseDetectionParams const &detectionParams,
std::vector<NvDsInferParseObjectInfo> &objectList);
extern "C" bool NvDsInferParseCustomYoloV2Tiny(
std::vector<NvDsInferLayerInfo> const &outputLayersInfo,
NvDsInferNetworkInfo const &networkInfo,
NvDsInferParseDetectionParams const &detectionParams,
std::vector<NvDsInferParseObjectInfo> &objectList);
extern "C" bool NvDsInferParseCustomYoloTLT(
std::vector<NvDsInferLayerInfo> const &outputLayersInfo,
NvDsInferNetworkInfo const &networkInfo,
NvDsInferParseDetectionParams const &detectionParams,
std::vector<NvDsInferParseObjectInfo> &objectList);
extern "C" bool NvDsInferParseCustomYoloV4(
std::vector<NvDsInferLayerInfo> const &outputLayersInfo,
NvDsInferNetworkInfo const &networkInfo,
NvDsInferParseDetectionParams const &detectionParams,
std::vector<NvDsInferParseObjectInfo> &objectList);
/* This is a sample bounding box parsing function for the sample YoloV3 detector model */
static NvDsInferParseObjectInfo convertBBox(const float &bx, const float &by, const float &bw,
const float &bh, const int &stride, const uint &netW,
const uint &netH)
{
NvDsInferParseObjectInfo b;
// Restore coordinates to network input resolution
float xCenter = bx * stride;
float yCenter = by * stride;
float x0 = xCenter - bw / 2;
float y0 = yCenter - bh / 2;
float x1 = x0 + bw;
float y1 = y0 + bh;
x0 = clamp(x0, 0, netW);
y0 = clamp(y0, 0, netH);
x1 = clamp(x1, 0, netW);
y1 = clamp(y1, 0, netH);
b.left = x0;
b.width = clamp(x1 - x0, 0, netW);
b.top = y0;
b.height = clamp(y1 - y0, 0, netH);
return b;
}
static void addBBoxProposal(const float bx, const float by, const float bw, const float bh,
const uint stride, const uint &netW, const uint &netH, const int maxIndex,
const float maxProb, std::vector<NvDsInferParseObjectInfo> &binfo)
{
NvDsInferParseObjectInfo bbi = convertBBox(bx, by, bw, bh, stride, netW, netH);
if (bbi.width < 1 || bbi.height < 1)
return;
bbi.detectionConfidence = maxProb;
bbi.classId = maxIndex;
binfo.push_back(bbi);
}
static std::vector<NvDsInferParseObjectInfo>
decodeYoloV2Tensor(
const float *detections, const std::vector<float> &anchors,
const uint gridSizeW, const uint gridSizeH, const uint stride, const uint numBBoxes,
const uint numOutputClasses, const uint &netW,
const uint &netH)
{
std::vector<NvDsInferParseObjectInfo> binfo;
for (uint y = 0; y < gridSizeH; ++y)
{
for (uint x = 0; x < gridSizeW; ++x)
{
for (uint b = 0; b < numBBoxes; ++b)
{
const float pw = anchors[b * 2];
const float ph = anchors[b * 2 + 1];
const int numGridCells = gridSizeH * gridSizeW;
const int bbindex = y * gridSizeW + x;
const float bx = x + detections[bbindex + numGridCells * (b * (5 + numOutputClasses) + 0)];
const float by = y + detections[bbindex + numGridCells * (b * (5 + numOutputClasses) + 1)];
const float bw = pw * exp(detections[bbindex + numGridCells * (b * (5 + numOutputClasses) + 2)]);
const float bh = ph * exp(detections[bbindex + numGridCells * (b * (5 + numOutputClasses) + 3)]);
const float objectness = detections[bbindex + numGridCells * (b * (5 + numOutputClasses) + 4)];
float maxProb = 0.0f;
int maxIndex = -1;
for (uint i = 0; i < numOutputClasses; ++i)
{
float prob = (detections[bbindex + numGridCells * (b * (5 + numOutputClasses) + (5 + i))]);
if (prob > maxProb)
{
maxProb = prob;
maxIndex = i;
}
}
maxProb = objectness * maxProb;
addBBoxProposal(bx, by, bw, bh, stride, netW, netH, maxIndex, maxProb, binfo);
}
}
}
return binfo;
}
static std::vector<NvDsInferParseObjectInfo>
decodeYoloV3Tensor(
const float *detections, const std::vector<int> &mask, const std::vector<float> &anchors,
const uint gridSizeW, const uint gridSizeH, const uint stride, const uint numBBoxes,
const uint numOutputClasses, const uint &netW,
const uint &netH)
{
std::vector<NvDsInferParseObjectInfo> binfo;
for (uint y = 0; y < gridSizeH; ++y)
{
for (uint x = 0; x < gridSizeW; ++x)
{
for (uint b = 0; b < numBBoxes; ++b)
{
const float pw = anchors[mask[b] * 2];
const float ph = anchors[mask[b] * 2 + 1];
const int numGridCells = gridSizeH * gridSizeW;
const int bbindex = y * gridSizeW + x;
const float bx = x + detections[bbindex + numGridCells * (b * (5 + numOutputClasses) + 0)];
const float by = y + detections[bbindex + numGridCells * (b * (5 + numOutputClasses) + 1)];
const float bw = pw * detections[bbindex + numGridCells * (b * (5 + numOutputClasses) + 2)];
const float bh = ph * detections[bbindex + numGridCells * (b * (5 + numOutputClasses) + 3)];
const float objectness = detections[bbindex + numGridCells * (b * (5 + numOutputClasses) + 4)];
float maxProb = 0.0f;
int maxIndex = -1;
for (uint i = 0; i < numOutputClasses; ++i)
{
float prob = (detections[bbindex + numGridCells * (b * (5 + numOutputClasses) + (5 + i))]);
if (prob > maxProb)
{
maxProb = prob;
maxIndex = i;
}
}
maxProb = objectness * maxProb;
addBBoxProposal(bx, by, bw, bh, stride, netW, netH, maxIndex, maxProb, binfo);
}
}
}
return binfo;
}
static inline std::vector<const NvDsInferLayerInfo *>
SortLayers(const std::vector<NvDsInferLayerInfo> &outputLayersInfo)
{
std::vector<const NvDsInferLayerInfo *> outLayers;
for (auto const &layer : outputLayersInfo)
{
outLayers.push_back(&layer);
}
std::sort(outLayers.begin(), outLayers.end(),
[](const NvDsInferLayerInfo *a, const NvDsInferLayerInfo *b) {
return a->inferDims.d[1] < b->inferDims.d[1];
});
return outLayers;
}
static bool NvDsInferParseYoloV3(
std::vector<NvDsInferLayerInfo> const &outputLayersInfo,
NvDsInferNetworkInfo const &networkInfo,
NvDsInferParseDetectionParams const &detectionParams,
std::vector<NvDsInferParseObjectInfo> &objectList,
const std::vector<float> &anchors,
const std::vector<std::vector<int>> &masks)
{
const uint kNUM_BBOXES = 3;
const std::vector<const NvDsInferLayerInfo *> sortedLayers =
SortLayers(outputLayersInfo);
if (sortedLayers.size() != masks.size())
{
std::cerr << "ERROR: yoloV3 output layer.size: " << sortedLayers.size()
<< " does not match mask.size: " << masks.size() << std::endl;
return false;
}
if (NUM_CLASSES_YOLO != detectionParams.numClassesConfigured)
{
std::cerr << "WARNING: Num classes mismatch. Configured:"
<< detectionParams.numClassesConfigured
<< ", detected by network: " << NUM_CLASSES_YOLO << std::endl;
}
std::vector<NvDsInferParseObjectInfo> objects;
for (uint idx = 0; idx < masks.size(); ++idx)
{
const NvDsInferLayerInfo &layer = *sortedLayers[idx]; // 255 x Grid x Grid
assert(layer.inferDims.numDims == 3);
const uint gridSizeH = layer.inferDims.d[1];
const uint gridSizeW = layer.inferDims.d[2];
const uint stride = DIVUP(networkInfo.width, gridSizeW);
assert(stride == DIVUP(networkInfo.height, gridSizeH));
std::vector<NvDsInferParseObjectInfo> outObjs =
decodeYoloV3Tensor((const float *)(layer.buffer), masks[idx], anchors, gridSizeW, gridSizeH, stride, kNUM_BBOXES,
NUM_CLASSES_YOLO, networkInfo.width, networkInfo.height);
objects.insert(objects.end(), outObjs.begin(), outObjs.end());
}
objectList = objects;
return true;
}
static NvDsInferParseObjectInfo convertBBoxYoloV4(const float &bx1, const float &by1, const float &bx2,
const float &by2, const uint &netW, const uint &netH)
{
NvDsInferParseObjectInfo b;
// Restore coordinates to network input resolution
float x1 = bx1 * netW;
float y1 = by1 * netH;
float x2 = bx2 * netW;
float y2 = by2 * netH;
x1 = clamp(x1, 0, netW);
y1 = clamp(y1, 0, netH);
x2 = clamp(x2, 0, netW);
y2 = clamp(y2, 0, netH);
b.left = x1;
b.width = clamp(x2 - x1, 0, netW);
b.top = y1;
b.height = clamp(y2 - y1, 0, netH);
return b;
}
static void addBBoxProposalYoloV4(const float bx, const float by, const float bw, const float bh,
const uint &netW, const uint &netH, const int maxIndex,
const float maxProb, std::vector<NvDsInferParseObjectInfo> &binfo)
{
NvDsInferParseObjectInfo bbi = convertBBoxYoloV4(bx, by, bw, bh, netW, netH);
if (bbi.width < 1 || bbi.height < 1)
return;
bbi.detectionConfidence = maxProb;
bbi.classId = maxIndex;
binfo.push_back(bbi);
}
static std::vector<NvDsInferParseObjectInfo>
decodeYoloV4Tensor(
const float *boxes, const float *scores,
const uint num_bboxes, NvDsInferParseDetectionParams const &detectionParams,
const uint &netW, const uint &netH)
{
std::vector<NvDsInferParseObjectInfo> binfo;
uint bbox_location = 0;
uint score_location = 0;
for (uint b = 0; b < num_bboxes; ++b)
{
float bx1 = boxes[bbox_location];
float by1 = boxes[bbox_location + 1];
float bx2 = boxes[bbox_location + 2];
float by2 = boxes[bbox_location + 3];
float maxProb = 0.0f;
int maxIndex = -1;
for (uint c = 0; c < detectionParams.numClassesConfigured; ++c)
{
float prob = scores[score_location + c];
if (prob > maxProb)
{
maxProb = prob;
maxIndex = c;
}
}
if (maxProb > detectionParams.perClassPreclusterThreshold[maxIndex])
{
addBBoxProposalYoloV4(bx1, by1, bx2, by2, netW, netH, maxIndex, maxProb, binfo);
}
bbox_location += 4;
score_location += detectionParams.numClassesConfigured;
}
return binfo;
}
/* C-linkage to prevent name-mangling */
static bool NvDsInferParseYoloV4(
std::vector<NvDsInferLayerInfo> const &outputLayersInfo,
NvDsInferNetworkInfo const &networkInfo,
NvDsInferParseDetectionParams const &detectionParams,
std::vector<NvDsInferParseObjectInfo> &objectList)
{
if (NUM_CLASSES_YOLO != detectionParams.numClassesConfigured)
{
std::cerr << "WARNING: Num classes mismatch. Configured:"
<< detectionParams.numClassesConfigured
<< ", detected by network: " << NUM_CLASSES_YOLO << std::endl;
}
std::vector<NvDsInferParseObjectInfo> objects;
const NvDsInferLayerInfo &boxes = outputLayersInfo[0]; // num_boxes x 4
const NvDsInferLayerInfo &scores = outputLayersInfo[1]; // num_boxes x num_classes
const NvDsInferLayerInfo &subbox = outputLayersInfo[2];
//* printf("%d\n", subbox.inferDims.numDims);
// 3 dimensional: [num_boxes, 1, 4]
assert(boxes.inferDims.numDims == 3);
// 2 dimensional: [num_boxes, num_classes]
assert(scores.inferDims.numDims == 2);
// The second dimension should be num_classes
assert(detectionParams.numClassesConfigured == scores.inferDims.d[1]);
uint num_bboxes = boxes.inferDims.d[0];
// std::cout << "Network Info: " << networkInfo.height << " " << networkInfo.width << std::endl;
std::vector<NvDsInferParseObjectInfo> outObjs =
decodeYoloV4Tensor(
(const float *)(boxes.buffer), (const float *)(scores.buffer), num_bboxes, detectionParams,
networkInfo.width, networkInfo.height);
objects.insert(objects.end(), outObjs.begin(), outObjs.end());
objectList = objects;
return true;
}
extern "C" bool NvDsInferParseCustomYoloV4(
std::vector<NvDsInferLayerInfo> const &outputLayersInfo,
NvDsInferNetworkInfo const &networkInfo,
NvDsInferParseDetectionParams const &detectionParams,
std::vector<NvDsInferParseObjectInfo> &objectList)
{
return NvDsInferParseYoloV4(
outputLayersInfo, networkInfo, detectionParams, objectList);
}
extern "C" bool NvDsInferParseCustomYoloV3(
std::vector<NvDsInferLayerInfo> const &outputLayersInfo,
NvDsInferNetworkInfo const &networkInfo,
NvDsInferParseDetectionParams const &detectionParams,
std::vector<NvDsInferParseObjectInfo> &objectList)
{
static const std::vector<float> kANCHORS = {
10.0, 13.0, 16.0, 30.0, 33.0, 23.0, 30.0, 61.0, 62.0,
45.0, 59.0, 119.0, 116.0, 90.0, 156.0, 198.0, 373.0, 326.0};
static const std::vector<std::vector<int>> kMASKS = {
{6, 7, 8},
{3, 4, 5},
{0, 1, 2}};
return NvDsInferParseYoloV3(
outputLayersInfo, networkInfo, detectionParams, objectList,
kANCHORS, kMASKS);
}
extern "C" bool NvDsInferParseCustomYoloV3Tiny(
std::vector<NvDsInferLayerInfo> const &outputLayersInfo,
NvDsInferNetworkInfo const &networkInfo,
NvDsInferParseDetectionParams const &detectionParams,
std::vector<NvDsInferParseObjectInfo> &objectList)
{
static const std::vector<float> kANCHORS = {
10, 14, 23, 27, 37, 58, 81, 82, 135, 169, 344, 319};
static const std::vector<std::vector<int>> kMASKS = {
{3, 4, 5},
//{0, 1, 2}}; // as per output result, select {1,2,3}
{1, 2, 3}};
return NvDsInferParseYoloV3(
outputLayersInfo, networkInfo, detectionParams, objectList,
kANCHORS, kMASKS);
}
static bool NvDsInferParseYoloV2(
std::vector<NvDsInferLayerInfo> const &outputLayersInfo,
NvDsInferNetworkInfo const &networkInfo,
NvDsInferParseDetectionParams const &detectionParams,
std::vector<NvDsInferParseObjectInfo> &objectList)
{
// copy anchor data from yolov2.cfg file
std::vector<float> anchors = {0.57273, 0.677385, 1.87446, 2.06253, 3.33843,
5.47434, 7.88282, 3.52778, 9.77052, 9.16828};
const uint kNUM_BBOXES = 5;
if (outputLayersInfo.empty())
{
std::cerr << "Could not find output layer in bbox parsing" << std::endl;
;
return false;
}
const NvDsInferLayerInfo &layer = outputLayersInfo[0];
if (NUM_CLASSES_YOLO != detectionParams.numClassesConfigured)
{
std::cerr << "WARNING: Num classes mismatch. Configured:"
<< detectionParams.numClassesConfigured
<< ", detected by network: " << NUM_CLASSES_YOLO << std::endl;
}
assert(layer.inferDims.numDims == 3);
const uint gridSizeH = layer.inferDims.d[1];
const uint gridSizeW = layer.inferDims.d[2];
const uint stride = DIVUP(networkInfo.width, gridSizeW);
assert(stride == DIVUP(networkInfo.height, gridSizeH));
for (auto &anchor : anchors)
{
anchor *= stride;
}
std::vector<NvDsInferParseObjectInfo> objects =
decodeYoloV2Tensor((const float *)(layer.buffer), anchors, gridSizeW, gridSizeH, stride, kNUM_BBOXES,
NUM_CLASSES_YOLO, networkInfo.width, networkInfo.height);
objectList = objects;
return true;
}
extern "C" bool NvDsInferParseCustomYoloV2(
std::vector<NvDsInferLayerInfo> const &outputLayersInfo,
NvDsInferNetworkInfo const &networkInfo,
NvDsInferParseDetectionParams const &detectionParams,
std::vector<NvDsInferParseObjectInfo> &objectList)
{
return NvDsInferParseYoloV2(
outputLayersInfo, networkInfo, detectionParams, objectList);
}
extern "C" bool NvDsInferParseCustomYoloV2Tiny(
std::vector<NvDsInferLayerInfo> const &outputLayersInfo,
NvDsInferNetworkInfo const &networkInfo,
NvDsInferParseDetectionParams const &detectionParams,
std::vector<NvDsInferParseObjectInfo> &objectList)
{
return NvDsInferParseYoloV2(
outputLayersInfo, networkInfo, detectionParams, objectList);
}
extern "C" bool NvDsInferParseCustomYoloTLT(
std::vector<NvDsInferLayerInfo> const &outputLayersInfo,
NvDsInferNetworkInfo const &networkInfo,
NvDsInferParseDetectionParams const &detectionParams,
std::vector<NvDsInferParseObjectInfo> &objectList)
{
if (outputLayersInfo.size() != 4)
{
std::cerr << "Mismatch in the number of output buffers."
<< "Expected 4 output buffers, detected in the network :"
<< outputLayersInfo.size() << std::endl;
return false;
}
const int topK = 200;
const int *keepCount = static_cast<const int *>(outputLayersInfo.at(0).buffer);
const float *boxes = static_cast<const float *>(outputLayersInfo.at(1).buffer);
const float *scores = static_cast<const float *>(outputLayersInfo.at(2).buffer);
const float *cls = static_cast<const float *>(outputLayersInfo.at(3).buffer);
for (int i = 0; (i < keepCount[0]) && (objectList.size() <= topK); ++i)
{
const float *loc = &boxes[0] + (i * 4);
const float *conf = &scores[0] + i;
const float *cls_id = &cls[0] + i;
if (conf[0] > 1.001)
continue;
if ((loc[0] < 0) || (loc[1] < 0) || (loc[2] < 0) || (loc[3] < 0))
continue;
if ((loc[0] > networkInfo.width) || (loc[2] > networkInfo.width) || (loc[1] > networkInfo.height) || (loc[3] > networkInfo.width))
continue;
if ((loc[2] < loc[0]) || (loc[3] < loc[1]))
continue;
if (((loc[3] - loc[1]) > networkInfo.height) || ((loc[2] - loc[0]) > networkInfo.width))
continue;
NvDsInferParseObjectInfo curObj{static_cast<unsigned int>(cls_id[0]),
loc[0], loc[1], (loc[2] - loc[0]),
(loc[3] - loc[1]), conf[0]};
objectList.push_back(curObj);
}
return true;
}
/* Check that the custom function has been defined correctly */
CHECK_CUSTOM_PARSE_FUNC_PROTOTYPE(NvDsInferParseCustomYoloV4);
CHECK_CUSTOM_PARSE_FUNC_PROTOTYPE(NvDsInferParseCustomYoloV3);
CHECK_CUSTOM_PARSE_FUNC_PROTOTYPE(NvDsInferParseCustomYoloV3Tiny);
CHECK_CUSTOM_PARSE_FUNC_PROTOTYPE(NvDsInferParseCustomYoloV2);
CHECK_CUSTOM_PARSE_FUNC_PROTOTYPE(NvDsInferParseCustomYoloV2Tiny);
CHECK_CUSTOM_PARSE_FUNC_PROTOTYPE(NvDsInferParseCustomYoloTLT);
================================================
FILE: deepstream_plugin_yolov4/trt_utils.cpp
================================================
/*
* Copyright (c) 2019-2020, NVIDIA CORPORATION. All rights reserved.
*
* Permission is hereby granted, free of charge, to any person obtaining a
* copy of this software and associated documentation files (the "Software"),
* to deal in the Software without restriction, including without limitation
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
* and/or sell copies of the Software, and to permit persons to whom the
* Software is furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL
* THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
* DEALINGS IN THE SOFTWARE.
*/
#include "trt_utils.h"
#include <experimental/filesystem>
#include <fstream>
#include <iomanip>
#include <functional>
#include <algorithm>
#include <math.h>
#include "NvInferPlugin.h"
static void leftTrim(std::string& s)
{
s.erase(s.begin(), std::find_if(s.begin(), s.end(), [](int ch) { return !isspace(ch); }));
}
static void rightTrim(std::string& s)
{
s.erase(std::find_if(s.rbegin(), s.rend(), [](int ch) { return !isspace(ch); }).base(), s.end());
}
std::string trim(std::string s)
{
leftTrim(s);
rightTrim(s);
return s;
}
float clamp(const float val, const float minVal, const float maxVal)
{
assert(minVal <= maxVal);
return std::min(maxVal, std::max(minVal, val));
}
bool fileExists(const std::string fileName, bool verbose)
{
if (!std::experimental::filesystem::exists(std::experimental::filesystem::path(fileName)))
{
if (verbose) std::cout << "File does not exist : " << fileName << std::endl;
return false;
}
return true;
}
std::vector<float> loadWeights(const std::string weightsFilePath, const std::string& networkType)
{
assert(fileExists(weightsFilePath));
std::cout << "Loading pre-trained weights..." << std::endl;
std::ifstream file(weightsFilePath, std::ios_base::binary);
assert(file.good());
std::string line;
if (networkType == "yolov2")
{
// Remove 4 int32 bytes of data from the stream belonging to the header
file.ignore(4 * 4);
}
else if ((networkType == "yolov3") || (networkType == "yolov3-tiny")
|| (networkType == "yolov2-tiny"))
{
// Remove 5 int32 bytes of data from the stream belonging to the header
file.ignore(4 * 5);
}
else
{
std::cout << "Invalid network type" << std::endl;
assert(0);
}
std::vector<float> weights;
char floatWeight[4];
while (!file.eof())
{
file.read(floatWeight, 4);
assert(file.gcount() == 4);
weights.push_back(*reinterpret_cast<float*>(floatWeight));
if (file.peek() == std::istream::traits_type::eof()) break;
}
std::cout << "Loading weights of " << networkType << " complete!"
<< std::endl;
std::cout << "Total Number of weights read : " << weights.size() << std::endl;
return weights;
}
std::string dimsToString(const nvinfer1::Dims d)
{
std::stringstream s;
assert(d.nbDims >= 1);
for (int i = 0; i < d.nbDims - 1; ++i)
{
s << std::setw(4) << d.d[i] << " x";
}
s << std::setw(4) << d.d[d.nbDims - 1];
return s.str();
}
void displayDimType(const nvinfer1::Dims d)
{
std::cout << "(" << d.nbDims << ") ";
for (int i = 0; i < d.nbDims; ++i)
{
switch (d.type[i])
{
case nvinfer1::DimensionType::kSPATIAL: std::cout << "kSPATIAL "; break;
case nvinfer1::DimensionType::kCHANNEL: std::cout << "kCHANNEL "; break;
case nvinfer1::DimensionType::kINDEX: std::cout << "kINDEX "; break;
case nvinfer1::DimensionType::kSEQUENCE: std::cout << "kSEQUENCE "; break;
}
}
std::cout << std::endl;
}
int getNumChannels(nvinfer1::ITensor* t)
{
nvinfer1::Dims d = t->getDimensions();
assert(d.nbDims == 3);
return d.d[0];
}
uint64_t get3DTensorVolume(nvinfer1::Dims inputDims)
{
assert(inputDims.nbDims == 3);
return inputDims.d[0] * inputDims.d[1] * inputDims.d[2];
}
nvinfer1::ILayer* netAddMaxpool(int layerIdx, std::map<std::string, std::string>& block,
nvinfer1::ITensor* input, nvinfer1::INetworkDefinition* network)
{
assert(block.at("type") == "maxpool");
assert(block.find("size") != block.end());
assert(block.find("stride") != block.end());
int size = std::stoi(block.at("size"));
int stride = std::stoi(block.at("stride"));
nvinfer1::IPoolingLayer* pool
= network->addPooling(*input, nvinfer1::PoolingType::kMAX, nvinfer1::DimsHW{size, size});
assert(pool);
std::string maxpoolLayerName = "maxpool_" + std::to_string(layerIdx);
pool->setStride(nvinfer1::DimsHW{stride, stride});
pool->setPaddingMode(nvinfer1::PaddingMode::kSAME_UPPER);
pool->setName(maxpoolLayerName.c_str());
return pool;
}
nvinfer1::ILayer* netAddConvLinear(int layerIdx, std::map<std::string, std::string>& block,
std::vector<float>& weights,
std::vector<nvinfer1::Weights>& trtWeights, int& weightPtr,
int& inputChannels, nvinfer1::ITensor* input,
nvinfer1::INetworkDefinition* network)
{
assert(block.at("type") == "convolutional");
assert(block.find("batch_normalize") == block.end());
assert(block.at("activation") == "linear");
assert(block.find("filters") != block.end());
assert(block.find("pad") != block.end());
assert(block.find("size") != block.end());
assert(block.find("stride") != block.end());
int filters = std::stoi(block.at("filters"));
int padding = std::stoi(block.at("pad"));
int kernelSize = std::stoi(block.at("size"));
int stride = std::stoi(block.at("stride"));
int pad;
if (padding)
pad = (kernelSize - 1) / 2;
else
pad = 0;
// load the convolution layer bias
nvinfer1::Weights convBias{nvinfer1::DataType::kFLOAT, nullptr, filters};
float* val = new float[filters];
for (int i = 0; i < filters; ++i)
{
val[i] = weights[weightPtr];
weightPtr++;
}
convBias.values = val;
trtWeights.push_back(convBias);
// load the convolutional layer weights
int size = filters * inputChannels * kernelSize * kernelSize;
nvinfer1::Weights convWt{nvinfer1::DataType::kFLOAT, nullptr, size};
val = new float[size];
for (int i = 0; i < size; ++i)
{
val[i] = weights[weightPtr];
weightPtr++;
}
convWt.values = val;
trtWeights.push_back(convWt);
nvinfer1::IConvolutionLayer* conv = network->addConvolution(
*input, filters, nvinfer1::DimsHW{kernelSize, kernelSize}, convWt, convBias);
assert(conv != nullptr);
std::string convLayerName = "conv_" + std::to_string(layerIdx);
conv->setName(convLayerName.c_str());
conv->setStride(nvinfer1::DimsHW{stride, stride});
conv->setPadding(nvinfer1::DimsHW{pad, pad});
return conv;
}
nvinfer1::ILayer* netAddConvBNLeaky(int layerIdx, std::map<std::string, std::string>& block,
std::vector<float>& weights,
std::vector<nvinfer1::Weights>& trtWeights, int& weightPtr,
int& inputChannels, nvinfer1::ITensor* input,
nvinfer1::INetworkDefinition* network)
{
assert(block.at("type") == "convolutional");
assert(block.find("batch_normalize") != block.end());
assert(block.at("batch_normalize") == "1");
assert(block.at("activation") == "leaky");
assert(block.find("filters") != block.end());
assert(block.find("pad") != block.end());
assert(block.find("size") != block.end());
assert(block.find("stride") != block.end());
bool batchNormalize, bias;
if (block.find("batch_normalize") != block.end())
{
batchNormalize = (block.at("batch_normalize") == "1");
bias = false;
}
else
{
batchNormalize = false;
bias = true;
}
// all conv_bn_leaky layers assume bias is false
assert(batchNormalize == true && bias == false);
UNUSED(batchNormalize);
UNUSED(bias);
int filters = std::stoi(block.at("filters"));
int padding = std::stoi(block.at("pad"));
int kernelSize = std::stoi(block.at("size"));
int stride = std::stoi(block.at("stride"));
int pad;
if (padding)
pad = (kernelSize - 1) / 2;
else
pad = 0;
/***** CONVOLUTION LAYER *****/
/*****************************/
// batch norm weights are before the conv layer
// load BN biases (bn_biases)
std::vector<float> bnBiases;
for (int i = 0; i < filters; ++i)
{
bnBiases.push_back(weights[weightPtr]);
weightPtr++;
}
// load BN weights
std::vector<float> bnWeights;
for (int i = 0; i < filters; ++i)
{
bnWeights.push_back(weights[weightPtr]);
weightPtr++;
}
// load BN running_mean
std::vector<float> bnRunningMean;
for (int i = 0; i < filters; ++i)
{
bnRunningMean.push_back(weights[weightPtr]);
weightPtr++;
}
// load BN running_var
std::vector<float> bnRunningVar;
for (int i = 0; i < filters; ++i)
{
// 1e-05 for numerical stability
bnRunningVar.push_back(sqrt(weights[weightPtr] + 1.0e-5));
weightPtr++;
}
// load Conv layer weights (GKCRS)
int size = filters * inputChannels * kernelSize * kernelSize;
nvinfer1::Weights convWt{nvinfer1::DataType::kFLOAT, nullptr, size};
float* val = new float[size];
for (int i = 0; i < size; ++i)
{
val[i] = weights[weightPtr];
weightPtr++;
}
convWt.values = val;
trtWeights.push_back(convWt);
nvinfer1::Weights convBias{nvinfer1::DataType::kFLOAT, nullptr, 0};
trtWeights.push_back(convBias);
nvinfer1::IConvolutionLayer* conv = network->addConvolution(
*input, filters, nvinfer1::DimsHW{kernelSize, kernelSize}, convWt, convBias);
assert(conv != nullptr);
std::string convLayerName = "conv_" + std::to_string(layerIdx);
conv->setName(convLayerName.c_str());
conv->setStride(nvinfer1::DimsHW{stride, stride});
conv->setPadding(nvinfer1::DimsHW{pad, pad});
/***** BATCHNORM LAYER *****/
/***************************/
size = filters;
// create the weights
nvinfer1::Weights shift{nvinfer1::DataType::kFLOAT, nullptr, size};
nvinfer1::Weights scale{nvinfer1::DataType::kFLOAT, nullptr, size};
nvinfer1::Weights power{nvinfer1::DataType::kFLOAT, nullptr, size};
float* shiftWt = new float[size];
for (int i = 0; i < size; ++i)
{
shiftWt[i]
= bnBiases.at(i) - ((bnRunningMean.at(i) * bnWeights.at(i)) / bnRunningVar.at(i));
}
shift.values = shiftWt;
float* scaleWt = new float[size];
for (int i = 0; i < size; ++i)
{
scaleWt[i] = bnWeights.at(i) / bnRunningVar[i];
}
scale.values = scaleWt;
float* powerWt = new float[size];
for (int i = 0; i < size; ++i)
{
powerWt[i] = 1.0;
}
power.values = powerWt;
trtWeights.push_back(shift);
trtWeights.push_back(scale);
trtWeights.push_back(power);
// Add the batch norm layers
nvinfer1::IScaleLayer* bn = network->addScale(
*conv->getOutput(0), nvinfer1::ScaleMode::kCHANNEL, shift, scale, power);
assert(bn != nullptr);
std::string bnLayerName = "batch_norm_" + std::to_string(layerIdx);
bn->setName(bnLayerName.c_str());
/***** ACTIVATION LAYER *****/
/****************************/
nvinfer1::ITensor* bnOutput = bn->getOutput(0);
nvinfer1::IActivationLayer* leaky = network->addActivation(
*bnOutput, nvinfer1::ActivationType::kLEAKY_RELU);
leaky->setAlpha(0.1);
assert(leaky != nullptr);
std::string leakyLayerName = "leaky_" + std::to_string(layerIdx);
leaky->setName(leakyLayerName.c_str());
return leaky;
}
nvinfer1::ILayer* netAddUpsample(int layerIdx, std::map<std::string, std::string>& block,
std::vector<float>& weights,
std::vector<nvinfer1::Weights>& trtWeights, int& inputChannels,
nvinfer1::ITensor* input, nvinfer1::INetworkDefinition* network)
{
assert(block.at("type") == "upsample");
nvinfer1::Dims inpDims = input->getDimensions();
assert(inpDims.nbDims == 3);
assert(inpDims.d[1] == inpDims.d[2]);
int h = inpDims.d[1];
int w = inpDims.d[2];
int stride = std::stoi(block.at("stride"));
// add pre multiply matrix as a constant
nvinfer1::Dims preDims{3,
{1, stride * h, w},
{nvinfer1::DimensionType::kCHANNEL, nvinfer1::DimensionType::kSPATIAL,
nvinfer1::DimensionType::kSPATIAL}};
int size = stride * h * w;
nvinfer1::Weights preMul{nvinfer1::DataType::kFLOAT, nullptr, size};
float* preWt = new float[size];
/* (2*h * w)
[ [1, 0, ..., 0],
[1, 0, ..., 0],
[0, 1, ..., 0],
[0, 1, ..., 0],
...,
...,
[0, 0, ..., 1],
[0, 0, ..., 1] ]
*/
for (int i = 0, idx = 0; i < h; ++i)
{
for (int s = 0; s < stride; ++s)
{
for (int j = 0; j < w; ++j, ++idx)
{
preWt[idx] = (i == j) ? 1.0 : 0.0;
}
}
}
preMul.values = preWt;
trtWeights.push_back(preMul);
nvinfer1::IConstantLayer* preM = network->addConstant(preDims, preMul);
assert(preM != nullptr);
std::string preLayerName = "preMul_" + std::to_string(layerIdx);
preM->setName(preLayerName.c_str());
// add post multiply matrix as a constant
nvinfer1::Dims postDims{3,
{1, h, stride * w},
{nvinfer1::DimensionType::kCHANNEL, nvinfer1::DimensionType::kSPATIAL,
nvinfer1::DimensionType::kSPATIAL}};
size = stride * h * w;
nvinfer1::Weights postMul{nvinfer1::DataType::kFLOAT, nullptr, size};
float* postWt = new float[size];
/* (h * 2*w)
[ [1, 1, 0, 0, ..., 0, 0],
[0, 0, 1, 1, ..., 0, 0],
...,
...,
[0, 0, 0, 0, ..., 1, 1] ]
*/
for (int i = 0, idx = 0; i < h; ++i)
{
for (int j = 0; j < stride * w; ++j, ++idx)
{
postWt[idx] = (j / stride == i) ? 1.0 : 0.0;
}
}
postMul.values = postWt;
trtWeights.push_back(postMul);
nvinfer1::IConstantLayer* post_m = network->addConstant(postDims, postMul);
assert(post_m != nullptr);
std::string postLayerName = "postMul_" + std::to_string(layerIdx);
post_m->setName(postLayerName.c_str());
// add matrix multiply layers for upsampling
nvinfer1::IMatrixMultiplyLayer* mm1
= network->addMatrixMultiply(*preM->getOutput(0), nvinfer1::MatrixOperation::kNONE, *input,
nvinfer1::MatrixOperation::kNONE);
assert(mm1 != nullptr);
std::string mm1LayerName = "mm1_" + std::to_string(layerIdx);
mm1->setName(mm1LayerName.c_str());
nvinfer1::IMatrixMultiplyLayer* mm2
= network->addMatrixMultiply(*mm1->getOutput(0), nvinfer1::MatrixOperation::kNONE,
*post_m->getOutput(0), nvinfer1::MatrixOperation::kNONE);
assert(mm2 != nullptr);
std::string mm2LayerName = "mm2_" + std::to_string(layerIdx);
mm2->setName(mm2LayerName.c_str());
return mm2;
}
void printLayerInfo(std::string layerIndex, std::string layerName, std::string layerInput,
std::string layerOutput, std::string weightPtr)
{
std::cout << std::setw(6) << std::left << layerIndex << std::setw(15) << std::left << layerName;
std::cout << std::setw(20) << std::left << layerInput << std::setw(20) << std::left
<< layerOutput;
std::cout << std::setw(6) << std::left << weightPtr << std::endl;
}
================================================
FILE: deepstream_plugin_yolov4/trt_utils.h
================================================
/*
* Copyright (c) 2019-2020, NVIDIA CORPORATION. All rights reserved.
*
* Permission is hereby granted, free of charge, to any person obtaining a
* copy of this software and associated documentation files (the "Software"),
* to deal in the Software without restriction, including without limitation
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
* and/or sell copies of the Software, and to permit persons to whom the
* Software is furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL
* THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
* DEALINGS IN THE SOFTWARE.
*/
#ifndef __TRT_UTILS_H__
#define __TRT_UTILS_H__
#include <set>
#include <map>
#include <string>
#include <vector>
#include <cassert>
#include <iostream>
#include <fstream>
#include "NvInfer.h"
#define UNUSED(expr) (void)(expr)
#define DIVUP(n, d) ((n) + (d)-1) / (d)
std::string trim(std::string s);
float clamp(const float val, const float minVal, const float maxVal);
bool fileExists(const std::string fileName, bool verbose = true);
std::vector<float> loadWeights(const std::string weightsFilePath, const std::string& networkType);
std::string dimsToString(const nvinfer1::Dims d);
void displayDimType(const nvinfer1::Dims d);
int getNumChannels(nvinfer1::ITensor* t);
uint64_t get3DTensorVolume(nvinfer1::Dims inputDims);
// Helper functions to create yolo engine
nvinfer1::ILayer* netAddMaxpool(int layerIdx, std::map<std::string, std::string>& block,
nvinfer1::ITensor* input, nvinfer1::INetworkDefinition* network);
nvinfer1::ILayer* netAddConvLinear(int layerIdx, std::map<std::string, std::string>& block,
std::vector<float>& weights,
std::vector<nvinfer1::Weights>& trtWeights, int& weightPtr,
int& inputChannels, nvinfer1::ITensor* input,
nvinfer1::INetworkDefinition* network);
nvinfer1::ILayer* netAddConvBNLeaky(int layerIdx, std::map<std::string, std::string>& block,
std::vector<float>& weights,
std::vector<nvinfer1::Weights>& trtWeights, int& weightPtr,
int& inputChannels, nvinfer1::ITensor* input,
nvinfer1::INetworkDefinition* network);
nvinfer1::ILayer* netAddUpsample(int layerIdx, std::map<std::string, std::string>& block,
std::vector<float>& weights,
std::vector<nvinfer1::Weights>& trtWeights, int& inputChannels,
nvinfer1::ITensor* input, nvinfer1::INetworkDefinition* network);
void printLayerInfo(std::string layerIndex, std::string layerName, std::string layerInput,
std::string layerOutput, std::string weightPtr);
#endif
================================================
FILE: deepstream_plugin_yolov4/yolo.cpp
================================================
/*
* Copyright (c) 2019-2020, NVIDIA CORPORATION. All rights reserved.
*
* Permission is hereby granted, free of charge, to any person obtaining a
* copy of this software and associated documentation files (the "Software"),
* to deal in the Software without restriction, including without limitation
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
* and/or sell copies of the Software, and to permit persons to whom the
* Software is furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL
* THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
* DEALINGS IN THE SOFTWARE.
*/
#include "yolo.h"
#include "yoloPlugins.h"
#include <fstream>
#include <iomanip>
#include <iterator>
Yolo::Yolo(const NetworkInfo& networkInfo)
: m_NetworkType(networkInfo.networkType), // yolov3
m_ConfigFilePath(networkInfo.configFilePath), // yolov3.cfg
m_WtsFilePath(networkInfo.wtsFilePath), // yolov3.weights
m_DeviceType(networkInfo.deviceType), // kDLA, kGPU
m_InputBlobName(networkInfo.inputBlobName), // data
m_InputH(0),
m_InputW(0),
m_InputC(0),
m_InputSize(0)
{}
Yolo::~Yolo()
{
destroyNetworkUtils();
}
nvinfer1::ICudaEngine *Yolo::createEngine (nvinfer1::IBuilder* builder)
{
assert (builder);
std::vector<float> weights = loadWeights(m_WtsFilePath, m_NetworkType);
std::vector<nvinfer1::Weights> trtWeights;
nvinfer1::INetworkDefinition *network = builder->createNetwork();
if (parseModel(*network) != NVDSINFER_SUCCESS) {
network->destroy();
return nullptr;
}
// Build the engine
std::cout << "Building the TensorRT Engine..." << std::endl;
nvinfer1::ICudaEngine * engine = builder->buildCudaEngine(*network);
if (engine) {
std::cout << "Building complete!" << std::endl;
} else {
std::cerr << "Building engine failed!" << std::endl;
}
// destroy
network->destroy();
return engine;
}
NvDsInferStatus Yolo::parseModel(nvinfer1::INetworkDefinition& network) {
destroyNetworkUtils();
m_ConfigBlocks = parseConfigFile(m_ConfigFilePath);
parseConfigBlocks();
std::vector<float> weights = loadWeights(m_WtsFilePath, m_NetworkType);
// build yolo network
std::cout << "Building Yolo network..." << std::endl;
NvDsInferStatus status = buildYoloNetwork(weights, network);
if (status == NVDSINFER_SUCCESS) {
std::cout << "Building yolo network complete!" << std::endl;
} else {
std::cerr << "Building yolo network failed!" << std::endl;
}
return status;
}
NvDsInferStatus Yolo::buildYoloNetwork(
std::vector<float>& weights, nvinfer1::INetworkDefinition& network) {
int weightPtr = 0;
int channels = m_InputC;
nvinfer1::ITensor* data =
network.addInput(m_InputBlobName.c_str(), nvinfer1::DataType::kFLOAT,
nvinfer1::DimsCHW{static_cast<int>(m_InputC),
static_cast<int>(m_InputH), static_cast<int>(m_InputW)});
assert(data != nullptr && data->getDimensions().nbDims > 0);
nvinfer1::ITensor* previous = data;
std::vector<nvinfer1::ITensor*> tensorOutputs;
uint outputTensorCount = 0;
// build the network using the network API
for (uint i = 0; i < m_ConfigBlocks.size(); ++i) {
// check if num. of channels is correct
assert(getNumChannels(previous) == channels);
std::string layerIndex = "(" + std::to_string(tensorOutputs.size()) + ")";
if (m_ConfigBlocks.at(i).at("type") == "net") {
printLayerInfo("", "layer", " inp_size", " out_size", "weightPtr");
} else if (m_ConfigBlocks.at(i).at("type") == "convolutional") {
std::string inputVol = dimsToString(previous->getDimensions());
nvinfer1::ILayer* out;
std::string layerType;
// check if batch_norm enabled
if (m_ConfigBlocks.at(i).find("batch_normalize") !=
m_ConfigBlocks.at(i).end()) {
out = netAddConvBNLeaky(i, m_ConfigBlocks.at(i), weights,
m_TrtWeights, weightPtr, channels, previous, &network);
layerType = "conv-bn-leaky";
}
else
{
out = netAddConvLinear(i, m_ConfigBlocks.at(i), weights,
m_TrtWeights, weightPtr, channels, previous, &network);
layerType = "conv-linear";
}
previous = out->getOutput(0);
assert(previous != nullptr);
channels = getNumChannels(previous);
std::string outputVol = dimsToString(previous->getDimensions());
tensorOutputs.push_back(out->getOutput(0));
printLayerInfo(layerIndex, layerType, inputVol, outputVol, std::to_string(weightPtr));
} else if (m_ConfigBlocks.at(i).at("type") == "shortcut") {
assert(m_ConfigBlocks.at(i).at("activation") == "linear");
assert(m_ConfigBlocks.at(i).find("from") !=
m_ConfigBlocks.at(i).end());
int from = stoi(m_ConfigBlocks.at(i).at("from"));
std::string inputVol = dimsToString(previous->getDimensions());
// check if indexes are correct
assert((i - 2 >= 0) && (i - 2 < tensorOutputs.size()));
assert((i + from - 1 >= 0) && (i + from - 1 < tensorOutputs.size()));
assert(i + from - 1 < i - 2);
nvinfer1::IElementWiseLayer* ew = network.addElementWise(
*tensorOutputs[i - 2], *tensorOutputs[i + from - 1],
nvinfer1::ElementWiseOperation::kSUM);
assert(ew != nullptr);
std::string ewLayerName = "shortcut_" + std::to_string(i);
ew->setName(ewLayerName.c_str());
previous = ew->getOutput(0);
assert(previous != nullptr);
std::string outputVol = dimsToString(previous->getDimensions());
tensorOutputs.push_back(ew->getOutput(0));
printLayerInfo(layerIndex, "skip", inputVol, outputVol, " -");
} else if (m_ConfigBlocks.at(i).at("type") == "yolo") {
nvinfer1::Dims prevTensorDims = previous->getDimensions();
assert(prevTensorDims.d[1] == prevTensorDims.d[2]);
TensorInfo& curYoloTensor = m_OutputTensors.at(outputTensorCount);
curYoloTensor.gridSize = prevTensorDims.d[1];
curYoloTensor.stride = m_InputW / curYoloTensor.gridSize;
m_OutputTensors.at(outputTensorCount).volume = curYoloTensor.gridSize
* curYoloTensor.gridSize
* (curYoloTensor.numBBoxes * (5 + curYoloTensor.numClasses));
std::string layerName = "yolo_" + std::to_string(i);
curYoloTensor.blobName = layerName;
nvinfer1::IPluginV2* yoloPlugin
= new YoloLayerV3(m_OutputTensors.at(outputTensorCount).numBBoxes,
m_OutputTensors.at(outputTensorCount).numClasses,
m_OutputTensors.at(outputTensorCount).gridSize);
assert(yoloPlugin != nullptr);
nvinfer1::IPluginV2Layer* yolo =
network.addPluginV2(&previous, 1, *yoloPlugin);
assert(yolo != nullptr);
yolo->setName(layerName.c_str());
std::string inputVol = dimsToString(previous->getDimensions());
previous = yolo->getOutput(0);
assert(previous != nullptr);
previous->setName(layerName.c_str());
std::string outputVol = dimsToString(previous->getDimensions());
network.markOutput(*previous);
channels = getNumChannels(previous);
tensorOutputs.push_back(yolo->getOutput(0));
printLayerInfo(layerIndex, "yolo", inputVol, outputVol, std::to_string(weightPtr));
++outputTensorCount;
} else if (m_ConfigBlocks.at(i).at("type") == "region") {
nvinfer1::Dims prevTensorDims = previous->getDimensions();
assert(prevTensorDims.d[1] == prevTensorDims.d[2]);
TensorInfo& curRegionTensor = m_OutputTensors.at(outputTensorCount);
curRegionTensor.gridSize = prevTensorDims.d[1];
curRegionTensor.stride = m_InputW / curRegionTensor.gridSize;
m_OutputTensors.at(outputTensorCount).volume = curRegionTensor.gridSize
* curRegionTensor.gridSize
* (curRegionTensor.numBBoxes * (5 + curRegionTensor.numClasses));
std::string layerName = "region_" + std::to_string(i);
curRegionTensor.blobName = layerName;
nvinfer1::plugin::RegionParameters RegionParameters{
static_cast<int>(curRegionTensor.numBBoxes), 4,
static_cast<int>(curRegionTensor.numClasses), nullptr};
std::string inputVol = dimsToString(previous->getDimensions());
nvinfer1::IPluginV2* regionPlugin
= createRegionPlugin(RegionParameters);
assert(regionPlugin != nullptr);
nvinfer1::IPluginV2Layer* region =
network.addPluginV2(&previous, 1, *regionPlugin);
assert(region != nullptr);
region->setName(layerName.c_str());
previous = region->getOutput(0);
assert(previous != nullptr);
previous->setName(layerName.c_str());
std::string outputVol = dimsToString(previous->getDimensions());
network.markOutput(*previous);
channels = getNumChannels(previous);
tensorOutputs.push_back(region->getOutput(0));
printLayerInfo(layerIndex, "region", inputVol, outputVol, std::to_string(weightPtr));
std::cout << "Anchors are being converted to network input resolution i.e. Anchors x "
<< curRegionTensor.stride << " (stride)" << std::endl;
for (auto& anchor : curRegionTensor.anchors) anchor *= curRegionTensor.stride;
++outputTensorCount;
} else if (m_ConfigBlocks.at(i).at("type") == "reorg") {
std::string inputVol = dimsToString(previous->getDimensions());
nvinfer1::IPluginV2* reorgPlugin = createReorgPlugin(2);
assert(reorgPlugin != nullptr);
nvinfer1::IPluginV2Layer* reorg =
network.addPluginV2(&previous, 1, *reorgPlugin);
assert(reorg != nullptr);
std::string layerName = "reorg_" + std::to_string(i);
reorg->setName(layerName.c_str());
previous = reorg->getOutput(0);
assert(previous != nullptr);
std::string outputVol = dimsToString(previous->getDimensions());
channels = getNumChannels(previous);
tensorOutputs.push_back(reorg->getOutput(0));
printLayerInfo(layerIndex, "reorg", inputVol, outputVol, std::to_string(weightPtr));
}
// route layers (single or concat)
else if (m_ConfigBlocks.at(i).at("type") == "route") {
std::string strLayers = m_ConfigBlocks.at(i).at("layers");
std::vector<int> idxLayers;
size_t lastPos = 0, pos = 0;
while ((pos = strLayers.find(',', lastPos)) != std::string::npos) {
int vL = std::stoi(trim(strLayers.substr(lastPos, pos - lastPos)));
idxLayers.push_back (vL);
lastPos = pos + 1;
}
if (lastPos < strLayers.length()) {
std::string lastV = trim(strLayers.substr(lastPos));
if (!lastV.empty()) {
idxLayers.push_back (std::stoi(lastV));
}
}
assert (!idxLayers.empty());
std::vector<nvinfer1::ITensor*> concatInputs;
for (int idxLayer : idxLayers) {
if (idxLayer < 0) {
idxLayer = tensorOutputs.size() + idxLayer;
}
assert (idxLayer >= 0 && idxLayer < (int)tensorOutputs.size());
concatInputs.push_back (tensorOutputs[idxLayer]);
}
nvinfer1::IConcatenationLayer* concat =
network.addConcatenation(concatInputs.data(), concatInputs.size());
assert(concat != nullptr);
std::string concatLayerName = "route_" + std::to_string(i - 1);
concat->setName(concatLayerName.c_str());
// concatenate along the channel dimension
concat->setAxis(0);
previous = concat->getOutput(0);
assert(previous != nullptr);
std::string outputVol = dimsToString(previous->getDimensions());
// set the output volume depth
channels
= getNumChannels(previous);
tensorOutputs.push_back(concat->getOutput(0));
printLayerInfo(layerIndex, "route", " -", outputVol,
std::to_string(weightPtr));
} else if (m_ConfigBlocks.at(i).at("type") == "upsample") {
std::string inputVol = dimsToString(previous->getDimensions());
nvinfer1::ILayer* out = netAddUpsample(i - 1, m_ConfigBlocks[i],
weights, m_TrtWeights, channels, previous, &network);
previous = out->getOutput(0);
std::string outputVol = dimsToString(previous->getDimensions());
tensorOutputs.push_back(out->getOutput(0));
printLayerInfo(layerIndex, "upsample", inputVol, outputVol, " -");
} else if (m_ConfigBlocks.at(i).at("type") == "maxpool") {
std::string inputVol = dimsToString(previous->getDimensions());
nvinfer1::ILayer* out =
netAddMaxpool(i, m_ConfigBlocks.at(i), previous, &network);
previous = out->getOutput(0);
assert(previous != nullptr);
std::string outputVol = dimsToString(previous->getDimensions());
tensorOutputs.push_back(out->getOutput(0));
printLayerInfo(layerIndex, "maxpool", inputVol, outputVol, std::to_string(weightPtr));
}
else
{
std::cout << "Unsupported layer type --> \""
<< m_ConfigBlocks.at(i).at("type") << "\"" << std::endl;
assert(0);
}
}
if ((int)weights.size() != weightPtr)
{
std::cout << "Number of unused weights left : " << weights.size() - weightPtr << std::endl;
assert(0);
}
std::cout << "Output yolo blob names :" << std::endl;
for (auto& tensor : m_OutputTensors) {
std::cout << tensor.blobName << std::endl;
}
int nbLayers = network.getNbLayers();
std::cout << "Total number of yolo layers: " << nbLayers << std::endl;
return NVDSINFER_SUCCESS;
}
std::vector<std::map<std::string, std::string>>
Yolo::parseConfigFile (const std::string cfgFilePath)
{
assert(fileExists(cfgFilePath));
std::ifstream file(cfgFilePath);
assert(file.good());
std::string line;
std::vector<std::map<std::string, std::string>> blocks;
std::map<std::string, std::string> block;
while (getline(file, line))
{
if (line.size() == 0) continue;
if (line.front() == '#') continue;
line = trim(line);
if (line.front() == '[')
{
if (block.size() > 0)
{
blocks.push_back(block);
block.clear();
}
std::string key = "type";
std::string value = trim(line.substr(1, line.size() - 2));
block.insert(std::pair<std::string, std::string>(key, value));
}
else
{
int cpos = line.find('=');
std::string key = trim(line.substr(0, cpos));
std::string value = trim(line.substr(cpos + 1));
block.insert(std::pair<std::string, std::string>(key, value));
}
}
blocks.push_back(block);
return blocks;
}
void Yolo::parseConfigBlocks()
{
for (auto block : m_ConfigBlocks) {
if (block.at("type") == "net")
{
assert((block.find("height") != block.end())
&& "Missing 'height' param in network cfg");
assert((block.find("width") != block.end()) && "Missing 'width' param in network cfg");
assert((block.find("channels") != block.end())
&& "Missing 'channels' param in network cfg");
m_InputH = std::stoul(block.at("height"));
m_InputW = std::stoul(block.at("width"));
m_InputC = std::stoul(block.at("channels"));
assert(m_InputW == m_InputH);
m_InputSize = m_InputC * m_InputH * m_InputW;
}
else if ((block.at("type") == "region") || (block.at("type") == "yolo"))
{
assert((block.find("num") != block.end())
&& std::string("Missing 'num' param in " + block.at("type") + " layer").c_str());
assert((block.find("classes") != block.end())
&& std::string("Missing 'classes' param in " + block.at("type") + " layer")
.c_str());
assert((block.find("anchors") != block.end())
&& std::string("Missing 'anchors' param in " + block.at("type") + " layer")
.c_str());
TensorInfo outputTensor;
std::string anchorString = block.at("anchors");
while (!anchorString.empty())
{
int npos = anchorString.find_first_of(',');
if (npos != -1)
{
float anchor = std::stof(trim(anchorString.substr(0, npos)));
outputTensor.anchors.push_back(anchor);
anchorString.erase(0, npos + 1);
}
else
{
float anchor = std::stof(trim(anchorString));
outputTensor.anchors.push_back(anchor);
break;
}
}
if ((m_NetworkType == "yolov3") || (m_NetworkType == "yolov3-tiny"))
{
assert((block.find("mask") != block.end())
&& std::string("Missing 'mask' param in " + block.at("type") + " layer")
.c_str());
std::string maskString = block.at("mask");
while (!maskString.empty())
{
int npos = maskString.find_first_of(',');
if (npos != -1)
{
uint mask = std::stoul(trim(maskString.substr(0, npos)));
outputTensor.masks.push_back(mask);
maskString.erase(0, npos + 1);
}
else
{
uint mask = std::stoul(trim(maskString));
outputTensor.masks.push_back(mask);
break;
}
}
}
outputTensor.numBBoxes = outputTensor.masks.size() > 0
? outputTensor.masks.size()
: std::stoul(trim(block.at("num")));
outputTensor.numClasses = std::stoul(block.at("classes"));
m_OutputTensors.push_back(outputTensor);
}
}
}
void Yolo::destroyNetworkUtils() {
// deallocate the weights
for (uint i = 0; i < m_TrtWeights.size(); ++i) {
if (m_TrtWeights[i].count > 0)
free(const_cast<void*>(m_TrtWeights[i].values));
}
m_TrtWeights.clear();
}
================================================
FILE: deepstream_plugin_yolov4/yolo.h
================================================
/*
* Copyright (c) 2019-2020, NVIDIA CORPORATION. All rights reserved.
*
* Permission is hereby granted, free of charge, to any person obtaining a
* copy of this software and associated documentation files (the "Software"),
* to deal in the Software without restriction, including without limitation
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
* and/or sell copies of the Software, and to permit persons to whom the
* Software is furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL
* THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
* DEALINGS IN THE SOFTWARE.
*/
#ifndef _YOLO_H_
#define _YOLO_H_
#include <stdint.h>
#include <string>
#include <vector>
#include <memory>
#include "NvInfer.h"
#include "trt_utils.h"
#include "nvdsinfer_custom_impl.h"
/**
* Holds all the file paths required to build a network.
*/
struct NetworkInfo
{
std::string networkType;
std::string configFilePath;
std::string wtsFilePath;
std::string deviceType;
std::string inputBlobName;
};
/**
* Holds information about an output tensor of the yolo network.
*/
struct TensorInfo
{
std::string blobName;
uint stride{0};
uint gridSize{0};
uint numClasses{0};
uint numBBoxes{0};
uint64_t volume{0};
std::vector<uint> masks;
std::vector<float> anchors;
int bindingIndex{-1};
float* hostBuffer{nullptr};
};
class Yolo : public IModelParser {
public:
Yolo(const NetworkInfo& networkInfo);
~Yolo() override;
bool hasFullDimsSupported() const override { return false; }
const char* getModelName() const override {
return m_ConfigFilePath.empty() ? m_NetworkType.c_str()
: m_ConfigFilePath.c_str();
}
NvDsInferStatus parseModel(nvinfer1::INetworkDefinition& network) override;
nvinfer1::ICudaEngine *createEngine (nvinfer1::IBuilder* builder);
protected:
const std::string m_NetworkType;
const std::string m_ConfigFilePath;
const std::string m_WtsFilePath;
const std::string m_DeviceType;
const std::string m_InputBlobName;
std::vector<TensorInfo> m_OutputTensors;
std::vector<std::map<std::string, std::string>> m_ConfigBlocks;
uint m_InputH;
uint m_InputW;
uint m_InputC;
uint64_t m_InputSize;
// TRT specific members
std::vector<nvinfer1::Weights> m_TrtWeights;
private:
NvDsInferStatus buildYoloNetwork(
std::vector<float>& weights, nvinfer1::INetworkDefinition& network);
std::vector<std::map<std::string, std::string>> parseConfigFile(
const std::string cfgFilePath);
void parseConfigBlocks();
void destroyNetworkUtils();
};
#endif // _YOLO_H_
================================================
FILE: deepstream_plugin_yolov4/yoloPlugins.cpp
================================================
/*
* Copyright (c) 2019, NVIDIA CORPORATION. All rights reserved.
*
* Permission is hereby granted, free of charge, to any person obtaining a
* copy of this software and associated documentation files (the "Software"),
* to deal in the Software without restriction, including without limitation
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
* and/or sell copies of the Software, and to permit persons to whom the
* Software is furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL
* THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
* DEALINGS IN THE SOFTWARE.
*/
#include "yoloPlugins.h"
#include "NvInferPlugin.h"
#include <cassert>
#include <iostream>
#include <memory>
namespace {
template <typename T>
void write(char*& buffer, const T& val)
{
*reinterpret_cast<T*>(buffer) = val;
buffer += sizeof(T);
}
template <typename T>
void read(const char*& buffer, T& val)
{
val = *reinterpret_cast<const T*>(buffer);
buffer += sizeof(T);
}
} //namespace
// Forward declaration of cuda kernels
cudaError_t cudaYoloLayerV3 (
const void* input, void* output, const uint& batchSize,
const uint& gridSize, const uint& numOutputClasses,
const uint& numBBoxes, uint64_t outputSize, cudaStream_t stream);
YoloLayerV3::YoloLayerV3 (const void* data, size_t length)
{
const char *d = static_cast<const char*>(data);
read(d, m_NumBoxes);
read(d, m_NumClasses);
read(d, m_GridSize);
read(d, m_OutputSize);
};
YoloLayerV3::YoloLayerV3 (
const uint& numBoxes, const uint& numClasses, const uint& gridSize) :
m_NumBoxes(numBoxes),
m_NumClasses(numClasses),
m_GridSize(gridSize)
{
assert(m_NumBoxes > 0);
assert(m_NumClasses > 0);
assert(m_GridSize > 0);
m_OutputSize = m_GridSize * m_GridSize * (m_NumBoxes * (4 + 1 + m_NumClasses));
};
nvinfer1::Dims
YoloLayerV3::getOutputDimensions(
int index, const nvinfer1::Dims* inputs, int nbInputDims)
{
assert(index == 0);
assert(nbInputDims == 1);
return inputs[0];
}
bool YoloLayerV3::supportsFormat (
nvinfer1::DataType type, nvinfer1::PluginFormat format) const {
return (type == nvinfer1::DataType::kFLOAT &&
format == nvinfer1::PluginFormat::kNCHW);
}
void
YoloLayerV3::configureWithFormat (
const nvinfer1::Dims* inputDims, int nbInputs,
const nvinfer1::Dims* outputDims, int nbOutputs,
nvinfer1::DataType type, nvinfer1::PluginFormat format, int maxBatchSize)
{
assert(nbInputs == 1);
assert (format == nvinfer1::PluginFormat::kNCHW);
assert(inputDims != nullptr);
}
int YoloLayerV3::enqueue(
int batchSize, const void* const* inputs, void** outputs, void* workspace,
cudaStream_t stream)
{
CHECK(cudaYoloLayerV3(
inputs[0], outputs[0], batchSize, m_GridSize, m_NumClasses, m_NumBoxes,
m_OutputSize, stream));
return 0;
}
size_t YoloLayerV3::getSerializationSize() const
{
return sizeof(m_NumBoxes) + sizeof(m_NumClasses) + sizeof(m_GridSize) + sizeof(m_OutputSize);
}
void YoloLayerV3::serialize(void* buffer) const
{
char *d = static_cast<char*>(buffer);
write(d, m_NumBoxes);
write(d, m_NumClasses);
write(d, m_GridSize);
write(d, m_OutputSize);
}
nvinfer1::IPluginV2* YoloLayerV3::clone() const
{
return new YoloLayerV3 (m_NumBoxes, m_NumClasses, m_GridSize);
}
REGISTER_TENSORRT_PLUGIN(YoloLayerV3PluginCreator);
================================================
FILE: deepstream_plugin_yolov4/yoloPlugins.h
================================================
/*
* Copyright (c) 2019, NVIDIA CORPORATION. All rights reserved.
*
* Permission is hereby granted, free of charge, to any person obtaining a
* copy of this software and associated documentation files (the "Software"),
* to deal in the Software without restriction, including without limitation
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
* and/or sell copies of the Software, and to permit persons to whom the
* Software is furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL
* THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
* DEALINGS IN THE SOFTWARE.
*/
#ifndef __YOLO_PLUGINS__
#define __YOLO_PLUGINS__
#include <cassert>
#include <cstring>
#include <cuda_runtime_api.h>
#include <iostream>
#include <memory>
#include "NvInferPlugin.h"
#define CHECK(status) \
{ \
if (status != 0) \
{ \
std::cout << "Cuda failure: " << cudaGetErrorString(status) << " in file " << __FILE__ \
<< " at line " << __LINE__ << std::endl; \
abort(); \
} \
}
namespace
{
const char* YOLOV3LAYER_PLUGIN_VERSION {"1"};
const char* YOLOV3LAYER_PLUGIN_NAME {"YoloLayerV3_TRT"};
} // namespace
class YoloLayerV3 : public nvinfer1::IPluginV2
{
public:
YoloLayerV3 (const void* data, size_t length);
YoloLayerV3 (const uint& numBoxes, const uint& numClasses, const uint& gridSize);
const char* getPluginType () const override { return YOLOV3LAYER_PLUGIN_NAME; }
const char* getPluginVersion () const override { return YOLOV3LAYER_PLUGIN_VERSION; }
int getNbOutputs () const override { return 1; }
nvinfer1::Dims getOutputDimensions (
int index, const nvinfer1::Dims* inputs,
int nbInputDims) override;
bool supportsFormat (
nvinfer1::DataType type, nvinfer1::PluginFormat format) const override;
void configureWithFormat (
const nvinfer1::Dims* inputDims, int nbInputs,
const nvinfer1::Dims* outputDims, int nbOutputs,
nvinfer1::DataType type, nvinfer1::PluginFormat format, int maxBatchSize) override;
int initialize () override { return 0; }
void terminate () override {}
size_t getWorkspaceSize (int maxBatchSize) const override { return 0; }
int enqueue (
int batchSize, const void* const* inputs, void** outputs,
void* workspace, cudaStream_t stream) override;
size_t getSerializationSize() const override;
void serialize (void* buffer) const override;
void destroy () override { delete this; }
nvinfer1::IPluginV2* clone() const override;
void setPluginNamespace (const char* pluginNamespace)override {
m_Namespace = pluginNamespace;
}
virtual const char* getPluginNamespace () const override {
return m_Namespace.c_str();
}
private:
uint m_NumBoxes {0};
uint m_NumClasses {0};
uint m_GridSize {0};
uint64_t m_OutputSize {0};
std::string m_Namespace {""};
};
class YoloLayerV3PluginCreator : public nvinfer1::IPluginCreator
{
public:
YoloLayerV3PluginCreator () {}
~YoloLayerV3PluginCreator () {}
const char* getPluginName () const override { return YOLOV3LAYER_PLUGIN_NAME; }
const char* getPluginVersion () const override { return YOLOV3LAYER_PLUGIN_VERSION; }
const nvinfer1::PluginFieldCollection* getFieldNames() override {
std::cerr<< "YoloLayerV3PluginCreator::getFieldNames is not implemented" << std::endl;
return nullptr;
}
nvinfer1::IPluginV2* createPlugin (
const char* name, const nvinfer1::PluginFieldCollection* fc) override
{
std::cerr<< "YoloLayerV3PluginCreator::getFieldNames is not implemented.\n";
return nullptr;
}
nvinfer1::IPluginV2* deserializePlugin (
const char* name, const void* serialData, size_t serialLength) override
{
std::cout << "Deserialize yoloLayerV3 plugin: " << name << std::endl;
return new YoloLayerV3(serialData, serialLength);
}
void setPluginNamespace(const char* libNamespace) override {
m_Namespace = libNamespace;
}
const char* getPluginNamespace() const override {
return m_Namespace.c_str();
}
private:
std::string m_Namespace {""};
};
#endif // __YOLO_PLUGINS__
================================================
FILE: docker/constraints.docker
================================================
scikit-learn==0.19.1
opencv-python==3.2.0
================================================
FILE: docker/opencv_python-3.2.0.egg-info
================================================
Metadata-Version: 1.1
Name: opencv-python
Version: 3.2.0
Summary: stub file to make pip aware of apt installed opencv
Home-page: UNKNOWN
Author: UNKNOWN
Author-email: UNKNOWN
License: UNKNOWN
Description: UNKNOWN
Platform: UNKNOWN
Classifier: Programming Language :: Python :: 3
================================================
FILE: docker/scikit-learn-0.19.1.egg-info
================================================
Metadata-Version: 1.1
Name: scikit-learn
Version: 0.19.1
Summary: stub file to make pip aware of apt installed package
Home-page: UNKNOWN
Author: UNKNOWN
Author-email: UNKNOWN
License: UNKNOWN
Description: UNKNOWN
Platform: UNKNOWN
Classifier: Programming Language :: Python :: 3
================================================
FILE: docker/start.sh
================================================
#!/usr/bin/env bash
nvargus-daemon &
echo
echo "Provided input:"
echo " - MASKCAM_INPUT = $MASKCAM_INPUT"
echo "Device Address:"
echo " - MASKCAM_DEVICE_ADDRESS = $MASKCAM_DEVICE_ADDRESS"
echo "Development mode:"
echo " - DEV_MODE = $DEV_MODE"
echo
echo "MQTT configuration:"
echo " - MQTT_BROKER_IP = $MQTT_BROKER_IP"
echo " - MQTT_DEVICE_NAME = $MQTT_DEVICE_NAME"
echo
if [[ $DEV_MODE -eq 1 ]]; then
echo "Development mode enabled, exec maskcam_run.py manually"
/bin/bash
else
./maskcam_run.py $MASKCAM_INPUT
fi
================================================
FILE: docker-compose.yml
================================================
version: '2'
# this file only exists for local development
# pushes to override the restart function
services:
mc_maskcam:
restart: no
build: .
privileged: true
ports:
- "1883:1883"
- "8080:8080"
- "8554:8554"
================================================
FILE: docs/BalenaOS-DevKit-Nano-Setup.md
================================================
# BalenaOS Developer Kit Nano Setup Instructions for MaskCam
BalenaOS is a very light weight distribution designed for running containers on edge devices. It has a number of advantages for fleet deployment and management, especially when combined with balena's balenaCloud mangament system. Explaining the details of how to set up balenaCloud applications is beyond the scope of this document, but you can test MaskCam on balenaOS using a local development environment setup.
Except for installing balenaOS and using a slightly modified launch command, this process is essentially the same as the Jetson Nano Development kit instructions from [the main README](https://github.com/bdtinc/maskcam#running-maskcam-from-a-container-on-a-jetson-nano-developer-kit).
If you want to use balenaCloud instead (i.e: see your device in the web dashboard), and you're willing to take some time to push the container to your own account, check [Using balenaCloud](#using-balenacloud) at the end of this section.
In any case, this will require a Jetson Nano Development Kit, a 32 GB or higher Micro-SD card, and another computer (referred to here as main system) on the same network.
### Installing balenaOS
As mentioned, this procedure will not link your device with a balenaCloud account, but instead it will enable local development.
First, go to https://www.balena.io/os/, scroll to the Download section, and download the development version for Nvidia Jetson Nano SD-CARD.
Next, go to https://www.balena.io/etcher/ and install balenaEtcher.
In balenaEtcher, simply select the zip file you downloaded, and after inserting the sd card into your main system select it, then press the 'Flash!' icon.
After the flashing process is completed, place the sd card into your Jetson Nano Development Kit, ensure the network cable is plugged into the device and power up the Jetson.
### Installing balena CLI
Use [these instructions](https://github.com/balena-io/balena-cli/blob/master/INSTALL.md) to install the balena CLI tool.
### Connecting to your Jetson
First, in a terminal on your main system run the command:
```
sudo balena scan
```
Note the ip address in the result.
Next connect to your Jetson:
```
balena ssh <device ip>
```
At this point you are in a console as root user on your Jetson running balenaOS. The commands from this point on are exactly the same as the instructions for running using JetPack on the Nano Developer Kit with the following differences.
1. The `docker` command is replaced by `balena`
2. Do not use the `--runtime nvidia` switch. It is automatic on balenaOS for Jetson and you will get errors if you include it.
So issuing the following commands will run MaskCam:
```
$ balena pull maskcam/maskcam-beta
$ balena run --privileged --rm -it --env MASKCAM_DEVICE_ADDRESS=<device ip> -p 1883:1883 -p 8080:8080 -p 8554:8554 maskcam/maskcam-beta
```
Note that setting `MASKCAM_DEVICE_ADDRESS` is optional, and you can also set other configuration parameters exactly as indicated in the [device configuration](https://github.com/bdtinc/maskcam#setting-device-configuration-parameters) section of the main docs.
### Using balenaCloud
You can create a free balenaCloud account that will allow you to link up to 10 devices, in order to test some of the most useful features that this platform provides.
You'll need to create an App, install the balena CLI and then follow these instructions in order to deploy the maskcam container to your app:
https://www.balena.io/docs/learn/deploy/deployment/
For a simple use case, you can just use the `balena push myApp` command from the root directory of this project (it will take a long time while it builds and pushes the whole image), but you should familiarize yourself with the platform and use the deployment method that better fits your needs.
================================================
FILE: docs/BalenaOS-Photon-Nano-Setup.md
================================================
# BalenaOS Setup Instructions for MaskCam on Jetson Nano with Photon Carrier Board
BalenaOS is a very light weight distribution designed for running containers on edge devices. It has a number of advantages for fleet deployment and management, especially when combined with balena's balenaCloud mangament system. Explaining the details of how to set up balenaCloud applications is beyond the scope of this document, but you can test MaskCam on balenaOS using a local development environment setup.
When using a Jetson Nano with a Photon carrier board (i.e. a "Photon Nano"), the process for installing balenaOS is different than with a Developer Kit. The production Jetson Nano module does not have an SD card slot, so balenaOS has to be directly flashed onto the device over USB, rather than using balenaEtcher. Fortunately, balena has created a flashing tool called [jetson-flash](https://github.com/balena-os/jetson-flash) that allows you to do this.
### Setting up jetson-flash
To flash the balenaOS image onto the Photon Nano, we need to use Balena's jetson-flash tool. The instructions here show how to install and use jetson-flash on an Ubuntu v18.04 PC. The tool also requires NodeJS >= v10, which can be installed on Ubuntu using [these installation instructions](https://github.com/nodesource/distributions/blob/master/README.md#installation-instructions).
First, clone the jetson-flash repository using:
```
git clone https://github.com/balena-os/jetson-flash.git
```
Next, go to the [balenaOS download page](https://www.balena.io/os/#download) and download the CTI Photon Nano Development image. Unzip the image, and move it to the jetson-flash directory.
Then, from inside the `jetson-flash` directory, issue the following command to download the NodeJS package dependencies.
```
npm install
```
Now jetson-flash is ready to be used to flash the OS image onto the Photon Nano.
### Flashing balenaOS onto the Jetson Nano over USB
Before flashing the OS, the Photon Nano has to be powered on and put into Force Recovery as shown in the [Photon manual](https://connecttech.com/ftp/pdf/CTIM_NGX002_Manual.pdf). Starting with a Photon carrier board that has a Jetson Nano module installed, plug in 12V power to the barrel jack on the carrier board. Then, press and hold SW2 for at least 10 seconds.
Plug a micro-USB cord from the Ubuntu PC to P13 on the bottom side of the Photon carrier board. Verify the board is in Force Recovery mode by issuing `lsusb` and checking that an Nvidia device is listed. If it isn't, try re-connecting the USB cable and repeating the process to put the board in Force Recovery mode.
Begin flashing by issuing the following command, where `balena.img` is replaced with the filename for the image that was downloaded and extracted previously.
```
sudo ./bin/cmd.js -f balena.img -m jetson-nano-emmc
```
This will initiate the flashing process, which takes about 10 minutes. Once it's complete, unplug the micro-USB cable and power cycle the Photon carrier board. Plug an Ethernet cable into the Photon to connect it to a local network.
### Installing balena CLI
Use [these instructions](https://github.com/balena-io/balena-cli/blob/master/INSTALL.md) to install the balena CLI tool on your Ubuntu PC.
### Connecting to your Jetson
On the Ubuntu PC, open a terminal and run:
```
sudo balena scan
```
This will report the IP address of your Photon Nano. Use this IP address with the following command to connect to your Jetson:
```
balena ssh <device ip>
```
At this point you are in a console as root user on your Jetson running balenaOS. Now, we just need to download the docker container and run it! On balenaOS, "docker" is replaced by "balena", as shown in the following command. Issue the two commands below to download and run MaskCam:
```
$ balena pull maskcam/maskcam-beta
$ balena run --privileged --rm -it --env MASKCAM_DEVICE_ADDRESS=<device ip> -p 1883:1883 -p 8080:8080 -p 8554:8554 maskcam/maskcam-beta
```
Note that setting `MASKCAM_DEVICE_ADDRESS` is optional, and you can also set other configuration parameters exactly as indicated in the [device configuration](https://github.com/bdtinc/maskcam#setting-device-configuration-parameters) section of the main docs.
### Using balenaCloud
You can create a free balenaCloud account that will allow you to link up to 10 devices, in order to test some of the most useful features that this platform provides.
You'll need to create an App, install the balena CLI and then follow these instructions in order to deploy the maskcam container to your app:
https://www.balena.io/docs/learn/deploy/deployment/
For a simple use case, you can just use the `balena push myApp` command from the root directory of this project (it will take a long time while it builds and pushes the whole image), but you should familiarize yourself with the platform and use the deployment method that better fits your needs.
================================================
FILE: docs/Custom-Container-Development.md
================================================
# Custom Container Development
The MaskCam code in this repository can be used as a starting point for developing your own smart camera application. If you'd like to develop a custom application (for example, a dog detector that counts how many dogs walk past your house and reports the count to a server), you can build your own container that has the custom code, files, and packages used for your unique application. This page gives instructions on how to build a custom container, rather than downloading our pre-built container from Docker.
This page is split in to two sections:
- [How to Build Your Own Container from Source on the Jetson Nano](#how-to-build-your-own-container-from-source-on-the-jetson-nano)
- [How to Use Your Own Detection Model](#how-to-use-your-own-detection-model)
## How to Build Your Own Container from Source on the Jetson Nano
The easiest way to get Maskcam running or set up for development purposes, is by using a container like the one provided in the main [Dockerfile](Dockerfile), which provides the right versions of the OS (Ubuntu 18.04 / Bionic Beaver) and all the system level packages required (mainly NVIDIA L4T packages, GStreamer and DeepStream among others).
For development, you could make modifications to the code or the container definition, and then rebuild locally using:
```
docker build . -t maskcam_custom
```
The above building step could be executed in the target Jetson Nano device (easier), or in another development environment (i.e: pushing the result to [Docker Hub](https://hub.docker.com/) and then pulling from device).
Either way, once the image is ready on the device, remember to run the container using the `--runtime nvidia` and `--privileged` flags (to access the camera device), and mapping the used ports (MQTT -1883-, static file serving -8080- and streaming -8554-, as defined in [maskcam_config.txt](maskcam_config.txt)):
```
docker run --runtime nvidia --privileged --rm -it -p 1883:1883 -p 8080:8080 -p 8554:8554 maskcam_custom
```
If you still want to better understand some of the [Dockerfile](Dockerfile) steps, or you need to run without a container and are willing to deal with version conflicts, please see the dependencies manual installation and building instructions at [docs/Manual-Dependency-Installation.md](docs/Manual-Dependencies-Installation.md)
## How to Use Your Own Detection Model
As mentioned above, MaskCam is a reference design for smart camera applications that need to perform computer vision tasks on the edge. Specifically, those involving **Object Detection** (for which you'll need a TensorRT engine) and **Tracking** (for which we use [Norfair](https://github.com/tryolabs/norfair)).
Depending on the degree of similarity with this particular use case, you might need to just change the configuration file or some parts of the source code.
### Changing the DeepStream model
If you train a new model that is compatible with DeepStream, and has exactly the same (or a subset of the) object classes that are used in this project (`mask`, `no_mask`, `not_visible`, `misplaced`), then you only need to edit the configuration file.
In particular, you should change only the corresponding parts of the [maskcam_config.txt](maskcam_config.txt) file, which are under the `[property]` section, and make them match your app's configuration parameters (usually under a file `config_infer_primary.txt` in NVIDIA sample apps). You should not need to change any of the `[face-processor]`, `[mqtt]` or `[maskcam]` sections of the config file, in order to use a new compatible model. Also, note that the `interval` parameter of that section will be ignored when `inference-interval-auto` is enabled.
As an example, you'll find there's commented code showing how to use a `Detectnet_v2` model like the one trained using the [NVIDIA facemask app](https://github.com/NVIDIA-AI-IOT/face-mask-detection), but after converting the label names as mentioned above.
Check the [DeepStream docs](https://docs.nvidia.com/metropolis/deepstream/dev-guide/text/DS_using_custom_model.html) for more information about how to convert a model in order to use it with DeepStream (in particular, the `nvinfer` GStreamer plugin).
Remember to include your new model engine file in the [Dockerfile](Dockerfile) before building the container!
### Changing the object labels
If your custom model does not have exactly the same label names, you should edit the [maskcam_inference.py](maskcam/maskcam_inference.py) file, and change the constants `LABEL_MASK`, `LABEL_NO_MASK`, `LABEL_MISPLACED` and `LABEL_NOT_VISIBLE`, to match your needs.
If your application has nothing to do with detecting face masks, then you'll probably need to change many other parts of the source code for this application, but a good place to start is the `FaceMaskProcessor` class definition, used in the same inference file, which contains all the code related to the DeepStream pipeline.
================================================
FILE: docs/Manual-Dependencies-Installation.md
================================================
## Manual installation and building of dependencies
These instructions are aimed to manually recreate a native environment similar to the one produced by the [Dockerfile](Dockerfile).
They are tested on **Ubuntu 18.04 (Bionic Beaver)** with **Jetpack 4.4.1**.
1. Make sure these packages are installed at system level (other required packages are not listed here since they're included with Jetpack, check the [Dockerfile](Dockerfile) for a complete list):
```
sudo apt install git, python3-pip, python3-opencv python3-libnvinfer python-gi-dev cuda-toolkit-10-2
```
2. Clone this repo:
```
git clone <copy https or ssh url>.git
```
3. Copy any `.egg-info` file under `docker/` to the python's `dist-packages` dir, so that system-level installed packages are visible by Pypi:
```
sudo cp docker/*.egg-info /usr/lib/python3/dist-packages/
```
4. Install the requirements listed on `requirements.txt`:
```
pip3 install -r requirements.txt
```
If any version above fails or you want to ignore the pinned versions for some reason, try:
```
# Only run this if you don't want to use the pinned versions
pip3 install -r requirements.in -c docker/constraints.docker
```
5. Install Nvidia DeepStream:
Aside from the system requirements of th previous step, you also need to install
[DeepStream 5.0](https://docs.nvidia.com/metropolis/deepstream/dev-guide/text/DS_Quickstart.html#jetson-setup)
(no need to install Kafka protocol adaptor)
and also make sure to install the corresponding **python bindings** for GStreamer
[gst-python](https://docs.nvidia.com/metropolis/deepstream/dev-guide/text/DS_Python_Sample_Apps.html#python-bindings),
and for DeepStream [pyds](https://docs.nvidia.com/metropolis/deepstream/dev-guide/text/DS_Python_Sample_Apps.html#metadata-access).
6. Compile YOLOv4 plugin for DeepStream:
After installing DeepStream, compile the YOLOv4 plugin for DeepStream:
```
cd <this repo path>/deepstream_plugin_yolov4
export CUDA_VER=10.2
make
```
If all went well, you should see a library `libnvdsinfer_custom_impl_Yolo.so` in that directory.
7. Download TensorRT engine file from [here](https://maskcam.s3.us-east-2.amazonaws.com/facemask_y4tiny_1024_608_fp16.trt) and save it as `yolo/facemask_y4tiny_1024_608_fp16.trt`.
8. Now you should be ready to run. By default, the device `/dev/video0` will be used, but other devices can be set as first argument:
```bash
# Use default input camera /dev/video0
python3 maskcam_run.py
# Equivalent as above:
python3 maskcam_run.py v4l2:///dev/video0
# Process an mp4 file instead (no network functions, MQTT and static file server disabled)
python3 maskcam_run.py file:///path/to/video.mp4
# Read from Raspi2 camera using device-id
python3 maskcam_run.py argus:///0
```
Check the main [README.md](README) for more parameters that can be configured before running, using environment variables.
================================================
FILE: docs/Useful-Development-Scripts.md
================================================
# Useful development scripts
These scripts are intended to be used by developers. They require some knowledge on the subject they're used for.
## Running TensorRT engine on images
This script will run the engine on a folder of images, and generate another folder
for the images with the bounding boxes drawn, and the detection score.
To run this script, you need basically the same general instructions that the regular installation, except that you don't need DeepStream and you do need OpenCV instead.
Usage:
```
cd yolo/
python3 run_yolo_images.py path/to/input/folder path/to/output/folder
```
## Debugging MQTT communication
If you want to see the raw messages that the MQTT broker receives,
and be able to send custom messages to the device (at your own risk),
there's a script `maskcam/mqtt_commander.py`, which may be useful for debugging
on your local computer or from the Jetson device itself.
The script connects to the MQTT broker and sniffs all the communication to/from any device to the broker.
```
export MQTT_BROKER_IP=<server ip (local or remote)>
export MQTT_DEVICE_NAME=<device to command>
python3 -m maskcam.mqtt_commander
```
## Convert weights generated using the original darknet implementation to TRT
1. Clone the pytorch implementation of YOLOv4:
```
git clone git@github.com:Tianxiaomo/pytorch-YOLOv4.git
```
2. Convert the Darknet model to ONNX using the script in `tool/darknet2onnx.py`, e.g:
```
PYTHONPATH='pytorch-YOLOv4:$PYTHONPATH' python3 pytorch-YOLOv4/tool/darknet2onnx.py yolo/facemask-yolov4-tiny.cfg yolo/facemask-yolov4-tiny_best.weights <optional batch size>
```
3. Convert the ONNX model to TRT (on the Jetson Nano, `trtexec` can be found under `/usr/src/tensorrt/bin/trtexec`):
```
/usr/src/tensorrt/bin/trtexec --fp16 --onnx=../yolo/yolov4_1_3_608_608_static.onnx --explicitBatch --saveEngine=tensorrt_fp16.trt
```
================================================
FILE: maskcam/common.py
================================================
################################################################################
# Copyright (c) 2020-2021, Berkeley Design Technology, Inc. All rights reserved.
#
# Permission is hereby granted, free of charge, to any person obtaining a
# copy of this software and associated documentation files (the "Software"),
# to deal in the Software without restriction, including without limitation
# the rights to use, copy, modify, merge, publish, distribute, sublicense,
# and/or sell copies of the Software, and to permit persons to whom the
# Software is furnished to do so, subject to the following conditions:
#
# The above copyright notice and this permission notice shall be included in
# all copies or substantial portions of the Software.
#
# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL
# THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
# FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
# DEALINGS IN THE SOFTWARE.
################################################################################
CODEC_MP4 = "MP4"
CODEC_H265 = "H265"
CODEC_H264 = "H264"
USBCAM_PROTOCOL = "v4l2://" # Invented by us since there's no URI for this
RASPICAM_PROTOCOL = "argus://" # Invented by us since there's no URI for this
CONFIG_FILE = "maskcam_config.txt" # Also used in nvinfer element
# Available commands (to send internally, between processes or via MQTT)
CMD_FILE_SAVE = "save_file"
CMD_STREAMING_START = "streaming_start"
CMD_STREAMING_STOP = "streaming_stop"
CMD_INFERENCE_RESTART = "inference_restart"
CMD_FILESERVER_RESTART = "fileserver_restart"
CMD_STATUS_REQUEST = "status_request"
================================================
FILE: maskcam/config.py
================================================
import os
import configparser
from maskcam.common import CONFIG_FILE
from maskcam.prints import print_common as print
config = configparser.ConfigParser()
config.read(CONFIG_FILE)
config.sections()
# Environment variables overriding config file values
# Each row is: (ENV_VAR_NAME, (config-section, config-param))
ENV_CONFIG_OVERRIDES = (
("MASKCAM_INPUT", ("maskcam", "default-input")), # Redundant with start.sh script
("MASKCAM_DEVICE_ADDRESS", ("maskcam", "device-address")),
("MASKCAM_DETECTION_THRESHOLD", ("face-processor", "detection-threshold")),
("MASKCAM_VOTING_THRESHOLD", ("face-processor", "voting-threshold")),
("MASKCAM_MIN_FACE_SIZE", ("face-processor", "min-face-size")),
("MASKCAM_DISABLE_TRACKER", ("face-processor", "disable-tracker")),
("MASKCAM_ALERT_MIN_VISIBLE_PEOPLE", ("maskcam", "alert-min-visible-people")),
("MASKCAM_ALERT_MAX_TOTAL_PEOPLE", ("maskcam", "alert-max-total-people")),
("MASKCAM_ALERT_NO_MASK_FRACTION", ("maskcam", "alert-no-mask-fraction")),
("MASKCAM_STATISTICS_PERIOD", ("maskcam", "statistics-period")),
("MASKCAM_TIMEOUT_INFERENCE_RESTART", ("maskcam", "timeout-inference-restart")),
("MASKCAM_CAMERA_FRAMERATE", ("maskcam", "camera-framerate")),
("MASKCAM_CAMERA_FLIP_METHOD", ("maskcam", "camera-flip-method")),
("MASKCAM_OUTPUT_VIDEO_WIDTH", ("maskcam", "output-video-width")),
("MASKCAM_OUTPUT_VIDEO_HEIGHT", ("maskcam", "output-video-height")),
("MASKCAM_INFERENCE_INTERVAL_AUTO", ("maskcam", "inference-interval-auto")),
("MASKCAM_INFERENCE_MAX_FPS", ("maskcam", "inference-max-fps")),
("MASKCAM_INFERENCE_LOG_INTERVAL", ("maskcam", "inference-log-interval")),
("MASKCAM_STREAMING_START_DEFAULT", ("maskcam", "streaming-start-default")),
("MASKCAM_STREAMING_PORT", ("maskcam", "streaming-port")),
("MASKCAM_FILESERVER_ENABLED", ("maskcam", "fileserver-enabled")),
("MASKCAM_FILESERVER_FORCE_SAVE", ("maskcam", "fileserver-force-save")),
("MASKCAM_FILESERVER_VIDEO_PERIOD", ("maskcam", "fileserver-video-period")),
("MASKCAM_FILESERVER_VIDEO_DURATION", ("maskcam", "fileserver-video-duration")),
("MASKCAM_FILESERVER_HDD_DIR", ("maskcam", "fileserver-hdd-dir")),
("MQTT_BROKER_IP", ("mqtt", "mqtt-broker-ip")),
("MQTT_BROKER_PORT", ("mqtt", "mqtt-broker-port")),
("MQTT_DEVICE_NAME", ("mqtt", "mqtt-device-name")),
("MQTT_DEVICE_DESCRIPTION", ("mqtt", "mqtt-device-description")),
)
# Apply overrides
for env_var, config_param in ENV_CONFIG_OVERRIDES:
override_value = os.environ.get(env_var, None)
if override_value is not None:
config[config_param[0]][config_param[1]] = override_value
def print_config_overrides():
# Leave prints separated so that it can be executed on demand
# by one single process instead of each import
for env_var, config_param in ENV_CONFIG_OVERRIDES:
override_value = os.environ.get(env_var, None)
if override_value is not None:
print(f"\nConfig override {env_var}={override_value}")
================================================
FILE: maskcam/maskcam_filesave.py
================================================
#!/usr/bin/env python3
################################################################################
# Copyright (c) 2020-2021, Berkeley Design Technology, Inc. All rights reserved.
#
# Permission is hereby granted, free of charge, to any person obtaining a
# copy of this software and associated documentation files (the "Software"),
# to deal in the Software without restriction, including without limitation
# the rights to use, copy, modify, merge, publish, distribute, sublicense,
# and/or sell copies of the Software, and to permit persons to whom the
# Software is furnished to do so, subject to the following conditions:
#
# The above copyright notice and this permission notice shall be included in
# all copies or substantial portions of the Software.
#
# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL
# THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
# FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
# DEALINGS IN THE SOFTWARE.
################################################################################
import os
import gi
import pyds
import sys
import time
import signal
import platform
import threading
import multiprocessing as mp
from datetime import datetime
gi.require_version("Gst", "1.0")
gi.require_version("GstBase", "1.0")
gi.require_version("GstRtspServer", "1.0")
from gi.repository import GLib, Gst, GstRtspServer, GstBase
from .prints import print_filesave as print
from .common import CODEC_MP4, CODEC_H264, CODEC_H265, CONFIG_FILE
from .utils import glib_cb_restart
from .config import config, print_config_overrides
e_interrupt = None
def make_elm_or_print_err(factoryname, name, printedname, detail=""):
"""Creates an element with Gst Element Factory make.
Return the element if successfully created, otherwise print
to stderr and return None.
"""
print("Creating", printedname)
elm = Gst.ElementFactory.make(factoryname, name)
if not elm:
print("Unable to create " + printedname, error=True)
if detail:
print(detail)
return elm
def sigint_handler(sig, frame):
# This function is not used if e_external_interrupt is provided
print("[red]Ctrl+C pressed. Interrupting file-save...[/red]")
e_interrupt.set()
def main(
config: dict,
output_filename: str,
udp_port: int,
e_external_interrupt: mp.Event = None,
):
global e_interrupt
codec = config["maskcam"]["codec"]
streaming_clock_rate = int(config["maskcam"]["streaming-clock-rate"])
udp_capabilities = f"application/x-rtp,media=video,encoding-name=(string){codec},clock-rate={streaming_clock_rate}"
# Standard GStreamer initialization
# GObject.threads_init() # Doesn't seem necessary (see https://pygobject.readthedocs.io/en/latest/guide/threading.html)
Gst.init(None)
# Create gstreamer elements
# Create Pipeline element that will form a connection of other elements
print(
"[green]Creating:[/green] file-saving pipeline "
f"UDP(port:{udp_port})->File({output_filename})"
)
pipeline = Gst.Pipeline()
if not pipeline:
print("Unable to create Pipeline", error=True)
udpsrc = make_elm_or_print_err("udpsrc", "udpsrc", "UDP Source")
udpsrc.set_property("port", udp_port)
udpsrc.set_property("buffer-size", 524288)
udpsrc.set_property("caps", Gst.Caps.from_string(udp_capabilities))
rtpjitterbuffer = make_elm_or_print_err(
"rtpjitterbuffer", "rtpjitterbuffer", "RTP Jitter Buffer"
)
# Default mode is 1 (slave), acts as a live source and gets laggy
rtpjitterbuffer.set_property("mode", 4)
# caps_udp = make_elm_or_print_err("capsfilter", "caps_udp", "UDP RTP capabilities")
# caps_udp.set_property("caps", Gst.Caps.from_string(udp_capabilities))
if codec == CODEC_MP4:
print("Creating MPEG-4 payload decoder")
rtpdepay = make_elm_or_print_err("rtpmp4vpay", "rtpdepay", "RTP MPEG-4 Payload Decoder")
codeparser = make_elm_or_print_err("mpeg4videoparse", "mpeg4-parser", "Code Parser")
elif codec == CODEC_H264:
print("Creating H264 payload decoder")
rtpdepay = make_elm_or_print_err("rtph264depay", "rtpdepay", "RTP H264 Payload Decoder")
codeparser = make_elm_or_print_err("h264parse", "h264-parser", "Code Parser")
else: # Default: H265 (recommended)
print("Creating H265 payload decoder")
rtpdepay = make_elm_or_print_err("rtph265depay", "rtpdepay", "RTP H265 Payload Decoder")
codeparser = make_elm_or_print_err("h265parse", "h265-parser", "Code Parser")
# Workaround for this issue: https://gitlab.freedesktop.org/gstreamer/gst-plugins-good/-/issues/410
GstBase.BaseParse.set_pts_interpolation(codeparser, True)
container = make_elm_or_print_err("qtmux", "qtmux", "Container")
filesink = make_elm_or_print_err("filesink", "filesink", "File Sink")
filesink.set_property("location", output_filename)
# filesink.set_property("sync", False)
# filesink.set_property("async", False)
pipeline.add(udpsrc)
pipeline.add(rtpjitterbuffer)
# pipeline.add(caps_udp)
pipeline.add(rtpdepay)
pipeline.add(codeparser)
pipeline.add(container)
pipeline.add(filesink)
# Pipeline Links
udpsrc.link(rtpjitterbuffer)
rtpjitterbuffer.link(rtpdepay)
# caps_udp.link(rtpdepay)
rtpdepay.link(codeparser)
codeparser.link(container)
container.link(filesink)
# GLib loop required for RTSP server
g_loop = GLib.MainLoop()
g_context = g_loop.get_context()
# GStreamer message bus
bus = pipeline.get_bus()
if e_external_interrupt is None:
# Use threading instead of mp.Event() for sigint_handler, see:
# https://bugs.python.org/issue41606
e_interrupt = threading.Event()
signal.signal(signal.SIGINT, sigint_handler)
print("[green bold]Press Ctrl+C to save video and exit[/green bold]")
else:
# If there's an external interrupt, don't capture SIGINT
e_interrupt = e_external_interrupt
# Periodic gloop interrupt (see utils.glib_cb_restart)
t_check = 50
GLib.timeout_add(t_check, glib_cb_restart, t_check)
# Custom event loop, allows saving file on Ctrl+C press
running = True
# start play back and listen to events
pipeline.set_state(Gst.State.PLAYING)
print("[green]Playing:[/green] file-saving pipeline UDP->File\n")
while running:
g_context.iteration(may_block=True)
message = bus.pop()
if message is not None:
t = message.type
if t == Gst.MessageType.EOS:
print(f"File saved: [yellow]{output_filename}[/yellow]")
running = False
elif t == Gst.MessageType.WARNING:
err, debug = message.parse_warning()
print("%s: %s" % (err, debug), warning=True)
elif t == Gst.MessageType.ERROR:
err, debug = message.parse_error()
print("%s: %s" % (err, debug), error=True)
running = False
if e_interrupt.is_set():
print("Interruption received. Sending EOS to generate video file.")
# This will allow the filesink to create a readable mp4 file
container.send_event(Gst.Event.new_eos())
e_interrupt.clear()
print("File-saver main loop ending.")
# cleanup
pipeline.set_state(Gst.State.NULL)
if __name__ == "__main__":
# Print any ENV var config override to avoid confusions
print_config_overrides()
# Check arguments
output_filename = None
udp_port = None
if len(sys.argv) > 1:
output_filename = sys.argv[1]
if len(sys.argv) > 2:
udp_port = int(sys.argv[2])
if not output_filename:
output_dir = config["maskcam"]["fileserver-hdd-dir"]
output_filename = f"{output_dir}/{datetime.today().strftime('%Y%m%d_%H%M%S')}.mp4"
if not udp_port: # Use first listed in config
udp_port = int(config["maskcam"]["udp-ports-filesave"].split(",")[0])
print(f"Output file: {output_filename}")
sys.exit(main(config=config, output_filename=output_filename, udp_port=udp_port))
================================================
FILE: maskcam/maskcam_fileserver.py
================================================
#!/usr/bin/env python3
################################################################################
# Copyright (c) 2020-2021, Berkeley Design Technology, Inc. All rights reserved.
#
# Permission is hereby granted, free of charge, to any person obtaining a
# copy of this software and associated documentation files (the "Software"),
# to deal in the Software without restriction, including without limitation
# the rights to use, copy, modify, merge, publish, distribute, sublicense,
# and/or sell copies of the Software, and to permit persons to whom the
# Software is furnished to do so, subject to the following conditions:
#
# The above copyright notice and this permission notice shall be included in
# all copies or substantial portions of the Software.
#
# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL
# THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
# FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
# DEALINGS IN THE SOFTWARE.
################################################################################
import os
import sys
import time
import socket
import threading
import multiprocessing as mp
from datetime import datetime
from http.server import SimpleHTTPRequestHandler
from socketserver import TCPServer, ThreadingTCPServer
from .config import config, print_config_overrides
from .utils import get_ip_address
from .prints import print_fileserver as print
class Handler(SimpleHTTPRequestHandler):
# Needed to set extensions_map
pass
def start_server(httpd_server):
httpd_server.serve_forever(poll_interval=0.5)
def cb_handle_error(request, client_address):
# Not important, happens very often but nothing actually fails
print(f"Static file server: File request interrupted [client: {client_address}]")
def main(config, directory=None, e_external_interrupt: mp.Event = None):
if directory is None:
directory = config["maskcam"]["fileserver-hdd-dir"]
directory = os.fspath(directory)
print(f"Serving static files from directory: [yellow]{directory}[/yellow]")
port = int(config["maskcam"]["fileserver-port"])
# Create dir if doesn't exist
os.system(f"mkdir -p {directory}")
os.chdir(directory) # easiest way
# Force download mp4 files
Handler.extensions_map[".mp4"] = "application/octet-stream"
print(f"[green]Static server STARTED[/green] at http://{get_ip_address()}:{port}")
with ThreadingTCPServer(("", port), Handler) as httpd:
httpd.handle_error = cb_handle_error
s = threading.Thread(target=start_server, args=(httpd,))
s.start()
try:
if e_external_interrupt is not None:
e_external_interrupt.wait() # blocking
else:
s.join() # blocking
except KeyboardInterrupt:
print("Ctrl+C pressed")
print("Shutting down static file server")
httpd.shutdown()
httpd.server_close()
s.join(timeout=1)
if s.is_alive():
print("Server thread did not stop", warning=True)
else:
print("Server shut down correctly")
print(f"Server alive threads: {threading.enumerate()}")
if __name__ == "__main__":
# Print any ENV var config override to avoid confusions
print_config_overrides()
# Input source
directory = sys.argv[1] if len(sys.argv) > 1 else None
main(config, directory=directory)
================================================
FILE: maskcam/maskcam_inference.py
================================================
#!/usr/bin/env python3
################################################################################
# Copyright (c) 2020-2021, Berkeley Design Technology, Inc. All rights reserved.
#
# Permission is hereby granted, free of charge, to any person obtaining a
# copy of this software and associated documentation files (the "Software"),
# to deal in the Software without restriction, including without limitation
# the rights to use, copy, modify, merge, publish, distribute, sublicense,
# and/or sell copies of the Software, and to permit persons to whom the
# Software is furnished to do so, subject to the following conditions:
#
# The above copyright notice and this permission notice shall be included in
# all copies or substantial portions of the Software.
#
# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL
# THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
# FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
# DEALINGS IN THE SOFTWARE.
################################################################################
import os
import gi
import pyds
import sys
import ipdb
import time
import signal
import platform
import threading
import numpy as np
import multiprocessing as mp
from rich.console import Console
from datetime import datetime, timezone
gi.require_version("Gst", "1.0")
gi.require_version("GstRtspServer", "1.0")
from gi.repository import GLib, Gst, GstRtspServer
from norfair.tracker import Tracker, Detection
from .config import config, print_config_overrides
from .prints import print_inference as print
from .common import (
CODEC_MP4,
CODEC_H264,
CODEC_H265,
USBCAM_PROTOCOL,
RASPICAM_PROTOCOL,
CONFIG_FILE,
)
from .utils import glib_cb_restart, load_udp_ports_filesaving
# YOLO labels. See obj.names file
LABEL_MASK = "mask"
LABEL_NO_MASK = "no_mask" # YOLOv4: no_mask
LABEL_MISPLACED = "misplaced"
LABEL_NOT_VISIBLE = "not_visible"
FRAMES_LOG_INTERVAL = int(config["maskcam"]["inference-log-interval"])
# Global vars
frame_number = 0
start_time = None
end_time = None
console = Console()
e_interrupt = None
class FaceMaskProcessor:
def __init__(
self, th_detection=0, th_vote=0, min_face_size=0, tracker_period=1, disable_tracker=False
):
self.people_votes = {}
self.current_people = set()
self.th_detection = th_detection
self.th_vote = th_vote
self.tracker_period = tracker_period
self.min_face_size = min_face_size
self.disable_detection_validation = False
self.min_votes = 5
self.max_votes = 50
self.color_mask = (0.0, 1.0, 0.0) # green
self.color_no_mask = (1.0, 0.0, 0.0) # red
self.color_unknown = (1.0, 1.0, 0.0) # yellow
self.draw_raw_detections = disable_tracker
self.draw_tracked_people = not disable_tracker
self.stats_lock = threading.Lock()
# Norfair Tracker
if disable_tracker:
self.tracker = None
else:
self.tracker = Tracker(
distance_function=self.keypoints_distance,
detection_threshold=self.th_detection,
distance_threshold=1,
point_transience=8,
hit_inertia_min=15,
hit_inertia_max=45,
)
def keypoints_distance(self, detected_pose, tracked_pose):
detected_points = detected_pose.points
estimated_pose = tracked_pose.estimate
min_box_size = min(
max(
detected_points[1][0] - detected_points[0][0], # x2 - x1
detected_points[1][1] - detected_points[0][1], # y2 - y1
1,
),
max(
estimated_pose[1][0] - estimated_pose[0][0], # x2 - x1
estimated_pose[1][1] - estimated_pose[0][1], # y2 - y1
1,
),
)
mean_distance_normalized = (
np.mean(np.linalg.norm(detected_points - estimated_pose, axis=1)) / min_box_size
)
return mean_distance_normalized
def validate_detection(self, box_points, score, label):
if self.disable_detection_validation:
return True
box_width = box_points[1][0] - box_points[0][0]
box_height = box_points[1][1] - box_points[0][1]
return min(box_width, box_height) >= self.min_face_size and score >= self.th_detection
def add_detection(self, person_id, label, score):
# This function is called from streaming thread
with self.stats_lock:
self.current_people.add(person_id)
if person_id not in self.people_votes:
self.people_votes[person_id] = 0
if score > self.th_vote:
if label == LABEL_MASK:
self.people_votes[person_id] += 1
elif label == LABEL_NO_MASK or LABEL_MISPLACED:
self.people_votes[person_id] -= 1
# max_votes limit
self.people_votes[person_id] = np.clip(
self.people_votes[person_id], -self.max_votes, self.max_votes
)
def get_person_label(self, person_id):
person_votes = self.people_votes[person_id]
if abs(person_votes) >= self.min_votes:
color = self.color_mask if person_votes > 0 else self.color_no_mask
label = "mask" if person_votes > 0 else "no mask"
else:
color = self.color_unknown
label = "not visible"
return f"{person_id}|{label}({abs(person_votes)})", color
def get_instant_statistics(self, refresh=True):
"""
Get statistics only including people that appeared on camera since last refresh
"""
instant_stats = self.get_statistics(filter_ids=self.current_people)
if refresh:
with self.stats_lock:
self.current_people = set()
return instant_stats
def get_statistics(self, filter_ids=None):
with self.stats_lock:
if filter_ids is not None:
filtered_people = {
id: votes for id, votes in self.people_votes.items() if id in filter_ids
}
else:
filtered_people = self.people_votes
total_people = len(filtered_people)
total_classified = 0
total_mask = 0
for person_id in filtered_people:
person_votes = filtered_people[person_id]
if abs(person_votes) >= self.min_votes:
total_classified += 1
if person_votes > 0:
total_mask += 1
return total_people, total_classified, total_mask
def cb_add_statistics(cb_args):
stats_period, stats_queue, face_processor = cb_args
people_total, people_classified, people_mask = face_processor.get_instant_statistics(
refresh=True
)
people_no_mask = people_classified - people_mask
# stats_queue is an mp.Queue optionally provided externally (in main())
stats_queue.put_nowait(
{
"people_total": people_total,
"people_with_mask": people_mask,
"people_without_mask": people_no_mask,
"timestamp": datetime.timestamp(datetime.now(timezone.utc)),
}
)
# Next report timeout
GLib.timeout_add_seconds(stats_period, cb_add_statistics, cb_args)
def sigint_handler(sig, frame):
# This function is not used if e_external_interrupt is provided
print("[red]Ctrl+C pressed. Interrupting inference...[/red]")
e_interrupt.set()
def is_aarch64():
return platform.uname()[4] == "aarch64"
def draw_detection(display_meta, n_draw, box_points, detection_label, color):
# print(f"Drawing {n_draw} | {detection_label}")
# print(box_points)
rect = display_meta.rect_params[n_draw]
((x1, y1), (x2, y2)) = box_points
rect.left = x1
rect.top = y1
rect.width = x2 - x1
rect.height = y2 - y1
# print(f"{x1} {y1}, {x2} {y2}")
# Bug: bg color is always green
# rect.has_bg_color = True
# rect.bg_color.set(0.5, 0.5, 0.5, 0.6) # RGBA
rect.border_color.set(*color, 1.0)
rect.border_width = 2
label = display_meta.text_params[n_draw]
label.x_offset = x1
label.y_offset = y2
label.font_params.font_name = "Verdana"
label.font_params.font_size = 9
label.font_params.font_color.set(0, 0, 0, 1.0) # Black
# label.display_text = f"{person.id} | {detection_p:.2f}"
label.display_text = detection_label
label.set_bg_clr = True
label.text_bg_clr.set(*color, 0.5)
display_meta.num_rects = n_draw + 1
display_meta.num_labels = n_draw + 1
def cb_buffer_probe(pad, info, cb_args):
global frame_number
global start_time
face_processor, e_ready = cb_args
gst_buffer = info.get_buffer()
if not gst_buffer:
print("Unable to get GstBuffer", error=True)
return
# Set e_ready event to notify the pipeline is working (e.g: for orchestrator)
if e_ready is not None and not e_ready.is_set():
print("Inference pipeline setting [green]e_ready[/green]")
e_ready.set()
# Retrieve batch metadata from the gst_buffer
# Note that pyds.gst_buffer_get_nvds_batch_meta() expects the
# C address of gst_buffer as input, which is obtained with hash(gst_buffer)
batch_meta = pyds.gst_buffer_get_nvds_batch_meta(hash(gst_buffer))
l_frame = batch_meta.frame_meta_list
while l_frame is not None:
try:
# Note that l_frame.data needs a cast to pyds.NvDsFrameMeta
# The casting is done by pyds.glist_get_nvds_frame_meta()
# The casting also keeps ownership of the underlying memory
# in the C code, so the Python garbage collector will leave
# it alone.
# frame_meta = pyds.glist_get_nvds_frame_meta(l_frame.data)
frame_meta = pyds.NvDsFrameMeta.cast(l_frame.data)
except StopIteration:
break
frame_number = frame_meta.frame_num
# num_detections = frame_meta.num_obj_meta
l_obj = frame_meta.obj_meta_list
detections = []
obj_meta_list = []
while l_obj is not None:
try:
# Casting l_obj.data to pyds.NvDsObjectMeta
# obj_meta=pyds.glist_get_nvds_object_meta(l_obj.data)
obj_meta = pyds.NvDsObjectMeta.cast(l_obj.data)
except StopIteration:
break
obj_meta_list.append(obj_meta)
obj_meta.rect_params.border_color.set(0.0, 0.0, 1.0, 0.0)
box = obj_meta.rect_params
# print(f"{obj_meta.obj_label} | {obj_meta.confidence}")
box_points = (
(box.left, box.top),
(box.left + box.width, box.top + box.height),
)
box_p = obj_meta.confidence
box_label = obj_meta.obj_label
if face_processor.validate_detection(box_points, box_p, box_label):
det_data = {"label": box_label, "p": box_p}
detections.append(
Detection(
np.array(box_points),
data=det_data,
)
)
# print(f"Added detection: {det_data}")
try:
l_obj = l_obj.next
except StopIteration:
break
# Remove all object meta to avoid drawing. Do this outside while since we're modifying list
for obj_meta in obj_meta_list:
# Remove this to avoid drawing label texts
pyds.nvds_remove_obj_meta_from_frame(frame_meta, obj_meta)
obj_meta_list = None
# Each meta object carries max 16 rects/labels/etc.
max_drawings_per_meta = 16 # This is hardcoded, not documented
if face_processor.tracker is not None:
# Track, count and draw tracked people
tracked_people = face_processor.tracker.update(
detections, period=face_processor.tracker_period
)
# Filter out people with no live points (don't draw)
drawn_people = [person for person in tracked_people if person.live_points.any()]
if face_processor.draw_tracked_people:
for n_person, person in enumerate(drawn_people):
points = person.estimate
box_points = points.clip(0).astype(int)
# Update mask votes
face_processor.add_detection(
person.id,
person.last_detection.data["label"],
person.last_detection.data["p"],
)
label, color = face_processor.get_person_label(person.id)
# Index of this person's drawing in the current meta
n_draw = n_person % max_drawings_per_meta
if n_draw == 0: # Initialize meta
# Acquiring a display meta object. The memory ownership remains in
# the C code so downstream plugins can still access it. Otherwise
# the garbage collector will claim it when this probe function exits.
display_meta = pyds.nvds_acquire_display_meta_from_pool(batch_meta)
pyds.nvds_add_display_meta_to_frame(frame_meta, display_meta)
draw_detection(display_meta, n_draw, box_points, label, color)
# Raw detections
if face_processor.draw_raw_detections:
for n_detection, detection in enumerate(detections):
points = detection.points
box_points = points.clip(0).astype(int)
label = detection.data["label"]
if label == LABEL_MASK:
color = face_processor.color_mask
elif label == LABEL_NO_MASK or label == LABEL_MISPLACED:
color = face_processor.color_no_mask
else:
color = face_processor.color_unknown
label = f"{label} | {detection.data['p']:.2f}"
n_draw = n_detection % max_drawings_per_meta
if n_draw == 0: # Initialize meta
# Acquiring a display meta object. The memory ownership remains in
# the C code so downstream plugins can still access it. Otherwise
# the garbage collector will claim it when this probe function exits.
display_meta = pyds.nvds_acquire_display_meta_from_pool(batch_meta)
pyds.nvds_add_display_meta_to_frame(frame_meta, display_meta)
draw_detection(display_meta, n_draw, box_points, label, color)
# Using pyds.get_string() to get display_text as string
# print(pyds.get_string(py_nvosd_text_params.display_text))
# print(".", end="", flush=True)
# print("")
if not frame_number % FRAMES_LOG_INTERVAL:
print(f"Processed {frame_number} frames...")
try:
l_frame = l_frame.next
except StopIteration:
break
# Start timer at the end of first frame processing
if start_time is None:
start_time = time.time()
return Gst.PadProbeReturn.OK
def cb_newpad(decodebin, decoder_src_pad, data):
print("In cb_newpad\n")
caps = decoder_src_pad.get_current_caps()
gststruct = caps.get_structure(0)
gstname = gststruct.get_name()
source_bin = data
features = caps.get_features(0)
# Need to check if the pad created by the decodebin is for video and not
# audio.
print("gstname=", gstname)
if gstname.find("video") != -1:
# Link the decodebin pad only if decodebin has picked nvidia
# decoder plugin nvdec_*. We do this by checking if the pad caps contain
# NVMM memory features.
print("features=", features)
if features.contains("memory:NVMM"):
# Get the source bin ghost pad
bin_ghost_pad = source_bin.get_static_pad("src")
if not bin_ghost_pad.set_target(decoder_src_pad):
print("Failed to link decoder src pad to source bin ghost pad", error=True)
else:
print("Decodebin did not pick nvidia decoder plugin", error=True)
def decodebin_child_added(child_proxy, Object, name, user_data):
print(f"Decodebin child added: {name}")
if name.find("decodebin") != -1:
Object.connect("child-added", decodebin_child_added, user_data)
if is_aarch64() and name.find("nvv4l2decoder") != -1:
Object.set_property("bufapi-version", True)
def create_source_bin(index, uri):
print("Creating source bin")
# Create a source GstBin to abstract this bin's content from the rest of the
# pipeline
bin_name = "source-bin-%02d" % index
print(bin_name)
nbin = Gst.Bin.new(bin_name)
if not nbin:
print("Unable to create source bin", error=True)
# Source element for reading from the uri.
# We will use decodebin and let it figure out the container format of the
# stream and the codec and plug the appropriate demux and decode plugins.
uri_decode_bin = Gst.ElementFactory.make("uridecodebin", "uri-decode-bin")
if not uri_decode_bin:
print("Unable to create uri decode bin", error=True)
# We set the input uri to the source element
uri_decode_bin.set_property("uri", uri)
# Connect to the "pad-added" signal of the decodebin which generates a
# callback once a new pad for raw data has beed created by the decodebin
uri_decode_bin.connect("pad-added", cb_newpad, nbin)
uri_decode_bin.connect("child-added", decodebin_child_added, nbin)
# We need to create a ghost pad for the source bin which will act as a proxy
# for the video decoder src pad. The ghost pad will not have a target right
# now. Once the decode bin creates the video decoder and generates the
# cb_newpad callback, we will set the ghost pad target to the video decoder
# src pad.
Gst.Bin.add(nbin, uri_decode_bin)
bin_pad = nbin.add_pad(Gst.GhostPad.new_no_target("src", Gst.PadDirection.SRC))
if not bin_pad:
print("Failed to add ghost pad in source bin", error=True)
return None
return nbin
def make_elm_or_print_err(factoryname, name, printedname):
"""Creates an element with Gst Element Factory make.
Return the element if successfully created, otherwise print
to stderr and return None.
"""
print("Creating", printedname)
elm = Gst.ElementFactory.make(factoryname, name)
if not elm:
print("Unable to create ", printedname, error=True)
show_troubleshooting()
return elm
def show_troubleshooting():
# On Jetson, there is a problem with the encoder failing to initialize
# due to limitation on TLS usage. To work around this, preload libgomp.
# Add a reminder here in case the user forgets.
print(
"""
[yellow]TROUBLESHOOTING HELP[/yellow]
[yellow]If the error is like: v4l-camera-source / reason not-negotiated[/yellow]
[green]Solution:[/green] configure camera capabilities
Run the script under utils/gst_capabilities.sh and find the lines with type
video/x-raw ...
Find a suitable framerate=X/1 (with X being an integer like 24, 15, etc.)
Then edit config_maskcam.txt and change the line:
camera-framerate=X
Or configure using --env MASKCAM_CAMERA_FRAMERATE=X (see README)
[yellow]If the error is like:
/usr/lib/aarch64-linux-gnu/libgomp.so.1: cannot allocate memory in static TLS block[/yellow]
[green]Solution:[/green] preload the offending library
export LD_PRELOAD=/usr/lib/aarch64-linux-gnu/libgomp.so.1
[yellow]END HELP[/yellow]
"""
)
def main(
config: dict,
input_filename: str,
output_filename: str = None,
e_external_interrupt: mp.Event = None,
stats_queue: mp.Queue = None,
e_ready: mp.Event = None,
):
global frame_number
global start_time
global end_time
global e_interrupt
# Load all udp ports to output video
udp_ports = {int(config["maskcam"]["udp-port-streaming"])}
load_udp_ports_filesaving(config, udp_ports)
codec = config["maskcam"]["codec"]
stats_period = int(config["maskcam"]["statistics-period"])
# Original: 1920x1080, bdti_resized: 1024x576, yolo-input: 1024x608
output_width = int(config["maskcam"]["output-video-width"])
output_height = int(config["maskcam"]["output-video-height"])
output_bitrate = 6000000 # Nice for h264@1024x576: 4000000
# Two types of camera supported: USB or Raspi
usbcam_input = USBCAM_PROTOCOL in input_filename
raspicam_input = RASPICAM_PROTOCOL in input_filename
camera_input = usbcam_input or raspicam_input
if camera_input:
camera_framerate = int(config["maskcam"]["camera-framerate"])
camera_flip_method = int(config["maskcam"]["camera-flip-method"])
# Set nvinfer.interval (number of frames to skip inference and use tracker instead)
if camera_input and int(config["maskcam"]["inference-interval-auto"]):
max_fps = int(config["maskcam"]["inference-max-fps"])
skip_inference = camera_framerate // max_fps
print(f"Auto calculated frames to skip inference: {skip_inference}")
else:
skip_inference = int(config["property"]["interval"])
print(f"Configured frames to skip inference: {skip_inference}")
# FaceMask initialization
face_tracker_period = skip_inference + 1 # tracker_period=skipped + inference frame(1)
face_detection_threshold = float(config["face-processor"]["detection-threshold"])
face_voting_threshold = float(config["face-processor"]["voting-threshold"])
face_min_face_size = int(config["face-processor"]["min-face-size"])
face_disable_tracker = int(config["face-processor"]["disable-tracker"])
face_processor = FaceMaskProcessor(
th_detection=face_detection_threshold,
th_vote=face_voting_threshold,
min_face_size=face_min_face_size,
tracker_period=face_tracker_period,
disable_tracker=face_disable_tracker,
)
# Standard GStreamer initialization
Gst.init(None)
# Create gstreamer elements
# Create Pipeline element that will form a connection of other elements
print("Creating Pipeline \n ")
pipeline = Gst.Pipeline()
if not pipeline:
print("Unable to create Pipeline", error=True)
if camera_input:
if usbcam_input:
input_device = input_filename[len(USBCAM_PROTOCOL) :]
source = make_elm_or_print_err("v4l2src", "v4l2-camera-source", "Camera input")
source.set_property("device", input_device)
nvvidconvsrc = make_elm_or_print_err(
"nvvideoconvert", "convertor_src2", "Convertor src 2"
)
# Input camera configuration
# Use ./gst_capabilities.sh to get the list of available capabilities from /dev/video0
camera_capabilities = f"video/x-raw, framerate={camera_framerate}/1"
elif raspicam_input:
input_device = input_filename[len(RASPICAM_PROTOCOL) :]
source = make_elm_or_print_err(
"nvarguscamerasrc", "nv-argus-camera-source", "RaspiCam input"
)
source.set_property("sensor-id", int(input_device))
source.set_property("bufapi-version", 1)
# Special camera_capabilities for raspicam
camera_capabilities = f"video/x-raw(memory:NVMM),framerate={camera_framerate}/1"
nvvidconvsrc = make_elm_or_print_err("nvvidconv", "convertor_flip", "Convertor flip")
nvvidconvsrc.set_property("flip-method", camera_flip_method)
# Misterious converting sequence from deepstream_test_1_usb.py
caps_camera = make_elm_or_print_err("capsfilter", "camera_src_caps", "Camera caps filter")
caps_camera.set_property(
"caps",
Gst.Caps.from_string(camera_capabilities),
)
vidconvsrc = make_elm_or_print_err("videoconvert", "convertor_src1", "Convertor src 1")
caps_vidconvsrc = make_elm_or_print_err(
"capsfilter", "nvmm_caps", "NVMM caps for input stream"
)
caps_vidconvsrc.set_property("caps", Gst.Caps.from_string("video/x-raw(memory:NVMM)"))
else:
source_bin = create_source_bin(0, input_filename)
# Create nvstreammux instance to form batches from one or more sources.
streammux = make_elm_or_print_err("nvstreammux", "Stream-muxer", "NvStreamMux")
streammux.set_property("width", output_width)
streammux.set_property("height", output_height)
streammux.set_property("enable-padding", True) # Keeps aspect ratio, but adds black margin
streammux.set_property("batch-size", 1)
streammux.set_property("batched-push-timeout", 4000000)
# Adding this element after muxer will cause detections to get delayed
# videorate = make_elm_or_print_err("videorate", "Vide-rate", "Video Rate")
# Inference element: object detection using TRT engine
pgie = make_elm_or_print_err("nvinfer", "primary-inference", "pgie")
pgie.set_property("config-file-path", CONFIG_FILE)
pgie.set_property("interval", skip_inference)
# Use convertor to convert from NV12 to RGBA as required by nvosd
convert_pre_osd = make_elm_or_print_err(
"nvvideoconvert", "convert_pre_osd", "Converter NV12->RGBA"
)
# OSD: to draw on the RGBA buffer
nvosd = make_elm_or_print_err("nvdsosd", "onscreendisplay", "OSD (nvosd)")
nvosd.set_property("process-mode", 2) # 0: CPU Mode, 1: GPU (only dGPU), 2: VIC (Jetson only)
# nvosd.set_property("display-bbox", False) # Bug: Removes all squares
nvosd.set_property("display-clock", False)
nvosd.set_property("display-text", True) # Needed for any text
# Finally encode and save the osd output
queue = make_elm_or_print_err("queue", "queue", "Queue")
convert_post_osd = make_elm_or_print_err(
"nvvideoconvert", "convert_post_osd", "Converter RGBA->NV12"
)
# Video capabilities: check format and GPU/CPU location
capsfilter = make_elm_or_print_err("capsfilter", "capsfilter", "capsfilter")
if codec == CODEC_MP4: # Not hw accelerated
caps = Gst.Caps.from_string("video/x-raw, format=I420")
else: # hw accelerated
caps = Gst.Caps.from_string("video/x-raw(memory:NVMM), format=I420")
capsfilter.set_property("caps", caps)
# Encoder: H265 has more efficient compression
if codec == CODEC_MP4:
print("Creating MPEG-4 stream")
encoder = make_elm_or_print_err("avenc_mpeg4", "encoder", "Encoder")
codeparser = make_elm_or_print_err("mpeg4videoparse", "mpeg4-parser", "Code Parser")
rtppay = make_elm_or_print_err("rtpmp4vpay", "rtppay", "RTP MPEG-44 Payload")
elif codec == CODEC_H264:
print("Creating H264 stream")
encoder = make_elm_or_print_err("nvv4l2h264enc", "encoder", "Encoder")
encoder.set_property("preset-level", 1)
encoder.set_property("bufapi-version", 1)
codeparser = make_elm_or_print_err("h264parse", "h264-parser", "Code Parser")
rtppay = make_elm_or_print_err("rtph264pay", "rtppay", "RTP H264 Payload")
else: # Default: H265 (recommended)
print("Creating H265 stream")
encoder = make_elm_or_print_err("nvv4l2h265enc", "encoder", "Encoder")
encoder.set_property("preset-level", 1)
encoder.set_property("bufapi-version", 1)
codeparser = make_elm_or_print_err("h265parse", "h265-parser", "Code Parser")
rtppay = make_elm_or_print_err("rtph265pay", "rtppay", "RTP H265 Payload")
encoder.set_property("insert-sps-pps", 1)
encoder.set_property("bitrate", output_bitrate)
splitter_file_udp = make_elm_or_print_err("tee", "tee_file_udp", "Splitter file/UDP")
# UDP streaming
queue_udp = make_elm_or_print_err("queue", "queue_udp", "UDP queue")
multiudpsink = make_elm_or_print_err("multiudpsink", "multi udpsink", "Multi UDP Sink")
# udpsink.set_property("host", "127.0.0.1")
# udpsink.set_property("port", udp_port)
# Comma separated list of clients, don't add spaces :S
client_list = [f"127.0.0.1:{udp_port}" for udp_port in udp_ports]
multiudpsink.set_property("clients", ",".join(client_list))
multiudpsink.set_property("async", False)
multiudpsink.set_property("sync", True)
if output_filename is not None:
queue_file = make_elm_or_print_err("queue", "queue_file", "File save queue")
# codeparser already created above depending on codec
container = make_elm_or_print_err("qtmux", "qtmux", "Container")
filesink = make_elm_or_print_err("filesink", "filesink", "File Sink")
filesink.set_property("location", output_filename)
else: # Fake sink, no save
fakesink = make_elm_or_print_err("fakesink", "fakesink", "Fake Sink")
# Add elements to the pipeline
if camera_input:
pipeline.add(source)
pipeline.add(caps_camera)
pipeline.add(vidconvsrc)
pipeline.add(nvvidconvsrc)
pipeline.add(caps_vidconvsrc)
else:
pipeline.add(source_bin)
pipeline.add(streammux)
pipeline.add(pgie)
pipeline.add(convert_pre_osd)
pipeline.add(nvosd)
pipeline.add(queue)
pipeline.add(convert_post_osd)
pipeline.add(capsfilter)
pipeline.add(encoder)
pipeline.add(splitter_file_udp)
if output_filename is not None:
pipeline.add(queue_file)
pipeline.add(codeparser)
pipeline.add(container)
pipeline.add(filesink)
else:
pipeline.add(fakesink)
# Output to UDP
pipeline.add(queue_udp)
pipeline.add(rtppay)
pipeline.add(multiudpsink)
print("Linking elements in the Pipeline \n")
# Pipeline Links
if camera_input:
source.link(caps_camera)
caps_camera.link(vidconvsrc)
vidconvsrc.link(nvvidconvsrc)
nvvidconvsrc.link(caps_vidconvsrc)
srcpad = caps_vidconvsrc.get_static_pad("src")
else:
srcpad = source_bin.get_static_pad("src")
sinkpad = streammux.get_request_pad("sink_0")
if not srcpad or not sinkpad:
print("Unable to get file source or mux sink pads", error=True)
srcpad.link(sinkpad)
streammux.link(pgie)
pgie.link(convert_pre_osd)
convert_pre_osd.link(nvosd)
nvosd.link(queue)
queue.link(convert_post_osd)
convert_post_osd.link(capsfilter)
capsfilter.link(encoder)
encoder.link(splitter_file_udp)
# Split stream to file and rtsp
tee_file = splitter_file_udp.get_request_pad("src_%u")
tee_udp = splitter_file_udp.get_request_pad("src_%u")
# Output to File or fake sinks
if output_filename is not None:
tee_file.link(queue_file.get_static_pad("sink"))
queue_file.link(codeparser)
codeparser.link(container)
container.link(filesink)
else:
tee_file.link(fakesink.get_static_pad("sink"))
# Output to UDP
tee_udp.link(queue_udp.get_static_pad("sink"))
queue_udp.link(rtppay)
rtppay.link(multiudpsink)
# Lets add probe to get informed of the meta data generated, we add probe to
# the sink pad of the osd element, since by that time, the buffer would have
# had got all the metadata.
osdsinkpad = nvosd.get_static_pad("sink")
if not osdsinkpad:
print("Unable to get sink pad of nvosd", error=True)
cb_args = (face_processor, e_ready)
osdsinkpad.add_probe(Gst.PadProbeType.BUFFER, cb_buffer_probe, cb_args)
# GLib loop required for RTSP server
g_loop = GLib.MainLoop()
g_context = g_loop.get_context()
# GStreamer message bus
bus = pipeline.get_bus()
if e_external_interrupt is None:
# Use threading instead of mp.Event() for sigint_handler, see:
# https://bugs.python.org/issue41606
e_interrupt = threading.Event()
signal.signal(signal.SIGINT, sigint_handler)
print("[green bold]Press Ctrl+C to stop pipeline[/green bold]")
else:
# If there's an external interrupt, don't capture SIGINT
e_interrupt = e_external_interrupt
# start play back and listen to events
pipeline.set_state(Gst.State.PLAYING)
# After setting pipeline to PLAYING, stop it even on exceptions
try:
time_start_playing = time.time()
# Timer to add statistics to queue
if stats_queue is not None:
cb_args = stats_period, stats_queue, face_processor
GLib.timeout_add_seconds(stats_period, cb_add_statistics, cb_args)
# Periodic gloop interrupt (see utils.glib_cb_restart)
t_check = 100
GLib.timeout_add(t_check, glib_cb_restart, t_check)
# Custom event loop
running = True
while running:
g_context.iteration(may_block=True)
message = bus.pop()
if message is not None:
t = message.type
if t == Gst.MessageType.EOS:
print("End-of-stream\n")
running = False
elif t == Gst.MessageType.WARNING:
err, debug = message.parse_warning()
print(f"{err}: {debug}", warning=True)
elif t == Gst.MessageType.ERROR:
err, debug = message.parse_error()
print(f"{err}: {debug}", error=True)
show_troubleshooting()
running = False
if e_interrupt.is_set():
# Send EOS to container to generate a valid mp4 file
if output_filename is not None:
container.send_event(Gst.Event.new_eos())
multiudpsink.send_event(Gst.Event.new_eos())
else:
pipeline.send_event(Gst.Event.new_eos()) # fakesink EOS won't work
end_time = time.time()
print("Inference main loop ending.")
pipeline.set_state(Gst.State.NULL)
# Profiling display
if start_time is not None and end_time is not None:
total_time = end_time - start_time
total_frames = frame_number
inference_frames = total_frames // (skip_inference + 1)
print()
print(f"[bold yellow] ---- Profiling ---- [/bold yellow]")
print(f"Inference frames: {inference_frames} | Processed frames: {total_frames}")
print(f"Time from time_start_playing: {end_time - time_start_playing:.2f} seconds")
print(f"Total time skipping first inference: {total_time:.2f} seconds")
print(f"Avg. time/frame: {total_time/total_frames:.4f} secs")
print(f"[bold yellow]FPS: {total_frames/total_time:.1f} frames/second[/bold yellow]\n")
if skip_inference != 0:
print(
"[red]NOTE: FPS calculated skipping inference every"
f" interval={skip_inference} frames[/red]"
)
if output_filename is not None:
print(f"Output file saved: [green bold]{output_filename}[/green bold]")
except:
console.print_exception()
pipeline.set_state(Gst.State.NULL)
if __name__ == "__main__":
print_config_overrides()
# Check input arguments
output_filename = None
if len(sys.argv) > 1:
input_filename = sys.argv[1]
print(f"Provided input source: {input_filename}")
if len(sys.argv) > 2:
output_filename = sys.argv[2]
print(f"Save output file: [green]{output_filename}[/green]")
else:
input_filename = config["maskcam"]["default-input"]
print(f"Using input from config file: {input_filename}")
sys.exit(
main(
config=config,
input_filename=input_filename,
output_filename=output_filename,
)
)
================================================
FILE: maskcam/maskcam_streaming.py
================================================
#!/usr/bin/env python3
################################################################################
# Copyright (c) 2020-2021, Berkeley Design Technology, Inc. All rights reserved.
#
# Permission is hereby granted, free of charge, to any person obtaining a
# copy of this software and associated documentation files (the "Software"),
# to deal in the Software without restriction, including without limitation
# the rights to use, copy, modify, merge, publish, distribute, sublicense,
# and/or sell copies of the Software, and to permit persons to whom the
# Software is furnished to do so, subject to the following conditions:
#
# The above copyright notice and this permission notice shall be included in
# all copies or substantial portions of the Software.
#
# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL
# THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
# FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
# DEALINGS IN THE SOFTWARE.
################################################################################
import gi
import pyds
import sys
import time
import signal
import platform
import threading
import multiprocessing as mp
from datetime import datetime
gi.require_version("Gst", "1.0")
gi.require_version("GstRtspServer", "1.0")
from gi.repository import GLib, Gst, GstRtspServer
from .config import config, print_config_overrides
from .prints import print_streaming as print
from .utils import get_ip_address, glib_cb_restart, get_streaming_address
from .common import CODEC_MP4, CODEC_H264, CODEC_H265, CONFIG_FILE
e_interrupt = None
def sigint_handler(sig, frame):
# This function is not used if e_external_interrupt is provided
print("[red]Ctrl+C pressed. Interrupting streaming...[/red]")
e_interrupt.set()
def main(config, e_external_interrupt: mp.Event = None):
global e_interrupt
udp_port = int(config["maskcam"]["udp-port-streaming"])
codec = config["maskcam"]["codec"]
# Streaming address: rtsp://<jetson-ip>:<rtsp-port>/<rtsp-address>
rtsp_port = int(config["maskcam"]["streaming-port"])
rtsp_address = config["maskcam"]["streaming-path"]
streaming_clock_rate = int(config["maskcam"]["streaming-clock-rate"])
# udp_capabilities = f"application/x-rtp,media=video,encoding-name={codec},payload=96"
print(f"Codec: {codec}")
# Standard GStreamer initialization
Gst.init(None)
# Start streaming
server = GstRtspServer.RTSPServer.new()
server.props.service = str(rtsp_port)
server.attach(None)
factory = GstRtspServer.RTSPMediaFactory.new()
factory.set_launch(
f"( udpsrc name=pay0 port={udp_port} buffer-size=524288"
f' caps="application/x-rtp, media=video, clock-rate={streaming_clock_rate},'
f' encoding-name=(string){codec}, payload=96 " )'
)
factory.set_shared(True)
server.get_mount_points().add_factory(rtsp_address, factory)
streaming_address = get_streaming_address(get_ip_address(), rtsp_port, rtsp_address)
print(f"\n\n[green bold]Streaming[/green bold] at {streaming_address}\n\n")
# GLib loop required for RTSP server
g_loop = GLib.MainLoop()
g_context = g_loop.get_context()
if e_external_interrupt is None:
# Use threading instead of mp.Event() for sigint_handler, see:
# https://bugs.python.org/issue41606
e_interrupt = threading.Event()
signal.signal(signal.SIGINT, sigint_handler)
print("[green bold]Press Ctrl+C to stop pipeline[/green bold]")
else:
# If there's an external interrupt, don't capture SIGINT
e_interrupt = e_external_interrupt
# Periodic gloop interrupt (see utils.glib_cb_restart)
t_check = 100
GLib.timeout_add(t_check, glib_cb_restart, t_check)
while not e_interrupt.is_set():
g_context.iteration(may_block=True)
print("Ending streaming")
if __name__ == "__main__":
# Print any config override by env variables to avoid confusions
print_config_overrides()
main(config)
================================================
FILE: maskcam/mqtt_commander.py
================================================
#!/usr/bin/env python3
################################################################################
# Copyright (c) 2020-2021, Berkeley Design Technology, Inc. All rights reserved.
#
# Permissio
gitextract_82ysmahp/
├── .gitignore
├── Dockerfile
├── LICENSE.md
├── README.md
├── deepstream_plugin_yolov4/
│ ├── Makefile
│ ├── README.md
│ ├── kernels.cu
│ ├── nvdsinfer_yolo_engine.cpp
│ ├── nvdsparsebbox_Yolo.cpp
│ ├── trt_utils.cpp
│ ├── trt_utils.h
│ ├── yolo.cpp
│ ├── yolo.h
│ ├── yoloPlugins.cpp
│ └── yoloPlugins.h
├── docker/
│ ├── constraints.docker
│ ├── opencv_python-3.2.0.egg-info
│ ├── scikit-learn-0.19.1.egg-info
│ └── start.sh
├── docker-compose.yml
├── docs/
│ ├── BalenaOS-DevKit-Nano-Setup.md
│ ├── BalenaOS-Photon-Nano-Setup.md
│ ├── Custom-Container-Development.md
│ ├── Manual-Dependencies-Installation.md
│ └── Useful-Development-Scripts.md
├── maskcam/
│ ├── common.py
│ ├── config.py
│ ├── maskcam_filesave.py
│ ├── maskcam_fileserver.py
│ ├── maskcam_inference.py
│ ├── maskcam_streaming.py
│ ├── mqtt_commander.py
│ ├── mqtt_common.py
│ ├── prints.py
│ └── utils.py
├── maskcam_config.txt
├── maskcam_run.py
├── requirements-dev.in
├── requirements.in
├── requirements.txt
├── server/
│ ├── backend/
│ │ ├── Dockerfile
│ │ ├── alembic.ini
│ │ ├── app/
│ │ │ ├── api/
│ │ │ │ ├── __init__.py
│ │ │ │ ├── exceptions.py
│ │ │ │ └── routes/
│ │ │ │ ├── device_routes.py
│ │ │ │ └── statistic_routes.py
│ │ │ ├── core/
│ │ │ │ └── config.py
│ │ │ ├── db/
│ │ │ │ ├── cruds/
│ │ │ │ │ ├── __init__.py
│ │ │ │ │ ├── crud_device.py
│ │ │ │ │ ├── crud_statistic.py
│ │ │ │ │ └── crud_video_file.py
│ │ │ │ ├── migrations/
│ │ │ │ │ ├── env.py
│ │ │ │ │ ├── script.py.mako
│ │ │ │ │ └── versions/
│ │ │ │ │ ├── 6a4d853aabce_added_database.py
│ │ │ │ │ ├── 6d5c250f098c_added_device_file_server_address.py
│ │ │ │ │ ├── 8f58cd776eda_added_database.py
│ │ │ │ │ └── fb245977373f_added_video_file_table.py
│ │ │ │ ├── schema/
│ │ │ │ │ ├── __init__.py
│ │ │ │ │ ├── base.py
│ │ │ │ │ ├── models.py
│ │ │ │ │ └── schemas.py
│ │ │ │ └── utils/
│ │ │ │ ├── __init__.py
│ │ │ │ ├── enums.py
│ │ │ │ └── utils.py
│ │ │ ├── main.py
│ │ │ └── mqtt/
│ │ │ ├── broker.py
│ │ │ ├── publisher.py
│ │ │ └── subscriber.py
│ │ ├── prestart.sh
│ │ ├── requirements.txt
│ │ └── test_crud.py
│ ├── backend.env.template
│ ├── build_docker.sh
│ ├── database.env.template
│ ├── docker-compose.yml
│ ├── frontend/
│ │ ├── Dockerfile
│ │ ├── main.py
│ │ ├── requirements.txt
│ │ ├── session_manager.py
│ │ └── utils/
│ │ ├── api_utils.py
│ │ └── format_utils.py
│ ├── frontend.env.template
│ ├── mosquitto.conf
│ ├── server_setup.sh
│ └── stop_docker.sh
├── utils/
│ ├── combine_coco.py
│ ├── gst_capabilities.sh
│ ├── mqtt-test/
│ │ ├── broker.py
│ │ ├── publisher.py
│ │ └── suscriber.py
│ ├── onnx_fix_mobilenet.py
│ ├── remove_images_coco.py
│ ├── tf1_trt_inference.py
│ ├── tf2_trt_convert.py
│ └── tf_trt_convert.py
└── yolo/
├── config.py
├── config_images.yml
├── data/
│ ├── obj.data
│ └── obj.names
├── facemask-yolov4-tiny.cfg
├── facemask-yolov4.cfg
├── integrations/
│ └── yolo/
│ ├── detector_trt.py
│ ├── utils_pytorch.py
│ └── yolo_adaptor.py
├── run_yolo_images.py
└── train_cu90.sh
SYMBOL INDEX (266 symbols across 51 files)
FILE: deepstream_plugin_yolov4/nvdsinfer_yolo_engine.cpp
function getYoloNetworkInfo (line 32) | static bool getYoloNetworkInfo (NetworkInfo &networkInfo, const NvDsInfe...
function IModelParser (line 80) | IModelParser* NvDsInferCreateModelParser(
function NvDsInferYoloCudaEngineGet (line 97) | bool NvDsInferYoloCudaEngineGet(nvinfer1::IBuilder * const builder,
FILE: deepstream_plugin_yolov4/nvdsparsebbox_Yolo.cpp
function NvDsInferParseObjectInfo (line 72) | static NvDsInferParseObjectInfo convertBBox(const float &bx, const float...
function addBBoxProposal (line 98) | static void addBBoxProposal(const float bx, const float by, const float ...
function decodeYoloV2Tensor (line 111) | static std::vector<NvDsInferParseObjectInfo>
function decodeYoloV3Tensor (line 159) | static std::vector<NvDsInferParseObjectInfo>
function SortLayers (line 207) | static inline std::vector<const NvDsInferLayerInfo *>
function NvDsInferParseYoloV3 (line 222) | static bool NvDsInferParseYoloV3(
function NvDsInferParseObjectInfo (line 272) | static NvDsInferParseObjectInfo convertBBoxYoloV4(const float &bx1, cons...
function addBBoxProposalYoloV4 (line 296) | static void addBBoxProposalYoloV4(const float bx, const float by, const ...
function decodeYoloV4Tensor (line 309) | static std::vector<NvDsInferParseObjectInfo>
function NvDsInferParseYoloV4 (line 353) | static bool NvDsInferParseYoloV4(
function NvDsInferParseCustomYoloV4 (line 396) | bool NvDsInferParseCustomYoloV4(
function NvDsInferParseCustomYoloV3 (line 406) | bool NvDsInferParseCustomYoloV3(
function NvDsInferParseCustomYoloV3Tiny (line 424) | bool NvDsInferParseCustomYoloV3Tiny(
function NvDsInferParseYoloV2 (line 442) | static bool NvDsInferParseYoloV2(
function NvDsInferParseCustomYoloV2 (line 486) | bool NvDsInferParseCustomYoloV2(
function NvDsInferParseCustomYoloV2Tiny (line 496) | bool NvDsInferParseCustomYoloV2Tiny(
function NvDsInferParseCustomYoloTLT (line 506) | bool NvDsInferParseCustomYoloTLT(
FILE: deepstream_plugin_yolov4/trt_utils.cpp
function leftTrim (line 34) | static void leftTrim(std::string& s)
function rightTrim (line 39) | static void rightTrim(std::string& s)
function trim (line 44) | std::string trim(std::string s)
function clamp (line 51) | float clamp(const float val, const float minVal, const float maxVal)
function fileExists (line 57) | bool fileExists(const std::string fileName, bool verbose)
function loadWeights (line 67) | std::vector<float> loadWeights(const std::string weightsFilePath, const ...
function dimsToString (line 107) | std::string dimsToString(const nvinfer1::Dims d)
function displayDimType (line 120) | void displayDimType(const nvinfer1::Dims d)
function getNumChannels (line 136) | int getNumChannels(nvinfer1::ITensor* t)
function get3DTensorVolume (line 144) | uint64_t get3DTensorVolume(nvinfer1::Dims inputDims)
function printLayerInfo (line 458) | void printLayerInfo(std::string layerIndex, std::string layerName, std::...
FILE: deepstream_plugin_yolov4/yolo.cpp
function NvDsInferStatus (line 74) | NvDsInferStatus Yolo::parseModel(nvinfer1::INetworkDefinition& network) {
function NvDsInferStatus (line 94) | NvDsInferStatus Yolo::buildYoloNetwork(
FILE: deepstream_plugin_yolov4/yolo.h
type NetworkInfo (line 39) | struct NetworkInfo
type TensorInfo (line 51) | struct TensorInfo
function uint (line 55) | uint gridSize{0}
function uint (line 56) | uint numClasses{0}
function uint (line 57) | uint numBBoxes{0}
function volume (line 58) | uint64_t volume{0}
function class (line 65) | class Yolo : public IModelParser {
FILE: deepstream_plugin_yolov4/yoloPlugins.cpp
function write (line 31) | void write(char*& buffer, const T& val)
function read (line 38) | void read(const char*& buffer, T& val)
FILE: deepstream_plugin_yolov4/yoloPlugins.h
function override (line 66) | void configureWithFormat (
function terminate (line 72) | void terminate () override {}
function getWorkspaceSize (line 73) | size_t getWorkspaceSize (int maxBatchSize) const override { return 0; }
function getSerializationSize (line 77) | size_t getSerializationSize() const override;
function setPluginNamespace (line 82) | void setPluginNamespace (const char* pluginNamespace)override {
function virtual (line 85) | virtual const char* getPluginNamespace () const override {
function uint (line 91) | uint m_NumClasses {0}
function uint (line 92) | uint m_GridSize {0}
function m_OutputSize (line 93) | uint64_t m_OutputSize {0}
function nvinfer1 (line 106) | const nvinfer1::PluginFieldCollection* getFieldNames() override {
function setPluginNamespace (line 125) | void setPluginNamespace(const char* libNamespace) override {
FILE: maskcam/config.py
function print_config_overrides (line 51) | def print_config_overrides():
FILE: maskcam/maskcam_filesave.py
function make_elm_or_print_err (line 49) | def make_elm_or_print_err(factoryname, name, printedname, detail=""):
function sigint_handler (line 63) | def sigint_handler(sig, frame):
function main (line 69) | def main(
FILE: maskcam/maskcam_fileserver.py
class Handler (line 40) | class Handler(SimpleHTTPRequestHandler):
function start_server (line 45) | def start_server(httpd_server):
function cb_handle_error (line 49) | def cb_handle_error(request, client_address):
function main (line 54) | def main(config, directory=None, e_external_interrupt: mp.Event = None):
FILE: maskcam/maskcam_inference.py
class FaceMaskProcessor (line 74) | class FaceMaskProcessor:
method __init__ (line 75) | def __init__(
method keypoints_distance (line 107) | def keypoints_distance(self, detected_pose, tracked_pose):
method validate_detection (line 127) | def validate_detection(self, box_points, score, label):
method add_detection (line 134) | def add_detection(self, person_id, label, score):
method get_person_label (line 150) | def get_person_label(self, person_id):
method get_instant_statistics (line 160) | def get_instant_statistics(self, refresh=True):
method get_statistics (line 170) | def get_statistics(self, filter_ids=None):
function cb_add_statistics (line 190) | def cb_add_statistics(cb_args):
function sigint_handler (line 212) | def sigint_handler(sig, frame):
function is_aarch64 (line 218) | def is_aarch64():
function draw_detection (line 222) | def draw_detection(display_meta, n_draw, box_points, detection_label, co...
function cb_buffer_probe (line 253) | def cb_buffer_probe(pad, info, cb_args):
function cb_newpad (line 405) | def cb_newpad(decodebin, decoder_src_pad, data):
function decodebin_child_added (line 430) | def decodebin_child_added(child_proxy, Object, name, user_data):
function create_source_bin (line 438) | def create_source_bin(index, uri):
function make_elm_or_print_err (line 475) | def make_elm_or_print_err(factoryname, name, printedname):
function show_troubleshooting (line 488) | def show_troubleshooting():
function main (line 515) | def main(
FILE: maskcam/maskcam_streaming.py
function sigint_handler (line 47) | def sigint_handler(sig, frame):
function main (line 53) | def main(config, e_external_interrupt: mp.Event = None):
FILE: maskcam/mqtt_commander.py
function show_message (line 47) | def show_message(mqtt_client, userdata, message):
FILE: maskcam/mqtt_common.py
function mqtt_send_queue (line 58) | def mqtt_send_queue(mqtt_client):
function mqtt_connect_broker (line 67) | def mqtt_connect_broker(
function mqtt_send_msg (line 99) | def mqtt_send_msg(mqtt_client, topic, message, enqueue=True):
FILE: maskcam/prints.py
function print_process (line 36) | def print_process(
function print_run (line 51) | def print_run(*args, **kwargs):
function print_fileserver (line 55) | def print_fileserver(*args, **kwargs):
function print_filesave (line 59) | def print_filesave(*args, **kwargs):
function print_streaming (line 63) | def print_streaming(*args, **kwargs):
function print_inference (line 67) | def print_inference(*args, **kwargs):
function print_mqtt (line 71) | def print_mqtt(*args, **kwargs):
function print_common (line 75) | def print_common(*args, **kwargs):
FILE: maskcam/utils.py
function get_ip_address (line 29) | def get_ip_address():
function get_streaming_address (line 36) | def get_streaming_address(host_address, rtsp_port, rtsp_path):
function format_tdelta (line 40) | def format_tdelta(time_delta):
function glib_cb_restart (line 47) | def glib_cb_restart(t_restart):
function load_udp_ports_filesaving (line 56) | def load_udp_ports_filesaving(config, udp_ports_pool):
FILE: maskcam_run.py
function sigint_handler (line 94) | def sigint_handler(sig, frame):
function start_process (line 99) | def start_process(name, target_function, config, **kwargs):
function terminate_process (line 116) | def terminate_process(name, process, e_interrupt_process, delete_info=Fa...
function new_command (line 135) | def new_command(command):
function mqtt_init (line 143) | def mqtt_init(config):
function mqtt_on_connect (line 166) | def mqtt_on_connect(mqtt_client):
function mqtt_process_message (line 171) | def mqtt_process_message(mqtt_client, userdata, message):
function mqtt_say_hello (line 182) | def mqtt_say_hello(mqtt_client):
function mqtt_send_device_status (line 191) | def mqtt_send_device_status(mqtt_client):
function mqtt_send_file_list (line 229) | def mqtt_send_file_list(mqtt_client):
function is_alert_condition (line 248) | def is_alert_condition(statistics, config):
function handle_statistics (line 269) | def handle_statistics(mqtt_client, stats_queue, config, is_live_input):
function allocate_free_udp_port (line 285) | def allocate_free_udp_port():
function release_udp_port (line 291) | def release_udp_port(port_number):
function handle_file_saving (line 296) | def handle_file_saving(
function finish_filesave_process (line 351) | def finish_filesave_process(active_process, hdd_dir, force_filesave, mqt...
function flag_keep_current_files (line 374) | def flag_keep_current_files():
FILE: server/backend/app/api/exceptions.py
class NoItemFoundException (line 26) | class NoItemFoundException(HTTPException):
method __init__ (line 27) | def __init__(self):
class ItemAlreadyExist (line 34) | class ItemAlreadyExist(HTTPException):
method __init__ (line 35) | def __init__(self):
class GenericException (line 42) | class GenericException(HTTPException):
method __init__ (line 43) | def __init__(self, message: str):
FILE: server/backend/app/api/routes/device_routes.py
function create_device_item (line 45) | def create_device_item(
function get_device_item (line 70) | def get_device_item(
function get_devices_items (line 97) | def get_devices_items(db: Session = Depends(get_db_generator)):
function update_device_item (line 111) | def update_device_item(
function delete_device_item (line 141) | def delete_device_item(
function get_device_files (line 165) | def get_device_files(
FILE: server/backend/app/api/routes/statistic_routes.py
function create_statistic_item (line 48) | def create_statistic_item(
function get_statistic_item (line 86) | def get_statistic_item(
function get_all_device_statistics_items (line 117) | def get_all_device_statistics_items(
function get_all_statistics_items (line 161) | def get_all_statistics_items(db: Session = Depends(get_db_generator)):
function update_statistic_item (line 178) | def update_statistic_item(
function delete_statistic_item (line 216) | def delete_statistic_item(
FILE: server/backend/app/db/cruds/crud_device.py
function create_device (line 32) | def create_device(
function get_device (line 62) | def get_device(
function get_devices (line 83) | def get_devices(db_session: Session) -> List[DeviceModel]:
function update_device (line 96) | def update_device(
function delete_device (line 131) | def delete_device(
function get_device_by_id (line 156) | def get_device_by_id(
FILE: server/backend/app/db/cruds/crud_statistic.py
function create_statistic (line 33) | def create_statistic(
function get_statistic (line 59) | def get_statistic(
function get_statistics (line 81) | def get_statistics(
function get_statistics_from_to (line 105) | def get_statistics_from_to(
function update_statistic (line 139) | def update_statistic(
function delete_statistic (line 186) | def delete_statistic(
function get_statistic_by_id_and_datetime (line 213) | def get_statistic_by_id_and_datetime(
FILE: server/backend/app/db/cruds/crud_video_file.py
function update_files (line 33) | def update_files(
function get_files_by_device (line 66) | def get_files_by_device(
FILE: server/backend/app/db/migrations/env.py
function run_migrations_offline (line 43) | def run_migrations_offline():
function run_migrations_online (line 67) | def run_migrations_online():
FILE: server/backend/app/db/migrations/versions/6a4d853aabce_added_database.py
function upgrade (line 19) | def upgrade():
function downgrade (line 25) | def downgrade():
FILE: server/backend/app/db/migrations/versions/6d5c250f098c_added_device_file_server_address.py
function upgrade (line 19) | def upgrade():
function downgrade (line 25) | def downgrade():
FILE: server/backend/app/db/migrations/versions/8f58cd776eda_added_database.py
function upgrade (line 19) | def upgrade():
function downgrade (line 39) | def downgrade():
FILE: server/backend/app/db/migrations/versions/fb245977373f_added_video_file_table.py
function upgrade (line 19) | def upgrade():
function downgrade (line 39) | def downgrade():
FILE: server/backend/app/db/schema/base.py
function get_db_session (line 32) | def get_db_session() -> Session:
function get_db_generator (line 46) | def get_db_generator() -> Generator:
FILE: server/backend/app/db/schema/models.py
class StatisticsModel (line 30) | class StatisticsModel(Base):
class VideoFilesModel (line 45) | class VideoFilesModel(Base):
class DeviceModel (line 55) | class DeviceModel(Base):
FILE: server/backend/app/db/schema/schemas.py
class StatisticSchema (line 30) | class StatisticSchema(BaseModel):
class Config (line 38) | class Config:
class DeviceSchema (line 42) | class DeviceSchema(BaseModel):
class Config (line 48) | class Config:
class VideoFileSchema (line 52) | class VideoFileSchema(BaseModel):
class Config (line 56) | class Config:
FILE: server/backend/app/db/utils/enums.py
class StatisticTypeEnum (line 4) | class StatisticTypeEnum(str, Enum):
FILE: server/backend/app/db/utils/utils.py
function convert_timestamp_to_datetime (line 6) | def convert_timestamp_to_datetime(timestamp: float) -> datetime:
function get_enum_type (line 20) | def get_enum_type(statistic_type: str) -> StatisticTypeEnum:
FILE: server/backend/app/main.py
function health_check (line 34) | def health_check():
FILE: server/backend/app/mqtt/broker.py
function connect_mqtt_broker (line 28) | def connect_mqtt_broker(client_id: str, cb_connect: Callable=None) -> mq...
FILE: server/backend/app/mqtt/publisher.py
function publish (line 30) | def publish(client):
function connect_mqtt_broker (line 80) | def connect_mqtt_broker(client_id: str):
function run (line 94) | def run():
FILE: server/backend/app/mqtt/subscriber.py
function subscribe (line 44) | def subscribe(client: mqtt_client):
function process_message (line 63) | def process_message(database_session, msg):
function main (line 126) | def main():
FILE: server/backend/test_crud.py
function test_create_device (line 49) | def test_create_device():
function test_create_device_more_fields (line 60) | def test_create_device_more_fields():
function test_create_same_device (line 71) | def test_create_same_device():
function test_get_device (line 82) | def test_get_device():
function test_update_device (line 89) | def test_update_device():
function test_create_statistic (line 101) | def test_create_statistic():
function test_create_same_statistic (line 128) | def test_create_same_statistic():
function test_create_another_statistic (line 149) | def test_create_another_statistic():
function test_get_statistic (line 176) | def test_get_statistic():
function test_update_statistic (line 194) | def test_update_statistic():
function test_delete_statistic (line 214) | def test_delete_statistic():
function test_delete_device (line 234) | def test_delete_device():
function test_get_deleted_device (line 241) | def test_get_deleted_device():
function test_update_deleted_device (line 246) | def test_update_deleted_device():
function test_get_devices (line 255) | def test_get_devices():
function test_get_devices (line 261) | def test_get_devices():
FILE: server/frontend/main.py
function display_sidebar (line 57) | def display_sidebar(all_devices, state):
function display_device (line 97) | def display_device(state):
function mqtt_set_status (line 220) | def mqtt_set_status(mqtt_status, text):
function _on_connect (line 226) | def _on_connect(client, userdata, flags, rc):
function _on_message (line 231) | def _on_message(client, userdata, msg):
function restore_client (line 245) | def restore_client():
function get_mqtt_client (line 251) | def get_mqtt_client():
function mqtt_wait_connection (line 258) | def mqtt_wait_connection(client, timeout):
function mqtt_wait_response (line 264) | def mqtt_wait_response(client, timeout):
function send_mqtt_message_wait_response (line 270) | def send_mqtt_message_wait_response(topic, message, mqtt_status):
function send_mqtt_command (line 316) | def send_mqtt_command(device_id, command, mqtt_status):
function main (line 322) | def main():
FILE: server/frontend/session_manager.py
class _SessionState (line 29) | class _SessionState:
method __init__ (line 30) | def __init__(self, session, hash_funcs):
method __call__ (line 42) | def __call__(self, **kwargs):
method __getitem__ (line 50) | def __getitem__(self, item):
method __getattr__ (line 56) | def __getattr__(self, item):
method __setitem__ (line 62) | def __setitem__(self, item, value):
method __setattr__ (line 66) | def __setattr__(self, item, value):
method clear (line 72) | def clear(self):
method sync (line 79) | def sync(self):
function _get_session (line 103) | def _get_session():
function get_state (line 113) | def get_state(hash_funcs=None):
FILE: server/frontend/utils/api_utils.py
function get_devices (line 32) | def get_devices():
function get_device (line 45) | def get_device(device_id: str):
function get_statistics_from_to (line 57) | def get_statistics_from_to(device_id, datetime_from, datetime_to):
function get_device_files (line 72) | def get_device_files(device_id):
FILE: server/frontend/utils/format_utils.py
function format_data (line 32) | def format_data(statistics: List = [], group_data_by: str = None):
function group_data (line 65) | def group_data(data: Dict, group_data_by: str):
function create_statistics_dict (line 126) | def create_statistics_dict():
function add_information (line 140) | def add_information(statistic_dict: Dict, statistic_information: Dict):
function create_chart (line 172) | def create_chart(reports: Dict = {}, alerts: Dict = {}):
function add_trace (line 231) | def add_trace(trace_information: Dict, figure, colors: Dict, trace_type=...
FILE: utils/combine_coco.py
function merge_2_into_1 (line 7) | def merge_2_into_1(json1, json2):
function print_coco (line 46) | def print_coco(js):
function open_coco (line 54) | def open_coco(file_name):
FILE: utils/mqtt-test/broker.py
function connect_mqtt_broker (line 8) | def connect_mqtt_broker(client_id: str) -> mqtt_client:
FILE: utils/mqtt-test/publisher.py
function publish (line 9) | def publish(client):
function run (line 31) | def run():
FILE: utils/mqtt-test/suscriber.py
function subscribe (line 7) | def subscribe(client: mqtt_client):
function main (line 19) | def main():
FILE: utils/remove_images_coco.py
function merge_2_into_1 (line 7) | def merge_2_into_1(json1, json2):
function print_coco (line 38) | def print_coco(js):
function open_coco (line 46) | def open_coco(file_name):
FILE: yolo/config.py
class Config (line 26) | class Config:
method __init__ (line 27) | def __init__(self, config_file_path):
method __getitem__ (line 53) | def __getitem__(self, name):
FILE: yolo/integrations/yolo/detector_trt.py
class HostDeviceMem (line 22) | class HostDeviceMem(object):
method __init__ (line 23) | def __init__(self, host_mem, device_mem):
method __str__ (line 27) | def __str__(self):
method __repr__ (line 30) | def __repr__(self):
class DetectorYoloTRT (line 34) | class DetectorYoloTRT:
method __init__ (line 37) | def __init__(self, config):
method print_profiler (line 72) | def print_profiler(self):
method detect (line 98) | def detect(self, frames, rescale_detections=True):
method _do_inference (line 170) | def _do_inference(self, context, bindings, inputs, outputs, stream):
method _do_inference_sync (line 186) | def _do_inference_sync(self, context, bindings, inputs, outputs, stream):
method _allocate_buffers (line 200) | def _allocate_buffers(self, engine):
method _allocate_buffers (line 232) | def _allocate_buffers(self, engine):
FILE: yolo/integrations/yolo/utils_pytorch.py
function nms_cpu (line 9) | def nms_cpu(boxes, confs, nms_thresh=0.5, min_mode=False):
function load_class_names (line 46) | def load_class_names(namesfile):
function post_processing (line 56) | def post_processing(img, conf_thresh, nms_thresh, output):
FILE: yolo/integrations/yolo/yolo_adaptor.py
class YoloAdaptor (line 7) | class YoloAdaptor:
method __init__ (line 8) | def __init__(self, config):
method classify_people (line 12) | def classify_people(self, tracked_people):
method keypoints_distance (line 27) | def keypoints_distance(self, detected_pose, tracked_pose):
method person_has_face (line 47) | def person_has_face(self, person):
method get_person_head (line 50) | def get_person_head(self, person):
method draw_raw_detections (line 56) | def draw_raw_detections(self, frame, detections):
Condensed preview — 106 files, each showing path, character count, and a content snippet. Download the .json file or copy for the full structured content (420K chars).
[
{
"path": ".gitignore",
"chars": 2154,
"preview": "# Project particular ignores\nbackup/\nvideos/inputs/*\nvideos/outputs/*\nimages*/\n*.mp4\n.DS_Store\n.vscode/\n\n# Intermediate "
},
{
"path": "Dockerfile",
"chars": 5906,
"preview": "# Installs maskcam on a BalenaOS container (devkit or Photon)\nFROM balenalib/jetson-nano-ubuntu:20210201\n\n# Don't prompt"
},
{
"path": "LICENSE.md",
"chars": 1112,
"preview": "MIT License\nCopyright (c) 2020, 2021 Berkeley Design Technology, Inc.. All rights reserved.\nPermission is hereby granted"
},
{
"path": "README.md",
"chars": 24651,
"preview": "# MaskCam <!-- omit in toc -->\n\n<p align=\"center\">\n <img src=\"/docs/imgs/MaskCam-Demo1.gif\">\n</p>\n\nMaskCam is a prototy"
},
{
"path": "deepstream_plugin_yolov4/Makefile",
"chars": 2420,
"preview": "################################################################################\n# Copyright (c) 2019, NVIDIA CORPORATIO"
},
{
"path": "deepstream_plugin_yolov4/README.md",
"chars": 216,
"preview": "## YOLOv4 plugin for DeepStream\nThis plugin was obtained from: https://github.com/Tianxiaomo/pytorch-YOLOv4/tree/master/"
},
{
"path": "deepstream_plugin_yolov4/kernels.cu",
"chars": 3373,
"preview": "/*\n * Copyright (c) 2018-2019 NVIDIA Corporation. All rights reserved.\n *\n * NVIDIA Corporation and its licensors retai"
},
{
"path": "deepstream_plugin_yolov4/nvdsinfer_yolo_engine.cpp",
"chars": 4101,
"preview": "/*\n * Copyright (c) 2019-2020, NVIDIA CORPORATION. All rights reserved.\n *\n * Permission is hereby granted, free of char"
},
{
"path": "deepstream_plugin_yolov4/nvdsparsebbox_Yolo.cpp",
"chars": 21255,
"preview": "/*\n * Copyright (c) 2019, NVIDIA CORPORATION. All rights reserved.\n *\n * Permission is hereby granted, free of charge, t"
},
{
"path": "deepstream_plugin_yolov4/trt_utils.cpp",
"chars": 16571,
"preview": "/*\n * Copyright (c) 2019-2020, NVIDIA CORPORATION. All rights reserved.\n *\n * Permission is hereby granted, free of char"
},
{
"path": "deepstream_plugin_yolov4/trt_utils.h",
"chars": 3449,
"preview": "/*\n * Copyright (c) 2019-2020, NVIDIA CORPORATION. All rights reserved.\n *\n * Permission is hereby granted, free of char"
},
{
"path": "deepstream_plugin_yolov4/yolo.cpp",
"chars": 20099,
"preview": "/*\n * Copyright (c) 2019-2020, NVIDIA CORPORATION. All rights reserved.\n *\n * Permission is hereby granted, free of char"
},
{
"path": "deepstream_plugin_yolov4/yolo.h",
"chars": 3242,
"preview": "/*\n * Copyright (c) 2019-2020, NVIDIA CORPORATION. All rights reserved.\n *\n * Permission is hereby granted, free of char"
},
{
"path": "deepstream_plugin_yolov4/yoloPlugins.cpp",
"chars": 3961,
"preview": "/*\n * Copyright (c) 2019, NVIDIA CORPORATION. All rights reserved.\n *\n * Permission is hereby granted, free of charge, t"
},
{
"path": "deepstream_plugin_yolov4/yoloPlugins.h",
"chars": 5346,
"preview": "/*\n * Copyright (c) 2019, NVIDIA CORPORATION. All rights reserved.\n *\n * Permission is hereby granted, free of charge, t"
},
{
"path": "docker/constraints.docker",
"chars": 41,
"preview": "scikit-learn==0.19.1\nopencv-python==3.2.0"
},
{
"path": "docker/opencv_python-3.2.0.egg-info",
"chars": 278,
"preview": "Metadata-Version: 1.1\nName: opencv-python\nVersion: 3.2.0\nSummary: stub file to make pip aware of apt installed opencv\nHo"
},
{
"path": "docker/scikit-learn-0.19.1.egg-info",
"chars": 279,
"preview": "Metadata-Version: 1.1\nName: scikit-learn\nVersion: 0.19.1\nSummary: stub file to make pip aware of apt installed package\nH"
},
{
"path": "docker/start.sh",
"chars": 528,
"preview": "#!/usr/bin/env bash\nnvargus-daemon &\n\necho\necho \"Provided input:\"\necho \" - MASKCAM_INPUT = $MASKCAM_INPUT\"\necho \"Device "
},
{
"path": "docker-compose.yml",
"chars": 248,
"preview": "version: '2'\n\n# this file only exists for local development\n# pushes to override the restart function\n\nservices:\n mc_ma"
},
{
"path": "docs/BalenaOS-DevKit-Nano-Setup.md",
"chars": 3820,
"preview": "# BalenaOS Developer Kit Nano Setup Instructions for MaskCam\n\nBalenaOS is a very light weight distribution designed for "
},
{
"path": "docs/BalenaOS-Photon-Nano-Setup.md",
"chars": 4924,
"preview": "# BalenaOS Setup Instructions for MaskCam on Jetson Nano with Photon Carrier Board\n\nBalenaOS is a very light weight dist"
},
{
"path": "docs/Custom-Container-Development.md",
"chars": 4949,
"preview": "# Custom Container Development\nThe MaskCam code in this repository can be used as a starting point for developing your o"
},
{
"path": "docs/Manual-Dependencies-Installation.md",
"chars": 2856,
"preview": "## Manual installation and building of dependencies\n\nThese instructions are aimed to manually recreate a native environm"
},
{
"path": "docs/Useful-Development-Scripts.md",
"chars": 1869,
"preview": "# Useful development scripts\nThese scripts are intended to be used by developers. They require some knowledge on the sub"
},
{
"path": "maskcam/common.py",
"chars": 1890,
"preview": "################################################################################\n# Copyright (c) 2020-2021, Berkeley Des"
},
{
"path": "maskcam/config.py",
"chars": 3043,
"preview": "import os\nimport configparser\nfrom maskcam.common import CONFIG_FILE\nfrom maskcam.prints import print_common as print\n\nc"
},
{
"path": "maskcam/maskcam_filesave.py",
"chars": 8477,
"preview": "#!/usr/bin/env python3\n\n################################################################################\n# Copyright (c)"
},
{
"path": "maskcam/maskcam_fileserver.py",
"chars": 3691,
"preview": "#!/usr/bin/env python3\n\n################################################################################\n# Copyright (c)"
},
{
"path": "maskcam/maskcam_inference.py",
"chars": 36403,
"preview": "#!/usr/bin/env python3\n\n################################################################################\n# Copyright (c)"
},
{
"path": "maskcam/maskcam_streaming.py",
"chars": 4296,
"preview": "#!/usr/bin/env python3\n\n################################################################################\n# Copyright (c)"
},
{
"path": "maskcam/mqtt_commander.py",
"chars": 3223,
"preview": "#!/usr/bin/env python3\n\n################################################################################\n# Copyright (c)"
},
{
"path": "maskcam/mqtt_common.py",
"chars": 4696,
"preview": "################################################################################\n# Copyright (c) 2020-2021, Berkeley Des"
},
{
"path": "maskcam/prints.py",
"chars": 2694,
"preview": "################################################################################\n# Copyright (c) 2020-2021, Berkeley Des"
},
{
"path": "maskcam/utils.py",
"chars": 2477,
"preview": "################################################################################\n# Copyright (c) 2020-2021, Berkeley Des"
},
{
"path": "maskcam_config.txt",
"chars": 4431,
"preview": "\n# NOTE: Some values might be overriden via ENV vars (check maskcam/config.py)\n\n[face-processor]\n# Detections with score"
},
{
"path": "maskcam_run.py",
"chars": 22878,
"preview": "#!/usr/bin/env python3\n\n################################################################################\n# Copyright (c)"
},
{
"path": "requirements-dev.in",
"chars": 54,
"preview": "# dev deps\npip-tools\nblack\nflake8\njupyter\nipython\nipdb"
},
{
"path": "requirements.in",
"chars": 113,
"preview": "# General deps\nnumpy\nscipy\nPyYAML\nipdb\n\n# MQTT\npaho-mqtt\n\n# Tracker\nnorfair\n\n# Colored prints and traceback\nrich\n"
},
{
"path": "requirements.txt",
"chars": 1032,
"preview": "# Versions frozen after `pip install -r requirements.in -c constraints.docker`\n# under balenalib/jetson-nano-ubuntu:bion"
},
{
"path": "server/backend/Dockerfile",
"chars": 220,
"preview": "FROM tiangolo/uvicorn-gunicorn-fastapi:python3.7\n\nCOPY ./app /app\nCOPY requirements.txt /app/requirements.txt\n\nENV PYTHO"
},
{
"path": "server/backend/alembic.ini",
"chars": 1967,
"preview": "# A generic, single database configuration.\n\n[alembic]\n# path to migration scripts\nscript_location = app/db/migrations\n\n"
},
{
"path": "server/backend/app/api/__init__.py",
"chars": 1485,
"preview": "################################################################################\n# Copyright (c) 2020-2021, Berkeley Des"
},
{
"path": "server/backend/app/api/exceptions.py",
"chars": 1923,
"preview": "################################################################################\n# Copyright (c) 2020-2021, Berkeley Des"
},
{
"path": "server/backend/app/api/routes/device_routes.py",
"chars": 5709,
"preview": "################################################################################\n# Copyright (c) 2020-2021, Berkeley Des"
},
{
"path": "server/backend/app/api/routes/statistic_routes.py",
"chars": 7876,
"preview": "################################################################################\n# Copyright (c) 2020-2021, Berkeley Des"
},
{
"path": "server/backend/app/core/config.py",
"chars": 1971,
"preview": "################################################################################\n# Copyright (c) 2020-2021, Berkeley Des"
},
{
"path": "server/backend/app/db/cruds/__init__.py",
"chars": 1662,
"preview": "################################################################################\n# Copyright (c) 2020-2021, Berkeley Des"
},
{
"path": "server/backend/app/db/cruds/crud_device.py",
"chars": 5273,
"preview": "################################################################################\n# Copyright (c) 2020-2021, Berkeley Des"
},
{
"path": "server/backend/app/db/cruds/crud_statistic.py",
"chars": 7742,
"preview": "################################################################################\n# Copyright (c) 2020-2021, Berkeley Des"
},
{
"path": "server/backend/app/db/cruds/crud_video_file.py",
"chars": 2985,
"preview": "################################################################################\n# Copyright (c) 2020-2021, Berkeley Des"
},
{
"path": "server/backend/app/db/migrations/env.py",
"chars": 3165,
"preview": "################################################################################\n# Copyright (c) 2020-2021, Berkeley Des"
},
{
"path": "server/backend/app/db/migrations/script.py.mako",
"chars": 494,
"preview": "\"\"\"${message}\n\nRevision ID: ${up_revision}\nRevises: ${down_revision | comma,n}\nCreate Date: ${create_date}\n\n\"\"\"\nfrom ale"
},
{
"path": "server/backend/app/db/migrations/versions/6a4d853aabce_added_database.py",
"chars": 554,
"preview": "\"\"\"Added database\n\nRevision ID: 6a4d853aabce\nRevises: 8f58cd776eda\nCreate Date: 2020-12-23 13:49:00.640607\n\n\"\"\"\nfrom ale"
},
{
"path": "server/backend/app/db/migrations/versions/6d5c250f098c_added_device_file_server_address.py",
"chars": 696,
"preview": "\"\"\"Added Device.file_server_address\n\nRevision ID: 6d5c250f098c\nRevises: fb245977373f\nCreate Date: 2021-01-26 14:55:11.50"
},
{
"path": "server/backend/app/db/migrations/versions/8f58cd776eda_added_database.py",
"chars": 1312,
"preview": "\"\"\"Added database\n\nRevision ID: 8f58cd776eda\nRevises: \nCreate Date: 2020-12-23 13:38:47.314749\n\n\"\"\"\nfrom alembic import "
},
{
"path": "server/backend/app/db/migrations/versions/fb245977373f_added_video_file_table.py",
"chars": 1604,
"preview": "\"\"\"Added video_file table\n\nRevision ID: fb245977373f\nRevises: 6a4d853aabce\nCreate Date: 2021-01-21 22:47:20.335928\n\n\"\"\"\n"
},
{
"path": "server/backend/app/db/schema/__init__.py",
"chars": 1501,
"preview": "################################################################################\n# Copyright (c) 2020-2021, Berkeley Des"
},
{
"path": "server/backend/app/db/schema/base.py",
"chars": 2186,
"preview": "################################################################################\n# Copyright (c) 2020-2021, Berkeley Des"
},
{
"path": "server/backend/app/db/schema/models.py",
"chars": 2497,
"preview": "################################################################################\n# Copyright (c) 2020-2021, Berkeley Des"
},
{
"path": "server/backend/app/db/schema/schemas.py",
"chars": 2010,
"preview": "################################################################################\n# Copyright (c) 2020-2021, Berkeley Des"
},
{
"path": "server/backend/app/db/utils/__init__.py",
"chars": 101,
"preview": "from .enums import StatisticTypeEnum\nfrom .utils import convert_timestamp_to_datetime, get_enum_type\n"
},
{
"path": "server/backend/app/db/utils/enums.py",
"chars": 102,
"preview": "from enum import Enum\n\n\nclass StatisticTypeEnum(str, Enum):\n REPORT = \"REPORT\"\n ALERT = \"ALERT\"\n"
},
{
"path": "server/backend/app/db/utils/utils.py",
"chars": 841,
"preview": "from datetime import datetime, timezone\n\nfrom .enums import StatisticTypeEnum\n\n\ndef convert_timestamp_to_datetime(timest"
},
{
"path": "server/backend/app/main.py",
"chars": 1603,
"preview": "################################################################################\n# Copyright (c) 2020-2021, Berkeley Des"
},
{
"path": "server/backend/app/mqtt/broker.py",
"chars": 2278,
"preview": "################################################################################\n# Copyright (c) 2020-2021, Berkeley Des"
},
{
"path": "server/backend/app/mqtt/publisher.py",
"chars": 3665,
"preview": "################################################################################\n# Copyright (c) 2020-2021, Berkeley Des"
},
{
"path": "server/backend/app/mqtt/subscriber.py",
"chars": 4990,
"preview": "################################################################################\n# Copyright (c) 2020-2021, Berkeley Des"
},
{
"path": "server/backend/prestart.sh",
"chars": 163,
"preview": "#!/bin/bash\n\n# Wait database initialization and apply migrations if needed\nsleep 3\nalembic upgrade head\n\n# Init subscrib"
},
{
"path": "server/backend/requirements.txt",
"chars": 126,
"preview": "paho-mqtt==1.5.1\nSQLAlchemy==1.3.21\npython-dotenv==0.15.0\npsycopg2-binary==2.8.6\nalembic==1.4.3\npytest==6.2.1\npydantic=="
},
{
"path": "server/backend/test_crud.py",
"chars": 8846,
"preview": "################################################################################\n# Copyright (c) 2020-2021, Berkeley Des"
},
{
"path": "server/backend.env.template",
"chars": 196,
"preview": "MQTT_BROKER=mosquitto\nMQTT_BROKER_PORT=1883\nSUBSCRIBER_CLIENT_ID=server_backend\nMQTT_HELLO_TOPIC=hello\nMQTT_ALERT_TOPIC="
},
{
"path": "server/build_docker.sh",
"chars": 64,
"preview": "#!/bin/bash\nsudo docker-compose build\nsudo docker-compose up -d\n"
},
{
"path": "server/database.env.template",
"chars": 115,
"preview": "POSTGRES_USER=<DATABASE_USER>\nPOSTGRES_PASSWORD=<DATABASE_PASSWORD>\nPOSTGRES_PORT=5432\nPOSTGRES_DB=<DATABASE_NAME>\n"
},
{
"path": "server/docker-compose.yml",
"chars": 1076,
"preview": "version: '3.1'\nservices:\n\n db:\n image: postgres:13.2\n env_file:\n - database.env\n volumes:\n - pgdata:"
},
{
"path": "server/frontend/Dockerfile",
"chars": 124,
"preview": "FROM python:3.7\n\nEXPOSE 8501\n\nWORKDIR /usr/src/app\n\nCOPY requirements.txt ./\n\nRUN pip install -r requirements.txt\n\nCOPY "
},
{
"path": "server/frontend/main.py",
"chars": 12795,
"preview": "################################################################################\n# Copyright (c) 2020-2021, Berkeley Des"
},
{
"path": "server/frontend/requirements.txt",
"chars": 67,
"preview": "streamlit==0.74.1\nrequests==2.25.1\nplotly==4.14.3\npaho-mqtt==1.5.1\n"
},
{
"path": "server/frontend/session_manager.py",
"chars": 4092,
"preview": "################################################################################\n# Copyright (c) 2020-2021, Berkeley Des"
},
{
"path": "server/frontend/utils/api_utils.py",
"chars": 2765,
"preview": "################################################################################\n# Copyright (c) 2020-2021, Berkeley Des"
},
{
"path": "server/frontend/utils/format_utils.py",
"chars": 8530,
"preview": "################################################################################\n# Copyright (c) 2020-2021, Berkeley Des"
},
{
"path": "server/frontend.env.template",
"chars": 93,
"preview": "SERVER_URL=backend\nMQTT_BROKER=mosquitto\nMQTT_BROKER_PORT=1883\nMQTT_CLIENT_ID=server_frontend"
},
{
"path": "server/mosquitto.conf",
"chars": 20,
"preview": "bind_address 0.0.0.0"
},
{
"path": "server/server_setup.sh",
"chars": 309,
"preview": "#!/bin/bash\nsudo apt-get update\nsudo apt install docker.io -y\nsudo systemctl start docker\nsudo curl -L \"https://github.c"
},
{
"path": "server/stop_docker.sh",
"chars": 37,
"preview": "#!/bin/bash\nsudo docker-compose down\n"
},
{
"path": "utils/combine_coco.py",
"chars": 2338,
"preview": "# %%\nimport json\nimport sys\n\n\n# %%\ndef merge_2_into_1(json1, json2):\n # ID offsets to put annotations and images from"
},
{
"path": "utils/gst_capabilities.sh",
"chars": 120,
"preview": "gst-launch-1.0 --gst-debug=v4l2src:5 v4l2src device=/dev/video0 ! fakesink 2>&1 | sed -une '/caps of src/ s/[:;] /\\n/gp'"
},
{
"path": "utils/mqtt-test/broker.py",
"chars": 519,
"preview": "import os\nfrom paho.mqtt import client as mqtt_client\n\nMQTT_BROKER = os.environ[\"MQTT_BROKER\"]\nMQTT_BROKER_PORT = 1883\n\n"
},
{
"path": "utils/mqtt-test/publisher.py",
"chars": 810,
"preview": "import json\nimport random\nimport time\nfrom datetime import datetime, timezone\n\nfrom broker import connect_mqtt_broker\n\n\n"
},
{
"path": "utils/mqtt-test/suscriber.py",
"chars": 588,
"preview": "import json\n\nfrom broker import connect_mqtt_broker\nfrom paho.mqtt import client as mqtt_client\n\n\ndef subscribe(client: "
},
{
"path": "utils/onnx_fix_mobilenet.py",
"chars": 737,
"preview": "import sys\nimport onnx_graphsurgeon as gs\nimport onnx\nimport numpy as np\n\n\"\"\"\nThis code is intended to change the uint8 "
},
{
"path": "utils/remove_images_coco.py",
"chars": 2279,
"preview": "# %%\nimport json\nimport sys\n\n\n# %%\ndef merge_2_into_1(json1, json2):\n # TODO: Remap category IDs according to their n"
},
{
"path": "utils/tf1_trt_inference.py",
"chars": 1678,
"preview": "import tensorflow as tf\nfrom tensorflow.python.compiler.tensorrt import trt_convert\nimport tensorflow.contrib.tensorrt a"
},
{
"path": "utils/tf2_trt_convert.py",
"chars": 1513,
"preview": "import sys\nimport tensorflow as tf\nfrom tensorflow.python.compiler.tensorrt import trt_convert as trt\n\ninput_saved_model"
},
{
"path": "utils/tf_trt_convert.py",
"chars": 3964,
"preview": "# %%\nimport sys\nimport os\nimport time\nimport urllib\nimport matplotlib\nimport numpy as np\nimport tensorflow as tf\nimport "
},
{
"path": "yolo/config.py",
"chars": 2317,
"preview": "################################################################################\n# Copyright (c) 2020-2021, Berkeley Des"
},
{
"path": "yolo/config_images.yml",
"chars": 635,
"preview": "yolo_generic:\n detection_threshold: 0.1\n nms_threshold: 0.1 # Lower values filter more\n distance_threshold: 1\n\nyolo_"
},
{
"path": "yolo/data/obj.data",
"chars": 98,
"preview": "classes = 4\ntrain = data/train.txt\nvalid = data/valid.txt\nnames = data/obj.names\nbackup = backup/\n"
},
{
"path": "yolo/data/obj.names",
"chars": 35,
"preview": "mask\nno_mask\nnot_visible\nmisplaced\n"
},
{
"path": "yolo/facemask-yolov4-tiny.cfg",
"chars": 3140,
"preview": "[net]\n# Testing\n#batch=1\n#subdivisions=1\n# Training\nbatch=64\nsubdivisions=16\n# Sizes: multiples of 32. Ratio (hd/4k vide"
},
{
"path": "yolo/facemask-yolov4.cfg",
"chars": 12252,
"preview": "[net]\n# Testing\n#batch=1\n#subdivisions=1\n# Training\nbatch=64\nsubdivisions=32\nwidth=608\nheight=608\nchannels=3\nmomentum=0."
},
{
"path": "yolo/integrations/yolo/detector_trt.py",
"chars": 10035,
"preview": "import sys\nimport os\nimport time\nimport argparse\nimport numpy as np\nimport cv2\nimport tensorrt as trt\n\nimport pycuda.dri"
},
{
"path": "yolo/integrations/yolo/utils_pytorch.py",
"chars": 3414,
"preview": "import numpy as np\n\n\n\"\"\"\nFunctions copied from pytorch-YOLOv4/tool/utils.py with all calls to print() removed\n\"\"\"\n\n\ndef "
},
{
"path": "yolo/integrations/yolo/yolo_adaptor.py",
"chars": 3079,
"preview": "import cv2\nimport numpy as np\n\nfrom norfair.drawing import Color\n\n\nclass YoloAdaptor:\n def __init__(self, config):\n "
},
{
"path": "yolo/run_yolo_images.py",
"chars": 3338,
"preview": "################################################################################\n# Copyright (c) 2020-2021, Berkeley Des"
},
{
"path": "yolo/train_cu90.sh",
"chars": 176,
"preview": "mkdir -p backup\nLD_LIBRARY_PATH=/usr/local/cuda-9.0/lib64/ ./darknet detector train data/obj.data facemask-yolov4-tiny.c"
}
]
About this extraction
This page contains the full source code of the bdtinc/maskcam GitHub repository, extracted and formatted as plain text for AI agents and large language models (LLMs). The extraction includes 106 files (388.6 KB), approximately 99.4k tokens, and a symbol index with 266 extracted functions, classes, methods, constants, and types. Use this with OpenClaw, Claude, ChatGPT, Cursor, Windsurf, or any other AI tool that accepts text input. You can copy the full output to your clipboard or download it as a .txt file.
Extracted by GitExtract — free GitHub repo to text converter for AI. Built by Nikandr Surkov.