├── .gitignore ├── LICENSE ├── README.md ├── _config.yml ├── model └── README.md ├── testing ├── README.md ├── config ├── config.py ├── config_reader.py ├── demo_3d_image.py ├── model.py ├── model │ └── keras │ │ └── README.md ├── samples │ ├── 03-18-11-27-03_3V_completed_D4_05433depth.pgm │ ├── 03-18-11-27-03_3V_completed_D4_05433flow.png │ ├── 03-18-11-27-03_3V_completed_D4_05433mc_blob.png │ ├── 03-18-11-27-03_3V_completed_D6_05433depth.pgm │ ├── 03-18-11-27-03_3V_completed_D6_05433flow.png │ ├── 03-18-11-27-03_3V_completed_D6_05433mc_blob.png │ ├── 03-18-11-27-03_3V_completed_D8_05433depth.pgm │ ├── 03-18-11-27-03_3V_completed_D8_05433flow.png │ ├── 03-18-11-27-03_3V_completed_D8_05433mc_blob.png │ ├── D4.extrinsics │ ├── D4.pmm │ ├── D6.extrinsics │ ├── D6.pmm │ ├── D8.extrinsics │ ├── D8.pmm │ └── README.md └── util.py └── tools ├── 2D-reflector-annotator ├── .vs │ └── 2D-reflector-annotator │ │ └── v14 │ │ └── .suo ├── 2D-reflector-annotator.csproj ├── 2D-reflector-annotator.sln ├── App.config ├── App.xaml ├── App.xaml.cs ├── JSONPoseFormatDataSet.cs ├── MainWindow.xaml ├── MainWindow.xaml.cs ├── Properties │ ├── AssemblyInfo.cs │ ├── Resources.Designer.cs │ ├── Resources.resx │ ├── Settings.Designer.cs │ └── Settings.settings ├── README.md ├── assemblies │ ├── Emgu.CV.UI.GL.dll │ ├── Emgu.CV.UI.dll │ ├── Emgu.CV.World.dll │ ├── MahApps.Metro.dll │ ├── MahApps.Metro.xml │ ├── Newtonsoft.Json.dll │ ├── Ookii.Dialogs.Wpf.dll │ └── VCL.Moto.dll ├── img │ └── legend.jpg ├── packages.config └── packages │ ├── MahApps.Metro.1.5.0 │ ├── MahApps.Metro.1.5.0.nupkg │ └── tools │ │ └── install.ps1 │ ├── Newtonsoft.Json.10.0.3 │ ├── LICENSE.md │ ├── Newtonsoft.Json.10.0.3.nupkg │ └── tools │ │ └── install.ps1 │ └── Ookii.Dialogs.1.0 │ ├── Ookii.Dialogs.1.0.nupkg │ ├── license.txt │ └── readme.html └── README.md /.gitignore: -------------------------------------------------------------------------------- 1 | # Byte-compiled / optimized / DLL files 2 | __pycache__/ 3 | *.py[cod] 4 | *$py.class 5 | 6 | # C extensions 7 | *.so 8 | 9 | # Distribution / packaging 10 | .Python 11 | build/ 12 | develop-eggs/ 13 | dist/ 14 | downloads/ 15 | eggs/ 16 | .eggs/ 17 | lib/ 18 | lib64/ 19 | parts/ 20 | sdist/ 21 | var/ 22 | wheels/ 23 | *.egg-info/ 24 | .installed.cfg 25 | *.egg 26 | MANIFEST 27 | 28 | # PyInstaller 29 | # Usually these files are written by a python script from a template 30 | # before PyInstaller builds the exe, so as to inject date/other infos into it. 31 | *.manifest 32 | *.spec 33 | 34 | # Installer logs 35 | pip-log.txt 36 | pip-delete-this-directory.txt 37 | 38 | # Unit test / coverage reports 39 | htmlcov/ 40 | .tox/ 41 | .coverage 42 | .coverage.* 43 | .cache 44 | nosetests.xml 45 | coverage.xml 46 | *.cover 47 | .hypothesis/ 48 | .pytest_cache/ 49 | 50 | # Translations 51 | *.mo 52 | *.pot 53 | 54 | # Django stuff: 55 | *.log 56 | local_settings.py 57 | db.sqlite3 58 | 59 | # Flask stuff: 60 | instance/ 61 | .webassets-cache 62 | 63 | # Scrapy stuff: 64 | .scrapy 65 | 66 | # Sphinx documentation 67 | docs/_build/ 68 | 69 | # PyBuilder 70 | target/ 71 | 72 | # Jupyter Notebook 73 | .ipynb_checkpoints 74 | 75 | # pyenv 76 | .python-version 77 | 78 | # celery beat schedule file 79 | celerybeat-schedule 80 | 81 | # SageMath parsed files 82 | *.sage.py 83 | 84 | # Environments 85 | .env 86 | .venv 87 | env/ 88 | venv/ 89 | ENV/ 90 | env.bak/ 91 | venv.bak/ 92 | 93 | # Spyder project settings 94 | .spyderproject 95 | .spyproject 96 | 97 | # Rope project settings 98 | .ropeproject 99 | 100 | # mkdocs documentation 101 | /site 102 | 103 | # mypy 104 | .mypy_cache/ 105 | -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- 1 | DeepMoCap: Optical Motion Capture leveraging multiple Depth Sensors, Retro-reflectors and Fully Convolutional Neural Networks 2 | SOFTWARE LICENSE AGREEMENT 3 | ACADEMIC OR NON-PROFIT ORGANIZATION NONCOMMERCIAL RESEARCH USE ONLY 4 | 5 | BY USING OR DOWNLOADING THE SOFTWARE, YOU ARE AGREEING TO THE TERMS OF THIS LICENSE AGREEMENT. IF YOU DO NOT AGREE WITH THESE TERMS, YOU MAY NOT USE OR DOWNLOAD THE SOFTWARE. 6 | 7 | This is a license agreement ("Agreement") between your academic institution or non-profit organization or self (called "Licensee" or "You" in this Agreement) and Carnegie Mellon University (called "Licensor" in this Agreement). All rights not specifically granted to you in this Agreement are reserved for Licensor. 8 | 9 | RESERVATION OF OWNERSHIP AND GRANT OF LICENSE: 10 | Licensor retains exclusive ownership of any copy of the Software (as defined below) licensed under this Agreement and hereby grants to Licensee a personal, non-exclusive, 11 | non-transferable license to use the Software for noncommercial research purposes, without the right to sublicense, pursuant to the terms and conditions of this Agreement. As used in this Agreement, the term "Software" means (i) the actual copy of all or any portion of code for program routines made accessible to Licensee by Licensor pursuant to this Agreement, inclusive of backups, updates, and/or merged copies permitted hereunder or subsequently supplied by Licensor, including all or any file structures, programming instructions, user interfaces and screen formats and sequences as well as any and all documentation and instructions related to it, and (ii) all or any derivatives and/or modifications created or made by You to any of the items specified in (i). 12 | 13 | CONFIDENTIALITY: Licensee acknowledges that the Software is proprietary to Licensor, and as such, Licensee agrees to receive all such materials in confidence and use the Software only in accordance with the terms of this Agreement. Licensee agrees to use reasonable effort to protect the Software from unauthorized use, reproduction, distribution, or publication. 14 | 15 | COPYRIGHT: The Software is owned by Licensor and is protected by United 16 | States copyright laws and applicable international treaties and/or conventions. 17 | 18 | PERMITTED USES: The Software may be used for your own noncommercial internal research purposes. You understand and agree that Licensor is not obligated to implement any suggestions and/or feedback you might provide regarding the Software, but to the extent Licensor does so, you are not entitled to any compensation related thereto. 19 | 20 | DERIVATIVES: You may create derivatives of or make modifications to the Software, however, You agree that all and any such derivatives and modifications will be owned by Licensor and become a part of the Software licensed to You under this Agreement. You may only use such derivatives and modifications for your own noncommercial internal research purposes, and you may not otherwise use, distribute or copy such derivatives and modifications in violation of this Agreement. 21 | 22 | BACKUPS: If Licensee is an organization, it may make that number of copies of the Software necessary for internal noncommercial use at a single site within its organization provided that all information appearing in or on the original labels, including the copyright and trademark notices are copied onto the labels of the copies. 23 | 24 | USES NOT PERMITTED: You may not distribute, copy or use the Software except as explicitly permitted herein. Licensee has not been granted any trademark license as part of this Agreement and may not use the name or mark “OpenPose", "Carnegie Mellon" or any renditions thereof without the prior written permission of Licensor. 25 | 26 | You may not sell, rent, lease, sublicense, lend, time-share or transfer, in whole or in part, or provide third parties access to prior or present versions (or any parts thereof) of the Software. 27 | 28 | ASSIGNMENT: You may not assign this Agreement or your rights hereunder without the prior written consent of Licensor. Any attempted assignment without such consent shall be null and void. 29 | 30 | TERM: The term of the license granted by this Agreement is from Licensee's acceptance of this Agreement by downloading the Software or by using the Software until terminated as provided below. 31 | 32 | The Agreement automatically terminates without notice if you fail to comply with any provision of this Agreement. Licensee may terminate this Agreement by ceasing using the Software. Upon any termination of this Agreement, Licensee will delete any and all copies of the Software. You agree that all provisions which operate to protect the proprietary rights of Licensor shall remain in force should breach occur and that the obligation of confidentiality described in this Agreement is binding in perpetuity and, as such, survives the term of the Agreement. 33 | 34 | FEE: Provided Licensee abides completely by the terms and conditions of this Agreement, there is no fee due to Licensor for Licensee's use of the Software in accordance with this Agreement. 35 | 36 | DISCLAIMER OF WARRANTIES: THE SOFTWARE IS PROVIDED "AS-IS" WITHOUT WARRANTY OF ANY KIND INCLUDING ANY WARRANTIES OF PERFORMANCE OR MERCHANTABILITY OR FITNESS FOR A PARTICULAR USE OR PURPOSE OR OF NON-INFRINGEMENT. LICENSEE BEARS ALL RISK RELATING TO QUALITY AND PERFORMANCE OF THE SOFTWARE AND RELATED MATERIALS. 37 | 38 | SUPPORT AND MAINTENANCE: No Software support or training by the Licensor is provided as part of this Agreement. 39 | 40 | EXCLUSIVE REMEDY AND LIMITATION OF LIABILITY: To the maximum extent permitted under applicable law, Licensor shall not be liable for direct, indirect, special, incidental, or consequential damages or lost profits related to Licensee's use of and/or inability to use the Software, even if Licensor is advised of the possibility of such damage. 41 | 42 | EXPORT REGULATION: Licensee agrees to comply with any and all applicable 43 | U.S. export control laws, regulations, and/or other laws related to embargoes and sanction programs administered by the Office of Foreign Assets Control. 44 | 45 | SEVERABILITY: If any provision(s) of this Agreement shall be held to be invalid, illegal, or unenforceable by a court or other tribunal of competent jurisdiction, the validity, legality and enforceability of the remaining provisions shall not in any way be affected or impaired thereby. 46 | 47 | NO IMPLIED WAIVERS: No failure or delay by Licensor in enforcing any right or remedy under this Agreement shall be construed as a waiver of any future or other exercise of such right or remedy by Licensor. 48 | 49 | GOVERNING LAW: This Agreement shall be construed and enforced in accordance with the laws of the Commonwealth of Pennsylvania without reference to conflict of laws principles. You consent to the personal jurisdiction of the courts of this County and waive their rights to venue outside of Allegheny County, Pennsylvania. 50 | 51 | ENTIRE AGREEMENT AND AMENDMENTS: This Agreement constitutes the sole and entire agreement between Licensee and Licensor as to the matter set forth herein and supersedes any previous agreements, understandings, and arrangements between the parties relating hereto. 52 | 53 | ************************************************************************ 54 | 55 | THIRD-PARTY SOFTWARE NOTICES AND INFORMATION 56 | 57 | COPYRIGHT 58 | 59 | All contributions by the University of California: 60 | Copyright (c) 2014-2017 The Regents of the University of California (Regents) 61 | All rights reserved. 62 | 63 | All other contributions: 64 | Copyright (c) 2014-2017, the respective contributors 65 | All rights reserved. 66 | 67 | Caffe uses a shared copyright model: each contributor holds copyright over 68 | their contributions to Caffe. The project versioning records all such 69 | contribution and copyright details. If a contributor wants to further mark 70 | their specific copyright on a particular contribution, they should indicate 71 | their copyright solely in the commit message of the change when it is 72 | committed. 73 | 74 | LICENSE 75 | 76 | Redistribution and use in source and binary forms, with or without 77 | modification, are permitted provided that the following conditions are met: 78 | 79 | 1. Redistributions of source code must retain the above copyright notice, this 80 | list of conditions and the following disclaimer. 81 | 2. Redistributions in binary form must reproduce the above copyright notice, 82 | this list of conditions and the following disclaimer in the documentation 83 | and/or other materials provided with the distribution. 84 | 85 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND 86 | ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED 87 | WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 88 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR 89 | ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES 90 | (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 91 | LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND 92 | ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT 93 | (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 94 | SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 95 | 96 | CONTRIBUTION AGREEMENT 97 | 98 | By contributing to the BVLC/caffe repository through pull-request, comment, 99 | or otherwise, the contributor releases their content to the 100 | license and copyright terms herein. 101 | 102 | ************END OF THIRD-PARTY SOFTWARE NOTICES AND INFORMATION********** -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # DeepMoCap: Deep Optical Motion Capture using multiple Depth Sensors and Retro-reflectors 2 | By [Anargyros Chatzitofis](https://www.iti.gr/iti/people/Anargyros_Chatzitofis.html), [Dimitris Zarpalas](https://www.iti.gr/iti/people/Dimitrios_Zarpalas.html), [Stefanos Kollias](https://www.ece.ntua.gr/gr/staff/15), [Petros Daras](https://www.iti.gr/iti/people/Petros_Daras.html). 3 | 4 | 5 | 6 | ## Introduction 7 | **DeepMoCap** constitutes a low-cost, marker-based optical motion capture method that consumes multiple spatio-temporally aligned infrared-depth sensor streams using retro-reflective straps and patches (reflectors). 8 | 9 | DeepMoCap explores motion capture by automatically localizing and labeling reflectors on depth images and, subsequently, on 3D space. Introducing a non-parametric representation to encode the temporal correlation among pairs of colorized depthmaps and 3D optical flow frames, a multi-stage Fully Convolutional Network (FCN) architecture is proposed to jointly learn reflector locations and their temporal dependency among sequential frames. The extracted reflector 2D locations are spatially mapped in 3D space, resulting in robust optical data extraction. To this end, the subject's motion is efficiently captured by applying a template-based fitting technique. 10 | 11 |  12 | 13 |  14 | 15 | This project is licensed under the terms of the [license](LICENSE). 16 | 17 | 18 | 19 | ## Contents 20 | 1. [Testing](#testing) 21 | 2. [Datasets](#datasets) 22 | 3. [Citation](#citation) 23 | 24 | ## Testing 25 | For testing the FCN model, please visit ["testing/"](/testing/) enabling the 3D optical data extraction from colorized depth and 3D optical flow input. The data should be appropriately formed and the DeepMoCap FCN model should be placed to ["testing/model/keras"](/testing/model/keras). 26 | 27 | The proposed FCN is evaluated on the DMC2.5D dataset measuring mean Average Precision (mAP) for the entire set, based on Percentage of Correct Keypoints (PCK) thresholds (a = 0.05). The proposed method outperforms the competitive methods as shown in the table below. 28 | 29 | | Method | Total | Total (without end-reflectors) | 30 | | :---: | :---: | :---: | 31 | | CPM | 92.16% | 95.27% | 32 | | CPM+PAFs | 92.79\% | 95.61% | 33 | | CPM+PAFs + 3D OF | 92.84\% | 95.67% | 34 | | **Proposed** | **93.73%** | **96.77%** | 35 | 36 |  37 | 38 | 39 | 40 | ## Supplementaty material (video) 41 | [](https://www.youtube.com/watch?v=OvCJ-WWyLcM) 42 | 43 | ## Datasets 44 | Two datasets have been created and made publicly available for evaluation purposes; one comprising multi-view depth and 3D optical flow annotated images (DMC2.5D), and a second, consisting of spatio-temporally aligned multi-view depth images along with skeleton, inertial and ground truth MoCap data (DMC3D). 45 | 46 | ### DMC2.5D 47 | The DMC2.5D Dataset was captured in order to train and test the DeepMoCap FCN. It comprises pairs per view of: 48 | - colorized depth and 49 | - 3D optical flow data (the primal-dual algorithm used in the present work can be found @ https://github.com/MarianoJT88/PD-Flow, using IR data instead of RGB). 50 | 51 | The samples were randomly selected from 8 subjects. More specifically, 25K single-view pair samples were annotated with over 300K total keypoints (i.e., reflector 2D locations of current and previous frames on the image), trying to cover a variety of poses and movements in the scene. 20K, 3K and 2K samples were used for training, validation and testing the FCN model, respectively. The annotation was semi-automatically realized by applying image processing and 3D vision techniques, while the dataset was manually refined using the [2D-reflectorset-annotator](/tools/2D-reflector-annotator/). 52 | 53 |  54 | 55 | To get the DMC2.5D dataset, please contact the owner of the repository via github or email (tofis@iti.gr). 56 | 57 | ### DMC3D 58 | 59 |  60 | 61 | The DMC3D dataset consists of multi-view depth and skeleton data as well as inertial and ground truth motion capture data. Specifically, 3 Kinect for Xbox One sensors were used to capture the IR-D and Kinect skeleton data along with 9 **XSens MT inertial** measurement units (IMU) to enable the comparison between the proposed method and inertial MoCap approaches. Further, a **PhaseSpace Impulse X2** solution was used to capture ground truth MoCap data. The preparation of the DMC3D dataset required the spatio-temporal alignment of the modalities (Kinect, PhaseSpace, XSens MTs). The setup used for the Kinect recordings provides spatio-temporally aligned IR-D and skeleton frames. 62 | 63 | | Exercise | # of repetitions | # of frames | Type | 64 | | :---: | :---: | :---: | :---: | 65 | | Walking on the spot | 10-20 | 200-300 | Free | 66 | | Single arm raise | 10-20 | 300-500 | Bilateral | 67 | | Elbow flexion | 10-20 | 300-500 | Bilateral | 68 | | Knee flexion | 10-20 | 300-500 | Bilateral | 69 | | Closing arms above head | 6-12 | 200-300 | Free | 70 | | Side steps | 6-12 | 300-500 | Bilateral | 71 | | Jumping jack | 6-12 | 200-300 | Free | 72 | | Butt kicks left-right | 6-12 | 300-500 | Bilateral | 73 | | Forward lunge left-right | 4-10 | 300-500 | Bilateral | 74 | | Classic squat | 6-12 | 200-300 | Free | 75 | | Side step + knee-elbow | 6-12 | 300-500 | Bilateral | 76 | | Side reaches | 6-12 | 300-500 | Bilateral | 77 | | Side jumps | 6-12 | 300-500 | Bilateral | 78 | | Alternate side reaches | 6-12 | 300-500 | Bilateral | 79 | | Kick-box kicking | 2-6 | 200-300 | Free | 80 | 81 | The annotation tool for the spatio-temporally alignment of the 3D data will be publicly available soon. 82 | 83 | To get the DMC3D dataset, please contact the owner of the repository via github or email (tofis@iti.gr). 84 | 85 | ## Citation 86 | This paper has been published in MDPI Sensors, Depth Sensors and 3D Vision Special Issue [[PDF]](https://www.mdpi.com/1424-8220/19/2/282) 87 | 88 | Please cite the paper in your publications if it helps your research: 89 | 90 |
91 | @article{chatzitofis2019deepmocap,
92 | title={DeepMoCap: Deep Optical Motion Capture Using Multiple Depth Sensors and Retro-Reflectors},
93 | author={Chatzitofis, Anargyros and Zarpalas, Dimitrios and Kollias, Stefanos and Daras, Petros},
94 | journal={Sensors},
95 | volume={19},
96 | number={2},
97 | pages={282},
98 | year={2019},
99 | publisher={Multidisciplinary Digital Publishing Institute}
100 | }
101 |
102 |
--------------------------------------------------------------------------------
/_config.yml:
--------------------------------------------------------------------------------
1 | theme: jekyll-theme-minimal
--------------------------------------------------------------------------------
/model/README.md:
--------------------------------------------------------------------------------
1 | Download the model from this [url](http://deepmocap.com/model/deepmocap_model.h5).
2 |
--------------------------------------------------------------------------------
/testing/README.md:
--------------------------------------------------------------------------------
1 | For testing the FCN model, please visit ["testing/"](/testing/) enabling the 3D optical data extraction from colorized depth and 3D optical flow input. The data should be appropriately formed and the DeepMoCap FCN model should be placed to ["testing/model/keras"](/testing/model/keras).
2 |
3 | The proposed FCN is evaluated on the DMC2.5D dataset measuring mean Average Precision (mAP) for the entire set, based on Percentage of Correct Keypoints (PCK) thresholds (a = 0.05). The proposed method outperforms the competitive methods as shown in the table below.
4 |
5 | | Method | Total | Total (without end-reflectors) |
6 | | :---: | :---: | :---: |
7 | | CPM | 92.16% | 95.27% |
8 | | CPM+PAFs | 92.79\% | 95.61% |
9 | | CPM+PAFs + 3D OF | 92.84\% | 95.67% |
10 | | **Proposed** | **93.73%** | **96.77%** |
11 |
12 | 
13 |
14 |
--------------------------------------------------------------------------------
/testing/config:
--------------------------------------------------------------------------------
1 | [param]
2 |
3 | # CPU mode or GPU mode
4 | use_gpu = 1
5 |
6 | # GPU device number (doesn't matter for CPU mode)
7 | GPUdeviceNumber = 0
8 |
9 | # Select model (default: 1)
10 | modelID = 1
11 |
12 | # Look in matlab counterpart for explanation
13 | octave = 3
14 | starting_range = 0.8
15 | ending_range = 2
16 | scale_search = 0.5, 1, 1.5, 2
17 | thre1 = 0.3
18 | thre2 = 0.0001
19 | thre3 = 0.5
20 | min_num = 4
21 | mid_num = 10
22 | crop_ratio = 2.5
23 | bbox_ratio = 0.25
24 |
25 | [models]
26 | ## don't edit this part
27 |
28 | [[1]]
29 | caffemodel = './model/_trained_COCO/pose_iter_440000.caffemodel'
30 | deployFile = './model/_trained_COCO/pose_deploy.prototxt'
31 | description = 'COCO Pose56 Two-level Linevec'
32 | boxsize = 368
33 | padValue = 128
34 | np = 12
35 | stride = 8
36 | part_str = [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, pt19]
37 |
--------------------------------------------------------------------------------
/testing/config.py:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 |
3 | import numpy as np
4 |
5 |
6 | Configs = {}
7 |
8 | class CanonicalConfig:
9 |
10 | def __init__(self):
11 |
12 | self.width = 368
13 | self.height = 368
14 |
15 | self.stride = 8
16 |
17 | self.parts = ["0", "1", "2", "3", "4", "5", "6", "7", "8", "9", "10", "11", "12", "13", "14", "15", "16", "17", "18", "19", "20", "21", "22", "23", "24", "25" ]
18 | self.num_parts = len(self.parts)
19 | self.parts_dict = dict(zip(self.parts, range(self.num_parts)))
20 | self.parts += ["background"]
21 | self.num_parts_with_background = len(self.parts)
22 |
23 | leftParts, rightParts = CanonicalConfig.ltr_parts(self.parts_dict)
24 | self.leftParts = leftParts
25 | self.rightParts = rightParts
26 |
27 |
28 | # this numbers probably copied from matlab they are 1.. based not 0.. based
29 | # self.limb_from = ['0', '0', '2', '14', '15', '16', '1', '9', '10', '11', '14', '9', '5', '6', '7', '18', '19', '20', '7', '22', '23', '24']
30 | # self.limb_to = ['1', '2', '14', '15', '16', '17', '9', '10', '11', '12', '4', '3', '6', '7', '18', '19', '20', '21', '22', '23', '24', '25']
31 |
32 | self.limb_from = ['0', '1', '2', '3', '4', '5', '6', '7', '8', '9', '10', '11', '12', '13', '14', '15', '16', '17', '18', '19', '20', '21', '22', '23', '24', '25' ]
33 | self.limb_to = ['0', '1', '2', '3', '4', '5', '6', '7', '8', '9', '10', '11', '12', '13', '14', '15', '16', '17', '18', '19', '20', '21', '22', '23', '24', '25' ]
34 |
35 |
36 | self.limb_from = [ self.parts_dict[n] for n in self.limb_from ]
37 | self.limb_to = [ self.parts_dict[n] for n in self.limb_to ]
38 |
39 | assert self.limb_from == [x-1 for x in [1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26]]
40 | assert self.limb_to == [x-1 for x in [1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26]]
41 |
42 | self.limbs_conn = list(zip(self.limb_from, self.limb_to))
43 |
44 | self.paf_layers = 2*len(self.limbs_conn)
45 | self.heat_layers = self.num_parts
46 | self.num_layers = self.paf_layers + self.heat_layers + 1
47 |
48 | self.paf_start = 0
49 | self.heat_start = self.paf_layers
50 | self.bkg_start = self.paf_layers + self.heat_layers
51 |
52 | #self.data_shape = (self.height, self.width, 3) # 368, 368, 3
53 | self.mask_shape = (self.height//self.stride, self.width//self.stride) # 46, 46
54 | self.parts_shape = (self.height//self.stride, self.width//self.stride, self.num_layers) # 46, 46, 57
55 |
56 | class TransformationParams:
57 |
58 | def __init__(self):
59 | self.target_dist = 0.6;
60 | self.scale_prob = 1; # TODO: this is actually scale unprobability, i.e. 1 = off, 0 = always, not sure if it is a bug or not
61 | self.scale_min = 0.5;
62 | self.scale_max = 1.1;
63 | self.max_rotate_degree = 40.
64 | self.center_perterb_max = 40.
65 | self.flip_prob = 0.5
66 | self.sigma = 7.
67 | self.paf_thre = 8. # it is original 1.0 * stride in this program
68 |
69 | self.transform_params = TransformationParams()
70 |
71 | @staticmethod
72 | def ltr_parts(parts_dict):
73 | # when we flip image left parts became right parts and vice versa. This is the list of parts to exchange each other.
74 | leftParts = [ parts_dict[p] for p in ["1", "3", "8", "9", "10", "11", "12", "18", "19", "20", "21"] ]
75 | rightParts = [ parts_dict[p] for p in ["2", "4", "13", "14", "15", "16", "17", "22", "23", "24", "25"] ]
76 | return leftParts,rightParts
77 |
78 |
79 |
80 | class COCOSourceConfig:
81 |
82 |
83 | def __init__(self, hdf5_source):
84 |
85 | self.hdf5_source = hdf5_source
86 | self.parts = ["0", "1", "2", "3", "4", "5", "6", "7", "8", "9", "10", "11", "12", "13", "14", "15", "16", "17", "18", "19", "20", "21", "22", "23", "24", "25"]
87 |
88 | self.num_parts = len(self.parts)
89 |
90 | # for COCO neck is calculated like mean of 2 shoulders.
91 | self.parts_dict = dict(zip(self.parts, range(self.num_parts)))
92 |
93 | def convert(self, meta, global_config):
94 |
95 | joints = np.array(meta['joints'])
96 | p_joints = np.array(meta['p_joints'])
97 |
98 | assert joints.shape[1] == len(self.parts)
99 | assert p_joints.shape[1] == len(self.parts)
100 |
101 | result = np.zeros((joints.shape[0], global_config.num_parts, 3), dtype=np.float)
102 | result[:,:,2]=3. # OURS - # 3 never marked up in this dataset, 2 - not marked up in this person, 1 - marked and visible, 0 - marked but invisible
103 |
104 | for p in self.parts:
105 | coco_id = self.parts_dict[p]
106 |
107 | if p in global_config.parts_dict:
108 | global_id = global_config.parts_dict[p]
109 | # assert global_id!=1, "neck shouldn't be known yet"
110 | result[:,global_id,:]=joints[:,coco_id,:]
111 |
112 |
113 | result_p = np.zeros((p_joints.shape[0], global_config.num_parts, 3), dtype=np.float)
114 | result_p[:,:,2]=3. # OURS - # 3 never marked up in this dataset, 2 - not marked up in this person, 1 - marked and visible, 0 - marked but invisible
115 |
116 | for p in self.parts:
117 | coco_id = self.parts_dict[p]
118 |
119 | if p in global_config.parts_dict:
120 | global_id = global_config.parts_dict[p]
121 | # assert global_id!=1, "neck shouldn't be known yet"
122 | result_p[:,global_id,:]=p_joints[:,coco_id,:]
123 | # there is no NECK in DeepMoCap
124 |
125 | # if 'neck' in global_config.parts_dict:
126 | # neckG = global_config.parts_dict['neck']
127 | # RshoC = self.parts_dict['Rsho']
128 | # LshoC = self.parts_dict['Lsho']
129 |
130 | # # no neck in coco database, we calculate it as average of shoulders
131 | # # TODO: we use 0 - hidden, 1 visible, 2 absent - it is not coco values they processed by generate_hdf5
132 | # both_shoulders_known = (joints[:, LshoC, 2]<2) & (joints[:, RshoC, 2] < 2)
133 |
134 | # result[~both_shoulders_known, neckG, 2] = 2. # otherwise they will be 3. aka 'never marked in this dataset'
135 |
136 | # result[both_shoulders_known, neckG, 0:2] = (joints[both_shoulders_known, RshoC, 0:2] +
137 | # joints[both_shoulders_known, LshoC, 0:2]) / 2
138 | # result[both_shoulders_known, neckG, 2] = np.minimum(joints[both_shoulders_known, RshoC, 2],
139 | # joints[both_shoulders_known, LshoC, 2])
140 |
141 | meta['joints'] = result
142 | meta['p_joints'] = result_p
143 |
144 | return meta
145 |
146 | def convert_mask(self, mask, global_config, joints = None):
147 |
148 | mask = np.repeat(mask[:,:,np.newaxis], global_config.num_layers, axis=2)
149 | return mask
150 |
151 | def source(self):
152 |
153 | return self.hdf5_source
154 |
155 |
156 |
157 | # more information on keypoints mapping is here
158 | # https://github.com/ZheC/Realtime_Multi-Person_Pose_Estimation/issues/7
159 |
160 |
161 | Configs["Canonical"] = CanonicalConfig
162 |
163 |
164 | def GetConfig(config_name):
165 |
166 | config = Configs[config_name]()
167 |
168 | dct = config.parts[:]
169 | dct = [None]*(config.num_layers-len(dct)) + dct
170 |
171 | for (i,(fr,to)) in enumerate(config.limbs_conn):
172 | name = "%s->%s" % (config.parts[fr], config.parts[to])
173 | print(i, name)
174 | x = i*2
175 | y = i*2+1
176 |
177 | assert dct[x] is None
178 | dct[x] = name + ":x"
179 | assert dct[y] is None
180 | dct[y] = name + ":y"
181 |
182 | from pprint import pprint
183 | pprint(dict(zip(range(len(dct)), dct)))
184 |
185 | return config
186 |
187 | if __name__ == "__main__":
188 |
189 | # test it
190 | foo = GetConfig("Canonical")
191 | print(foo.paf_layers, foo.heat_layers)
192 |
193 |
194 |
--------------------------------------------------------------------------------
/testing/config_reader.py:
--------------------------------------------------------------------------------
1 | from configobj import ConfigObj
2 | import numpy as np
3 |
4 |
5 | def config_reader():
6 | config = ConfigObj('config')
7 |
8 | param = config['param']
9 | model_id = param['modelID']
10 | model = config['models'][model_id]
11 | model['boxsize'] = int(model['boxsize'])
12 | model['stride'] = int(model['stride'])
13 | model['padValue'] = int(model['padValue'])
14 | #param['starting_range'] = float(param['starting_range'])
15 | #param['ending_range'] = float(param['ending_range'])
16 | param['octave'] = int(param['octave'])
17 | param['use_gpu'] = int(param['use_gpu'])
18 | param['starting_range'] = float(param['starting_range'])
19 | param['ending_range'] = float(param['ending_range'])
20 | param['scale_search'] = map(float, param['scale_search'])
21 | param['thre1'] = float(param['thre1'])
22 | param['thre2'] = float(param['thre2'])
23 | param['thre3'] = float(param['thre3'])
24 | param['mid_num'] = int(param['mid_num'])
25 | param['min_num'] = int(param['min_num'])
26 | param['crop_ratio'] = float(param['crop_ratio'])
27 | param['bbox_ratio'] = float(param['bbox_ratio'])
28 | param['GPUdeviceNumber'] = int(param['GPUdeviceNumber'])
29 |
30 | return param, model
31 |
32 | if __name__ == "__main__":
33 | config_reader()
34 |
--------------------------------------------------------------------------------
/testing/demo_3d_image.py:
--------------------------------------------------------------------------------
1 | import argparse
2 | import cv2
3 | import math
4 | import time
5 | import numpy as np
6 | import util
7 | from config_reader import config_reader
8 | from scipy.ndimage.filters import gaussian_filter
9 | from model import get_testing_model
10 | import re
11 | from sklearn.cluster import KMeans
12 |
13 | import glob, os
14 |
15 |
16 | # reflectors
17 | reflectors = [
18 | "NONE",
19 | "F_SPINEMID",
20 | "F_R_CHEST",
21 | "F_L_CHEST",
22 | "F_R_HEAD",
23 | "F_L_HEAD",
24 | "B_HEAD",
25 | "B_BACK",
26 | "B_SPINEMID",
27 | "B_R_SHOULDER",
28 | "F_R_SHOULDER",
29 | "R_ELBOW",
30 | "R_WRIST",
31 | "R_HAND",
32 | "B_L_SHOULDER",
33 | "F_L_SHOULDER",
34 | "L_ELBOW",
35 | "L_WRIST",
36 | "L_HAND",
37 | "R_PELVIS",
38 | "R_CALF",
39 | "R_ANKLE",
40 | "R_FOOT",
41 | "L_PELVIS",
42 | "L_CALF",
43 | "L_ANKLE",
44 | "L_FOOT",
45 | "NOSE"]
46 |
47 | # find connection in the specified sequence, center 29 is in the position 15
48 | limbSeq = [[1, 2], [1, 3], [2, 10], [10, 11], [11, 12], [12, 13], [3, 15], [15, 16], [16, 17], \
49 | [17, 18], [1, 19], [19, 20], [20, 21], [21, 22], [1, 23], [23, 24], [24, 25], [25, 26], \
50 | [4, 6], [5, 6], [6, 7], [7, 8], [8, 19], [8, 23], [7, 9], [9, 11], [7, 14], [14, 16]]
51 |
52 | # the middle joints heatmap correpondence
53 | mapIdx = [[28,29], [29,30], [31,32], [33,34], [35,36], [37,38], [39,40], [41,42], \
54 | [43,44], [45,46], [47,48], [49,50], [51,52], [53,54], [55,56], \
55 | [57,58], [59,60], [61,62], [63,64], [65,66], [67,68], [69, 70],
56 | [71, 72], [73, 74], [75, 76], [77, 78]]
57 |
58 | # visualize
59 | colors = [[255, 0, 0], [255, 85, 0], [255, 170, 0], [255, 255, 0], [170, 255, 0], [85, 255, 0],
60 | [0, 255, 0], \
61 | [0, 255, 85], [0, 255, 170], [0, 255, 255], [0, 170, 255], [0, 85, 255], [0, 0, 255],
62 | [85, 0, 255], \
63 | [170, 0, 255], [255, 0, 255], [255, 0, 170], [255, 0, 85], [17, 145, 170], [89, 145, 240],
64 | [200, 55, 163], [45, 20, 240], [110, 255, 23], [176, 0, 12], [105, 100, 70], [70, 70, 70],
65 | [25, 96, 189]]
66 |
67 |
68 | def intersection(a,b):
69 | x = max(a[0], b[0])
70 | y = max(a[1], b[1])
71 | w = min(a[0]+a[2], b[0]+b[2]) - x
72 | h = min(a[1]+a[3], b[1]+b[3]) - y
73 | if w<0 or h<0: return 0 # or (0,0,0,0) ?
74 | return (x, y, w, h)
75 |
76 | def isMergedRegion(a,b):
77 | inter = intersection(a, b)
78 | if inter != 0:
79 | e_in = inter[2]*inter[3]
80 | e_a = a[2]*a[3]
81 | e_b = b[2]*b[3]
82 |
83 | print(str(e_in) + " " + str(e_a) + " " + str(e_b))
84 | if (np.abs(e_in - e_a) < 4) and (np.abs(e_in - e_b) < 4):
85 | return True
86 | else:
87 | return False
88 |
89 | def cluster(data, maxgap):
90 | '''Arrange data into groups where successive elements
91 | differ by no more than *maxgap*
92 |
93 | >>> cluster([1, 6, 9, 100, 102, 105, 109, 134, 139], maxgap=10)
94 | [[1, 6, 9], [100, 102, 105, 109], [134, 139]]
95 |
96 | >>> cluster([1, 6, 9, 99, 100, 102, 105, 134, 139, 141], maxgap=10)
97 | [[1, 6, 9], [99, 100, 102, 105], [134, 139, 141]]
98 |
99 | '''
100 | data.sort()
101 | groups = [[data[0]]]
102 | for x in data[1:]:
103 | if abs(x - groups[-1][-1]) <= maxgap:
104 | groups[-1].append(x)
105 | else:
106 | groups.append([x])
107 | return groups
108 |
109 | def cluster2(data, maxgap):
110 | '''Arrange data into groups where successive elements
111 | differ by no more than *maxgap*
112 |
113 | >>> cluster([1, 6, 9, 100, 102, 105, 109, 134, 139], maxgap=10)
114 | [[1, 6, 9], [100, 102, 105, 109], [134, 139]]
115 |
116 | >>> cluster([1, 6, 9, 99, 100, 102, 105, 134, 139, 141], maxgap=10)
117 | [[1, 6, 9], [99, 100, 102, 105], [134, 139, 141]]
118 |
119 | '''
120 | # data.sort()
121 | groups = [[data[0]]]
122 | for x in range(len(data)):
123 | if abs(data[x][2] - groups[-1][-1][2]) <= maxgap:
124 | groups[-1].append(data[x])
125 | else:
126 | groups.append([data[x]])
127 |
128 | toDel = []
129 | for i in range(len(groups)):
130 | if len(groups[i]) < 15:
131 | toDel.append(groups[i])
132 |
133 | groups = [x for x in groups if x not in toDel]
134 |
135 | return groups
136 |
137 | def process (input_CD_image, input_OF_image, params, model_params,
138 | num_of_heatmaps = 27, # 26 + background --> 27
139 | num_of_OFFs = 52, # 26 pairs: 52 layers in total
140 | num_of_OFFs_normal = 27): # number of pairs (26) + 1 --> 27
141 |
142 | print(input_CD_image)
143 | print(input_OF_image)
144 |
145 | oriImgCD = cv2.imread(input_CD_image) # B,G,R order
146 | oriImgOF = cv2.imread(input_OF_image) # B,G,R order
147 |
148 | rawDepth = read_pgm(input_CD_image.replace("mc_blob.png", "depth.pgm"), byteorder='>')
149 |
150 | heatmap_avg = np.zeros((oriImgCD.shape[0], oriImgCD.shape[1], num_of_heatmaps))
151 | off_avg = np.zeros((oriImgOF.shape[0], oriImgOF.shape[1], num_of_OFFs))
152 |
153 | for m in range(len(multiplier)):
154 | scale = multiplier[m]
155 |
156 | image_CD_ToTest = cv2.resize(oriImgCD, (0, 0), fx=scale, fy=scale, interpolation=cv2.INTER_CUBIC)
157 | image_CD_ToTest_padded, pad = util.padRightDownCorner(image_CD_ToTest, model_params['stride'],
158 | model_params['padValue'])
159 |
160 | input_img_CD = np.transpose(np.float32(image_CD_ToTest_padded[:,:,:,np.newaxis]), (3,0,1,2)) # required shape (1, width, height, channels)
161 |
162 | image_OF_ToTest = cv2.resize(oriImgCD, (0, 0), fx=scale, fy=scale, interpolation=cv2.INTER_CUBIC)
163 | image_OF_ToTest_padded, pad = util.padRightDownCorner(image_OF_ToTest, model_params['stride'],
164 | model_params['padValue'])
165 |
166 | input_img_OF = np.transpose(np.float32(image_OF_ToTest_padded[:,:,:,np.newaxis]), (3,0,1,2)) # required shape (1, width, height, channels)
167 |
168 | output_blobs = model.predict([input_img_OF, input_img_CD])
169 |
170 | # extract outputs, resize, and remove padding
171 | # The CD input is used for having the required parameters since they are the same for both inputs
172 |
173 | heatmap = np.squeeze(output_blobs[1]) # output 1 is heatmaps
174 | heatmap = cv2.resize(heatmap, (0, 0), fx=model_params['stride'], fy=model_params['stride'],
175 | interpolation=cv2.INTER_CUBIC)
176 | heatmap = heatmap[:image_CD_ToTest_padded.shape[0] - pad[2], :image_CD_ToTest_padded.shape[1] - pad[3],
177 | :]
178 | heatmap = cv2.resize(heatmap, (oriImgCD.shape[1], oriImgCD.shape[0]), interpolation=cv2.INTER_CUBIC)
179 |
180 | off = np.squeeze(output_blobs[0]) # output 0 is OFFs
181 | off = cv2.resize(off, (0, 0), fx=model_params['stride'], fy=model_params['stride'],
182 | interpolation=cv2.INTER_CUBIC)
183 | off = off[:image_CD_ToTest_padded.shape[0] - pad[2], :image_CD_ToTest_padded.shape[1] - pad[3], :]
184 | off = cv2.resize(off, (oriImgCD.shape[1], oriImgCD.shape[0]), interpolation=cv2.INTER_CUBIC)
185 |
186 | heatmap_avg = heatmap_avg + heatmap / len(multiplier)
187 | off_avg = off_avg + off / len(multiplier)
188 |
189 | all_peaks = []
190 | peak_counter = 0
191 |
192 | for part in range(num_of_heatmaps):
193 | map_ori = heatmap_avg[:, :, part]
194 | map = gaussian_filter(map_ori, sigma=3)
195 |
196 | map_left = np.zeros(map.shape)
197 | map_left[1:, :] = map[:-1, :]
198 | map_right = np.zeros(map.shape)
199 | map_right[:-1, :] = map[1:, :]
200 | map_up = np.zeros(map.shape)
201 | map_up[:, 1:] = map[:, :-1]
202 | map_down = np.zeros(map.shape)
203 | map_down[:, :-1] = map[:, 1:]
204 |
205 | peaks_binary = np.logical_and.reduce(
206 | (map >= map_left, map >= map_right, map >= map_up, map >= map_down, map > params['thre1']))
207 | peaks = list(zip(np.nonzero(peaks_binary)[1], np.nonzero(peaks_binary)[0])) # note reverse
208 | peaks_with_score = [x + (map_ori[x[1], x[0]],) for x in peaks]
209 | id = range(peak_counter, peak_counter + len(peaks))
210 | peaks_with_score_and_id = [peaks_with_score[i] + (id[i],) for i in range(len(id))]
211 |
212 | all_peaks.append(peaks_with_score_and_id)
213 | peak_counter += len(peaks)
214 |
215 | connection_all = []
216 | special_k = []
217 | mid_num = 4
218 |
219 | for k in range(len(mapIdx)):
220 | score_mid = off_avg[:, :, [x - num_of_OFFs_normal for x in mapIdx[k]]]
221 | candA = all_peaks[limbSeq[k][0] - 1]
222 | candB = all_peaks[limbSeq[k][1] - 1]
223 | nA = len(candA)
224 | nB = len(candB)
225 | indexA, indexB = limbSeq[k]
226 | if (nA != 0 and nB != 0):
227 | connection_candidate = []
228 | for i in range(nA):
229 | for j in range(nB):
230 | vec = np.subtract(candB[j][:2], candA[i][:2])
231 | norm = math.sqrt(vec[0] * vec[0] + vec[1] * vec[1])
232 | # failure case when 2 body parts overlaps
233 | if norm == 0:
234 | continue
235 | vec = np.divide(vec, norm)
236 |
237 | startend = list(zip(np.linspace(candA[i][0], candB[j][0], num=mid_num), \
238 | np.linspace(candA[i][1], candB[j][1], num=mid_num)))
239 |
240 | vec_x = np.array(
241 | [score_mid[int(round(startend[I][1])), int(round(startend[I][0])), 0] \
242 | for I in range(len(startend))])
243 | vec_y = np.array(
244 | [score_mid[int(round(startend[I][1])), int(round(startend[I][0])), 1] \
245 | for I in range(len(startend))])
246 |
247 | score_midpts = np.multiply(vec_x, vec[0]) + np.multiply(vec_y, vec[1])
248 | score_with_dist_prior = sum(score_midpts) / len(score_midpts) + min(
249 | 0.5 * oriImgCD.shape[0] / norm - 1, 0)
250 | criterion1 = len(np.nonzero(score_midpts > params['thre2'])[0]) > 0.8 * len(
251 | score_midpts)
252 | criterion2 = score_with_dist_prior > 0
253 | if criterion1 and criterion2:
254 | connection_candidate.append([i, j, 3 * score_with_dist_prior,
255 | 3 * score_with_dist_prior + candA[i][2] + candB[j][2]])
256 |
257 | connection_candidate = sorted(connection_candidate, key=lambda x: x[2], reverse=True)
258 | connection = np.zeros((0, 5))
259 | for c in range(len(connection_candidate)):
260 | i, j, s = connection_candidate[c][0:3]
261 | if (i not in connection[:, 3] and j not in connection[:, 4]):
262 | connection = np.vstack([connection, [candA[i][3], candB[j][3], s, i, j]])
263 | if (len(connection) >= min(nA, nB)):
264 | break
265 |
266 | connection_all.append(connection)
267 | else:
268 | special_k.append(k)
269 | connection_all.append([])
270 |
271 | # last number in each row is the total parts number of that person
272 | # the second last number in each row is the score of the overall configuration
273 | subset = -1 * np.ones((0, num_of_OFFs_normal + 1))
274 | candidate = np.array([item for sublist in all_peaks for item in sublist])
275 |
276 | for k in range(len(mapIdx)):
277 | if k not in special_k:
278 | partAs = connection_all[k][:, 0]
279 | partBs = connection_all[k][:, 1]
280 | indexA, indexB = np.array(limbSeq[k]) - 1
281 |
282 | for i in range(len(connection_all[k])): # = 1:size(temp,1)
283 | found = 0
284 | subset_idx = [-1, -1]
285 | for j in range(len(subset)): # 1:size(subset,1):
286 | if subset[j][indexA] == partAs[i] or subset[j][indexB] == partBs[i]:
287 | subset_idx[found] = j
288 | found += 1
289 |
290 | if found == 1:
291 | j = subset_idx[0]
292 | if (subset[j][indexB] != partBs[i]):
293 | subset[j][indexB] = partBs[i]
294 | subset[j][-1] += 1
295 | subset[j][-2] += candidate[partBs[i].astype(int), 2] + connection_all[k][i][2]
296 | elif found == 2: # if found 2 and disjoint, merge them
297 | j1, j2 = subset_idx
298 | membership = ((subset[j1] >= 0).astype(int) + (subset[j2] >= 0).astype(int))[:-2]
299 | if len(np.nonzero(membership == 2)[0]) == 0: # merge
300 | subset[j1][:-2] += (subset[j2][:-2] + 1)
301 | subset[j1][-2:] += subset[j2][-2:]
302 | subset[j1][-2] += connection_all[k][i][2]
303 | subset = np.delete(subset, j2, 0)
304 | else: # as like found == 1
305 | subset[j1][indexB] = partBs[i]
306 | subset[j1][-1] += 1
307 | subset[j1][-2] += candidate[partBs[i].astype(int), 2] + connection_all[k][i][2]
308 |
309 | # if find no partA in the subset, create a new subset
310 | elif not found and k < num_of_heatmaps - 1:
311 | row = -1 * np.ones(num_of_OFFs_normal + 1)
312 | row[indexA] = partAs[i]
313 | row[indexB] = partBs[i]
314 | row[-1] = 2
315 | row[-2] = sum(candidate[connection_all[k][i, :2].astype(int), 2]) + \
316 | connection_all[k][i][2]
317 | subset = np.vstack([subset, row])
318 |
319 | # delete some rows of subset which has few parts occur
320 | deleteIdx = []
321 | for i in range(len(subset)):
322 | if subset[i][-1] < 4 or subset[i][-2] / subset[i][-1] < 0.4:
323 | deleteIdx.append(i)
324 | # subset = np.delete(subset, deleteIdx, axis=0)
325 |
326 | canvas = oriImgCD # B,G,R order
327 |
328 | all_peaks_max_index = np.zeros(num_of_heatmaps - 1, dtype=int)
329 | for i in range(num_of_heatmaps - 1):
330 | if len(all_peaks[i]) > 0:
331 | max_value = 0
332 | for j in range(len(all_peaks[i])):
333 | if max_value < all_peaks[i][j][2]:
334 | max_value = all_peaks[i][j][2]
335 | all_peaks_max_index[i] = j
336 |
337 | deleteIdReflector = []
338 | for i in range(num_of_heatmaps - 1):
339 | if len(all_peaks[i]) > 0:
340 | for j in range(num_of_heatmaps - 1):
341 | if i != j and len(all_peaks[j]) > 0:
342 | vec = np.subtract(all_peaks[i][all_peaks_max_index[i]][:2], all_peaks[j][all_peaks_max_index[j]][:2])
343 | norm = math.sqrt(vec[0] * vec[0] + vec[1] * vec[1])
344 | if norm < 6:
345 | if (all_peaks[i][all_peaks_max_index[i]][2] > all_peaks[j][all_peaks_max_index[j]][2]):
346 | deleteIdReflector.append(j)
347 | else:
348 | deleteIdReflector.append(i)
349 | for i in range(len(deleteIdReflector)):
350 | all_peaks[deleteIdReflector[i]] = []
351 |
352 | file_3d.write(str(frameIndex) + '\n')
353 | file_3d.write('NONE { }\n')
354 |
355 | detected_contour_depth_values = []
356 | detected_contour_coordinates = []
357 | detected_rectangles = []
358 | detected_ids = []
359 | merged_sets = []
360 |
361 | for i in range(num_of_heatmaps - 1):
362 | if len(all_peaks[i]) > 0 and all_peaks[i] != []:
363 | # cv2.circle(canvas, all_peaks[i][all_peaks_max_index[i]][0:2], 4, colors[i], thickness=4)
364 | # Copy the thresholded image.
365 | im_floodfill = canvas.copy()
366 |
367 | # Mask used to flood filling.
368 | # Notice the size needs to be 2 pixels than the image.
369 | h, w = canvas.shape[:2]
370 | mask = np.zeros((h+2, w+2), np.uint8)
371 |
372 | # Floodfill from point (0, 0)
373 | flood_return = cv2.floodFill(im_floodfill, mask, all_peaks[i][all_peaks_max_index[i]][0:2], [255,255,255])
374 |
375 | for j in range(len(detected_rectangles)):
376 | if (detected_ids[j] != i):
377 | if isMergedRegion(detected_rectangles[j], flood_return[3]):
378 |
379 | # if ()
380 | # del detected_rectangles[j]
381 | # break
382 | merged_sets.append([i, detected_ids[j]])
383 |
384 | # cv2.imshow("image", flood_return[1])
385 | # cv2.waitKey(0)
386 | detected_ids.append(i)
387 | detected_rectangles.append(flood_return[3])
388 |
389 |
390 | # Invert floodfilled image
391 | im_floodfill_inv = cv2.bitwise_not(im_floodfill)
392 |
393 | # Combine the two images to get the foreground.
394 | fill_image = canvas | im_floodfill_inv
395 |
396 | mask_gray = cv2.cvtColor(fill_image, cv2.COLOR_BGR2GRAY)
397 | # mask_gray = cv2.normalize(src=mask_gray, dst=None, alpha=0, beta=255, norm_type=cv2.NORM_MINMAX, dtype=cv2.CV_8UC1)
398 |
399 | im2, contours, hierarchy = cv2.findContours(mask_gray, cv2.RETR_CCOMP, cv2.CHAIN_APPROX_NONE)
400 | if len(contours) > 1:
401 |
402 | values = np.zeros((contours[1].shape[0]), dtype=float)
403 | for p in range(contours[1].shape[0]):
404 | depth_value = rawDepth[contours[1][p][0][1]][contours[1][p][0][0]]
405 | # print(str(i) + " " + str(depth_value))
406 | if depth_value > 1000 and depth_value < 2500 and contours[1][p][0][1] > 10 and contours[1][p][0][1] < 400 and contours[1][p][0][0] > 40 and contours[1][p][0][0] < 400:
407 | values[p] = depth_value
408 | else:
409 | values[p] = 0
410 | if (values[p] > 0):
411 | detected_contour_coordinates.append([contours[1][p][0][1], contours[1][p][0][0], values[p]])
412 |
413 | detected_contour_coordinates.sort(key=lambda x : x[2]) # = np.sort(detected_contour_coordinates, axis=2)
414 | values[::-1].sort()
415 | values = [x for x in values if x > 0]
416 |
417 | if np.median(values) != np.nan and np.median(values) > 0:
418 | detected_contour_depth_values.append(values)
419 | else:
420 | del detected_ids[-1]
421 | del detected_rectangles[-1]
422 | else:
423 | del detected_ids[-1]
424 | del detected_rectangles[-1]
425 |
426 | ## Clustering
427 | temp_detected = [x for x in detected_ids]
428 |
429 | for i in range(len(merged_sets)):
430 | if (merged_sets[i][0] in temp_detected) and (merged_sets[i][1] in temp_detected):
431 | kmeans = KMeans(n_clusters=2, random_state=0).fit(detected_contour_coordinates)
432 |
433 | detected_contour_depth_values[detected_ids.index(merged_sets[i][0])] = [x[2] for x in detected_contour_coordinates if kmeans.labels_[detected_contour_coordinates.index(x)] == 0]
434 | detected_contour_depth_values[detected_ids.index(merged_sets[i][1])] = [x[2] for x in detected_contour_coordinates if kmeans.labels_[detected_contour_coordinates.index(x)] == 1]
435 |
436 | temp_detected.remove(merged_sets[i][0])
437 | temp_detected.remove(merged_sets[i][1])
438 |
439 | # spatial mapping from depthmap to 3D world using the intrinsic and extrinsic camera matrices
440 | # the extracted 3D points are stored in text files
441 | detected_index = 0
442 | for i in range(num_of_heatmaps - 1):
443 | if (i in detected_ids):
444 | depth = np.median(detected_contour_depth_values[detected_index])
445 | if "D4" in input_image:
446 | vec3 = [KRT4_x[all_peaks[i][all_peaks_max_index[i]][0]][int(all_peaks[i][all_peaks_max_index[i]][1])]*depth, KRT4_y[all_peaks[i][all_peaks_max_index[i]][0]][int(all_peaks[i][all_peaks_max_index[i]][1])]*depth, depth, 1000.0]
447 | vec3 = np.true_divide(vec3, 1000.0)
448 | final_vec3 = np.matmul(Ext4, vec3, out=None)
449 |
450 | file_3d.write(reflectors[i+1] + ' { ' + str(final_vec3[0]) + ' ' + str(final_vec3[1]) + ' ' + str(final_vec3[2]) + ' ' + str(final_vec3[0]) + ' ' + str(final_vec3[1]) + ' ' + str(final_vec3[2]) + ' }\n')
451 | elif "D6" in input_image:
452 | vec3 = [KRT6_x[all_peaks[i][all_peaks_max_index[i]][0]][int(all_peaks[i][all_peaks_max_index[i]][1])]*depth, KRT6_y[all_peaks[i][all_peaks_max_index[i]][0]][int(all_peaks[i][all_peaks_max_index[i]][1])]*depth, depth, 1000.0]
453 | vec3 = np.true_divide(vec3, 1000.0)
454 | final_vec3 = np.matmul(Ext6, vec3, out=None)
455 |
456 | file_3d.write(reflectors[i+1] + ' { ' + str(final_vec3[0]) + ' ' + str(final_vec3[1]) + ' ' + str(final_vec3[2]) + ' ' + str(final_vec3[0]) + ' ' + str(final_vec3[1]) + ' ' + str(final_vec3[2]) + ' }\n')
457 | elif "D8" in input_image:
458 | vec3 = [KRT8_x[all_peaks[i][all_peaks_max_index[i]][0]][int(all_peaks[i][all_peaks_max_index[i]][1])]*depth, KRT8_y[all_peaks[i][all_peaks_max_index[i]][0]][int(all_peaks[i][all_peaks_max_index[i]][1])]*depth, depth, 1000.0]
459 | vec3 = np.true_divide(vec3, 1000.0)
460 | final_vec3 = np.matmul(Ext8, vec3, out=None)
461 |
462 | file_3d.write(reflectors[i+1] + ' { ' + str(final_vec3[0]) + ' ' + str(final_vec3[1]) + ' ' + str(final_vec3[2]) + ' ' + str(final_vec3[0]) + ' ' + str(final_vec3[1]) + ' ' + str(final_vec3[2]) + ' }\n')
463 |
464 | detected_index += 1
465 | else:
466 | file_3d.write(reflectors[i+1] + ' { }\n')
467 | else:
468 | file_3d.write(reflectors[i+1] + ' { }\n')
469 |
470 |
471 | file_3d.write('NOSE { }\n')
472 | stickwidth = 4
473 |
474 | # for i in range(num_of_heatmaps):
475 | # # for n in range(len(subset)):
476 | # # index = subset[n][np.array(limbSeq[i]) - 1]
477 | # # if -1 in index:
478 | # # continue
479 | # for n in range(len(connection_all)):
480 | # if len(connection_all[n]):
481 | # partAs = connection_all[n][:, 0]
482 | # partBs = connection_all[n][:, 1]
483 | # indexA, indexB = np.array(limbSeq[n]) - 1
484 |
485 | # cur_canvas = canvas.copy()
486 | # Y = candidate[indexA, 0]
487 | # X = candidate[indexB, 1]
488 | # mX = np.mean(X)
489 | # mY = np.mean(Y)
490 | # length = ((X[0] - X[1]) ** 2 + (Y[0] - Y[1]) ** 2) ** 0.5
491 | # angle = math.degrees(math.atan2(X[0] - X[1], Y[0] - Y[1]))
492 | # polygon = cv2.ellipse2Poly((int(mY), int(mX)), (int(length / 2), stickwidth), int(angle), 0,
493 | # 360, 1)
494 | # cv2.fillConvexPoly(cur_canvas, polygon, colors[i])
495 | # canvas = cv2.addWeighted(canvas, 0.4, cur_canvas, 0.6, 0)
496 |
497 |
498 | #### PAPER FIGURE
499 | # at this stage, the estimates are overlayed on the depth images - the depth images occur by grayscaling the colorized images *NOT the raw depth
500 | canvas = cv2.cvtColor(canvas, cv2.COLOR_BGR2GRAY)
501 | canvas = cv2.cvtColor(canvas, cv2.COLOR_GRAY2BGR)
502 |
503 | for i in range(len(limbSeq)):
504 | if len(all_peaks[limbSeq[i][0]-1]) > 0 and len(all_peaks[limbSeq[i][1]-1]) > 0:
505 | cur_canvas = canvas.copy()
506 | Y = all_peaks[limbSeq[i][0] - 1][all_peaks_max_index[limbSeq[i][0] - 1]]
507 | X = all_peaks[limbSeq[i][1] - 1][all_peaks_max_index[limbSeq[i][1] - 1]]
508 | mX = (X[1] + Y[1]) / 2
509 | mY = (X[0] + Y[0]) / 2
510 | length = ((X[0] - Y[0]) ** 2 + (X[1] - Y[1]) ** 2) ** 0.5
511 | angle = math.degrees(math.atan2(X[1] - Y[1], X[0] - Y[0]))
512 | polygon = cv2.ellipse2Poly((int(mY), int(mX)), (int(length / 2), stickwidth), int(angle), 0,
513 | 360, 1)
514 | cv2.fillConvexPoly(cur_canvas, polygon, colors[limbSeq[i][0] - 1])
515 | canvas = cv2.addWeighted(canvas, 0.4, cur_canvas, 0.6, 0)
516 |
517 |
518 | for i in range(num_of_heatmaps - 1):
519 | if len(all_peaks[i]) > 0:
520 | cv2.putText(canvas, str(i+1), all_peaks[i][all_peaks_max_index[i]][0:2], cv2.FONT_HERSHEY_SIMPLEX, 1.0, colors[i], thickness=2, lineType=cv2.LINE_AA)
521 |
522 | cv2.imwrite(input_image_CD.replace(".png", "_processed.jpg"), canvas)
523 | return canvas
524 |
525 | def read_pgm(filename, byteorder='>'):
526 | """Return image data from a raw PGM file as numpy array.
527 |
528 | Format specification: http://netpbm.sourceforge.net/doc/pgm.html
529 |
530 | """
531 | with open(filename, 'rb') as f:
532 | buffer = f.read()
533 | try:
534 | header, width, height, maxval = re.search(
535 | b"(^P5\s(?:\s*#.*[\r\n])*"
536 | b"(\d+)\s(?:\s*#.*[\r\n])*"
537 | b"(\d+)\s(?:\s*#.*[\r\n])*"
538 | b"(\d+)\s(?:\s*#.*[\r\n]\s)*)", buffer).groups()
539 | except AttributeError:
540 | raise ValueError("Not a raw PGM file: '%s'" % filename)
541 | return np.frombuffer(buffer,
542 | dtype='u1' if int(maxval) < 256 else byteorder+'u2',
543 | count=int(width)*int(height),
544 | offset=len(header)
545 | ).reshape((int(height), int(width)))
546 |
547 |
548 | if __name__ == '__main__':
549 | parser = argparse.ArgumentParser()
550 | parser.add_argument('--dir', type=str, default='samples/', help='input dir')
551 | parser.add_argument('--image', type=str, default='samples/test.png', help='input image')
552 | parser.add_argument('--output', type=str, default='result.png', help='output image')
553 | parser.add_argument('--model', type=str, default='model/keras/deepmocap_model.h5', help='path to the weights file')
554 |
555 | args = parser.parse_args()
556 | input_image = args.image
557 | output = args.output
558 | keras_weights_file = args.model
559 | imageDir = args.dir
560 |
561 | print('start processing...')
562 |
563 | # matrices initialization
564 | KRT4_x = np.zeros((512, 424), dtype=float)
565 | KRT4_y = np.zeros((512, 424), dtype=float)
566 |
567 | KRT6_x = np.zeros((512, 424), dtype=float)
568 | KRT6_y = np.zeros((512, 424), dtype=float)
569 |
570 | KRT8_x = np.zeros((512, 424), dtype=float)
571 | KRT8_y = np.zeros((512, 424), dtype=float)
572 |
573 | file4 = open(imageDir + "D4.pmm", 'r')
574 | file6 = open(imageDir + "D6.pmm", 'r')
575 | file8 = open(imageDir + "D8.pmm", 'r')
576 |
577 | text4 = file4.read(-1)
578 | lines4 = re.split('\n|\r', text4)
579 |
580 | for i in range(3, len(lines4)):
581 | textValues = re.split(' |\r', lines4[i])
582 | for j in range(0, len(textValues)-1):
583 | xy = re.split(';| |\n|\t|\r', textValues[j])
584 | KRT4_x[j][i-3] = float(xy[0])
585 | KRT4_y[j][i-3] = float(xy[1])
586 |
587 | text6 = file6.read(-1)
588 | lines6 = re.split('\n|\r', text6)
589 |
590 | for i in range(3, len(lines6)):
591 | textValues = re.split(' |\r', lines6[i])
592 | for j in range(0, len(textValues)-1):
593 | xy = re.split(';| |\n|\t|\r', textValues[j])
594 | KRT6_x[j][i-3] = float(xy[0])
595 | KRT6_y[j][i-3] = float(xy[1])
596 |
597 | text8 = file8.read(-1)
598 | lines8 = re.split('\n|\r', text8)
599 |
600 | for i in range(3, len(lines8)):
601 | textValues = re.split(' |\r', lines8[i])
602 | for j in range(0, len(textValues)-1):
603 | xy = re.split(';| |\n|\t|\r', textValues[j])
604 | KRT8_x[j][i-3] = float(xy[0])
605 | KRT8_y[j][i-3] = float(xy[1])
606 |
607 | Ext4 = np.zeros((4, 4), dtype=float)
608 | Ext6 = np.zeros((4, 4), dtype=float)
609 | Ext8 = np.zeros((4, 4), dtype=float)
610 | tempExt = np.zeros((4, 4), dtype=float)
611 |
612 | file4extrinsics = open(imageDir + "D4.extrinsics", 'r')
613 | file6extrinsics = open(imageDir + "D6.extrinsics", 'r')
614 | file8extrinsics = open(imageDir + "D8.extrinsics", 'r')
615 |
616 | ext_text4 = file4extrinsics.read(-1)
617 | lines_ext4 = re.split('\n|\r', ext_text4)
618 |
619 | ext_text6 = file6extrinsics.read(-1)
620 | lines_ext6 = re.split('\n|\r', ext_text6)
621 |
622 | ext_text8 = file8extrinsics.read(-1)
623 | lines_ext8 = re.split('\n|\r', ext_text8)
624 |
625 |
626 | for i in range(0, len(lines_ext4)):
627 | textValues = re.split(' |\r', lines_ext4[i])
628 | for j in range(0, len(textValues)-1):
629 | # xyz = re.split(';| |\n|\t|\r', textValues[j])
630 | tempExt[i][j] = float(textValues[j])
631 |
632 | Ext4[:][0] = tempExt[:][0]
633 | Ext4[:][1] = tempExt[:][2]
634 | Ext4[:][2] = -tempExt[:][1]
635 |
636 | Ext4[0][3] = tempExt[3][0] / 1000.0
637 | Ext4[1][3] = tempExt[3][2] / 1000.0
638 | Ext4[2][3] = -tempExt[3][1] / 1000.0
639 |
640 | Ext4[3][3] = 1
641 |
642 | tempExt = np.zeros((4, 4), dtype=float)
643 |
644 | for i in range(0, len(lines_ext6)):
645 | textValues = re.split(' |\r', lines_ext6[i])
646 | for j in range(0, len(textValues)-1):
647 | tempExt[i][j] = float(textValues[j])
648 |
649 | Ext6[:][0] = tempExt[:][0]
650 | Ext6[:][1] = tempExt[:][2]
651 | Ext6[:][2] = -tempExt[:][1]
652 |
653 | Ext6[0][3] = tempExt[3][0] / 1000.0
654 | Ext6[1][3] = tempExt[3][2] / 1000.0
655 | Ext6[2][3] = -tempExt[3][1] / 1000.0
656 |
657 | Ext6[3][3] = 1
658 | tempExt = np.zeros((4, 4), dtype=float)
659 |
660 | for i in range(0, len(lines_ext8)):
661 | textValues = re.split(' |\r', lines_ext8[i])
662 | for j in range(0, len(textValues)-1):
663 | tempExt[i][j] = float(textValues[j])
664 |
665 | Ext8[:][0] = tempExt[:][0]
666 | Ext8[:][1] = tempExt[:][2]
667 | Ext8[:][2] = -tempExt[:][1]
668 |
669 | Ext8[0][3] = tempExt[3][0] / 1000.0
670 | Ext8[1][3] = tempExt[3][2] / 1000.0
671 | Ext8[2][3] = -tempExt[3][1] / 1000.0
672 |
673 | Ext8[3][3] = 1
674 |
675 | #
676 | model = get_testing_model()
677 | model.load_weights(keras_weights_file)
678 |
679 | # load config
680 | params, model_params = config_reader()
681 | multiplier = [x * model_params['boxsize'] / 424 for x in params['scale_search']]
682 | imageFiles = []
683 |
684 | if (imageDir):
685 |
686 | os.chdir(imageDir)
687 | imageFiles = glob.glob("*mc_blob.png")
688 | frameIndex = 0
689 | for input_image_CD in imageFiles:
690 | file_3d = open(input_image_CD.replace(".png", "_reflectors.txt"), 'w')
691 | input_image_OF = input_image_CD.replace("mc_blob.png", "flow.png")
692 | # generate image with body parts
693 | canvas = process(input_image_CD, input_image_OF, params, model_params)
694 | frameIndex = frameIndex + 1
695 |
696 | file_3d.close()
697 | else:
698 | tic = time.time()
699 | # generate image with body parts
700 | input_image_OF = input_image.replace("mc_blob.png", "flow.png")
701 | canvas = process(input_image, input_image_OF, params, model_params)
702 |
703 | toc = time.time()
704 | print ('processing time is %.5f' % (toc - tic))
705 |
706 | cv2.imwrite(output, canvas)
707 | cv2.imshow("MCuDaRT", canvas)
708 |
709 | cv2.waitKey(0)
710 | cv2.destroyAllWindows()
711 |
712 |
713 |
714 |
--------------------------------------------------------------------------------
/testing/model.py:
--------------------------------------------------------------------------------
1 | from keras.models import Model
2 | from keras.layers.merge import Concatenate
3 | from keras.layers import Activation, Input, Lambda
4 | from keras.layers.convolutional import Conv2D
5 | from keras.layers.pooling import MaxPooling2D
6 | from keras.layers.merge import Multiply
7 | from keras.regularizers import l2
8 | from keras.initializers import random_normal, constant
9 |
10 | import re
11 |
12 | def relu(x): return Activation('relu')(x)
13 |
14 | def conv(x, nf, ks, name, weight_decay):
15 | kernel_reg = l2(weight_decay[0]) if weight_decay else None
16 | bias_reg = l2(weight_decay[1]) if weight_decay else None
17 |
18 | x = Conv2D(nf, (ks, ks), padding='same', name=name,
19 | kernel_regularizer=kernel_reg,
20 | bias_regularizer=bias_reg,
21 | kernel_initializer=random_normal(stddev=0.01),
22 | bias_initializer=constant(0.0))(x)
23 | return x
24 |
25 | def pooling(x, ks, st, name):
26 | x = MaxPooling2D((ks, ks), strides=(st, st), name=name)(x)
27 | return x
28 |
29 | def vgg_block(x, weight_decay):
30 | # Block 1
31 | x = conv(x, 64, 3, "conv1_1", (weight_decay, 0))
32 | x = relu(x)
33 | x = conv(x, 64, 3, "conv1_2", (weight_decay, 0))
34 | x = relu(x)
35 | x = pooling(x, 2, 2, "pool1_1")
36 |
37 | # Block 2
38 | x = conv(x, 128, 3, "conv2_1", (weight_decay, 0))
39 | x = relu(x)
40 | x = conv(x, 128, 3, "conv2_2", (weight_decay, 0))
41 | x = relu(x)
42 | x = pooling(x, 2, 2, "pool2_1")
43 |
44 | # Block 3
45 | x = conv(x, 256, 3, "conv3_1", (weight_decay, 0))
46 | x = relu(x)
47 | x = conv(x, 256, 3, "conv3_2", (weight_decay, 0))
48 | x = relu(x)
49 | x = conv(x, 256, 3, "conv3_3", (weight_decay, 0))
50 | x = relu(x)
51 | x = conv(x, 256, 3, "conv3_4", (weight_decay, 0))
52 | x = relu(x)
53 | x = pooling(x, 2, 2, "pool3_1")
54 |
55 | # Block 4
56 | x = conv(x, 512, 3, "conv4_1", (weight_decay, 0))
57 | x = relu(x)
58 | x = conv(x, 512, 3, "conv4_2", (weight_decay, 0))
59 | x = relu(x)
60 |
61 | # Additional non vgg layers
62 | x = conv(x, 256, 3, "conv4_3_CPM", (weight_decay, 0))
63 | x = relu(x)
64 | x = conv(x, 128, 3, "conv4_4_CPM", (weight_decay, 0))
65 | x = relu(x)
66 |
67 | return x
68 |
69 | def vgg_flow_block(x, weight_decay):
70 | # Block 1
71 | x = conv(x, 64, 3, "conv1_1f", (weight_decay, 0))
72 | x = relu(x)
73 | x = conv(x, 64, 3, "conv1_2f", (weight_decay, 0))
74 | x = relu(x)
75 | x = pooling(x, 2, 2, "pool1_1f")
76 |
77 | # Block 2
78 | x = conv(x, 128, 3, "conv2_1f", (weight_decay, 0))
79 | x = relu(x)
80 | x = conv(x, 128, 3, "conv2_2f", (weight_decay, 0))
81 | x = relu(x)
82 | x = pooling(x, 2, 2, "pool2_1f")
83 |
84 | # Block 3
85 | x = conv(x, 256, 3, "conv3_1f", (weight_decay, 0))
86 | x = relu(x)
87 | x = conv(x, 256, 3, "conv3_2f", (weight_decay, 0))
88 | x = relu(x)
89 | x = conv(x, 256, 3, "conv3_3f", (weight_decay, 0))
90 | x = relu(x)
91 | x = conv(x, 256, 3, "conv3_4f", (weight_decay, 0))
92 | x = relu(x)
93 | x = pooling(x, 2, 2, "pool3_1f")
94 |
95 | # Block 4
96 | x = conv(x, 512, 3, "conv4_1f", (weight_decay, 0))
97 | x = relu(x)
98 | x = conv(x, 512, 3, "conv4_2f", (weight_decay, 0))
99 | x = relu(x)
100 |
101 | # Additional non vgg layers
102 | x = conv(x, 256, 3, "conv4_3_CPMf", (weight_decay, 0))
103 | x = relu(x)
104 | x = conv(x, 128, 3, "conv4_4_CPMf", (weight_decay, 0))
105 | x = relu(x)
106 |
107 | return x
108 |
109 |
110 | def stage1_block(x, num_p, branch, weight_decay):
111 | # Block 1
112 | x = conv(x, 128, 3, "Mconv1_stage1_L%d" % branch, (weight_decay, 0))
113 | x = relu(x)
114 | x = conv(x, 128, 3, "Mconv2_stage1_L%d" % branch, (weight_decay, 0))
115 | x = relu(x)
116 | x = conv(x, 128, 3, "Mconv3_stage1_L%d" % branch, (weight_decay, 0))
117 | x = relu(x)
118 | x = conv(x, 512, 1, "Mconv4_stage1_L%d" % branch, (weight_decay, 0))
119 | x = relu(x)
120 | x = conv(x, num_p, 1, "Mconv5_stage1_L%d" % branch, (weight_decay, 0))
121 |
122 | return x
123 |
124 |
125 | def stageT_block(x, num_p, stage, branch, weight_decay):
126 | # Block 1
127 | x = conv(x, 128, 7, "Mconv1_stage%d_L%d" % (stage, branch), (weight_decay, 0))
128 | x = relu(x)
129 | x = conv(x, 128, 7, "Mconv2_stage%d_L%d" % (stage, branch), (weight_decay, 0))
130 | x = relu(x)
131 | x = conv(x, 128, 7, "Mconv3_stage%d_L%d" % (stage, branch), (weight_decay, 0))
132 | x = relu(x)
133 | x = conv(x, 128, 7, "Mconv4_stage%d_L%d" % (stage, branch), (weight_decay, 0))
134 | x = relu(x)
135 | x = conv(x, 128, 7, "Mconv5_stage%d_L%d" % (stage, branch), (weight_decay, 0))
136 | x = relu(x)
137 | x = conv(x, 128, 1, "Mconv6_stage%d_L%d" % (stage, branch), (weight_decay, 0))
138 | x = relu(x)
139 | x = conv(x, num_p, 1, "Mconv7_stage%d_L%d" % (stage, branch), (weight_decay, 0))
140 |
141 | return x
142 |
143 |
144 | def apply_mask(x, mask1, mask2, num_p, stage, branch, np_branch1, np_branch2):
145 | w_name = "weight_stage%d_L%d" % (stage, branch)
146 |
147 | # TODO: we have branch number here why we made so strange check
148 | # assert np_branch1 != np_branch2 # we selecting branches by number of pafs, if they accidentally became the same it will be disaster
149 |
150 | if num_p == np_branch1:
151 | w = Multiply(name=w_name)([x, mask1]) # vec_weight
152 | elif num_p == np_branch2:
153 | w = Multiply(name=w_name)([x, mask2]) # vec_heat
154 | else:
155 | assert False, "wrong number of layers num_p=%d " % num_p
156 | return w
157 |
158 |
159 | def get_training_model(weight_decay, np_branch1, np_branch2, stages = 6, gpus = None):
160 | img_input_shape = (None, None, 3)
161 | img_flow_input_shape = (None, None, 3)
162 | vec_flow_input_shape = (None, None, np_branch1)
163 | heat_input_shape = (None, None, np_branch2)
164 |
165 | inputs = []
166 | outputs = []
167 |
168 | img_input = Input(shape=img_input_shape)
169 | img_flow_input = Input(shape=img_flow_input_shape)
170 | vec_flow_weight_input = Input(shape=vec_flow_input_shape)
171 | heat_weight_input = Input(shape=heat_input_shape)
172 |
173 | inputs.append(img_flow_input)
174 | inputs.append(img_input)
175 |
176 | if np_branch1 > 0:
177 | inputs.append(vec_flow_weight_input)
178 |
179 | if np_branch2 > 0:
180 | inputs.append(heat_weight_input)
181 |
182 | #img_normalized = Lambda(lambda x: x / 256 - 0.5)(img_input) # [-0.5, 0.5]
183 | img_normalized = img_input # will be done on augmentation stage
184 | img_flow_normalized = img_flow_input # will be done on augmentation stage
185 |
186 | # VGG
187 | vgg_merged = []
188 |
189 | stage0_out = vgg_block(img_normalized, weight_decay)
190 | stage0_flow_out = vgg_flow_block(img_flow_normalized, weight_decay)
191 |
192 | vgg_merged.append(stage0_out)
193 | vgg_merged.append(stage0_flow_out)
194 |
195 | vgg_merged_input = Concatenate()(vgg_merged)
196 |
197 | new_x = []
198 |
199 | # stage 1 - branch 1 (flow confidence maps)
200 |
201 | if np_branch1 > 0:
202 | stage1_branch1_out = stage1_block(vgg_merged_input, np_branch1, 1, weight_decay)
203 | w1 = apply_mask(stage1_branch1_out, vec_flow_weight_input, heat_weight_input, np_branch1, 1, 1, np_branch1, np_branch2)
204 | outputs.append(w1)
205 | new_x.append(stage1_branch1_out)
206 |
207 | # stage 1 - branch 2 (confidence maps)
208 |
209 | if np_branch2 > 0:
210 | stage1_branch2_out = stage1_block(vgg_merged_input, np_branch2, 2, weight_decay)
211 | w2 = apply_mask(stage1_branch2_out, vec_flow_weight_input, heat_weight_input, np_branch2, 1, 2, np_branch1, np_branch2)
212 | outputs.append(w2)
213 | new_x.append(stage1_branch2_out)
214 |
215 | new_x.append(vgg_merged_input)
216 | # new_x.append(stage0_flow_out)
217 |
218 | x = Concatenate()(new_x)
219 |
220 | # stage sn >= 2
221 | for sn in range(2, stages + 1):
222 |
223 | new_x = []
224 | # stage SN - branch 1 (flow confidence maps)
225 | if np_branch1 > 0:
226 | stageT_branch1_out = stageT_block(x, np_branch1, sn, 1, weight_decay)
227 | w1 = apply_mask(stageT_branch1_out, vec_flow_weight_input, heat_weight_input, np_branch1, sn, 1, np_branch1, np_branch2)
228 | outputs.append(w1)
229 | new_x.append(stageT_branch1_out)
230 |
231 | # stage SN - branch 2 (confidence maps)
232 | if np_branch2 > 0:
233 | stageT_branch2_out = stageT_block(x, np_branch2, sn, 2, weight_decay)
234 | w2 = apply_mask(stageT_branch2_out, vec_flow_weight_input, heat_weight_input, np_branch2, sn, 2, np_branch1, np_branch2)
235 | outputs.append(w2)
236 | new_x.append(stageT_branch2_out)
237 |
238 | new_x.append(vgg_merged_input)
239 | # new_x.append(stage0_out)
240 |
241 | if sn < stages:
242 | x = Concatenate()(new_x)
243 |
244 | model = Model(inputs=inputs, outputs=outputs)
245 | return model
246 |
247 | def get_lrmult(model):
248 |
249 | # setup lr multipliers for conv layers
250 | lr_mult = dict()
251 |
252 | for layer in model.layers:
253 |
254 | if isinstance(layer, Conv2D):
255 |
256 | # stage = 1
257 | if re.match("Mconv\d_stage1.*", layer.name):
258 | kernel_name = layer.weights[0].name
259 | bias_name = layer.weights[1].name
260 | lr_mult[kernel_name] = 1
261 | lr_mult[bias_name] = 2
262 |
263 | # stage > 1
264 | elif re.match("Mconv\d_stage.*", layer.name):
265 | kernel_name = layer.weights[0].name
266 | bias_name = layer.weights[1].name
267 | lr_mult[kernel_name] = 4
268 | lr_mult[bias_name] = 8
269 |
270 | # vgg
271 | else:
272 | print("matched as vgg layer", layer.name)
273 | kernel_name = layer.weights[0].name
274 | bias_name = layer.weights[1].name
275 | lr_mult[kernel_name] = 1
276 | lr_mult[bias_name] = 2
277 |
278 | return lr_mult
279 |
280 |
281 | def get_testing_model(np_branch1=52, np_branch2=27, stages = 6):
282 |
283 | img_input_shape = (None, None, 3)
284 | img_flow_input_shape = (None, None, 3)
285 |
286 | img_input = Input(shape=img_input_shape)
287 | img_flow_input = Input(shape=img_flow_input_shape)
288 |
289 | img_normalized = Lambda(lambda x: x / 256 - 0.5)(img_input) # [-0.5, 0.5]
290 | img_flow_normalized = Lambda(lambda x: x / 256 - 0.5)(img_flow_input) # [-0.5, 0.5]
291 |
292 | # VGG
293 | vgg_merged = []
294 |
295 | stage0_out = vgg_block(img_normalized, None)
296 | stage0_flow_out = vgg_flow_block(img_flow_normalized, None)
297 |
298 | vgg_merged.append(stage0_out)
299 | vgg_merged.append(stage0_flow_out)
300 |
301 | vgg_merged_input = Concatenate()(vgg_merged)
302 |
303 | stages_out = []
304 |
305 | # stage 1 - branch 1 (PAF)
306 | if np_branch1 > 0:
307 | stage1_branch1_out = stage1_block(vgg_merged_input, np_branch1, 1, None)
308 | stages_out.append(stage1_branch1_out)
309 |
310 | # stage 1 - branch 2 (confidence maps)
311 | if np_branch2 > 0:
312 | stage1_branch2_out = stage1_block(vgg_merged_input, np_branch2, 2, None)
313 | stages_out.append(stage1_branch2_out)
314 |
315 | stages_out.append(vgg_merged_input)
316 |
317 | x = Concatenate()(stages_out)
318 | # x = Concatenate()(stage0_flow_out + [stage0_flow_out])
319 |
320 | # stage t >= 2
321 | stageT_branch1_out = None
322 | stageT_branch2_out = None
323 | for sn in range(2, stages + 1):
324 |
325 | stages_out = []
326 |
327 | if np_branch1 > 0:
328 | stageT_branch1_out = stageT_block(x, np_branch1, sn, 1, None)
329 | stages_out.append(stageT_branch1_out)
330 | if np_branch2 > 0:
331 | stageT_branch2_out = stageT_block(x, np_branch2, sn, 2, None)
332 | stages_out.append(stageT_branch2_out)
333 |
334 | stages_out.append(vgg_merged_input)
335 |
336 | if sn < stages:
337 | x = Concatenate()(stages_out)
338 |
339 | model = Model(inputs=[img_flow_input, img_input], outputs=[stageT_branch1_out, stageT_branch2_out])
340 |
341 | return model
--------------------------------------------------------------------------------
/testing/model/keras/README.md:
--------------------------------------------------------------------------------
1 | At this folder, the .h5 file of the FCN model should be placed for properly running the testing script. Download the model from this [url](http://deepmocap.com/model/deepmocap_model.h5).
2 |
3 |
--------------------------------------------------------------------------------
/testing/samples/03-18-11-27-03_3V_completed_D4_05433depth.pgm:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/tofis/DeepMoCap/a6d37e0fb74deeb80b489850e1dbb2e5e4f64366/testing/samples/03-18-11-27-03_3V_completed_D4_05433depth.pgm
--------------------------------------------------------------------------------
/testing/samples/03-18-11-27-03_3V_completed_D4_05433flow.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/tofis/DeepMoCap/a6d37e0fb74deeb80b489850e1dbb2e5e4f64366/testing/samples/03-18-11-27-03_3V_completed_D4_05433flow.png
--------------------------------------------------------------------------------
/testing/samples/03-18-11-27-03_3V_completed_D4_05433mc_blob.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/tofis/DeepMoCap/a6d37e0fb74deeb80b489850e1dbb2e5e4f64366/testing/samples/03-18-11-27-03_3V_completed_D4_05433mc_blob.png
--------------------------------------------------------------------------------
/testing/samples/03-18-11-27-03_3V_completed_D6_05433depth.pgm:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/tofis/DeepMoCap/a6d37e0fb74deeb80b489850e1dbb2e5e4f64366/testing/samples/03-18-11-27-03_3V_completed_D6_05433depth.pgm
--------------------------------------------------------------------------------
/testing/samples/03-18-11-27-03_3V_completed_D6_05433flow.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/tofis/DeepMoCap/a6d37e0fb74deeb80b489850e1dbb2e5e4f64366/testing/samples/03-18-11-27-03_3V_completed_D6_05433flow.png
--------------------------------------------------------------------------------
/testing/samples/03-18-11-27-03_3V_completed_D6_05433mc_blob.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/tofis/DeepMoCap/a6d37e0fb74deeb80b489850e1dbb2e5e4f64366/testing/samples/03-18-11-27-03_3V_completed_D6_05433mc_blob.png
--------------------------------------------------------------------------------
/testing/samples/03-18-11-27-03_3V_completed_D8_05433depth.pgm:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/tofis/DeepMoCap/a6d37e0fb74deeb80b489850e1dbb2e5e4f64366/testing/samples/03-18-11-27-03_3V_completed_D8_05433depth.pgm
--------------------------------------------------------------------------------
/testing/samples/03-18-11-27-03_3V_completed_D8_05433flow.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/tofis/DeepMoCap/a6d37e0fb74deeb80b489850e1dbb2e5e4f64366/testing/samples/03-18-11-27-03_3V_completed_D8_05433flow.png
--------------------------------------------------------------------------------
/testing/samples/03-18-11-27-03_3V_completed_D8_05433mc_blob.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/tofis/DeepMoCap/a6d37e0fb74deeb80b489850e1dbb2e5e4f64366/testing/samples/03-18-11-27-03_3V_completed_D8_05433mc_blob.png
--------------------------------------------------------------------------------
/testing/samples/D4.extrinsics:
--------------------------------------------------------------------------------
1 | -0.899 -0.052 -0.435
2 | -0.436 -0.005 0.900
3 | -0.049 0.999 -0.019
4 | 822.847 -1852.757 728.803
5 |
--------------------------------------------------------------------------------
/testing/samples/D6.extrinsics:
--------------------------------------------------------------------------------
1 | 0.888 0.028 -0.459
2 | -0.459 0.024 -0.888
3 | -0.014 0.999 0.034
4 | 831.748 1973.294 640.856
5 |
--------------------------------------------------------------------------------
/testing/samples/D8.extrinsics:
--------------------------------------------------------------------------------
1 | 0.186 -0.140 0.972
2 | 0.982 -0.006 -0.189
3 | 0.033 0.990 0.136
4 | -2232.347 132.203 556.134
5 |
--------------------------------------------------------------------------------
/testing/samples/README.md:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/tofis/DeepMoCap/a6d37e0fb74deeb80b489850e1dbb2e5e4f64366/testing/samples/README.md
--------------------------------------------------------------------------------
/testing/util.py:
--------------------------------------------------------------------------------
1 | import numpy as np
2 | from io import StringIO
3 | import PIL.Image
4 | from IPython.display import Image, display
5 |
6 | def showBGRimage(a, fmt='jpeg'):
7 | a = np.uint8(np.clip(a, 0, 255))
8 | a[:,:,[0,2]] = a[:,:,[2,0]] # for B,G,R order
9 | f = StringIO()
10 | PIL.Image.fromarray(a).save(f, fmt)
11 | display(Image(data=f.getvalue()))
12 |
13 | def showmap(a, fmt='png'):
14 | a = np.uint8(np.clip(a, 0, 255))
15 | f = StringIO()
16 | PIL.Image.fromarray(a).save(f, fmt)
17 | display(Image(data=f.getvalue()))
18 |
19 | #def checkparam(param):
20 | # octave = param['octave']
21 | # starting_range = param['starting_range']
22 | # ending_range = param['ending_range']
23 | # assert starting_range <= ending_range, 'starting ratio should <= ending ratio'
24 | # assert octave >= 1, 'octave should >= 1'
25 | # return starting_range, ending_range, octave
26 |
27 | def getJetColor(v, vmin, vmax):
28 | c = np.zeros((3))
29 | if (v < vmin):
30 | v = vmin
31 | if (v > vmax):
32 | v = vmax
33 | dv = vmax - vmin
34 | if (v < (vmin + 0.125 * dv)):
35 | c[0] = 256 * (0.5 + (v * 4)) #B: 0.5 ~ 1
36 | elif (v < (vmin + 0.375 * dv)):
37 | c[0] = 255
38 | c[1] = 256 * (v - 0.125) * 4 #G: 0 ~ 1
39 | elif (v < (vmin + 0.625 * dv)):
40 | c[0] = 256 * (-4 * v + 2.5) #B: 1 ~ 0
41 | c[1] = 255
42 | c[2] = 256 * (4 * (v - 0.375)) #R: 0 ~ 1
43 | elif (v < (vmin + 0.875 * dv)):
44 | c[1] = 256 * (-4 * v + 3.5) #G: 1 ~ 0
45 | c[2] = 255
46 | else:
47 | c[2] = 256 * (-4 * v + 4.5) #R: 1 ~ 0.5
48 | return c
49 |
50 | def colorize(gray_img):
51 | out = np.zeros(gray_img.shape + (3,))
52 | for y in range(out.shape[0]):
53 | for x in range(out.shape[1]):
54 | out[y,x,:] = getJetColor(gray_img[y,x], 0, 1)
55 | return out
56 |
57 | def padRightDownCorner(img, stride, padValue):
58 | h = img.shape[0]
59 | w = img.shape[1]
60 |
61 | pad = 4 * [None]
62 | pad[0] = 0 # up
63 | pad[1] = 0 # left
64 | pad[2] = 0 if (h%stride==0) else stride - (h % stride) # down
65 | pad[3] = 0 if (w%stride==0) else stride - (w % stride) # right
66 |
67 | img_padded = img
68 | pad_up = np.tile(img_padded[0:1,:,:]*0 + padValue, (pad[0], 1, 1))
69 | img_padded = np.concatenate((pad_up, img_padded), axis=0)
70 | pad_left = np.tile(img_padded[:,0:1,:]*0 + padValue, (1, pad[1], 1))
71 | img_padded = np.concatenate((pad_left, img_padded), axis=1)
72 | pad_down = np.tile(img_padded[-2:-1,:,:]*0 + padValue, (pad[2], 1, 1))
73 | img_padded = np.concatenate((img_padded, pad_down), axis=0)
74 | pad_right = np.tile(img_padded[:,-2:-1,:]*0 + padValue, (1, pad[3], 1))
75 | img_padded = np.concatenate((img_padded, pad_right), axis=1)
76 |
77 | return img_padded, pad
78 |
--------------------------------------------------------------------------------
/tools/2D-reflector-annotator/.vs/2D-reflector-annotator/v14/.suo:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/tofis/DeepMoCap/a6d37e0fb74deeb80b489850e1dbb2e5e4f64366/tools/2D-reflector-annotator/.vs/2D-reflector-annotator/v14/.suo
--------------------------------------------------------------------------------
/tools/2D-reflector-annotator/2D-reflector-annotator.csproj:
--------------------------------------------------------------------------------
1 |
2 |