├── .gitignore ├── LICENSE ├── README.md ├── core ├── .gitignore ├── CMakeLists.txt ├── README.md ├── detection_wrappers │ ├── openpose_detector.cpp │ └── openpose_detector.h ├── event_representations │ ├── representations.cpp │ └── representations.h ├── fusion │ ├── fusion.cpp │ └── fusion.h ├── motion_estimation │ ├── motion.cpp │ ├── motion.h │ ├── motion_estimation.cpp │ ├── motion_estimation.h │ ├── reprojection.cpp │ └── reprojection.h └── utility │ ├── test.cpp │ └── utility.h ├── datasets ├── .gitignore ├── README.md ├── __init__.py ├── dhp19 │ ├── README.md │ ├── e2vid │ │ ├── Dockerfile │ │ ├── README.md │ │ ├── create_grayscale_frames.sh │ │ └── run_e2vid.py │ ├── export_eros.py │ ├── export_eventframe.py │ ├── export_gt_to_numpy.py │ ├── export_to_yarp.py │ ├── preprocess.m │ ├── preprocess_all.m │ └── utils │ │ ├── __init__.py │ │ ├── constants.py │ │ ├── matlab │ │ ├── BackgroundFilter.m │ │ ├── HotPixelFilter.m │ │ ├── ImportAedat.m │ │ ├── ImportAedatBasicSourceName.m │ │ ├── ImportAedatDataVersion1or2.m │ │ ├── ImportAedatHeaders.m │ │ ├── extract_from_aedat.m │ │ ├── filterAndSeparateChannels.m │ │ ├── maskRegionFilter.m │ │ └── saveCams.m │ │ └── parsing.py ├── h36m │ ├── README.MD │ ├── Run_v2e_on_h36m.py │ ├── __init__.py │ ├── export_eros.py │ ├── export_eventframe.py │ ├── export_pim.py │ ├── export_to_yarp.py │ ├── h36_h5_to_yarp.py │ └── utils │ │ ├── __init__.py │ │ └── parsing.py ├── mpii │ ├── README.md │ ├── export_to_eros.py │ ├── export_to_movenet.py │ ├── export_to_yarp.py │ └── utils │ │ └── parsing.py └── utils │ ├── constants.py │ ├── events_representation.py │ ├── export.py │ ├── genYarpImages.py │ ├── mat_files.py │ └── parsing.py ├── evaluation ├── .gitignore ├── README.md ├── evaluate_hpe.py ├── evaluate_vel.py ├── utils │ ├── __init__.py │ ├── metrics.py │ ├── parsing.py │ └── plots.py └── velocity_study.py ├── example ├── README.md ├── movenet │ ├── .gitignore │ ├── CMakeLists.txt │ ├── Dockerfile │ ├── Dockerfile_cpu │ ├── LICENSE │ ├── README.md │ ├── config.py │ ├── eros-framer.cpp │ ├── evaluate.py │ ├── models │ │ ├── dhp19_allcams_e33_valacc0.87996.pth │ │ ├── dhp19_frontcams_e88_valacc0.97142.pth │ │ ├── dhp19_sidecams_e44_valacc0.87217.pth │ │ ├── e97_valacc0.81209.pth │ │ ├── h36m_finetuned.pth │ │ ├── h36m_only-trained.pth │ │ ├── mpii_pre-trained.pth │ │ └── upper.pth │ ├── moveEnet-offline.py │ ├── movenet_online.py │ ├── predict.py │ ├── requirements.txt │ ├── scripts │ │ ├── data │ │ │ ├── delImg.py │ │ │ ├── findImgNolabel.py │ │ │ ├── make_handlabel_data_7keypooints.py │ │ │ ├── mergeJson.py │ │ │ ├── moveDifferent.py │ │ │ ├── moveSame.py │ │ │ ├── resize.py │ │ │ ├── show_crop.py │ │ │ ├── split_trainval.py │ │ │ └── video2img.py │ │ ├── my_weight_center.npy │ │ └── split_trainval.py │ └── yarpmanagerapplication.xml ├── op_detector_example_module │ ├── .gitignore │ ├── CMakeLists.txt │ ├── Dockerfile │ ├── README.md │ ├── conf │ │ ├── yarpapp_demo.xml │ │ └── yarpapp_demo_atis.xml │ ├── e2vid │ │ ├── e2vid.py │ │ └── image_reconstructor.py │ ├── e2vid_example_module.py │ ├── e2vid_framer.cpp │ └── op_detector_example_module.cpp ├── reprojection_test │ ├── CMakeLists.txt │ └── test.cpp └── yarp-glhpe │ ├── .gitignore │ ├── CMakeLists.txt │ ├── Dockerfile │ ├── README.md │ ├── app_yarp-glhpe.xml │ ├── evaluate.py │ ├── glhpe-framer.cpp │ └── run-model.py └── pycore ├── __init__.py ├── moveenet ├── __init__.py ├── config.py ├── data │ ├── __init__.py │ ├── center_weight_origin.npy │ ├── data.py │ ├── data_augment.py │ └── data_tools.py ├── loss │ ├── __init__.py │ └── movenet_loss.py ├── models │ ├── __init__.py │ └── movenet_mobilenetv2.py ├── task │ ├── __init__.py │ ├── task.py │ └── task_tools.py ├── utils │ ├── __init__.py │ ├── metrics.py │ └── utils.py └── visualization │ └── visualization.py └── movenet_rgb ├── __init__.py ├── constants.py ├── funcs.py └── run_movenet.py /.gitignore: -------------------------------------------------------------------------------- 1 | # Prerequisites 2 | *.d 3 | 4 | # Compiled Object files 5 | *.slo 6 | *.lo 7 | *.o 8 | *.obj 9 | 10 | # Precompiled Headers 11 | *.gch 12 | *.pch 13 | 14 | # Compiled Dynamic libraries 15 | *.so 16 | *.dylib 17 | *.dll 18 | 19 | # Fortran module files 20 | *.mod 21 | *.smod 22 | 23 | # Compiled Static libraries 24 | *.lai 25 | *.la 26 | *.a 27 | *.lib 28 | 29 | # Executables 30 | *.exe 31 | *.out 32 | *.app 33 | *.orig 34 | 35 | *.idea 36 | *.user 37 | 38 | #compiled python caches 39 | *.pyc 40 | .vscode/ 41 | build/ -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- 1 | BSD 3-Clause License 2 | 3 | Copyright (c) 2021, Event Driven Perception for Robotics 4 | All rights reserved. 5 | 6 | Redistribution and use in source and binary forms, with or without 7 | modification, are permitted provided that the following conditions are met: 8 | 9 | 1. Redistributions of source code must retain the above copyright notice, this 10 | list of conditions and the following disclaimer. 11 | 12 | 2. Redistributions in binary form must reproduce the above copyright notice, 13 | this list of conditions and the following disclaimer in the documentation 14 | and/or other materials provided with the distribution. 15 | 16 | 3. Neither the name of the copyright holder nor the names of its 17 | contributors may be used to endorse or promote products derived from 18 | this software without specific prior written permission. 19 | 20 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 21 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 22 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 23 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE 24 | FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL 25 | DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR 26 | SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 27 | CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, 28 | OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE 29 | OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 30 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # Human Pose Estimation Core Library 2 | _A library of functions for human pose estimation with event-driven cameras_ 3 | 4 | ![demo](https://user-images.githubusercontent.com/9265237/216939617-703fc4ef-b4b9-4cbc-aab8-a87c04822be2.gif) 5 | 6 | Please cite: 7 | ``` 8 | @InProceedings{Goyal_2023_CVPR, 9 | author = {Goyal, Gaurvi and Di Pietro, Franco and Carissimi, Nicolo and Glover, Arren and Bartolozzi, Chiara}, 10 | title = {MoveEnet: Online High-Frequency Human Pose Estimation With an Event Camera}, 11 | booktitle = {Proceedings of the IEEE/CVF Conference on Computer Vision and Pattern Recognition (CVPR) Workshops}, 12 | month = {June}, 13 | year = {2023}, 14 | pages = {4023-4032} 15 | } 16 | ``` 17 | Article: [MoveEnet: Online High-Frequency Human Pose Estimation With an Event Camera](https://github.com/user-attachments/files/17659249/MoveEnet-CVPR-WEBV2023.pdf) 18 | 19 | The eH3.6m dataset: 20 | ``` 21 | https://zenodo.org/record/7842598 22 | ``` 23 | and checkout [other publications](#see-also) 24 | 25 | Please contribute your event-driven HPE application and datasets to enable comparisons! 26 | 27 | ### [Core (C++)](https://github.com/event-driven-robotics/hpe-core/tree/main/core) 28 | 29 | Compile and link the core C++ library in your application to use the event-based human pose estimation functions including: 30 | * joint detectors: OpenPose built upon greyscales formed from events 31 | * joint velocity estimation @>500Hz 32 | * asynchronous pose fusion of joint velocity and detection 33 | * event representation methods to be compatible with convolutional neural networks. 34 | 35 | ### [PyCore](https://github.com/event-driven-robotics/hpe-core/tree/main/pycore) 36 | 37 | Importable python libraries for joint detection 38 | * Event-based movenet: MoveEnet built on PyTorch 39 | * MoveEnet training code is available in a separate, unconnected repository: [https://github.com/event-driven-robotics/MoveEnet](https://github.com/event-driven-robotics/MoveEnet). 40 | 41 | ### [Examples](https://github.com/event-driven-robotics/hpe-core/tree/main/example) 42 | 43 | Some example applications are available giving ideas on how to use the HPE-core libraries 44 | - MoveEnet inference code in corresponding example [here](https://github.com/event-driven-robotics/hpe-core/tree/main/example/movenet). 45 | 46 | ### [Evaluation](https://github.com/event-driven-robotics/hpe-core/tree/main/evaluation) 47 | 48 | Python scripts can be used to compare different detectors and velocity estimation combinations 49 | 50 | ### [Datasets and Conversion](https://github.com/event-driven-robotics/hpe-core/tree/main/datasets) 51 | 52 | Scripts to convert datasets into common formats to easily facilitate valid comparisons, and consistency 53 | 54 | ### Authors 55 | 56 | > [@arrenglover](https://www.linkedin.com/in/arren-glover/) 57 | > [@nicolocarissimi](https://www.linkedin.com/in/nicolocarissimi/) 58 | > [@gaurvigoyal](https://www.linkedin.com/in/gaurvigoyal/) 59 | > [@francodipietro](https://www.linkedin.com/in/francodipietrophd/) 60 | 61 | [Event-driven Perception for Robotics](https://www.edpr.iit.it/research) 62 | 63 | ### See Also 64 | 65 | ``` 66 | @INPROCEEDINGS{9845526, 67 | author={Carissimi, Nicolò and Goyal, Gaurvi and Pietro, Franco Di and Bartolozzi, Chiara and Glover, Arren}, 68 | booktitle={2022 8th International Conference on Event-Based Control, Communication, and Signal Processing (EBCCSP)}, 69 | title={Unlocking Static Images for Training Event-driven Neural Networks}, 70 | year={2022}, 71 | pages={1-4}, 72 | doi={10.1109/EBCCSP56922.2022.9845526}} 73 | ``` 74 | -------------------------------------------------------------------------------- /core/.gitignore: -------------------------------------------------------------------------------- 1 | build/ 2 | .vscode/ 3 | *.code-workspace -------------------------------------------------------------------------------- /core/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | # Copyright: (C) 2021 EDPR - Istituto Italiano di Tecnologia 2 | # Authors: Arren Glover 3 | 4 | cmake_minimum_required(VERSION 3.16.0) 5 | 6 | project(hpe-core 7 | LANGUAGES CXX 8 | VERSION 0.1) 9 | 10 | include(GNUInstallDirs) 11 | 12 | set(CMAKE_RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/${CMAKE_INSTALL_BINDIR}") 13 | set(CMAKE_LIBRARY_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/${CMAKE_INSTALL_LIBDIR}") 14 | set(CMAKE_ARCHIVE_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/${CMAKE_INSTALL_LIBDIR}") 15 | 16 | #set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON) 17 | 18 | if(MSVC) 19 | set(CMAKE_DEBUG_POSTFIX "d") 20 | endif() 21 | 22 | #set(CMAKE_POSITION_INDEPENDENT_CODE ON) 23 | 24 | set(CMAKE_C_EXTENSIONS OFF) 25 | set(CMAKE_CXX_EXTENSIONS OFF) 26 | 27 | option(BUILD_SHARED_LIBS "Build libraries as shared as opposed to static" ON) 28 | 29 | find_package(YCM) 30 | #set_package_properties(YCM PROPERTIES TYPE RECOMMENDED) 31 | 32 | #if(NOT YCM_FOUND) 33 | # list(APPEND CMAKE_MODULE_PATH ${CMAKE_CURRENT_SOURCE_DIR}/cmake) 34 | #endif() 35 | 36 | include(AddInstallRPATHSupport) 37 | add_install_rpath_support(BIN_DIRS "${CMAKE_INSTALL_FULL_BINDIR}" 38 | LIB_DIRS "${CMAKE_INSTALL_FULL_LIBDIR}" 39 | INSTALL_NAME_DIR "${CMAKE_INSTALL_FULL_LIBDIR}" 40 | USE_LINK_PATH) 41 | 42 | if(NOT CMAKE_CONFIGURATION_TYPES) 43 | if(NOT CMAKE_BUILD_TYPE) 44 | message(STATUS "Setting build type to 'Release' as none was specified.") 45 | set_property(CACHE CMAKE_BUILD_TYPE PROPERTY VALUE "Release") 46 | endif() 47 | endif() 48 | 49 | find_package(OpenCV) 50 | if(OpenCV_FOUND) 51 | message(STATUS "Found OpenCV: (found version ${OpenCV_VERSION})") 52 | endif() 53 | 54 | set( folder_source 55 | event_representations/representations.cpp 56 | motion_estimation/reprojection.cpp 57 | motion_estimation/motion_estimation.cpp 58 | motion_estimation/motion.cpp 59 | fusion/fusion.cpp 60 | ) 61 | 62 | set( folder_header 63 | utility/utility.h 64 | motion_estimation/motion_estimation.h 65 | motion_estimation/reprojection.h 66 | motion_estimation/motion.h 67 | event_representations/representations.h 68 | fusion/fusion.h 69 | ) 70 | 71 | find_package(OpenPose QUIET) 72 | if( OpenPose_FOUND ) 73 | message(STATUS "Found Openpose: (found version ${OpenPose_VERSION})") 74 | list(APPEND folder_source detection_wrappers/openpose_detector.cpp) 75 | list(APPEND folder_header detection_wrappers/openpose_detector.h) 76 | else () 77 | message(STATUS "Not Found Openpose: wrappers not compiled") 78 | endif() 79 | 80 | 81 | add_library(${PROJECT_NAME} ${folder_source} ${folder_header}) 82 | 83 | set_target_properties(${PROJECT_NAME} PROPERTIES PUBLIC_HEADER "${folder_header}" 84 | VERSION ${hpe-core_VERSION} 85 | SOVERSION 2) 86 | 87 | target_include_directories(${PROJECT_NAME} PRIVATE utility event_representations 88 | PUBLIC "$" 89 | "$/${CMAKE_INSTALL_INCLUDEDIR}>") # FIXME INSTALL PATH 90 | 91 | target_compile_options(${PROJECT_NAME} PRIVATE -Wall) 92 | 93 | target_link_libraries(${PROJECT_NAME} PUBLIC ${OpenPose_LIBS} ${OpenCV_LIBRARIES} pthread) 94 | 95 | install(TARGETS ${PROJECT_NAME} 96 | EXPORT hpecore 97 | LIBRARY DESTINATION "${CMAKE_INSTALL_LIBDIR}" COMPONENT shlib 98 | ARCHIVE DESTINATION "${CMAKE_INSTALL_LIBDIR}" COMPONENT lib 99 | RUNTIME DESTINATION "${CMAKE_INSTALL_BINDIR}" COMPONENT bin 100 | PUBLIC_HEADER DESTINATION "${CMAKE_INSTALL_INCLUDEDIR}/${PROJECT_NAME}" COMPONENT dev) 101 | 102 | include(InstallBasicPackageFiles) 103 | install_basic_package_files(${PROJECT_NAME} 104 | EXPORT hpecore 105 | VERSION ${${PROJECT_NAME}_VERSION} 106 | COMPATIBILITY SameMajorVersion 107 | LOWERCASE_FILENAMES 108 | NAMESPACE hpe-core:: 109 | DEPENDENCIES OpenCV) 110 | include(AddUninstallTarget) 111 | 112 | 113 | #find_package(hpe-core REQUIRED) 114 | #add_executable(test utility/test.cpp) 115 | #target_link_libraries(test PUBLIC ${OpenCV_LIBRARIES} hpe-core::hpe-core) 116 | -------------------------------------------------------------------------------- /core/README.md: -------------------------------------------------------------------------------- 1 | # Core Library Functions for human pose estimation tasks 2 | 3 | C++ src for compiling a library of functions useful for HPE: 4 | 5 | * human pose estimation from events 6 | * joint tracking 7 | * skeleton tracking 8 | * position and velocity fusion 9 | * on-line visualisation 10 | 11 | # Build the library 12 | 13 | The library is designed to use CMake to configure and build. 14 | 15 | * Clone the repository: e.g. `git clone https://github.com/event-driven-robotics/hpe-core.git` 16 | * `cd hpe-core/core` 17 | * `mkdir build && cd build` 18 | * `cmake ..` 19 | * `make` 20 | 21 | CMake will search for installed dependencies, which are needed for the pose detection wrappers. To install specific dependencies, check the Dockerfile in example modules for tips. If you want all dependencies we provide a (large) Dockerfile [here](todo). 22 | 23 | # Link the library to your repository 24 | 25 | Using cmake, add the following to your `CMakeLists.txt` 26 | 27 | * `find_package(hpe-core)` 28 | * `target_link_libraries(${PROJECT_NAME} PRIVATE hpe-core::hpe-core)` 29 | 30 | # Example 31 | 32 | Examples of how to install dependencies, build the library, and link it in your own project can be found [here](https://github.com/event-driven-robotics/hpe-core/tree/main/example/op_detector_example_module). The Dockerfile can be used to automatically build the dependencies required in a isolated container, or if you prefer, your can follow it's instructions to install the dependencies natively on your machine. [Interested to learn more about Docker?](https://www.docker.com/) 33 | -------------------------------------------------------------------------------- /core/detection_wrappers/openpose_detector.h: -------------------------------------------------------------------------------- 1 | /* BSD 3-Clause License 2 | 3 | Copyright (c) 2021, Event Driven Perception for Robotics 4 | All rights reserved. 5 | 6 | Redistribution and use in source and binary forms, with or without 7 | modification, are permitted provided that the following conditions are met: 8 | 9 | 1. Redistributions of source code must retain the above copyright notice, this 10 | list of conditions and the following disclaimer. 11 | 12 | 2. Redistributions in binary form must reproduce the above copyright notice, 13 | this list of conditions and the following disclaimer in the documentation 14 | and/or other materials provided with the distribution. 15 | 16 | 3. Neither the name of the copyright holder nor the names of its 17 | contributors may be used to endorse or promote products derived from 18 | this software without specific prior written permission. 19 | 20 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 21 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 22 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 23 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE 24 | FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL 25 | DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR 26 | SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 27 | CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, 28 | OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE 29 | OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. */ 30 | #pragma once 31 | 32 | #include "utility.h" 33 | #include 34 | #include 35 | 36 | namespace hpecore { 37 | 38 | class OpenPoseDetector { 39 | 40 | op::Wrapper detector{op::ThreadManagerMode::Asynchronous}; 41 | int poseJointsNum; 42 | 43 | public: 44 | bool init(std::string poseModel, std::string poseMode, std::string size = "256"); 45 | skeleton13 detect(cv::Mat &input); 46 | void stop(); 47 | }; 48 | 49 | class openposethread 50 | { 51 | private: 52 | std::thread th; 53 | hpecore::OpenPoseDetector detop; 54 | hpecore::stampedPose pose{0.0, -1.0, 0.0}; 55 | cv::Mat image; 56 | 57 | bool stop{false}; 58 | bool data_ready{true}; 59 | std::mutex m; 60 | 61 | void run(); 62 | 63 | public: 64 | bool init(std::string model_path, std::string model_name, 65 | std::string model_size = "256"); 66 | void close(); 67 | bool update(cv::Mat next_image, double image_timestamp, 68 | hpecore::stampedPose &previous_result); 69 | }; 70 | 71 | } -------------------------------------------------------------------------------- /core/event_representations/representations.cpp: -------------------------------------------------------------------------------- 1 | /* BSD 3-Clause License 2 | 3 | Copyright (c) 2021, Event Driven Perception for Robotics 4 | All rights reserved. 5 | 6 | Redistribution and use in source and binary forms, with or without 7 | modification, are permitted provided that the following conditions are met: 8 | 9 | 1. Redistributions of source code must retain the above copyright notice, this 10 | list of conditions and the following disclaimer. 11 | 12 | 2. Redistributions in binary form must reproduce the above copyright notice, 13 | this list of conditions and the following disclaimer in the documentation 14 | and/or other materials provided with the distribution. 15 | 16 | 3. Neither the name of the copyright holder nor the names of its 17 | contributors may be used to endorse or promote products derived from 18 | this software without specific prior written permission. 19 | 20 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 21 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 22 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 23 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE 24 | FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL 25 | DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR 26 | SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 27 | CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, 28 | OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE 29 | OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. */ 30 | #include "representations.h" 31 | 32 | using namespace cv; 33 | using namespace std; 34 | 35 | namespace hpecore { 36 | 37 | void varianceNormalisation(cv::Mat &input) 38 | { 39 | constexpr double threshold = 0.1 / 255; 40 | 41 | //get the average value of any pixel 42 | int count_unique = cv::countNonZero(input); 43 | double mean_pval = cv::sum(input)[0] / count_unique; 44 | 45 | //calculate the variance of the (non-zero) pixels 46 | double var = 0; 47 | for (auto x = 0; x < input.cols; x++) { 48 | for (auto y = 0; y < input.rows; y++) { 49 | auto &p = input.at(x, y); 50 | if (p > 0) { 51 | double e = p - mean_pval; 52 | var += e * e; 53 | } 54 | } 55 | } 56 | var /= count_unique; 57 | double sigma = sqrt(var); 58 | if (sigma < threshold) sigma = threshold; 59 | 60 | //scale each pixel by the scale factor 61 | double scale_factor = 255.0 / (3.0 * sigma); 62 | for (auto x = 0; x < input.cols; x++) { 63 | for (auto y = 0; y < input.rows; y++) { 64 | auto &p = input.at(x, y); 65 | if (p > 0) { 66 | double v = p * scale_factor; 67 | if (v > 255.0) v = 255.0; 68 | if (v < 0.0) v = 0.0; 69 | p = (uchar)v; 70 | } 71 | } 72 | } 73 | } 74 | 75 | point_flow estimateVisualFlow(pixel_3d px3, const camera_velocity &vcam, const camera_params &pcam) 76 | { 77 | 78 | double f_inv = 1.0 / pcam.f; 79 | double x = px3.x - pcam.cx; 80 | double y = px3.y - pcam.cy; 81 | point_flow flow; 82 | flow.udot = (x * y * f_inv)*vcam[3] + -(pcam.f + pow(x, 2) * f_inv)*vcam[4] + y*vcam[5]; 83 | flow.vdot = (pcam.f + pow(y, 2) * f_inv)*vcam[3] + (-x * y * f_inv)*vcam[4] + -x*vcam[5]; 84 | 85 | if (px3.d) { 86 | flow.udot = flow.udot + (-pcam.f / px3.d) * vcam[0] + x / px3.d * vcam[2]; 87 | flow.vdot = flow.vdot + (-pcam.f / px3.d) * vcam[1] + y / px3.d * vcam[2]; 88 | } 89 | return flow; 90 | } 91 | 92 | 93 | cv::Mat surface::getSurface() 94 | { 95 | return surf(actual_region); 96 | } 97 | 98 | void surface::init(int width, int height, int kernel_size, double parameter) 99 | { 100 | if (kernel_size % 2 == 0) 101 | kernel_size++; 102 | this->kernel_size = kernel_size; //kernel_size should be odd 103 | this->half_kernel = kernel_size / 2; 104 | this->parameter = parameter; 105 | 106 | surf = cv::Mat(height+half_kernel*2, width+half_kernel*2, CV_64F, cv::Scalar(0.0)); 107 | actual_region = {half_kernel, half_kernel, width, height}; 108 | } 109 | 110 | void surface::temporalDecay(double ts, double alpha) { 111 | surf *= cv::exp(alpha * (time_now - ts)); 112 | time_now = ts; 113 | } 114 | 115 | void surface::spatialDecay(int k) 116 | { 117 | cv::GaussianBlur(surf, surf, cv::Size(k, k), 0); 118 | } 119 | 120 | } -------------------------------------------------------------------------------- /core/event_representations/representations.h: -------------------------------------------------------------------------------- 1 | /* BSD 3-Clause License 2 | 3 | Copyright (c) 2021, Event Driven Perception for Robotics 4 | All rights reserved. 5 | 6 | Redistribution and use in source and binary forms, with or without 7 | modification, are permitted provided that the following conditions are met: 8 | 9 | 1. Redistributions of source code must retain the above copyright notice, this 10 | list of conditions and the following disclaimer. 11 | 12 | 2. Redistributions in binary form must reproduce the above copyright notice, 13 | this list of conditions and the following disclaimer in the documentation 14 | and/or other materials provided with the distribution. 15 | 16 | 3. Neither the name of the copyright holder nor the names of its 17 | contributors may be used to endorse or promote products derived from 18 | this software without specific prior written permission. 19 | 20 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 21 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 22 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 23 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE 24 | FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL 25 | DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR 26 | SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 27 | CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, 28 | OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE 29 | OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. */ 30 | #pragma once 31 | 32 | #include 33 | #include 34 | #include 35 | #include "utility.h" 36 | 37 | namespace hpecore { 38 | 39 | // Image creation 40 | 41 | template 42 | inline void createCountImage(std::deque &input, cv::Mat &output) 43 | { 44 | output.setTo(0); 45 | for (auto &v : input) 46 | output.at(v.x, v.y)++; 47 | } 48 | 49 | void varianceNormalisation(cv::Mat &input); 50 | 51 | // Event warping 52 | using camera_velocity = std::array; 53 | 54 | typedef struct camera_params 55 | { 56 | float f; 57 | float cx; 58 | float cy; 59 | } camera_params; 60 | 61 | typedef struct pixel_3d 62 | { 63 | double x{0}; 64 | double y{0}; 65 | double d{0}; 66 | } pixel_3d; 67 | 68 | point_flow estimateVisualFlow(pixel_3d px3, const camera_velocity &vcam, const camera_params &pcam); 69 | 70 | 71 | 72 | template 73 | T spatiotemporalWarp(T original, point_flow flow, double deltat) 74 | { 75 | T output; 76 | output.stamp = original.stamp + deltat; 77 | output.y = original.y + flow.vdot * deltat + 0.5; 78 | output.x = original.x + flow.udot * deltat + 0.5; 79 | return output; 80 | } 81 | 82 | class surface 83 | { 84 | protected: 85 | int kernel_size{0}; 86 | int half_kernel{0}; 87 | double parameter{0}; 88 | double time_now{0}; 89 | 90 | cv::Rect actual_region; 91 | cv::Mat surf; 92 | 93 | public: 94 | 95 | virtual cv::Mat getSurface(); 96 | virtual void init(int width, int height, int kernel_size = 5, double parameter = 0.0); 97 | virtual inline void update(int x, int y, double ts, int p) = 0; 98 | void temporalDecay(double ts, double alpha); 99 | void spatialDecay(int k); 100 | }; 101 | 102 | class EROS : public surface { 103 | public: 104 | inline void update(int x, int y, double t = 0, int p = 0) override 105 | { 106 | static double odecay = pow(parameter, 1.0 / kernel_size); 107 | surf({x, y, kernel_size, kernel_size}) *= odecay; 108 | surf.at(y+half_kernel, x+half_kernel) = 255.0; 109 | } 110 | }; 111 | 112 | class TOS : public surface 113 | { 114 | public: 115 | inline void update(int x, int y, double t = 0, int p = 0) override { 116 | (void)t; (void)p; 117 | // parameter default = 2 118 | static const double threshold = 255.0 - kernel_size * parameter; 119 | static cv::Rect roi = {0, 0, kernel_size, kernel_size}; 120 | 121 | roi.x = x; roi.y = y; 122 | static cv::Mat region = surf(roi); 123 | 124 | for (auto xi = 0; xi < region.cols; xi++) { 125 | for (auto yi = 0; yi < region.rows; yi++) { 126 | double &p = region.at(yi, xi); 127 | if (p < threshold) p = 0; 128 | else p--; 129 | } 130 | } 131 | surf.at(y+half_kernel, x+half_kernel) = 255.0; 132 | } 133 | }; 134 | 135 | class SITS : public surface { 136 | public: 137 | inline void update(int x, int y, double t = 0, int p = 0) override { 138 | static const int maximum_value = kernel_size * kernel_size; 139 | static cv::Rect roi = {0, 0, kernel_size, kernel_size}; 140 | 141 | roi.x = x; roi.y = y; 142 | static cv::Mat region = surf(roi); 143 | 144 | double &c = surf.at(y+half_kernel, x+half_kernel); 145 | for (auto xi = 0; xi < region.cols; xi++) { 146 | for (auto yi = 0; yi < region.rows; yi++) { 147 | double &p = region.at(yi, xi); 148 | if (p > c) p--; 149 | } 150 | } 151 | c = maximum_value; 152 | } 153 | }; 154 | 155 | class PIM : public surface { 156 | public: 157 | inline void update(int x, int y, double t = 0, int p = 0) override 158 | { 159 | if (p) 160 | surf.at(y+half_kernel, x+half_kernel) -= 1.0f; 161 | else 162 | surf.at(y+half_kernel, x+half_kernel) += 1.0f; 163 | } 164 | }; 165 | 166 | class SAE : public surface 167 | { 168 | public: 169 | inline void update(int x, int y, double t = 0, int p = 0) override 170 | { 171 | surf.at(y+half_kernel, x+half_kernel) = t; 172 | } 173 | }; 174 | 175 | class BIN : public surface 176 | { 177 | public: 178 | inline void update(int x, int y, double t = 0, int p = 0) override 179 | { 180 | surf.at(y+half_kernel, x+half_kernel) = 255.0; 181 | } 182 | }; 183 | 184 | } // namespace hpecore -------------------------------------------------------------------------------- /core/motion_estimation/motion.cpp: -------------------------------------------------------------------------------- 1 | #include "utility.h" 2 | #include "motion.h" 3 | 4 | namespace hpecore{ 5 | 6 | const std::vector< std::vector > pwtripletvelocity::is = {{{0,0},{1,1}}, 7 | {{0,2},{1,2}}, 8 | {{0,4},{1,3}}, 9 | {{2,4},{2,3}}, 10 | {{4,4},{3,3}}, 11 | {{4,2},{3,2}}, 12 | {{4,0},{3,1}}, 13 | {{2,0},{2,1}}}; 14 | 15 | const std::vector pwtripletvelocity::vs ={{1, 1}, 16 | {1, 0}, 17 | {1, -1}, 18 | {0, -1}, 19 | {-1,-1}, 20 | {-1, 0}, 21 | {-1, 1}, 22 | {0, 1}}; 23 | 24 | pwtripletvelocity::wjv pwtripletvelocity::point_velocity(const cv::Mat &local_sae) 25 | { 26 | 27 | wjv wvel = {{0,0}, 0}; 28 | 29 | for(size_t i = 0; i < is.size(); i++) 30 | { 31 | const double &t0 = local_sae.at(2, 2); 32 | const double &t1 = local_sae.at(is[i][1]); 33 | const double &t2 = local_sae.at(is[i][0]); 34 | double dta = t0-t1; 35 | double dtb = t1-t2; 36 | bool valid = dta > 0 && dtb > 0 && t1 > 0 && t2 > 0; 37 | if(!valid) continue; 38 | double error = fabs(1 - dtb/dta); 39 | if(error > tolerance) continue; 40 | //valid triplet. calulate the velocity. 41 | double invt = 2.0 / (dta + dtb); 42 | wvel.v.u += vs[i].u * invt; 43 | wvel.v.v += vs[i].v * invt; 44 | wvel.c++; 45 | //test rectification of the vector here. in theory slowest vector is most accurate. 46 | } 47 | return wvel; 48 | } 49 | 50 | 51 | jDot pwtripletvelocity::area_velocity(const cv::Mat &area_sae) 52 | { 53 | wjv wvel = {{0,0}, 0}; 54 | auto s = area_sae.size(); 55 | for(int y = 2; y < s.height-2; y++) { 56 | for(int x = 2; x < s.width-2; x++) { 57 | const double &ts = area_sae.at(y, x); 58 | if(ts > prev_update_ts) 59 | wvel += point_velocity(area_sae({x-2,y-2,5,5})); 60 | } 61 | } 62 | if(wvel.c > 0) 63 | return {wvel.v.u/wvel.c, wvel.v.v/wvel.c}; 64 | else 65 | return {0, 0}; 66 | } 67 | 68 | std::vector pwtripletvelocity::multi_area_velocity(const cv::Mat &full_sae, double ts, std::vector js, int radius) 69 | { 70 | std::vector output; 71 | 72 | for(auto j : js) { 73 | cv::Rect joint_region = cv::Rect(j.u - radius, j.v - radius, radius*2+1, radius*2+1) & cv::Rect({0, 0}, full_sae.size()); 74 | if(joint_region.width < 5 || joint_region.height < 5) 75 | output.push_back({0, 0}); 76 | else 77 | output.push_back(area_velocity(full_sae(joint_region))); 78 | } 79 | prev_update_ts = ts; 80 | return output; 81 | } 82 | 83 | skeleton13 pwtripletvelocity::multi_area_velocity(const cv::Mat &full_sae, double ts, skeleton13 js, int radius) 84 | { 85 | skeleton13 output; 86 | int i = 0; 87 | for(auto j : js) { 88 | cv::Rect joint_region = cv::Rect(j.u - radius, j.v - radius, radius*2+1, radius*2+1) & cv::Rect({0, 0}, full_sae.size()); 89 | if(joint_region.width < 5 || joint_region.height < 5) 90 | output[i++] = {0, 0}; 91 | else 92 | output[i++] = area_velocity(full_sae(joint_region)) * 1.4; 93 | } 94 | prev_update_ts = ts; 95 | return output; 96 | } 97 | 98 | 99 | 100 | } -------------------------------------------------------------------------------- /core/motion_estimation/motion.h: -------------------------------------------------------------------------------- 1 | /* BSD 3-Clause License 2 | 3 | Copyright (c) 2021, Event Driven Perception for Robotics 4 | All rights reserved. 5 | 6 | Redistribution and use in source and binary forms, with or without 7 | modification, are permitted provided that the following conditions are met: 8 | 9 | 1. Redistributions of source code must retain the above copyright notice, this 10 | list of conditions and the following disclaimer. 11 | 12 | 2. Redistributions in binary form must reproduce the above copyright notice, 13 | this list of conditions and the following disclaimer in the documentation 14 | and/or other materials provided with the distribution. 15 | 16 | 3. Neither the name of the copyright holder nor the names of its 17 | contributors may be used to endorse or promote products derived from 18 | this software without specific prior written permission. 19 | 20 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 21 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 22 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 23 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE 24 | FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL 25 | DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR 26 | SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 27 | CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, 28 | OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE 29 | OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. */ 30 | #pragma once 31 | 32 | #include "utility.h" 33 | #include 34 | 35 | namespace hpecore 36 | { 37 | 38 | class pwtripletvelocity 39 | { 40 | private: 41 | double tolerance{0.15}; 42 | 43 | static const std::vector< std::vector > is; 44 | static const std::vector vs; 45 | 46 | typedef struct wjv { 47 | jDot v; 48 | int c; 49 | wjv& operator+=(const wjv& rhs) { 50 | this->c += rhs.c; 51 | this->v = {this->v.u + rhs.v.u, this->v.v + rhs.v.v}; 52 | return *this; 53 | } 54 | } wjv; 55 | 56 | wjv point_velocity(const cv::Mat &local_sae); 57 | 58 | public: 59 | double prev_update_ts; 60 | jDot area_velocity(const cv::Mat &area_sae); 61 | std::vector multi_area_velocity(const cv::Mat &full_sae, double ts, std::vector js, int radius); 62 | skeleton13 multi_area_velocity(const cv::Mat &full_sae, double ts, skeleton13 js, int radius); 63 | 64 | }; 65 | 66 | 67 | 68 | } -------------------------------------------------------------------------------- /core/motion_estimation/motion_estimation.cpp: -------------------------------------------------------------------------------- 1 | #include "motion_estimation.h" 2 | 3 | /* BSD 3-Clause License 4 | 5 | Copyright (c) 2021, Event Driven Perception for Robotics 6 | All rights reserved. 7 | 8 | Redistribution and use in source and binary forms, with or without 9 | modification, are permitted provided that the following conditions are met: 10 | 11 | 1. Redistributions of source code must retain the above copyright notice, this 12 | list of conditions and the following disclaimer. 13 | 14 | 2. Redistributions in binary form must reproduce the above copyright notice, 15 | this list of conditions and the following disclaimer in the documentation 16 | and/or other materials provided with the distribution. 17 | 18 | 3. Neither the name of the copyright holder nor the names of its 19 | contributors may be used to endorse or promote products derived from 20 | this software without specific prior written permission. 21 | 22 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 23 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 24 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 25 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE 26 | FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL 27 | DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR 28 | SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 29 | CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, 30 | OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE 31 | OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. */ 32 | 33 | #include "motion_estimation.h" 34 | -------------------------------------------------------------------------------- /core/motion_estimation/reprojection.cpp: -------------------------------------------------------------------------------- 1 | #include "reprojection.h" -------------------------------------------------------------------------------- /core/motion_estimation/reprojection.h: -------------------------------------------------------------------------------- 1 | /* BSD 3-Clause License 2 | 3 | Copyright (c) 2023, Event Driven Perception for Robotics 4 | All rights reserved. 5 | 6 | Redistribution and use in source and binary forms, with or without 7 | modification, are permitted provided that the following conditions are met: 8 | 9 | 1. Redistributions of source code must retain the above copyright notice, this 10 | list of conditions and the following disclaimer. 11 | 12 | 2. Redistributions in binary form must reproduce the above copyright notice, 13 | this list of conditions and the following disclaimer in the documentation 14 | and/or other materials provided with the distribution. 15 | 16 | 3. Neither the name of the copyright holder nor the names of its 17 | contributors may be used to endorse or promote products derived from 18 | this software without specific prior written permission. 19 | 20 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 21 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 22 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 23 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE 24 | FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL 25 | DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR 26 | SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 27 | CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, 28 | OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE 29 | OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. */ 30 | #pragma once 31 | 32 | #include "utility.h" 33 | #include 34 | #include 35 | namespace hpecore { 36 | 37 | class skeletonCFT { 38 | private: 39 | 40 | typedef struct intrinsic { 41 | int w; 42 | int h; 43 | int u0; 44 | int v0; 45 | double fu; 46 | double fv; 47 | double k1; 48 | double k2; 49 | } intrinsic; 50 | 51 | intrinsic cam1; 52 | intrinsic cam2; 53 | 54 | cv::Mat mapx1, mapy1; 55 | 56 | cv::Mat T; 57 | 58 | public: 59 | 60 | void setCam1Parameters(std::array res, std::array dis) 61 | { 62 | cam1.w = res[0]; cam1.h = res[1]; cam1.u0 = res[2]; cam1.v0 = res[3]; 63 | cam1.fu = dis[0]; cam1.fv = dis[1]; cam1.k1 = dis[2]; cam1.k2 = dis[3]; 64 | cv::Mat cam_matrix = (cv::Mat_(3, 3) << cam1.fu, 0, cam1.u0, 0, cam1.fv, cam1.v0, 0, 0, 1); 65 | cv::Mat dst_matrix = (cv::Mat_(4, 1) << cam1.k1, cam1.k2, 0, 0); 66 | cv::Mat ocm1 = cv::getOptimalNewCameraMatrix(cam_matrix, dst_matrix, {cam1.w, cam1.h}, 1.0); 67 | cv::initUndistortRectifyMap(cam_matrix, dst_matrix, cv::noArray(), ocm1, {cam1.w, cam1.h}, CV_32F, mapx1, mapy1); 68 | } 69 | 70 | void setCam2Parameters(std::array res, std::array dis) 71 | { 72 | cam2.w = res[0]; cam2.h = res[1]; cam2.u0 = res[2]; cam2.v0 = res[3]; 73 | cam2.fu = dis[0]; cam2.fv = dis[1]; cam2.k1 = dis[2]; cam2.k2 = dis[3]; 74 | // cv::Mat cam_matrix = (cv::Mat_(3, 3) << cam2.fu, 0, cam2.u0, 0, cam2.fv, cam2.v0, 0, 0, 1); 75 | // cv::Mat dst_matrix = (cv::Mat_(4, 1) << cam2.k1, cam2.k2, 0, 0); 76 | // cv::Mat ocm2 = cv::getOptimalNewCameraMatrix(cam_matrix, dst_matrix, {cam2.w, cam2.h}, 1.0); 77 | } 78 | 79 | void setExtrinsicTransform(std::array E) 80 | { 81 | cv::Mat(4, 4, CV_64F, E.data()).copyTo(T); 82 | 83 | } 84 | 85 | joint cft(joint in, double depth) 86 | { 87 | //undistort point 88 | joint und1 = {mapx1.at(in.v, in.u), mapy1.at(in.v, in.u)}; 89 | 90 | //project to 3D 91 | cv::Mat X1 = (cv::Mat_(4,1) << depth * (und1.u-cam1.u0) / cam1.fu, depth * (und1.v-cam1.v0) / cam1.fv, depth, 1.0); 92 | 93 | //transform point to second camera reference 94 | cv::Mat X2 = T * X1; 95 | 96 | //project to 2D 97 | joint und2; 98 | und2.u = cam2.fu * X2.at(0, 0) / X2.at(0, 2) + cam2.u0; 99 | und2.v = cam2.fv * X2.at(0, 1) / X2.at(0, 2) + cam2.v0; 100 | 101 | //distort point 102 | joint out = und2; //we don't know if we want the undistorted or distorted point here. 103 | 104 | return out; 105 | } 106 | 107 | skeleton13 cft(skeleton13 in, double depth) 108 | { 109 | skeleton13 out = {0}; 110 | int i = 0; 111 | for(auto &j : in) 112 | out[i++] = cft(j, depth); 113 | return out; 114 | } 115 | 116 | 117 | 118 | 119 | }; 120 | 121 | } 122 | 123 | -------------------------------------------------------------------------------- /core/utility/test.cpp: -------------------------------------------------------------------------------- 1 | /* BSD 3-Clause License 2 | 3 | Copyright (c) 2021, Event Driven Perception for Robotics 4 | All rights reserved. 5 | 6 | Redistribution and use in source and binary forms, with or without 7 | modification, are permitted provided that the following conditions are met: 8 | 9 | 1. Redistributions of source code must retain the above copyright notice, this 10 | list of conditions and the following disclaimer. 11 | 12 | 2. Redistributions in binary form must reproduce the above copyright notice, 13 | this list of conditions and the following disclaimer in the documentation 14 | and/or other materials provided with the distribution. 15 | 16 | 3. Neither the name of the copyright holder nor the names of its 17 | contributors may be used to endorse or promote products derived from 18 | this software without specific prior written permission. 19 | 20 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 21 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 22 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 23 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE 24 | FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL 25 | DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR 26 | SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 27 | CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, 28 | OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE 29 | OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. */ 30 | 31 | #include 32 | #include 33 | #include 34 | 35 | bool test_representations() 36 | { 37 | 38 | cv::namedWindow("EROS"); 39 | cv::namedWindow("BINARY"); 40 | cv::namedWindow("SAE"); 41 | 42 | hpecore::EROS eros; 43 | hpecore::BIN binary; 44 | hpecore::SAE sae; 45 | 46 | hpecore::pwtripletvelocity pwtv; 47 | 48 | eros.init(640, 480, 7, 0.3); 49 | binary.init(640, 480, 0); 50 | sae.init(640, 480, 0); 51 | 52 | bool exit = false; 53 | 54 | double t = 0; 55 | while (!exit) { 56 | for (int y = 0; y < 480; y++) { 57 | for (int x = 0; x < 640; x++) { 58 | eros.update(x, y); 59 | binary.update(x, y); 60 | sae.update(x, y, t); 61 | } 62 | if(y > 10 && y < 470) { 63 | cv::Mat csae = sae.getSurface(); 64 | 65 | //auto k = pwtv.area_velocity(csae({320-10, y-10, 21, 21})); 66 | auto k = pwtv.multi_area_velocity(csae, t, {{320.0f, (float)y}}, 10); 67 | std::cout << k[0].u << " " << k[0].v << std::endl; 68 | } 69 | 70 | if(++t > 1000.0) t = 0; 71 | cv::imshow("EROS", eros.getSurface() / 255.0); 72 | cv::imshow("BINARY", binary.getSurface() / 255.0); 73 | cv::imshow("SAE", sae.getSurface() / 1000.0); 74 | char c = cv::waitKey(1); 75 | if(c == '\e') exit = true; 76 | } 77 | binary.getSurface().setTo(0.0); 78 | } 79 | 80 | cv::destroyAllWindows(); 81 | 82 | return true; 83 | } 84 | 85 | int main(int argc, char* argv[]) 86 | { 87 | 88 | test_representations(); 89 | 90 | 91 | 92 | 93 | return 0; 94 | 95 | } -------------------------------------------------------------------------------- /datasets/.gitignore: -------------------------------------------------------------------------------- 1 | .vscode 2 | -------------------------------------------------------------------------------- /datasets/README.md: -------------------------------------------------------------------------------- 1 | # Dataset Conversion 2 | 3 | This folder contains scripts for reading, preprocessing and exporting HPE datasets to common formats to enable valid comparison of human pose estimation algorithms. As each dataset has a unique format, tailored scripts are required per-dataset. As a final step we use [BIMVEE](https://github.com/event-driven-robotics/bimvee) to export events to any common format. 4 | 5 | We currently support the folowing datasets 6 | * [DHP19](dhp19/README.md) 7 | * [H3.6M](h36m/README.md) 8 | * [MPII](mpii/README.md) 9 | 10 | Human Pose across all hpe-core modules is defined with 13 joints, with the following map for joints (unless explicitly mentioned): 11 | ```Python 12 | KEYPOINTS_MAP = {'head': 0, 'shoulder_right': 1, 'shoulder_left': 2, 'elbow_right': 3, 'elbow_left': 4, 13 | 'hip_left': 5, 'hip_right': 6, 'wrist_right': 7, 'wrist_left': 8, 'knee_right': 9, 'knee_left': 10, 14 | 'ankle_right': 11, 'ankle_left': 12} 15 | ``` 16 | -------------------------------------------------------------------------------- /datasets/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/event-driven-robotics/hpe-core/178ac06fbf35f4b6ea9aca1a2a35bb6906b35213/datasets/__init__.py -------------------------------------------------------------------------------- /datasets/dhp19/README.md: -------------------------------------------------------------------------------- 1 | # DHP19 2 | 3 | The [Dynamic Vision Sensor 3D Human Pose (DHP19) dataset](https://sites.google.com/view/dhp19/home) is the first human 4 | pose dataset with data collected from DVS event cameras. It has recordings from 4 synchronized 346x260 pixel DVS cameras 5 | and marker positions in 3D space from Vicon motion capture system. The files have event streams and 3D positions recorded 6 | from 17 subjects each performing 33 movements. 7 | 8 | In order to use this dataset in the context of our pipeline, data must be preprocessed. 9 | 10 | ## Pre-Processing 11 | 12 | Pre-processing the raw data consists in filtering the events and separating them into four distinct camera channels. 13 | Code is written in *Matlab*. The script `preprocess.m` pre-processes a single recording file and requires the following 14 | variables to be set: 15 | 16 | * `subj`, `sess` and `mov` that define the selected recording to pre-process by choosing a subject, a session and a movement. 17 | * `rootCodeFolder` is the folder where the *hpe-core* repo is located 18 | * `rootDataFolder` points to the location where the raw dataset was downloaded 19 | * `outFolder` is the destination folder where the output of the pre-processing will be stored 20 | 21 | The script `preprocess_all.m` pre-processes all recording files and requires variables `rootCodeFolder`, `rootDataFolder` 22 | and `outFolder` to be set. 23 | 24 | The output of these scripts is a set of files named `S__.mat` containing a dictionary with the following format 25 | 26 | ``` 27 | { 28 | 'info': {}, 29 | 'data': 30 | { 31 | 'ch0': 32 | { 33 | 'dvs': 34 | { 35 | 'x': numpy_array of uint16, 36 | 'y': numpy_array of uint16, 37 | 'ts': numpy_array of float64, 38 | 'pol': numpy_array of bool, 39 | } 40 | 'ch1': {...}, 41 | 'ch2': {...}, 42 | 'ch3': {...} 43 | } 44 | ``` 45 | 46 | where `ch` specifies the camera id, `x` and `y` contain the events' coordinates and `pol` the events' polarity. 47 | 48 | 49 | ## Export to Yarp Format 50 | 51 | Once data has been preprocessed, it can be exported to the Yarp format. Code for this step is written in Python and can 52 | be executed by calling 53 | 54 | ```shell 55 | $ python3 export_to_yarp.py 56 | -e 57 | -v 58 | -p # used for projecting 3D ground truth poses to the camera plane 59 | -w # optional, used for computing an event frame 60 | -o 61 | ``` 62 | 63 | The output of this script is a set of folders, one for each camera and data type (`dvs` for event data, `skeleton` for 64 | ground truth poses) containing [Bimvee](https://github.com/event-driven-robotics/bimvee) and [Mustard](https://github.com/event-driven-robotics/mustard) 65 | compatible `data.log` and `info.log` files, and an additional `play.xml` file for the `yarpmanager` app. 66 | 67 | 68 | ## Export to Numpy Format 69 | 70 | It is also possible to export only the ground truth poses (arrays of skeletons) to numpy's file format by calling 71 | 72 | ```shell 73 | $ python3 export_gt_to_numpy.py 74 | -e 75 | -v 76 | -p # used for projecting 3D ground truth poses to the camera plane 77 | -w # optional, used for computing an event frame 78 | -o 79 | -td 80 | ``` 81 | 82 | The output of this script is a set of `.npy` files containing numpy arrays of skeletons. 83 | 84 | 85 | ## Export to TOS 86 | ... 87 | -------------------------------------------------------------------------------- /datasets/dhp19/e2vid/Dockerfile: -------------------------------------------------------------------------------- 1 | 2 | # base image 3 | FROM nvidia/cuda:10.0-cudnn7-devel-ubuntu18.04 4 | 5 | # install utils 6 | RUN apt-get update && \ 7 | DEBIAN_FRONTEND=noninteractive apt-get install -y \ 8 | git \ 9 | vim \ 10 | wget \ 11 | openssh-server \ 12 | libmysqlclient-dev \ 13 | ffmpeg libsm6 libxext6 14 | 15 | ####################### 16 | # set github ssh keys # 17 | ####################### 18 | ARG ssh_prv_key 19 | ARG ssh_pub_key 20 | 21 | # Authorize SSH Host 22 | RUN mkdir -p /root/.ssh && \ 23 | chmod 0700 /root/.ssh && \ 24 | ssh-keyscan github.com > /root/.ssh/known_hosts 25 | 26 | # Add the keys and set permissions 27 | RUN echo "$ssh_prv_key" > /root/.ssh/id_rsa && \ 28 | echo "$ssh_pub_key" > /root/.ssh/id_rsa.pub && \ 29 | chmod 600 /root/.ssh/id_rsa && \ 30 | chmod 600 /root/.ssh/id_rsa.pub 31 | 32 | 33 | ################## 34 | # setup anaconda # 35 | ################## 36 | 37 | # install anaconda 38 | RUN wget https://repo.anaconda.com/archive/Anaconda3-2021.05-Linux-x86_64.sh && \ 39 | chmod +x Anaconda3-2021.05-Linux-x86_64.sh && \ 40 | bash Anaconda3-2021.05-Linux-x86_64.sh -b -p /root/anaconda && \ 41 | rm Anaconda3-2021.05-Linux-x86_64.sh 42 | 43 | # make non-activate conda commands available 44 | ENV CONDA_DIR /root/anaconda 45 | ENV PATH=$CONDA_DIR/bin:$PATH 46 | 47 | # make conda activate command available from /bin/bash --interative shells 48 | RUN conda init 49 | 50 | RUN eval "$(/root/anaconda/bin/conda shell.bash hook)" && \ 51 | conda create -n hpe-core && \ 52 | conda activate hpe-core && \ 53 | conda install pytorch torchvision cudatoolkit=10.0 -c pytorch && \ 54 | conda install pandas && \ 55 | conda install -c conda-forge opencv && \ 56 | conda install -c anaconda scipy 57 | 58 | RUN echo "conda activate hpe-core" >> ~/.bashrc 59 | 60 | 61 | ############### 62 | # setup e2vid # 63 | ############### 64 | 65 | # download hpe-core repository 66 | RUN git clone git@github.com:event-driven-robotics/hpe-core.git && \ 67 | cd hpe-core 68 | 69 | # download e2vid repository 70 | RUN cd hpe-core/evaluation/dhp19/e2vid && \ 71 | git clone git@github.com:uzh-rpg/rpg_e2vid.git && \ 72 | 73 | # fix e2vid incompatibility with recent pytorch versions (https://github.com/uzh-rpg/rpg_e2vid/issues/5) \ 74 | cd rpg_e2vid && \ 75 | sed -ie 's/index=xs[valid_indices]/index=(xs[valid_indices]/g' utils/inference_utils.py && \ 76 | sed -ie 's/tis_long[valid_indices] * width * height/tis_long[valid_indices] * width * height).type(torch.cuda.LongTensor)/g' utils/inference_utils.py && \ 77 | sed -ie 's/tis_long[valid_indices] + 1) * width * height/tis_long[valid_indices] + 1) * width * height).type(torch.cuda.LongTensor)/g' utils/inference_utils.py && \ 78 | 79 | # download e2vid pretrained model 80 | wget "http://rpg.ifi.uzh.ch/data/E2VID/models/E2VID_lightweight.pth.tar" -O pretrained/E2VID_lightweight.pth.tar 81 | 82 | WORKDIR hpe-core/evaluation/dhp19/e2vid/rpg_e2vid 83 | 84 | # setup scripts for creating grayscale frames 85 | RUN cp ../e2vid.py . && \ 86 | cp ../../utils/mat_files.py . && \ 87 | cp ../../utils/parsing.py . && \ 88 | cp ../create_grayscale_frames.sh . && \ 89 | chmod +x create_grayscale_frames.sh 90 | -------------------------------------------------------------------------------- /datasets/dhp19/e2vid/README.md: -------------------------------------------------------------------------------- 1 | # Generating Grayscale Images 2 | Some baseline human pose estimation (HPE) algorithms work with frame-based data. In order to evaluate those algorithms 3 | on the DHP19 dataset and compare them with event-based HPE algorithms, events need to be converted to a suitable format. 4 | 5 | For this purpose, we use the algorithm [1], which converts set of events into grayscale images using a recurrent 6 | convolutional neural network. For ease of use, the algorithm is run in a Docker container. 7 | 8 | ## Step-by-Step Guide 9 | 10 | - Install the latest [Nvidia driver](https://github.com/NVIDIA/nvidia-docker/wiki/Frequently-Asked-Questions#how-do-i-install-the-nvidia-driver) 11 | - Install [Docker Engine](https://docs.docker.com/engine/install/ubuntu) 12 | - Install [Nvidia Docker Toolkit](https://docs.nvidia.com/datacenter/cloud-native/container-toolkit/install-guide.html#docker) 13 | - Download the `S%d_%d_%d.mat` files containing the preprocessed DHP19 events to a desired folder (they are located in 14 | `//10.240.102.11/human_pose_estimation/Datasets/DHP19/Preprocessed_data`; see /hep-core/evaluation/dhp19/README.md). 15 | - Create an `output` folder for storing the grayscale frames generated by e2vid 16 | - Be sure to have generated ssh keys for access to this repository (see this [guide](https://docs.github.com/en/github/authenticating-to-github/connecting-to-github-with-ssh/generating-a-new-ssh-key-and-adding-it-to-the-ssh-agent) 17 | for generating the keys and this [guide](https://docs.github.com/en/github/authenticating-to-github/connecting-to-github-with-ssh/adding-a-new-ssh-key-to-your-github-account) 18 | for adding the keys to your github account) 19 | - Download this repository and build the Docker image 20 | ```shell 21 | $ cd /hpe-core/evaluation/dhp19/e2vid 22 | $ docker build -t hpe-core --build-arg ssh_prv_key="$(cat ~/.ssh/id_ed25519)" --build-arg ssh_pub_key="$(cat ~/.ssh/id_ed25519.pub)" - < Dockerfile 23 | ``` 24 | (the public and private ssh keys are supposed to be named `id_ed25519.pub` and `id_ed25519` respectively, and be stored 25 | in the `~/.ssh` directory) 26 | - run the Docker container with 27 | ```shell 28 | $ docker run -it -v /path/to/mat/files:/data --runtime=nvidia 29 | ``` 30 | - when inside the Docker container, create grayscale frames by running e2vid 31 | ```shell 32 | $ ./create_grayscale_frames.sh -i -o 33 | ``` 34 | The generated frames will be located in folder `output_folder_name`. 35 | 36 | ## References 37 | [1] - Rebecq, Henri, et al. "High speed and high dynamic range video with an event camera." IEEE transactions on pattern analysis and machine intelligence (2019). -------------------------------------------------------------------------------- /datasets/dhp19/e2vid/create_grayscale_frames.sh: -------------------------------------------------------------------------------- 1 | #!/bin/bash 2 | 3 | # read cmd line arguments 4 | while getopts ":i:o:" opt; do 5 | case $opt in 6 | i) input_events="$OPTARG" 7 | ;; 8 | o) output_folder="$OPTARG" 9 | ;; 10 | \?) echo "Invalid option -$OPTARG" >&3 11 | ;; 12 | esac 13 | done 14 | 15 | python run_e2vid.py --events_file "$input_events" --cam_id 0 --output_folder "$output_folder" --auto_hdr 16 | python run_e2vid.py --events_file "$input_events" --cam_id 1 --output_folder "$output_folder" --auto_hdr 17 | python run_e2vid.py --events_file "$input_events" --cam_id 2 --output_folder "$output_folder" --auto_hdr 18 | python run_e2vid.py --events_file "$input_events" --cam_id 3 --output_folder "$output_folder" --auto_hdr 19 | -------------------------------------------------------------------------------- /datasets/dhp19/export_gt_to_numpy.py: -------------------------------------------------------------------------------- 1 | import argparse 2 | import numpy as np 3 | import os 4 | import pathlib 5 | 6 | import datasets.dhp19.utils.constants as dhp19_const 7 | import datasets.utils.mat_files as mat_utils 8 | import datasets.dhp19.utils.parsing as dhp19_parse 9 | 10 | 11 | def extract_2d_poses(data_events, data_vicon, projection_mat, window_size): 12 | """ 13 | Extracts a 2d pose for each window of events. 14 | For each window of events generated by the specified camera, the matching Vicon poses are selected and averaged 15 | to create a single pose for each window, and finally projected to a 2d plane using a projection matrix. 16 | The matching of events and poses is based on timestamps. 17 | 18 | Parameters: 19 | data_events (dict): dictionary containing event data from all cameras, as generated by the preprocess.m matlab script 20 | data_vicon (dict): dictionary containing Vicon data, provided by DHP19 dataset 21 | projection_mat (numpy array): array with shape (4, 3) containing the projection matrix 22 | camera_id (int): camera id, must belong to range [0, 3] 23 | window_size (int): maximum number of events per window (DHP19 default is 7500) 24 | Returns: 25 | a numpy array with shape (num_of_windows, num_of_dhp19_joints, 2) containing the 2d poses 26 | """ 27 | 28 | avg_poses_3d, ts = dhp19_parse.extract_3d_poses(data_events, data_vicon, window_size) 29 | 30 | avg_poses_2d = dhp19_parse.project_poses_to_2d(avg_poses_3d, np.transpose(projection_mat)) 31 | 32 | # is this needed? 33 | # avg_poses_2d = avg_poses_2d.astype(np.uint16) 34 | 35 | return avg_poses_2d, ts 36 | 37 | 38 | if __name__ == '__main__': 39 | parser = argparse.ArgumentParser(description='Extract 2D or 3D ground-truth poses from DHP19 preprocessed data files \ 40 | and save them to .npy files') 41 | parser.add_argument('-e', '--events_file_path', help='path to preprocessed events .mat file', required=True) 42 | parser.add_argument('-v', '--vicon_file_path', help='path to Vicon .mat files', required=True) 43 | parser.add_argument('-p', '--projection_matrices_folder', help='path to the projection matrix .npy file used for extracting 2D poses (use P4.npy for cam_id 0, P1 for cam_id 1, P3 for cam_id 2 and P2 for cam_id 3)', required=True) 44 | parser.add_argument('-w', '--window_size', help=f'approximate number of events used to compute an event frame (default value for DHP19 is {dhp19_const.DHP19_CAM_FRAME_EVENTS_NUM})', default=dhp19_const.DHP19_CAM_FRAME_EVENTS_NUM) 45 | parser.add_argument('-o', '--output_folder', help='path to the folder where output .npy file will be saved; if not present, the folder will be created', required=True) 46 | parser.add_argument('-td', '--two_dimensional', dest='two_dimensional', help='flag specifying if 2D poses will be extracted; if not specified, 3D poses will be extracted', action='store_true') 47 | parser.set_defaults(two_dimensional=False) 48 | args = parser.parse_args() 49 | 50 | # read data from .mat files 51 | data_events = mat_utils.loadmat(args.events_file_path) 52 | data_vicon = mat_utils.loadmat(args.vicon_file_path) 53 | 54 | proj_matrices_folder = pathlib.Path(args.p) 55 | proj_matrices_folder = pathlib.Path(proj_matrices_folder.resolve()) 56 | 57 | if args.two_dimensional: 58 | for cn in range(dhp19_const.DHP19_CAM_NUM): 59 | proj_mat = dhp19_parse.get_projection_matrix(cn, proj_matrices_folder) 60 | poses, ts = extract_2d_poses(data_events, data_vicon, proj_mat, args.window_size) 61 | file_name = f'2d_poses_cam_{cn}_{args.window_size}.npy' 62 | ts_file_name = f'2d_poses_cam_{cn}_{args.window_size}_ts.npy' 63 | else: 64 | poses, ts = dhp19_parse.extract_3d_poses(data_events, data_vicon, args.window_size) 65 | file_name = f'3d_poses_{args.window_size}.npy' 66 | ts_file_name = f'3d_poses_{args.window_size}_ts.npy' 67 | 68 | os.makedirs(args.output_folder, exist_ok=True) 69 | 70 | np.save(os.path.join(args.output_folder, file_name), poses, allow_pickle=False) 71 | np.save(os.path.join(args.output_folder, ts_file_name), ts, allow_pickle=False) 72 | -------------------------------------------------------------------------------- /datasets/dhp19/export_to_yarp.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # -*- coding: utf-8 -*- 3 | """ 4 | Copyright (C) 2021 Event-driven Perception for Robotics 5 | Authors: 6 | Franco Di Pietro 7 | Nicolo' Carissimi 8 | 9 | LICENSE GOES HERE 10 | """ 11 | 12 | import argparse 13 | import numpy as np 14 | import pathlib 15 | 16 | from bimvee import exportIitYarp 17 | 18 | import datasets.dhp19.utils.constants as dhp19_const 19 | import datasets.dhp19.utils.parsing as dhp19_parse 20 | import datasets.utils.export as hpecore_export 21 | import datasets.utils.mat_files as mat_utils 22 | 23 | from datasets.utils.constants import HPECoreSkeleton 24 | 25 | 26 | def export_to_yarp(data_dvs: dict, data_vicon: dict, projection_mat_folder: pathlib.Path, output_folder: pathlib.Path): 27 | 28 | ############### 29 | # export events 30 | ############### 31 | 32 | # create yarp container 33 | container = {'info': {}, 'data': {}} 34 | 35 | start_time = data_dvs['out']['extra']['startTime'] 36 | for cn in range(dhp19_const.DHP19_CAM_NUM): 37 | 38 | data = data_dvs['out']['data'][f'cam{cn}'] 39 | 40 | # parse event coordinates 41 | data['dvs']['x'] = data['dvs']['x'] - 1 - dhp19_const.DHP19_SENSOR_WIDTH * cn 42 | data['dvs']['y'] = data['dvs']['y'] - 1 43 | 44 | # normalize timestamp 45 | data['dvs']['ts'] = (data['dvs']['ts'] - start_time) * 1e-6 46 | 47 | # convert polarity to an array of booleans 48 | data['dvs']['pol'] = np.array(data['dvs']['pol'], dtype=bool) 49 | 50 | # remove out of bounds events 51 | correct_events_ind = (data['dvs']['x'] >= 0) | (data['dvs']['x'] < dhp19_const.DHP19_SENSOR_WIDTH) | \ 52 | (data['dvs']['y'] >= 0) | (data['dvs']['y'] < dhp19_const.DHP19_SENSOR_HEIGHT) 53 | data['dvs']['x'] = data['dvs']['x'][correct_events_ind] 54 | data['dvs']['y'] = data['dvs']['y'][correct_events_ind] 55 | data['dvs']['ts'] = data['dvs']['ts'][correct_events_ind] 56 | data['dvs']['pol'] = data['dvs']['pol'][correct_events_ind] 57 | 58 | container['data'][f'ch{cn}'] = data 59 | 60 | exportIitYarp.exportIitYarp(container, exportFilePath=str(output_folder.resolve()), protectedWrite=True) 61 | 62 | ################## 63 | # export skeletons 64 | ################## 65 | 66 | # create array of timestamps for the poses 67 | dt = 10000 68 | poses_ts = np.arange(data_dvs['out']['extra']['ts'][0] - start_time, data_dvs['out']['extra']['ts'][-1] - start_time + dt, 69 | dt) * 1e-6 # Vicon timestams @ 100Hz 70 | diff = len(poses_ts) - data_vicon['XYZPOS']['head'].shape[0] 71 | if diff > 0: 72 | poses_ts = poses_ts[:-diff] 73 | 74 | poses_3d = extract_3d_poses(data_vicon) 75 | poses_3d = dhp19_parse.dhp19_to_hpecore_skeletons(poses_3d) 76 | 77 | for cn in range(dhp19_const.DHP19_CAM_NUM): 78 | if projection_mat_folder: 79 | projection_mat = dhp19_parse.get_projection_matrix(cn, projection_mat_folder) 80 | poses_2d, joints_mask = dhp19_parse.project_poses_to_2d(poses_3d, np.transpose(projection_mat)) 81 | 82 | torsos_size = HPECoreSkeleton.compute_torso_sizes(poses_2d) 83 | 84 | # export skeletons for current camera 85 | output_folder_cam = output_folder / f'ch{cn}skeleton' 86 | hpecore_export.export_skeletons_to_yarp(poses_2d, poses_ts, output_folder_cam, cn, torso_sizes=torsos_size) 87 | else: 88 | torsos_size = HPECoreSkeleton.compute_torso_sizes(poses_3d) 89 | 90 | # export skeletons for current camera 91 | output_folder_cam = output_folder / f'ch{cn}skeleton' 92 | hpecore_export.export_skeletons_to_yarp(poses_3d, poses_ts, output_folder_cam, cn, torso_sizes=torsos_size) 93 | 94 | 95 | def extract_3d_poses(data_vicon): 96 | """ 97 | ... 98 | 99 | Parameters: 100 | data_vicon (dict): dictionary containing Vicon data, provided by DHP19 dataset 101 | Returns: 102 | a numpy array with shape (num_of_poses, num_of_dhp19_joints, 3) containing the 3d poses 103 | """ 104 | 105 | poses_3d = np.zeros(shape=(len(data_vicon['XYZPOS']['head']), len(dhp19_parse.DHP19_BODY_PARTS), 3)) 106 | 107 | for body_part in dhp19_parse.DHP19_BODY_PARTS: 108 | coords = data_vicon['XYZPOS'][body_part] 109 | poses_3d[:, dhp19_parse.DHP19_BODY_PARTS[body_part], :] = coords 110 | 111 | return poses_3d 112 | 113 | 114 | def main(args): 115 | 116 | # read dvs file 117 | data_dvs_path = pathlib.Path(args.e) 118 | data_dvs_path = pathlib.Path(data_dvs_path.resolve()) 119 | data_dvs = mat_utils.loadmat(str(data_dvs_path)) 120 | 121 | # read vicon file 122 | data_vicon_path = pathlib.Path(args.v) 123 | data_vicon_path = pathlib.Path(data_vicon_path.resolve()) 124 | data_vicon = mat_utils.loadmat(str(data_vicon_path)) 125 | 126 | # projection matrix folder 127 | proj_matrices_folder = pathlib.Path(args.p) 128 | proj_matrices_folder = pathlib.Path(proj_matrices_folder.resolve()) 129 | 130 | # output folder 131 | export_folder = pathlib.Path(args.o) 132 | export_folder = pathlib.Path(export_folder.resolve()) 133 | 134 | export_to_yarp(data_dvs, data_vicon, proj_matrices_folder, export_folder) 135 | 136 | 137 | if __name__ == '__main__': 138 | parser = argparse.ArgumentParser() 139 | parser.add_argument('-e', help='path to .mat DVS file') 140 | parser.add_argument('-v', help='path to .mat Vicon file') 141 | parser.add_argument('-p', help='path to projection matrices folder') 142 | parser.add_argument('-o', help='path to output folder') 143 | args = parser.parse_args() 144 | 145 | main(args) 146 | -------------------------------------------------------------------------------- /datasets/dhp19/preprocess.m: -------------------------------------------------------------------------------- 1 | tic 2 | 3 | % Set recording to pre-process 4 | subj = 1; 5 | sess = 3; 6 | mov = 6; 7 | % Set the paths of code repository folder, data folder and output folder 8 | rootCodeFolder = '/home/fdipietro/projects/hpe-core'; % root directory of the git repo. 9 | rootDataFolder = '/mnt/0058555E5855540E'; % root directory of the data downloaded from resiliosync. 10 | outFolder = '/home/fdipietro/hpe-data/DVS'; 11 | 12 | addpath(fullfile(rootCodeFolder)); 13 | addpath(fullfile(rootCodeFolder, 'datasets/dhp19/')); 14 | addpath(fullfile(rootCodeFolder, 'datasets/dhp19/utils/matlab')); 15 | outFile_string = sprintf('S%d_%d_%d.mat',subj,sess,mov); 16 | 17 | if(not(exist(outFile_string, 'file') == 2)) 18 | filterAndSeparateChannels(subj, sess, mov, rootCodeFolder, rootDataFolder, outFolder); 19 | else 20 | fprintf('File already esists: %s\n', outFile_string); 21 | end 22 | 23 | toc -------------------------------------------------------------------------------- /datasets/dhp19/preprocess_all.m: -------------------------------------------------------------------------------- 1 | tic 2 | 3 | % Set the paths of code repository folder, data folder and output folder 4 | rootCodeFolder = '/home/fdipietro/projects/hpe-core'; % root directory of the git repo. 5 | rootDataFolder = '/mnt/0058555E5855540E'; % root directory of the data downloaded from resiliosync. 6 | outFolder = '/home/fdipietro/hpe-data/DVS'; 7 | 8 | addpath(fullfile(rootCodeFolder)); 9 | addpath(fullfile(rootCodeFolder, 'datasets/dhp19/')); 10 | addpath(fullfile(rootCodeFolder, 'datasets/dhp19/utils/matlab')); 11 | 12 | DVSrecFolder = fullfile(rootDataFolder,'DVS_movies/'); 13 | numSubjects = 17; 14 | numSessions = 5; 15 | 16 | for subj = 1:numSubjects 17 | subj_string = sprintf('S%d',subj); 18 | sessionsPath = fullfile(DVSrecFolder, subj_string); 19 | 20 | for sess = 1:numSessions 21 | sessString = sprintf('session%d',sess); 22 | 23 | movementsPath = fullfile(sessionsPath, sessString); 24 | 25 | if sess == 1, numMovements = 8; 26 | elseif sess == 2, numMovements = 6; 27 | elseif sess == 3, numMovements = 6; 28 | elseif sess == 4, numMovements = 6; 29 | elseif sess == 5, numMovements = 7; 30 | end 31 | 32 | for mov = 1:numMovements 33 | outFile_string = sprintf('S%d_%d_%d.mat',subj,sess,mov); 34 | 35 | if (not(exist(outFile_string, 'file') == 2)) 36 | filterAndSeparateChannels(subj, sess, mov, rootCodeFolder, rootDataFolder, outFolder); 37 | else 38 | 39 | fprintf('File already esists: %s\n', outFile_string); 40 | end 41 | 42 | end 43 | end 44 | end 45 | 46 | 47 | toc -------------------------------------------------------------------------------- /datasets/dhp19/utils/__init__.py: -------------------------------------------------------------------------------- 1 | 2 | from .constants import DHP19_SENSOR_HEIGHT, DHP19_SENSOR_WIDTH, DHP19_CAM_FRAME_EVENTS_NUM, DHP19_CAM_NUM 3 | # from .constants import DHP19_BODY_PARTS, OPENPOSE_TO_DHP19_INDICES 4 | from .parsing import openpose_to_dhp19, Dhp19Iterator 5 | -------------------------------------------------------------------------------- /datasets/dhp19/utils/constants.py: -------------------------------------------------------------------------------- 1 | 2 | import numpy as np 3 | 4 | from datasets.utils.constants import HPECoreSkeleton 5 | 6 | 7 | # DVS camera 8 | DHP19_SENSOR_HEIGHT = 260 9 | DHP19_SENSOR_WIDTH = 346 10 | DHP19_CAM_FRAME_EVENTS_NUM = 7500 # fixed number of events used in DHP19 for generating event frames 11 | DHP19_CAM_NUM = 4 # number of synchronized cameras used for recording events 12 | 13 | DHP19_NUM_OF_SESSIONS = 5 14 | DHP19_NUM_OF_SUBJECTS = 17 15 | 16 | # map from body parts to indices for dhp19 17 | DHP19_BODY_PARTS_INDICES = { 18 | 'head': 0, 19 | 'shoulderR': 1, 20 | 'shoulderL': 2, 21 | 'elbowR': 3, 22 | 'elbowL': 4, 23 | 'hipL': 5, 24 | 'hipR': 6, 25 | 'handR': 7, 26 | 'handL': 8, 27 | 'kneeR': 9, 28 | 'kneeL': 10, 29 | 'footR': 11, 30 | 'footL': 12 31 | } 32 | 33 | DHP19_TO_HPECORE_SKELETON_IND = [ 34 | DHP19_BODY_PARTS_INDICES['head'], 35 | DHP19_BODY_PARTS_INDICES['shoulderR'], 36 | DHP19_BODY_PARTS_INDICES['shoulderL'], 37 | DHP19_BODY_PARTS_INDICES['elbowR'], 38 | DHP19_BODY_PARTS_INDICES['elbowL'], 39 | DHP19_BODY_PARTS_INDICES['hipL'], 40 | DHP19_BODY_PARTS_INDICES['hipR'], 41 | DHP19_BODY_PARTS_INDICES['handR'], 42 | DHP19_BODY_PARTS_INDICES['handL'], 43 | DHP19_BODY_PARTS_INDICES['kneeR'], 44 | DHP19_BODY_PARTS_INDICES['kneeL'], 45 | DHP19_BODY_PARTS_INDICES['footR'], 46 | DHP19_BODY_PARTS_INDICES['footL'] 47 | ] 48 | -------------------------------------------------------------------------------- /datasets/dhp19/utils/matlab/BackgroundFilter.m: -------------------------------------------------------------------------------- 1 | function [x,y,t,pol,cam] =BackgroundFilter(x,y,t,pol,cam,xdim,ydim,dt) 2 | %filter out the events that are not support the neighborhood events 3 | %dt, define the time to consider an event valid or not 4 | %if nargin<7 5 | % dt= 30000; %default value for dt us 6 | %end 7 | 8 | lastTimesMap=zeros(xdim,ydim); 9 | index=zeros(length(t),1); 10 | for i=1:length(t) 11 | ts=t(i); xs=x(i); ys=y(i); 12 | deltaT=ts-lastTimesMap(xs,ys); 13 | 14 | if deltaT>dt 15 | index(i)=NaN; 16 | end 17 | 18 | if ~(xs==1 || xs==xdim || ys==1 || ys==ydim) 19 | lastTimesMap(xs-1, ys) = ts; 20 | lastTimesMap(xs+1, ys) = ts; 21 | lastTimesMap(xs, ys-1) = ts; 22 | lastTimesMap(xs, ys+1) = ts; 23 | lastTimesMap(xs-1, ys-1) = ts; 24 | lastTimesMap(xs+1, ys+1) = ts; 25 | lastTimesMap(xs-1, ys+1) = ts; 26 | lastTimesMap(xs+1, ys-1) = ts; 27 | end 28 | end 29 | 30 | x(isnan(index))=[]; 31 | y(isnan(index))=[]; 32 | t(isnan(index))=[]; 33 | pol(isnan(index))=[]; 34 | cam(isnan(index))=[]; 35 | 36 | end 37 | -------------------------------------------------------------------------------- /datasets/dhp19/utils/matlab/HotPixelFilter.m: -------------------------------------------------------------------------------- 1 | function [x,y,t,pol,cam] = HotPixelFilter(x,y,t,pol,cam,xdim,ydim,threventhotpixel) 2 | %ignore the Hot Pixel 3 | %hot pixels are define as the pixels that record a number of event 4 | %bigger than threventhotpixel 5 | if nargin<7 6 | threventhotpixel= 100; %default value for timehotpixel us 7 | end 8 | 9 | hotpixelarray=zeros(xdim,ydim); 10 | 11 | for i=1:length(t) 12 | hotpixelarray(x(i),y(i))=hotpixelarray(x(i),y(i))+1; 13 | end 14 | 15 | selindexarray = hotpixelarray>= threventhotpixel; 16 | [hpx,hpy]=find(selindexarray); 17 | 18 | for k=1:length(hpx) 19 | selindexvector= x==hpx(k) & y==hpy(k); 20 | x=x(~selindexvector); 21 | y=y(~selindexvector); 22 | t=t(~selindexvector); 23 | pol=pol(~selindexvector); 24 | cam=cam(~selindexvector); 25 | end 26 | 27 | end 28 | -------------------------------------------------------------------------------- /datasets/dhp19/utils/matlab/ImportAedatBasicSourceName.m: -------------------------------------------------------------------------------- 1 | function output = ImportAedatBasicSourceName(input) 2 | 3 | %{ 4 | input is a device name; output is the key device name associated with that 5 | name 6 | %} 7 | 8 | dbstop if error 9 | 10 | input = lower(input); 11 | 12 | devices = { ... 13 | 'File' 'file'; ... 14 | 'Network' 'network'; ... 15 | 'Dvs128' 'dvs128'; ... 16 | 'Dvs128' 'tmpdiff128'; ... 17 | 'Davis240A' 'davis240a'; ... 18 | 'Davis240A' 'sbret10'; ... 19 | 'Davis240B' 'davis240b'; ... 20 | 'Davis240B' 'sbret20'; ... 21 | 'Davis240C' 'davis240c'; ... 22 | 'Davis240C' 'sbret21'; ... 23 | 'Davis128Mono' 'davis128mono'; ... 24 | 'Davis128Rgb' 'davis128rgb'; ... 25 | 'Davis128Rgb' 'davis128'; ... 26 | 'Davis208Mono' 'davis208mono'; ... 27 | 'Davis208Rgbw' 'davis208rgbw'; ... 28 | 'Davis208Rgbw' 'pixelparade'; ... 29 | 'Davis208Rgbw' 'sensdavis192'; ... 30 | 'Davis208Rgbw' 'davis208'; ... 31 | 'Davis346AMono' 'davis346amono'; ... 32 | 'Davis346ARgb' 'davis346argb'; ... 33 | 'Davis346ARgb' 'davis346'; ... 34 | 'Davis346BMono' 'davis346bmono'; ... 35 | 'Davis346BRgb' 'davis346brgb'; ... 36 | 'Davis346BRgb' 'davis346b'; ... 37 | 'Davis346CBsi' 'davis346cbsi'; ... 38 | 'Davis346CBsi' 'davis346bsi'; ... 39 | 'Davis346Blue' 'davis346blue';... 40 | 'Davis640Mono' 'davis640mono'; ... 41 | 'Davis640Rgb' 'davis640rgb'; ... 42 | 'Davis640Rgb' 'davis640'; ... 43 | 'DavisHet640Mono' 'davishet640mono'; ... 44 | 'DavisHet640Rgbw' 'davishet640rgbw'; ... 45 | 'DavisHet640Rgbw' 'cdavis640'; ... 46 | 'DavisHet640Rgbw' 'cdavis640rgbw'; ... 47 | 'Das1' 'das1'; ... 48 | 'Das1' 'cochleaams1c'; ... 49 | 'multidavis346bcamerachip' 'multidavis346bcamerachip'}; 50 | 51 | 52 | sourceNameMatchLogical = cellfun(@strcmp, devices(:, 2), repmat({input}, length(devices), 1)); 53 | if any(sourceNameMatchLogical) 54 | output = devices{sourceNameMatchLogical, 1}; 55 | else 56 | error(['Source name not recognised: ' input]) 57 | end 58 | 59 | 60 | -------------------------------------------------------------------------------- /datasets/dhp19/utils/matlab/extract_from_aedat.m: -------------------------------------------------------------------------------- 1 | function [startIndex, stopIndex, ... 2 | pol_tmp3, X_tmp3, y_tmp3, cam_tmp3, timeStamp_tmp3] = ... 3 | extract_from_aedat(... 4 | aedat, events, ... 5 | startTime, stopTime, sx, sy, nbcam, ... 6 | thrEventHotPixel, dt, ... 7 | xmin_mask1, xmax_mask1, ymin_mask1, ymax_mask1, ... 8 | xmin_mask2, xmax_mask2, ymin_mask2, ymax_mask2) 9 | 10 | 11 | if events(end) > events(1) 12 | % startIndex: event right after startTime 13 | % stopIndex: event right before stopTime 14 | startIndexes = find(events > startTime); 15 | stopIndexes = find(events < stopTime); 16 | startIndex = startIndexes(1); 17 | stopIndex = stopIndexes(end); 18 | else 19 | %%% special case if timeStamp overflows(for S14_1_1) %%% 20 | startIndexes = find(events == startTime); 21 | stopIndexes = find(events == stopTime); 22 | startIndex = startIndexes(1); 23 | stopIndex = stopIndexes(1); 24 | end 25 | 26 | pol = aedat.data.polarity.polarity(startIndex:stopIndex); 27 | x = aedat.data.polarity.x(startIndex:stopIndex); 28 | y_raw = aedat.data.polarity.y(startIndex:stopIndex); 29 | cam = aedat.data.polarity.cam(startIndex:stopIndex); 30 | timeStamp = uint32(events(startIndex:stopIndex)); 31 | 32 | % remove events out of the boundaries. 33 | cond = (x<0) | (x>sx-1) | (y_raw<0) | (y_raw>sy-1) | (cam<0) | (cam>nbcam-1); 34 | x(cond)=[]; 35 | y_raw(cond)=[]; 36 | pol(cond)=[]; 37 | cam(cond)=[]; 38 | timeStamp(cond)=[]; 39 | 40 | X = (sx-x)+cam*sx; 41 | y = sy-y_raw; 42 | 43 | % apply filters to the events. 44 | [X_tmp, y_tmp, timeStamp_tmp, pol_tmp, cam_tmp] = ... 45 | HotPixelFilter(X, y, timeStamp, pol, cam, sx*nbcam, sy, thrEventHotPixel); 46 | 47 | [X_tmp1, y_tmp1, timeStamp_tmp1, pol_tmp1, cam_tmp1] = ... 48 | BackgroundFilter(X_tmp, y_tmp, timeStamp_tmp, pol_tmp, cam_tmp, sx*nbcam, sy, dt); 49 | 50 | [X_tmp2, y_tmp2, timeStamp_tmp2, pol_tmp2, cam_tmp2] = ... 51 | maskRegionFilter(X_tmp1, y_tmp1, timeStamp_tmp1, pol_tmp1, cam_tmp1, ... 52 | xmin_mask1, xmax_mask1, ymin_mask1, ymax_mask1); 53 | 54 | [X_tmp3, y_tmp3, timeStamp_tmp3, pol_tmp3, cam_tmp3] = ... 55 | maskRegionFilter(X_tmp2, y_tmp2, timeStamp_tmp2, pol_tmp2, cam_tmp2, ... 56 | xmin_mask2, xmax_mask2, ymin_mask2, ymax_mask2); 57 | 58 | end -------------------------------------------------------------------------------- /datasets/dhp19/utils/matlab/maskRegionFilter.m: -------------------------------------------------------------------------------- 1 | function [x2,y2,t2,pol2,cam2] =maskRegionFilter(x,y,t,pol,cam,xmin,xmax,ymin,ymax) 2 | cond=(x>xmin)&(xymin)&(yheight: 58 | height = 0.75*width 59 | elif 0.75 * width <= height: 60 | width = height / 0.75 61 | if width>1000: 62 | width=1000 63 | center[0] = 500 64 | if height>1000: 65 | height = 1000 66 | center[1] = 500 67 | 68 | 69 | crop_left = center[0] - int(width / 2) 70 | crop_right = 1000 - int(center[0] + width/2) 71 | crop_top = center[1] - int(height / 2) 72 | crop_bottom = 1000 - int(center[1] + height/2) 73 | 74 | if crop_left<0: 75 | crop_right = crop_right + crop_left 76 | crop_left = 0 77 | if crop_right < 0: 78 | crop_left = crop_right + crop_left 79 | crop_right = 0 80 | if crop_top < 0: 81 | crop_bottom = crop_bottom + crop_top 82 | crop_top = 0 83 | if crop_bottom < 0: 84 | crop_top = crop_bottom + crop_top 85 | crop_bottom = 0 86 | 87 | crop = f'{crop_left},{crop_right},{crop_top},{crop_bottom}' 88 | 89 | return crop 90 | 91 | if dev: 92 | base_output_folder = os.path.join(base_output_folder,'tester') 93 | else: 94 | base_output_folder = os.path.join(base_output_folder,'events_fullHD') 95 | 96 | files = list([]) 97 | anno_files = list([]) 98 | output_folders = list([]) 99 | for sub in subs: 100 | for cam in cams: 101 | path = os.path.join(dataset_path, sub, 'Videos') 102 | temp_name = path + '/*' + all_cameras[cam] + '.mp4' 103 | files_temp = glob.glob(temp_name) 104 | for file in files_temp: 105 | if 'ALL' not in file: 106 | files.append(file.replace(' ', '\ ')) 107 | anno_file = os.path.join(dataset_path, sub, "Poses_D2_Positions", os.path.basename(file).replace('mp4', 'cdf')) 108 | anno_files.append(anno_file) 109 | out_name = 'cam'+ str(cam)+ '_'+ sub + '_'+ os.path.basename(file).split('.')[0].replace(' ', '_') 110 | output_folders.append(out_name) 111 | 112 | # Check that everything went well 113 | assert len(files) == len(output_folders) 114 | 115 | # Call the v2e command for each file. 116 | n = 0 117 | # for i in range(20): 118 | # for i in range(1): 119 | for i in tqdm(range(len(files))): 120 | crop = get_cropping(anno_files[i]) 121 | # crop = '(0,0,0,0)' # (left, right, top, bottom) 122 | # print(output_folders[i], '>>>>' ,files[i],'>>>>',anno_files[i]) 123 | 124 | print("\nFile {} of {} being processed.\n".format(i + 1, len(files))) 125 | output_folder = os.path.join(base_output_folder, output_folders[i]) 126 | if os.path.exists(output_folder): 127 | print("Folder already exists. File {} being skipped.".format(files[i])) 128 | continue 129 | command = "python v2e.py -i " + files[i] + " --overwrite --slomo_model " + slomo_model_path + \ 130 | " --timestamp_resolution=" + ts_res + " --auto_timestamp_resolution=" + auto_ts_res + \ 131 | " --dvs_exposure duration " + dvs_exposure_duration + " --output_folder=" + output_folder + " --pos_thres=" + pos_thres + \ 132 | " --neg_thres=" + neg_thres + " --sigma_thres=" + sigma_thres + " --dvs_h5 " + dvs_h5 + " --output_width=" + str(output_width) + \ 133 | " --output_height=" + str(output_height) + " --cutoff_hz=" + cutoff_hz + " --dvs_aedat2 None --dvs640 " + \ 134 | "--crop " + crop 135 | if not dev: 136 | command = command + " --batch_size " + batch_size + " --skip_video_output --no_preview stop_time=2" 137 | # print(command) 138 | os.system(command) 139 | print("File {} processed.".format(files[i])) 140 | with open(cropping_log_file, 'a') as f: 141 | f.write("%s %s" % (output_folders[i], crop)) 142 | f.write("\n") 143 | if dev: 144 | exit() 145 | 146 | print("Process completed.") 147 | -------------------------------------------------------------------------------- /datasets/h36m/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/event-driven-robotics/hpe-core/178ac06fbf35f4b6ea9aca1a2a35bb6906b35213/datasets/h36m/__init__.py -------------------------------------------------------------------------------- /datasets/h36m/export_pim.py: -------------------------------------------------------------------------------- 1 | """ 2 | Copyright (C) 2021 Event-driven Perception for Robotics 3 | Author: 4 | Gaurvi Goyal 5 | 6 | LICENSE GOES HERE 7 | """ 8 | 9 | from tqdm import tqdm 10 | import argparse 11 | import cv2 12 | import pathlib 13 | import os 14 | 15 | from datasets.utils.parsing import import_yarp_skeleton_data, batchIterator 16 | from datasets.utils.events_representation import PIM 17 | from datasets.utils.export import str2bool, checkframecount 18 | from bimvee.importIitYarp import importIitYarp as import_dvs 19 | 20 | 21 | def export_to_pim(data_dvs_file, data_vicon_file, video_output_path, skip=None, args=None): 22 | if skip == None: 23 | skip = 1 24 | else: 25 | skip = int(skip) + 1 26 | 27 | ground_truth = import_yarp_skeleton_data(pathlib.Path(data_vicon_file)) 28 | data_dvs = import_dvs(filePathOrName=data_dvs_file[:-9]) 29 | data_dvs['data']['left']['dvs']['ts'] /= args.ts_scaler 30 | iterator = batchIterator(data_dvs['data']['left']['dvs'], ground_truth) 31 | 32 | pim = PIM(frame_height=args.frame_height, frame_width=args.frame_width, tau=args.tau) 33 | 34 | video_out = cv2.VideoWriter(video_output_path, cv2.VideoWriter_fourcc(*'avc1'), args.fps, (args.frame_width, args.frame_height)) 35 | 36 | for fi, (batch, skeleton, batch_size) in enumerate(iterator): 37 | 38 | for ei in range(batch_size): 39 | pim.update(vx=int(batch['x'][ei]), vy=int(batch['y'][ei]), p=int(batch['pol'][ei])) 40 | 41 | if fi % skip == 0: 42 | pim.perform_decay(skeleton['ts']) 43 | frame = pim.get_normed_rgb() 44 | video_out.write(frame) 45 | if fi % args.fps == 0: 46 | cv2.imshow('', frame) 47 | cv2.waitKey(1) 48 | if args.dev: 49 | print('frame: ', fi, 'timestamp: ', skeleton['ts']) 50 | 51 | video_out.release() 52 | 53 | return 54 | 55 | def main(args): 56 | 57 | input_data_dir = os.path.abspath(args.data_home) 58 | 59 | if args.dev: 60 | dir_list = ['cam2_S9_Directions'] 61 | else: 62 | dir_list = os.listdir(input_data_dir) 63 | dir_list.sort() 64 | 65 | for i in tqdm(range(len(dir_list))): 66 | sample = dir_list[i] 67 | 68 | #cam = sample[3] 69 | #data_vicon_file = os.path.join(input_data_dir, sample, f'ch{cam}GT50Hzskeleton/data.log') 70 | 71 | dvs_data = os.path.join(input_data_dir, sample, 'ch0dvs/data.log') 72 | data_vicon_file = os.path.join(input_data_dir, sample, 'ch2GT50Hzskeleton/data.log') 73 | output_video_path = os.path.join(input_data_dir, sample, 'pim.mp4') 74 | 75 | process = True 76 | print("=====", sample, "=====") 77 | #check that the file already exists, and that it is the right size 78 | if os.path.exists(output_video_path): 79 | if checkframecount(output_video_path, data_vicon_file): 80 | print('skipping: ', output_video_path, '(already exists)') 81 | process = False 82 | elif not os.path.exists(dvs_data): 83 | print('skipping: ', dvs_data, 'does not exist') 84 | process = False 85 | elif not os.path.exists(data_vicon_file): 86 | print('skipping: ', data_vicon_file, 'does not exist') 87 | process = False 88 | 89 | if process: 90 | print('processing: ', output_video_path) 91 | export_to_pim(dvs_data, data_vicon_file, output_video_path, skip=args.skip_image, args=args) 92 | print('') 93 | 94 | 95 | if __name__ == '__main__': 96 | 97 | parser = argparse.ArgumentParser() 98 | parser.add_argument('-tau', help='', default=1.0, type=float) 99 | parser.add_argument('-frame_width', help='', default=640, type=int) 100 | parser.add_argument('-frame_height', help='', default=480, type=int) 101 | parser.add_argument('-fps', help='', default=50, type=int) 102 | parser.add_argument('-skip_image', help='', default=None) 103 | parser.add_argument('-data_home', help='Path to dataset folder', default='/home/ggoyal/data/h36m/', type=str) 104 | parser.add_argument("-dev", type=str2bool, nargs='?', const=True, default=False, help="Run in dev mode.") 105 | parser.add_argument("-ts_scaler", help='', default=1.0, type=float) 106 | 107 | args = parser.parse_args() 108 | try: 109 | args = parser.parse_args() 110 | except argparse.ArgumentError: 111 | print('Catching an argumentError') 112 | main(args) 113 | 114 | -------------------------------------------------------------------------------- /datasets/h36m/h36_h5_to_yarp.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # -*- coding: utf-8 -*- 3 | """ 4 | Copyright (C) 2021 Event-driven Perception for Robotics 5 | Author: Franco Di Pietro 6 | 7 | LICENSE GOES HERE 8 | """ 9 | 10 | # %% Preliminaries 11 | import numpy as np 12 | import os 13 | import sys 14 | import h5py 15 | from tqdm import tqdm 16 | 17 | # Load env variables set on .bashrc 18 | bimvee_path = os.environ.get('BIMVEE_PATH') 19 | # Add local paths 20 | sys.path.insert(0, bimvee_path) 21 | 22 | from bimvee import exportIitYarp 23 | 24 | 25 | # Directory with 26 | datadir = '/data/h36m/events_v2e/' 27 | outputdir = '/data/h36m/yarp/' 28 | # datadir = '/home/fdipietro/hpe-data/h36_server/' 29 | dir_list = os.listdir(datadir) 30 | if 'yarp' in dir_list: dir_list.remove('yarp') 31 | # dir_list = ['S1_Discussion_1'] 32 | 33 | # %% Import/Export 34 | for i in tqdm(range(len(dir_list))): 35 | filename = datadir + dir_list[i] + '/Directions.h5' 36 | print('\nProcessing '+filename) 37 | hf = h5py.File(filename, 'r') 38 | data = np.array(hf["events"][:]) #dataset_name is same as hdf5 object name 39 | container = {} 40 | fileExport = outputdir + dir_list[i] 41 | # if os.path.isdir(os.path.join(fileExport,'ch0dvs')): 42 | # continue 43 | container['info'] = {} 44 | container['info']['filePathOrName'] = fileExport 45 | container['data'] = {} 46 | container['data']['ch0'] = {} 47 | container['data']['ch0']['dvs'] = {} 48 | try: 49 | container['data']['ch0']['dvs']['ts'] = (data[:,0]-data[0,0])*1e-6 50 | except IndexError: 51 | continue 52 | container['data']['ch0']['dvs']['x'] = data[:,1] 53 | container['data']['ch0']['dvs']['y'] = data[:,2] 54 | container['data']['ch0']['dvs']['pol'] = data[:,3].astype(bool) 55 | exportIitYarp.exportIitYarp(container, exportFilePath=fileExport, protectedWrite=False) 56 | -------------------------------------------------------------------------------- /datasets/h36m/utils/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/event-driven-robotics/hpe-core/178ac06fbf35f4b6ea9aca1a2a35bb6906b35213/datasets/h36m/utils/__init__.py -------------------------------------------------------------------------------- /datasets/h36m/utils/parsing.py: -------------------------------------------------------------------------------- 1 | 2 | import numpy as np 3 | import os 4 | 5 | from time import time 6 | 7 | 8 | # DVS camera 9 | H36M_VIDEO_HEIGHT = 1000 10 | H36M_VIDEO_WIDTH = 1000 11 | H36M_DVS_WIDTH = '346' 12 | H36M_DVS_HEIGHT = '260' 13 | # DHP19_CAM_FRAME_EVENTS_NUM = 7500 # fixed number of events used in DHP19 for generating event frames 14 | subs = ['S1', 'S5', 'S6', 'S7', 'S8', 'S9', 'S11'] 15 | all_cameras = {1: '54138969', 2: '55011271', 3: '58860488', 4: '60457274'} 16 | 17 | # map from indices to body parts for h36m 18 | H36M_BODY_PARTS_rev = {0: 'PelvisC', 1: 'PelvisR', 2: 'KneeR', 3: 'AnkleR', 4: 'ToeR', 5: 'ToeROther', 6: 'PelvisL', 19 | 7: 'KneeL', 8: 'AnkleL', 9: 'ToeR', 10: 'ToeROther', 11: 'Spine', 12: 'SpineM', 13: 'Neck', 20 | 14: 'Head', 15: 'HeadOther', 16: 'NextAgain', 17: 'ShoulderL', 18: 'ElbowL', 19: 'WristL', 21 | 20: 'WristLAgain', 21: 'ThumbL', 22: 'BOHR', 23: 'BOHRAgain', 24: 'NeckAgainAgain', 22 | 25: 'ShoulderR', 26: 'ElbowR', 27: 'WristR', 28: 'WristAgain', 29: 'ThumbR', 30: 'BOHL', 23 | 31: 'BOHLAgain'} 24 | 25 | H36M_BODY_PARTS = {v: k for k, v in H36M_BODY_PARTS_rev.items()} 26 | 27 | # Following markers coincide with each other 28 | # 0 = 11 29 | # 13 = 16 = 24 30 | # 19 = 20 31 | # 22 = 23 32 | # 26 = 27 33 | # 30 = 31 34 | 35 | # { 36 | # 'head': 0, 37 | # 'shoulderR': 1, 38 | # 'shoulderL': 2, 39 | # 'elbowR': 3, 40 | # 'elbowL': 4, 41 | # 'hipL': 5, 42 | # 'hipR': 6, 43 | # 'handR': 7, 44 | # 'handL': 8, 45 | # 'kneeR': 9, 46 | # 'kneeL': 10, 47 | # 'footR': 11, 48 | # 'footL': 12 49 | # } 50 | 51 | H36M_TO_DHP19_INDICES = np.array([ 52 | # TODO: compute head 53 | [14, 0], # head 54 | [25, 1], # shoulderR 55 | [17, 2], # shoulderL 56 | [26, 3], # elbowR 57 | [18, 4], # elbowL 58 | [6, 5], # hipL 59 | [1, 6], # hipR 60 | [27, 7], # handR 61 | [19, 8], # handL 62 | [2, 9], # kneeR 63 | [7, 10], # kneeL 64 | [3, 11], # footR 65 | [8, 12] # footL 66 | ]) 67 | 68 | DHP19_TO_MOVENET_INDICES = np.array([ 69 | # TODO: fix to be similar to the previous one. 70 | [0, 0], # head 71 | [1, 2], # lshoulder 72 | [2, 1], # rshoulder 73 | [3, 4], # lelbow 74 | [4, 3], # relbow 75 | [5, 8], # lwrist 76 | [6, 7], # rwrist 77 | [7, 5], # lhip 78 | [8, 6], # rhip 79 | [9, 10], # lknee 80 | [10, 9], # rknee 81 | [11, 12], # lankle 82 | [12, 11] # rankle 83 | ]) 84 | 85 | MOVENET_TO_DHP19_INDICES = DHP19_TO_MOVENET_INDICES[np.argsort(DHP19_TO_MOVENET_INDICES[:,1]),:] 86 | 87 | # H36M_TO_HPECORE_SKELETON_MAP = OrderedDict() 88 | # H36M_TO_HPECORE_SKELETON_MAP['head'] = 14 89 | # H36M_TO_HPECORE_SKELETON_MAP['shoulderL'] = 17 90 | # H36M_TO_HPECORE_SKELETON_MAP['shoulderR'] = 25 91 | # H36M_TO_HPECORE_SKELETON_MAP['elbowL'] = 18 92 | # H36M_TO_HPECORE_SKELETON_MAP['elbowR'] = 26 93 | # H36M_TO_HPECORE_SKELETON_MAP['handL'] = 19 94 | # H36M_TO_HPECORE_SKELETON_MAP['handR'] = 27 95 | # H36M_TO_HPECORE_SKELETON_MAP['hipL'] = 6 96 | # H36M_TO_HPECORE_SKELETON_MAP['hipR'] = 1 97 | # H36M_TO_HPECORE_SKELETON_MAP['kneeL'] = 7 98 | # H36M_TO_HPECORE_SKELETON_MAP['kneeR'] = 2 99 | # H36M_TO_HPECORE_SKELETON_MAP['footL'] = 8 100 | # H36M_TO_HPECORE_SKELETON_MAP['footR'] = 3 101 | 102 | H36M_TO_HPECORE_SKELETON_MAP = [ 103 | 14, # head 104 | 25, # shoulderR 105 | 17, # shoulderL 106 | 26, # elbowR 107 | 18, # elbowL 108 | 6, # hipL 109 | 1, # hipR 110 | 27, # handR 111 | 19, # handL 112 | 2, # kneeR 113 | 7, # kneeL 114 | 3, # footR 115 | 8 # footL 116 | ] 117 | 118 | 119 | def h36m_to_hpecore_skeleton(pose): 120 | return pose[H36M_TO_HPECORE_SKELETON_MAP, :] 121 | 122 | 123 | def h36m_to_dhp19(pose): 124 | return pose[H36M_TO_DHP19_INDICES[:, 0], :] 125 | 126 | 127 | def dhp19_to_movenet(pose): 128 | return pose[DHP19_TO_MOVENET_INDICES[:, 1], :] 129 | 130 | def hpecore_to_movenet(pose): 131 | return dhp19_to_movenet(pose) 132 | 133 | def movenet_to_dhp19(pose): 134 | return pose[MOVENET_TO_DHP19_INDICES[:, 0],:] 135 | 136 | def movenet_to_hpecore(pose): 137 | return movenet_to_dhp19(pose) 138 | 139 | def dhp19_to_h36m(pose): 140 | # TODO 141 | pass 142 | 143 | def get_h36m_body_parts(pose): 144 | inv_map = {v: k for k, v in pose.items()} 145 | return inv_map 146 | 147 | 148 | # def openpose_to_dhp19(pose_op): 149 | # # TODO: compute dhp19's head joints from openpose 150 | # return pose_op[OPENPOSE_TO_DHP19_INDICES[:, 0], :] 151 | 152 | def writer(directory, datalines, infolines): 153 | if not os.path.exists(directory): 154 | os.makedirs(directory) 155 | 156 | # datafile.log 157 | dataFile = directory + '/data.log' 158 | with open(dataFile, 'w') as f: 159 | for line in datalines: 160 | f.write("%s\n" % line) 161 | # info.log 162 | 163 | infoFile = directory + '/info.log' 164 | with open(infoFile, 'w') as f: 165 | for line in infolines: 166 | f.write("%s\n" % line) 167 | -------------------------------------------------------------------------------- /datasets/mpii/README.md: -------------------------------------------------------------------------------- 1 | # MPII Human Pose Dataset 2 | [MPII Human Pose dataset](http://human-pose.mpi-inf.mpg.de) is a state of the art benchmark for evaluation of articulated human pose estimation. The dataset 3 | includes around 25K images containing over 40K people with annotated body joints. The images were systematically 4 | collected using an established taxonomy of every day human activities. Overall the dataset covers 410 human activities 5 | and each image is provided with an activity label. Each image was extracted from a YouTube video and provided with 6 | preceding and following un-annotated frames. 7 | 8 | ## Export to EROS-Like Format 9 | Although it provides RGB images, MPII can be converted to a representation similar to the one generated by the EROS 10 | algorithm. The resulting images can then be used for training an EROS based human pose estimation algorithm. 11 | 12 | 1. Download the MPII images and annotations from this [url](http://human-pose.mpi-inf.mpg.de/#download) 13 | 2. Unzip the data 14 | 3. Run the script 15 | ```shell 16 | $ python export_to_eros.py -a -i -o 17 | ``` 18 | The script will generate EROS-like images and saves them in the specified output folder. 19 | 20 | The EROS-like representation is based on a combination of Canny edge detection, Gaussian blur and salt and pepper noise. 21 | Below is a list of other parameters that can be modified 22 | 23 | ``` 24 | # canny edge detector params 25 | -gk: gaussian blur kernel size, default=5 26 | -gs: gaussian blur sigma, default=0 27 | -cl: canny edge low threshold, default=0 28 | -ch: canny edge high threshold, default=1000 29 | -ca: canny edge aperture, default=5 30 | -cg: canny edge l2 gradient flag, default False 31 | 32 | # salt and pepper params 33 | -sl: salt and pepper low threshold, default=5 34 | -sh: salt and pepper high threshold, default=250 35 | ``` 36 | 37 | ## Export to Movenet's Format 38 | Once the EROS-like frames have been created, MPII annotations can be converted to a format compatible with the training 39 | code of Movenet's algorithm 40 | 41 | 1. Run the script 42 | ```shell 43 | $ python export_to_movenet.py -a -i -o -crop 44 | ``` 45 | 46 | The script will generate a `poses.json` file in the output folder, containing the annotated poses in the correct format 47 | (see example below) 48 | 49 | ``` 50 | [ 51 | {"img_name": "0.jpg", 52 | "keypoints": [x0,y0,z0,x1,y1,z1,...], # flattened array of x, y coordinates and value z: 0 for no label, 1 for labeled but invisible, 2 for labeled and visible 53 | "center": [x,y], # pose center 54 | "bbox":[x0,y0,x1,y1], # pose bounding box 55 | "other_centers": [[x0,y0],[x1,y1],...], # list of other poses' centers 56 | "other_keypoints": [[[x0,y0],[x1,y1],...],[[x0,y0],[x1,y1],...],...], # list of other poses' keypoints; other_keypoints[i] = list of keypoints for joint 'i' 57 | }, 58 | ... 59 | ] 60 | ``` 61 | 62 | Additionally, images will be cropped using the bounding boxes around single poses and saved to the output folder as 63 | `_.`; keypoints coordinates will also be transformed to the bounding box reference system. 64 | This post-processing step can be eliminated by removing parameter `-crop`. 65 | 66 | ## Export to YARP Format 67 | Export of MPII to YARP format has not been implemented yet. 68 | -------------------------------------------------------------------------------- /datasets/mpii/export_to_eros.py: -------------------------------------------------------------------------------- 1 | 2 | import argparse 3 | import cv2 4 | import pathlib 5 | 6 | from tqdm import tqdm 7 | 8 | import datasets.utils.mat_files as mat_utils 9 | import datasets.mpii.utils.parsing as mpii_parse 10 | 11 | from datasets.utils.events_representation import EROSSynthetic 12 | 13 | 14 | def export_to_eros(data_ann: dict, image_folder: pathlib.Path, output_folder: pathlib.Path, gaussian_blur_k_size: int, 15 | gaussian_blur_sigma: int, canny_low_th: int, canny_high_th: int, canny_aperture: int, 16 | canny_l2_grad: bool, salt_pepper_low_th: int, salt_pepper_high_th: int) -> None: 17 | 18 | """Export MPII images to EROS-like frames. 19 | 20 | The function converts MPII frames to a EROS-like representation by applying Gaussian blur, a Canny edge detector 21 | and salt and pepper noise to the original RGB frames (see class EROSSynthetic in datasets/utils/events_representation.py 22 | for implementation details). 23 | 24 | Parameters 25 | ---------- 26 | data_ann: dict 27 | Dictionary containing MPII annotation data 28 | image_folder: pathlib.Path 29 | Path to the images folder 30 | output_folder: pathlib.Path 31 | Path to the output folder where the EROS-like frames and the json file will be saved 32 | gaussian_blur_k_size: int 33 | kernel size used for pre-Canny edge detection Gaussian blurring 34 | gaussian_blur_sigma: int 35 | sigma used for pre-Canny edge detection Gaussian blurring 36 | canny_low_th: int 37 | min value for Canny's hysteresis thresholding 38 | canny_high_th: int 39 | max value for Canny's hysteresis thresholding 40 | canny_aperture: int 41 | aperture size for Canny's Sobel operator 42 | canny_l2_grad: bool 43 | flag indicating if L2 norm has to be used for Canny's gradient computation 44 | salt_pepper_low_th: int 45 | salt and pepper min value for post-Canny edge noise addition 46 | salt_pepper_high_th: int 47 | salt and pepper max value for post-Canny edge noise addition 48 | """ 49 | 50 | iterator = mpii_parse.MPIIIterator(data_ann, image_folder) 51 | 52 | eros = EROSSynthetic(gaussian_blur_k_size, gaussian_blur_sigma, canny_low_th, canny_high_th, 53 | canny_aperture, canny_l2_grad, salt_pepper_low_th, salt_pepper_high_th) 54 | 55 | for fi, (img, _, img_name) in enumerate(tqdm(iterator)): 56 | 57 | if img is None: 58 | print(f'image {img_name} does not exist') 59 | continue 60 | 61 | frame = eros.get_frame(img) 62 | file_path = output_folder / img_name 63 | if not cv2.imwrite(str(file_path), frame): 64 | print(f'could not save image to {str(file_path)}') 65 | continue 66 | 67 | 68 | def main(args): 69 | 70 | data_ann_path = pathlib.Path(args.a) 71 | data_ann_path = pathlib.Path(data_ann_path.resolve()) 72 | data_ann = mat_utils.loadmat(str(data_ann_path)) 73 | 74 | img_folder_path = pathlib.Path(args.i) 75 | img_folder_path = pathlib.Path(img_folder_path.resolve()) 76 | 77 | output_folder_path = pathlib.Path(args.o) 78 | output_folder_path = pathlib.Path(output_folder_path.resolve()) 79 | output_folder_path.mkdir(parents=True, exist_ok=True) 80 | 81 | export_to_eros(data_ann, img_folder_path, output_folder_path, 82 | gaussian_blur_k_size=args.gk, gaussian_blur_sigma=args.gs, 83 | canny_low_th=args.cl, canny_high_th=args.ch, canny_aperture=args.ca, canny_l2_grad=args.cg, 84 | salt_pepper_low_th=args.sl, salt_pepper_high_th=args.sh) 85 | 86 | 87 | if __name__ == '__main__': 88 | parser = argparse.ArgumentParser() 89 | 90 | ################ 91 | # general params 92 | ################ 93 | 94 | parser.add_argument('-a', help='path to annotations file') 95 | parser.add_argument('-i', help='path to images folder') 96 | parser.add_argument('-o', help='path to output folder') 97 | 98 | ################## 99 | # EROS-like params 100 | ################## 101 | 102 | # canny edge detector params 103 | parser.add_argument('-gk', help='gaussian blur kernel size', type=int, default=5) 104 | parser.add_argument('-gs', help='gaussian blur sigma', type=int, default=0) 105 | parser.add_argument('-cl', help='canny edge low threshold', type=int, default=0) 106 | parser.add_argument('-ch', help='canny edge high threshold', type=int, default=1000) 107 | parser.add_argument('-ca', help='canny edge aperture', type=int, default=5) 108 | parser.add_argument('-cg', help='canny edge l2 gradient flag', dest='cg', action='store_true') 109 | parser.set_defaults(cg=False) 110 | 111 | # salt and pepper params 112 | parser.add_argument('-sl', help='salt and pepper low threshold', type=int, default=5) 113 | parser.add_argument('-sh', help='salt and pepper high threshold', type=int, default=250) 114 | 115 | args = parser.parse_args() 116 | 117 | main(args) 118 | -------------------------------------------------------------------------------- /datasets/mpii/export_to_yarp.py: -------------------------------------------------------------------------------- 1 | 2 | import argparse 3 | import pathlib 4 | 5 | 6 | def export_to_yarp(input_folder, annotations_path, output_folder): 7 | print('export_to_yarp is not implemented yet for MPII dataset') 8 | pass 9 | 10 | 11 | def main(args): 12 | 13 | # annotations file path 14 | annotations_path = pathlib.Path(args.a) 15 | annotations_path = pathlib.Path(annotations_path.resolve()) 16 | 17 | # input image folder 18 | input_folder = pathlib.Path(args.i) 19 | input_folder = pathlib.Path(input_folder.resolve()) 20 | 21 | # output folder 22 | output_folder = pathlib.Path(args.o) 23 | output_folder = pathlib.Path(output_folder.resolve()) 24 | 25 | export_to_yarp(input_folder, annotations_path, output_folder) 26 | 27 | 28 | if __name__ == '__main__': 29 | parser = argparse.ArgumentParser() 30 | parser.add_argument('-i', help='path to input images folder') 31 | parser.add_argument('-a', help='path to input annotations folder') 32 | parser.add_argument('-o', help='path to output folder') 33 | args = parser.parse_args() 34 | 35 | main(args) 36 | -------------------------------------------------------------------------------- /datasets/mpii/utils/parsing.py: -------------------------------------------------------------------------------- 1 | import cv2 2 | 3 | # map from body parts to indices for mpii 4 | MPII_BODY_PARTS = { 5 | 'headtop': 9, 6 | 'rshoulder': 12, 7 | 'lshoulder': 13, 8 | 'relbow': 11, 9 | 'lelbow': 14, 10 | 'lhip': 3, 11 | 'rhip': 2, 12 | 'rwrist': 10, 13 | 'lwrist': 15, 14 | 'rknee': 1, 15 | 'lknee': 4, 16 | 'rankle': 0, 17 | 'lankle': 5, 18 | 'pelvis': 6, 19 | 'thorax': 7, 20 | 'upperneck': 8 21 | } 22 | 23 | 24 | class MPIIIterator: 25 | 26 | def __init__(self, data_annotations, images_folder): 27 | 28 | self.data = data_annotations['RELEASE'] 29 | 30 | # get training indices, i.e. indices of images with pose annotations 31 | # images without pose annotations are used for evaluation on mpii's servers 32 | self.training_indices = [ind for ind, is_train in enumerate(self.data['img_train']) if is_train == 1] 33 | 34 | self.images_folder = images_folder 35 | 36 | self.curr_ind = 0 37 | 38 | def __iter__(self): 39 | return self 40 | 41 | def __len__(self): 42 | return len(self.training_indices) 43 | 44 | def __next__(self): 45 | 46 | if self.curr_ind == -1: 47 | raise StopIteration 48 | 49 | # get annotation 50 | ind = self.training_indices[self.curr_ind] 51 | self.__update_current_index() 52 | 53 | annotation = self.data['annolist'][ind] 54 | 55 | img = self.__get_image(annotation) 56 | 57 | # get pose annotations, i.e. list of dictionaries containing bounding box, keypoints, scale and object position 58 | pose_ann = self.__get_pose_annotation(annotation) 59 | 60 | return img, pose_ann, annotation['image']['name'] 61 | 62 | def __get_image(self, annotation): 63 | image_path = self.images_folder / annotation['image']['name'] 64 | return cv2.imread(str(image_path.resolve())) 65 | 66 | def __get_pose_annotation(self, annotation): 67 | if isinstance(annotation['annorect'], dict): 68 | return [annotation['annorect']] 69 | else: 70 | return annotation['annorect'] 71 | 72 | def __update_current_index(self): 73 | 74 | if self.curr_ind >= self.__len__() - 1: 75 | self.curr_ind = -1 76 | else: 77 | self.curr_ind += 1 78 | -------------------------------------------------------------------------------- /datasets/utils/constants.py: -------------------------------------------------------------------------------- 1 | 2 | import numpy 3 | 4 | 5 | class Movenet: 6 | 7 | KEYPOINTS_COCO = ['nose', 'left_eye', 'right_eye', 'left_ear', 'right_ear', 8 | 'left_shoulder', 'right_shoulder', 'left_elbow', 'right_elbow', 'left_wrist', 9 | 'right_wrist', 'left_hip', 'right_hip', 'left_knee', 'right_knee', 'left_ankle', 10 | 'right_ankle'] 11 | 12 | KEYPOINTS_NUM = 13 13 | 14 | 15 | class HPECoreSkeleton: 16 | 17 | # the order of the joints is the same as the DHP19 one 18 | # differences: 19 | # - more descriptive labels 20 | # - we use the more common 'wrist' and 'ankle' labels instead of DHP19's 'hand' and 'foot' ones 21 | # - all joints are listed as first 'right' and then 'left' except for the 'hip' ones: it is not an error, 22 | # it is DHP19's order 23 | KEYPOINTS_MAP = {'head': 0, 'shoulder_right': 1, 'shoulder_left': 2, 'elbow_right': 3, 'elbow_left': 4, 24 | 'hip_left': 5, 'hip_right': 6, 'wrist_right': 7, 'wrist_left': 8, 'knee_right': 9, 'knee_left': 10, 25 | 'ankle_right': 11, 'ankle_left': 12} 26 | 27 | @staticmethod 28 | def compute_torso_sizes(skeletons: numpy.array) -> float: 29 | 30 | if len(skeletons.shape) == 2: 31 | l_hip = skeletons[HPECoreSkeleton.KEYPOINTS_MAP['hip_left'], :] 32 | r_shoulder = skeletons[HPECoreSkeleton.KEYPOINTS_MAP['shoulder_right'], :] 33 | torso_sizes = numpy.linalg.norm(l_hip - r_shoulder) 34 | 35 | elif len(skeletons.shape) == 3: 36 | l_hips = skeletons[:, HPECoreSkeleton.KEYPOINTS_MAP['hip_left'], :] 37 | r_shoulders = skeletons[:, HPECoreSkeleton.KEYPOINTS_MAP['shoulder_right'], :] 38 | torso_sizes = numpy.linalg.norm(l_hips - r_shoulders, axis=1) 39 | 40 | return torso_sizes 41 | -------------------------------------------------------------------------------- /datasets/utils/genYarpImages.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # -*- coding: utf-8 -*- 3 | """ 4 | Created on Thu Sep 9 14:59:09 2021 5 | 6 | @author: fdipietro and ggoyal 7 | """ 8 | 9 | # %% Preliminaries 10 | import numpy as np 11 | import os 12 | from os.path import join 13 | import sys 14 | from pathlib import Path 15 | 16 | import datasets.utils.events_representation 17 | from datasets.utils import mat_files 18 | from datasets.h36m.utils import parsing 19 | 20 | # Load env variables set on .bashrc 21 | bimvee_path = os.environ.get('BIMVEE_PATH') 22 | mustard_path = os.environ.get('MUSTARD_PATH') 23 | 24 | # Add local paths 25 | sys.path.insert(0, bimvee_path) 26 | sys.path.insert(0, mustard_path) 27 | 28 | # Directory with DVS (after Matlab processing) and Vicon Data 29 | datadir = '/home/ggoyal/data/h36m/' 30 | 31 | input_type = 'videos' # 'images' or 'videos' 32 | 33 | if input_type == 'images': 34 | # Selected recording 35 | subj, sess, mov = 13, 1, 8 36 | recording = 'S{}_{}_{}'.format(subj, sess, mov) 37 | cam = str(3) 38 | 39 | # read data 40 | poses_gt = np.load('/home/fdipietro/hpe-data/2d_Nicolo/' + recording +'/2d_poses_cam_3_7500_events.npy') 41 | poses_pred_files = sorted(Path('/home/fdipietro/hpe-data/open-pose/' + recording).glob('*.json')) 42 | image_files = sorted(Path('/home/fdipietro/hpe-data/grayscale/' + recording +'/' + cam +'/reconstruction').glob('*.png')) 43 | 44 | data_events = mat_files.loadmat('/home/fdipietro/hpe-data/DVS/' + recording + '.mat') 45 | startTime = data_events['out']['extra']['startTime'] 46 | t_op = np.loadtxt('/home/fdipietro/hpe-data/grayscale/' + recording +'/' + cam +'/reconstruction/timestamps.txt', dtype = np.float64) 47 | t_op = (t_op-startTime)*1e-6 48 | 49 | imgs_dir = join(datadir, 'grayscale/'+recording+'/') 50 | # dataDvs = loadmat(join(DVS_dir,datafile)) 51 | 52 | from os import walk 53 | 54 | 55 | for ch in range(4): 56 | # read all image file names 57 | path = join(imgs_dir, str(ch)+'/reconstruction/') 58 | filenames = next(walk(path), (None, None, []))[2] 59 | filenames.remove('timestamps.txt') 60 | filenames = sorted(filenames) 61 | # read timestamps 62 | t_op = np.loadtxt('/home/fdipietro/hpe-data/grayscale/' + recording +'/' + str(ch) +'/reconstruction/timestamps.txt', dtype = np.float64) 63 | t_op = (t_op-startTime)*1e-6 64 | # create dirs 65 | directory = '/home/fdipietro/hpe-data/yarp_imgs/'+ str(recording)+ '/ch' + str(ch) + 'frames' 66 | if not os.path.exists(directory): 67 | os.makedirs(directory) 68 | 69 | # datafile.log 70 | lines = [None] * len(t_op) 71 | for i in range(len(t_op)): 72 | lines[i] = str(i+1) + ' ' + str(t_op[i]) + ' ' + str(filenames[i]) + ' [mono]' 73 | 74 | # info.log 75 | info = 'Type: Image;\n[0.0] /file/ch'+ str(ch) +'frames:o [connected]' 76 | 77 | datasets.utils.export.export_list_to_yarp(lines, info, Path(directory)) 78 | 79 | if input_type == 'videos': 80 | import cv2 81 | 82 | vid_file = '/home/ggoyal/data/h36m/extracted/S1/Videos/Purchases.55011271.mp4' 83 | output_width = 346 84 | output_height = 260 85 | dim = (output_width, output_height) 86 | directory = os.path.join(datadir,'yarp/S1_Purchases/ch0frames/') 87 | if not os.path.exists(directory): 88 | os.makedirs(directory) 89 | counter = 0 90 | lines = [] 91 | 92 | vid = cv2.VideoCapture(vid_file) 93 | 94 | assert vid.isOpened() 95 | while vid.isOpened(): 96 | frame_exists, frame = vid.read() 97 | if frame_exists: 98 | timestamp = vid.get(cv2.CAP_PROP_POS_MSEC)/1000 # convert timestamp to seconds 99 | else: 100 | break 101 | if counter>10 and timestamp == 0.0: 102 | continue 103 | frame_resized = cv2.resize(src=frame, dsize=dim, interpolation=cv2.INTER_AREA) 104 | filename = 'frame_' + str(counter).zfill(10) + '.png' 105 | filename_full = os.path.join(directory,filename) 106 | cv2.imwrite(filename_full,frame_resized) 107 | 108 | # data.log 109 | lines.append(str(counter) + ' ' + str(timestamp) + ' ' + str(filename) + ' [rgb]') 110 | 111 | counter += 1 112 | 113 | vid.release() 114 | 115 | # info.log 116 | info = 'Type: Image;\n[0.0] /file/ch0frames:o [connected]' 117 | 118 | datasets.utils.export.export_list_to_yarp(lines, info, Path(directory)) 119 | print(lines) 120 | print(info) 121 | -------------------------------------------------------------------------------- /datasets/utils/mat_files.py: -------------------------------------------------------------------------------- 1 | 2 | import numpy as np 3 | import scipy.io as spio 4 | 5 | 6 | def loadmat(filename): 7 | ''' 8 | this function should be called instead of direct spio.loadmat 9 | as it cures the problem of not properly recovering python dictionaries 10 | from mat files. It calls the function check keys to cure all entries 11 | which are still mat-objects 12 | ''' 13 | data = spio.loadmat(filename, struct_as_record=False, squeeze_me=True) 14 | return _parse(data) 15 | 16 | 17 | # def loadmat_old(filename): 18 | # ''' 19 | # this function should be called instead of direct spio.loadmat 20 | # as it cures the problem of not properly recovering python dictionaries 21 | # from mat files. It calls the function check keys to cure all entries 22 | # which are still mat-objects 23 | # ''' 24 | # data = spio.loadmat(filename, struct_as_record=False, squeeze_me=True) 25 | # return _check_keys(data) 26 | 27 | 28 | ########### 29 | # PRIVATE # 30 | ########### 31 | 32 | # def _check_keys(dict): 33 | # ''' 34 | # checks if entries in dictionary are mat-objects. If yes 35 | # todict is called to change them to nested dictionaries 36 | # ''' 37 | # for key in dict: 38 | # if isinstance(dict[key], spio.matlab.mio5_params.mat_struct): 39 | # dict[key] = _todict(dict[key]) 40 | # return dict 41 | # 42 | # 43 | # def _todict(matobj): 44 | # ''' 45 | # A recursive function which constructs from matobjects nested dictionaries 46 | # ''' 47 | # dict = {} 48 | # for strg in matobj._fieldnames: 49 | # elem = matobj.__dict__[strg] 50 | # if isinstance(elem, spio.matlab.mio5_params.mat_struct): 51 | # dict[strg] = _todict(elem) 52 | # else: 53 | # dict[strg] = elem 54 | # return dict 55 | 56 | 57 | def _parse(elem): 58 | 59 | if isinstance(elem, spio.matlab.mio5_params.mat_struct): 60 | data = {} 61 | for name in elem._fieldnames: 62 | sub_elem = elem.__dict__[name] 63 | data[name] = _parse(sub_elem) 64 | return data 65 | elif isinstance(elem, np.ndarray): 66 | data = [] 67 | for sub_elem in elem: 68 | data.append(_parse(sub_elem)) 69 | return np.array(data) 70 | elif isinstance(elem, list): 71 | for ei, sub_elem in enumerate(elem): 72 | elem[ei] = _parse(sub_elem) 73 | return elem 74 | elif isinstance(elem, dict): 75 | for key in elem.keys(): 76 | elem[key] = _parse(elem[key]) 77 | return elem 78 | 79 | return elem 80 | 81 | -------------------------------------------------------------------------------- /evaluation/.gitignore: -------------------------------------------------------------------------------- 1 | .vscode 2 | -------------------------------------------------------------------------------- /evaluation/README.md: -------------------------------------------------------------------------------- 1 | # Evaluating HPE and Joints Tracking Algorithms 2 | 3 | This folder contains scripts for evaluating HPE and joints tracking algorithms. In particular, each algorithm to be compared should process each dataset to produce a `.csv` file and stored in a particular folder structure as outlined below. The scripts can be run to evaluate joint position comparisons, or joint velocity comparisons. 4 | 5 | ## Usage 6 | 7 | The pose evaluation script can be run with 8 | ```shell 9 | $ python3 evaluate_hpe.py 10 | $ -d path/to/datasets/folder 11 | $ -p path/to/predictions/folder 12 | $ -o path/to/output/folder 13 | $ -pck 14 | $ -rmse 15 | $ -latex 16 | ``` 17 | 18 | - `-d path/to/datasets/folder` must point to a folder containing all datasets in yarp format the algorithms must be evaluated 19 | ``` 20 | path/to/datasets/folder 21 | └───ds_a 22 | └─── chskeleton 23 | └─── data.log 24 | └─── info.log 25 | └───ds_b 26 | └─── chskeleton 27 | └─── data.log 28 | └─── info.log 29 | ... 30 | ``` 31 | - `-p path/to/predictions/folder` must point to a folder containing the outputs of all algorithms that must be evaluated 32 | ``` 33 | path/to/predictions/folder 34 | └───ds_a 35 | └─── ch0skeleton 36 | └─── algo_a.txt 37 | └─── algo_b.txt 38 | ... 39 | └─── chskeleton 40 | └─── algo_a.txt 41 | └─── algo_b.txt 42 | ... 43 | └───ds_b 44 | └─── ch0skeleton 45 | └─── algo_a.txt 46 | └─── algo_b.txt 47 | ... 48 | └─── chskeleton 49 | └─── algo_a.txt 50 | └─── algo_b.txt 51 | ... 52 | ... 53 | ``` 54 | - `-o path/to/output/folder` is the path to the output folder that will be created and will contain all plots and tables for 55 | the specified metrics 56 | - `-pck ` specifies a list of thresholds over which the PCK will be computed; if not specified, 57 | PCK will not be computed 58 | - `-rmse` flag specifying that RMSE must be computed 59 | - `-latex` flag specifying that tables must be saved to latex format. 60 | 61 | The output folder will contain files with metric tables and prediction plots. 62 | 63 | ## Metrics 64 | 65 | The following metrics are computed for every algorithm 66 | 67 | ### Percentage of Correct Keypoints (PCK) 68 | PCK is computed 69 | * for every single body joint 70 | * as an average on all body joints 71 | 72 | and 73 | 74 | * for each single input dataset 75 | * for all datasets 76 | * for every specified classification threshold. 77 | 78 | The classification uses the body's head or torso size, depending on the available ground truth. 79 | 80 | Metric output 81 | * tables with all computed PCK values for every input algorithm's predictions 82 | * plots showing average PCK for every algorithm over the selected classification thresholds. 83 | 84 | ### Root Mean Square Error (RMSE) 85 | RMSE is computed 86 | * for every body joint coordinate 87 | * as an average on all joints for each coordinate 88 | 89 | and 90 | 91 | * for each single input dataset 92 | * for all datasets. 93 | 94 | Metric output 95 | * tables with all computed RMSE values for every input algorithm's predictions 96 | * plots for each joint showing ground truth and predicted x and y coordinates over time. 97 | -------------------------------------------------------------------------------- /evaluation/utils/__init__.py: -------------------------------------------------------------------------------- 1 | 2 | from .parsing import OPENPOSE_BODY_PARTS_25, JOINT_NOT_PRESENT 3 | from .parsing import parse_openpose_keypoints_json 4 | -------------------------------------------------------------------------------- /evaluation/utils/parsing.py: -------------------------------------------------------------------------------- 1 | 2 | import json 3 | import numpy as np 4 | 5 | 6 | # map from indices to body parts for openpose 7 | OPENPOSE_BODY_PARTS_25 = { 8 | 0: "Nose", 9 | 1: "Neck", 10 | 2: "RShoulder", 11 | 3: "RElbow", 12 | 4: "RWrist", 13 | 5: "LShoulder", 14 | 6: "LElbow", 15 | 7: "LWrist", 16 | 8: "MidHip", 17 | 9: "RHip", 18 | 10: "RKnee", 19 | 11: "RAnkle", 20 | 12: "LHip", 21 | 13: "LKnee", 22 | 14: "LAnkle", 23 | 15: "REye", 24 | 16: "LEye", 25 | 17: "REar", 26 | 18: "LEar", 27 | 19: "LBigToe", 28 | 20: "LSmallToe", 29 | 21: "LHeel", 30 | 22: "RBigToe", 31 | 23: "RSmallToe", 32 | 24: "RHeel", 33 | 25: "Background" 34 | } 35 | 36 | JOINT_NOT_PRESENT = np.zeros(2) 37 | 38 | 39 | def parse_openpose_keypoints_json(json_path): 40 | """ 41 | 42 | """ 43 | with open(json_path, 'r') as fp: 44 | json_dict = json.load(fp) 45 | 46 | # if there are no detections, return zero metrix 47 | if len(json_dict['people']) == 0: 48 | return np.zeros((len(OPENPOSE_BODY_PARTS_25), 2), dtype=int) 49 | 50 | # TODO: return all poses from openpose? 51 | # for now assume there's at most one predicted pose 52 | keypoints = np.array(json_dict['people'][0]['pose_keypoints_2d']).reshape((-1, 3)) 53 | 54 | # return 2d coordinates only, remove prediction confidence 55 | return keypoints[:, :-1] 56 | -------------------------------------------------------------------------------- /evaluation/utils/plots.py: -------------------------------------------------------------------------------- 1 | import cv2 2 | import numpy as np 3 | 4 | from .parsing import JOINT_NOT_PRESENT 5 | 6 | ALGO_COLORS = { 7 | 'GraphEnet': 'blue', 8 | # 'openpose_pim': 'green', 9 | # 'movenet_cam2': 'orange', 10 | # 'movenet_cam-24': 'red', 11 | 'movenet_eF': (122.0/255,1.0/255,119.0/255), 12 | 'movenet_wo_finetune': (251.0/255,180.0/255,185.0/255), 13 | 'gl-hpe':(37.0/255,52.0/255,148.0/255), 14 | 'movenet': (197.0/255, 27.0/255, 138.0/255), 15 | 'movenet_wo_pretrain': (247.0/255, 104.0/255, 161.0/255), 16 | 'openpose_rgb': (44.0/255,127.0/255,184.0/255), 17 | 'openpose_pim': (194.0/255,230.0/255,153.0/255), 18 | 'movenet_cam2': (255.0/255, 255.0/255, 255.0/255), 19 | 'movenet_cam-24': (197.0/255, 27.0/255, 138.0/255), 20 | 'movenet_rgb':(37.0/255,52.0/255,148.0/255) 21 | } 22 | 23 | OTHER_COLORS = ['black', 'violet','grey'] 24 | 25 | RENAMING = {'movenet_cam-24': 'moveEnet', 26 | 'movenet_eF': 'movenet_fixedCount', 27 | 'movenet': 'moveEnet', 28 | 'gl-hpe':'liftmono-hpe', 29 | 'hpeGnn_splineConv':'gnn' 30 | } 31 | 32 | 33 | def plot_poses(img, pose_gt, pose_pred): 34 | for joint_gt, joint_pred in zip(pose_gt, pose_pred): 35 | cv2.circle(img, (joint_gt[1], joint_gt[0]), 5, (0, 255, 0), cv2.FILLED) 36 | if _is_no_joint(joint_pred): 37 | continue 38 | cv2.circle(img, (joint_pred[0], joint_pred[1]), 5, (0, 0, 255), cv2.FILLED) 39 | cv2.imshow('',img) 40 | cv2.waitKey(1) 41 | 42 | 43 | ########### 44 | # PRIVATE # 45 | ########### 46 | 47 | def _is_no_joint(joint): 48 | return np.sum(joint == JOINT_NOT_PRESENT) == 2 49 | -------------------------------------------------------------------------------- /example/README.md: -------------------------------------------------------------------------------- 1 | # Example application and test-cases 2 | 3 | The following example modules are available to get an idea of how to use the core functionality in your own project. Many of the example modules are built upon [YARP](www.yarp.it) but have Dockerfiles to enable simple environment set-up. 4 | 5 | * OpenPose extracing 2D joint positions, example module using e2vid functionality to produce images from events 6 | * [GL-HPE](https://github.com/gianscarpe/event-based-monocular-hpe) extracing 2D joint positions from event-images, intregrated with live play-back functionality 7 | * movenet extracing 2D joint positions from Exponentially-reduced Ordinal Surfaces 8 | * event-based velocity estimation and simple integration > 100 Hz. 9 | * event-volume compensation using IMU input to remove motion blur from rotating cameras. 10 | -------------------------------------------------------------------------------- /example/movenet/.gitignore: -------------------------------------------------------------------------------- 1 | build/ 2 | *.orig 3 | -------------------------------------------------------------------------------- /example/movenet/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | # requires minimum cmake version 2 | cmake_minimum_required(VERSION 3.5) 3 | 4 | # produce the cmake var PROJECT_NAME 5 | project(eros-framer) 6 | 7 | #find_package(YCM REQUIRED) 8 | find_package(YARP COMPONENTS os sig REQUIRED) 9 | find_package(event-driven REQUIRED) 10 | find_package(hpe-core REQUIRED) 11 | 12 | #default the install location to that of event-driven 13 | 14 | add_executable(${PROJECT_NAME} eros-framer.cpp) 15 | 16 | target_link_libraries(${PROJECT_NAME} PRIVATE YARP::YARP_os 17 | YARP::YARP_init 18 | ev::event-driven 19 | hpe-core::hpe-core) 20 | 21 | install(TARGETS ${PROJECT_NAME} DESTINATION ${CMAKE_INSTALL_BINDIR}) 22 | 23 | -------------------------------------------------------------------------------- /example/movenet/LICENSE: -------------------------------------------------------------------------------- 1 | MIT License 2 | 3 | Copyright (c) 2020 Mr.Fire 4 | 5 | Permission is hereby granted, free of charge, to any person obtaining a copy 6 | of this software and associated documentation files (the "Software"), to deal 7 | in the Software without restriction, including without limitation the rights 8 | to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 9 | copies of the Software, and to permit persons to whom the Software is 10 | furnished to do so, subject to the following conditions: 11 | 12 | The above copyright notice and this permission notice shall be included in all 13 | copies or substantial portions of the Software. 14 | 15 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 16 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 17 | FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 18 | AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 19 | LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 20 | OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 21 | SOFTWARE. 22 | -------------------------------------------------------------------------------- /example/movenet/README.md: -------------------------------------------------------------------------------- 1 | # Movenet.Pytorch 2 | 3 | [![license](https://img.shields.io/github/license/mashape/apistatus.svg?maxAge=2592000)](https://github.com/fire717/Fire/blob/main/LICENSE) 4 | 5 | ## Intro 6 | 7 | MoveNet is an ultra fast and accurate model that detects 17 keypoints of a body. 8 | This is A Pytorch implementation of a variation of MoveNet inspired from the [Movenet.Pytorch](https://github.com/fire717/movenet.pytorch), modified to detect 13 keypoints trained on EROS, an event based representation. This example only consists of the inference code. 9 | 10 | ![moveEnet](https://github.com/user-attachments/assets/9ea56f92-a22a-4202-8340-1a0a6faeec73) 11 | 12 | For complete explanation, refer to the [MoveEnet](https://openaccess.thecvf.com/content/CVPR2023W/EventVision/papers/Goyal_MoveEnet_Online_High-Frequency_Human_Pose_Estimation_With_an_Event_Camera_CVPRW_2023_paper.pdf) paper. 13 | 14 | ## Installation 15 | 16 | The environment can be installed in 2 different ways: 17 | 18 | 1. Compile the Docker file to create the environment. 19 | 20 | - Download the repository and build the Docker image 21 | ```shell 22 | $ cd 23 | $ git clone git@github.com:event-driven-robotics/hpe-core.git 24 | $ cd hpe-core/example/movenet 25 | $ docker build -t moveEnet - < Dockerfile 26 | ``` 27 | -`` is the parent directory of choice in which the repository is cloned 28 | - If your computer does not have a GPU, replace `Dockerfile` with `Dockerfile_cpu` 29 | 30 | his will create a Docker image names movenet. 31 | 32 | Before running docker, instruct the host to accept GUI windows with the following command: 33 | 34 | ```shell 35 | $ xhost local:docker 36 | ``` 37 | 38 | Then run a container with the right parameters: 39 | 40 | ```shell 41 | $ docker run -it --privileged --network host -v /dev/bus/usb:/dev/bus/usb 42 | -v /tmp/.X11-unix:/tmp/.X11-unix -e DISPLAY=unix$DISPLAY \ 43 | --name movenet:latest 44 | ``` 45 | 46 | The meaning of the options are: 47 | * -it : runs the container in an interactive bash 48 | * --privileged : give the docker rights to open devices (to read the camera over usb) 49 | * -v /dev/bus/usb:/dev/bus/usb : mount the /dev folder so the docker can find the right device 50 | * -v /tmp/.X11-unix:/tmp/.X11-unix : mount the temporary configuration for x11 to use the same options as the host 51 | * -e DISPLAY=unix$DISPLAY : set the environment variable for X11 forwarding 52 | * --name : name your container so you remember it, if not specified docker will assign a random name that you will have to remember 53 | 54 | In case you wish to load any data present on host system or save results to a location external to the docker container, load a path as a volume when creating the container by adding another parameters in the command in the format: ` 55 | -v /path/on/host:/usr/local/data` 56 | 57 | 2. Create a python environment on you local machine. 58 | If you want to run this offline only, this option can be used. 59 | - Create a virtual environment and enter it. 60 | - Install dependencies from the requirements.txt: 61 | 62 | ```shell 63 | $ python3 -m pip install --upgrade pip && python3 -m pip install -r requirements.txt 64 | ``` 65 | - Add hpe core to your PYTHONPATH 66 | ```shell 67 | $ export PYTHONPATH=$PYTHONPATH:/path/to/hpe-core/ 68 | ``` 69 | ## Usage (Inference) 70 | 71 | To reopen a running container: 72 | ```shell 73 | $ docker exec -it bash 74 | ``` 75 | 76 | ### Online Inference on Camera input 77 | To run online pose estimation on a camera input, in commandline, run: 78 | ```shell 79 | $ yarpmanager 80 | ``` 81 | 82 | then load the file `/usr/local/hpe-core/examples/movenet/yarpmanagerapplication.xml`. Run all and connect all to detect pose from the camera input 83 | 84 | ### Offline Inference on a data sample 85 | 86 | A event sample from the [event-human 3.6m dataset](https://zenodo.org/records/7842598) is provided. To see the result on it, run: 87 | 88 | ```shell 89 | $ mkdir data && cd data && wget https://github.com/user-attachments/files/17645984/cam2_S1_Directions.zip 90 | $ unzip cam2_S1_Directions.zip && cd .. 91 | $ python3 moveEnet-offline.py -visualise False -write_video data/cam2_S1_Directions/moveEnet.mp4 -input data/cam2_S1_Directions/ch0dvs/ 92 | ``` 93 | Note: You can point the -write_video path to the host volume if you mounted one while creating the container. 94 | 95 | ### Quantitative evaluation 96 | 97 | For evaluation with hpe-core scripts, csv files can be created. 98 | - First use the export_eros.py scripts of the appropriate dataset from [here](https://github.com/event-driven-robotics/hpe-core/tree/moveEnet_offline/datasets) 99 | or download a sample with eros images from [here](https://github.com/event-driven-robotics/hpe-core/issues/115) 100 | 101 | ```shell 102 | $ python3 evaluate.py --write_output --eval_img_path <> \ 103 | --eval_label_path <> \ 104 | --results_path <> 105 | ``` 106 | -------------------------------------------------------------------------------- /example/movenet/config.py: -------------------------------------------------------------------------------- 1 | """ 2 | @Fire 3 | https://github.com/fire717 4 | """ 5 | 6 | dataset = 'dhp19' 7 | home = '/data' 8 | cfg = { 9 | ##### Global Setting 10 | 'gpu' : False, 11 | 'GPU_ID': '0,1', 12 | "num_workers": 4, 13 | "random_seed": 42, 14 | "cfg_verbose": True, 15 | "save_dir": home , 16 | "num_classes": 13, 17 | "width_mult": 1.0, 18 | "img_size": 192, 19 | 'label': '', 20 | 21 | ##### Train Setting 22 | 'pre-separated_data': True, 23 | 'training_data_split': 80, 24 | "dataset": dataset, 25 | 'balance_data': False, 26 | 'log_interval': 10, 27 | 'save_best_only': False, 28 | 29 | 'pin_memory': True, 30 | 'newest_ckpt': home + '/output/newest.json', 31 | 'th': 50, # percentage of headsize 32 | 'from_scratch': True, 33 | 34 | ##### Train Hyperparameters 35 | 'learning_rate': 0.001, # 1.25e-4 36 | 'batch_size': 64, 37 | 'epochs': 300, 38 | 'optimizer': 'Adam', # Adam SGD 39 | 'scheduler': 'MultiStepLR-70,100-0.1', # default SGDR-5-2 CVPR step-4-0.8 MultiStepLR 40 | # multistepLR-<<>milestones>-<> 41 | 'weight_decay': 0.001, # 5.e-4, # 0.0001, 42 | 'class_weight': None, # [1., 1., 1., 1., 1., 1., 1., ] 43 | 'clip_gradient': 5, # 1, 44 | 'w_heatmap': 1, 45 | 'w_bone': 20, 46 | 'w_center': 1, 47 | 'w_reg': 3, 48 | 'w_offset': 1, 49 | 50 | ##### File paths 51 | 'predict_output_path': home + "/predict/", 52 | 'results_path': home + "/results/", 53 | "img_path": home + "/dhp19_eros/", 54 | "test_img_path": home + '/dhp19_eros/', 55 | "eval_img_path": home + '/dhp19_eros/', 56 | "eval_outputs": home + '/dhp-outputs/', 57 | "eval_label_path": home + "/dhp19_eros/poses.json", 58 | 'train_label_path': '', 59 | 'val_label_path': '', 60 | 'ckpt': '' 61 | } 62 | 63 | -------------------------------------------------------------------------------- /example/movenet/eros-framer.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | #include 4 | #include 5 | #include 6 | 7 | using namespace ev; 8 | using namespace yarp::os; 9 | using namespace yarp::sig; 10 | 11 | class eroser : public RFModule { 12 | 13 | private: 14 | 15 | ev::EROS eros; 16 | ev::window input_port; 17 | yarp::os::BufferedPort > output_port; 18 | 19 | resolution res; 20 | Stamp yarpstamp; 21 | int freq; 22 | 23 | std::thread erosloop; 24 | 25 | public: 26 | 27 | bool configure(yarp::os::ResourceFinder& rf) override 28 | { 29 | //set the module name used to name ports 30 | setName((rf.check("name", Value("/eroser")).asString()).c_str()); 31 | 32 | /* initialize yarp network */ 33 | yarp::os::Network yarp; 34 | if(!yarp.checkNetwork(2.0)) { 35 | std::cout << "Could not connect to YARP" << std::endl; 36 | return false; 37 | } 38 | 39 | //open io ports 40 | if(!input_port.open(getName("/AE:i"))) { 41 | yError() << "Could not open input port"; 42 | return false; 43 | } 44 | 45 | if(!output_port.open(getName("/img:o"))) { 46 | yError() << "Could not open output port"; 47 | return false; 48 | } 49 | 50 | //read flags and parameters 51 | res.height = rf.check("height", Value(480)).asInt32(); 52 | res.width = rf.check("width", Value(640)).asInt32(); 53 | 54 | eros.init(res.width, res.height, 7, 0.3); 55 | 56 | freq = rf.check("f", Value(50)).asInt32(); 57 | 58 | erosloop = std::thread([this]{events2eros();}); 59 | 60 | //start the asynchronous and synchronous threads 61 | return true; 62 | } 63 | 64 | virtual double getPeriod() override 65 | { 66 | return 1.0/freq; //period of synchrnous thread 67 | } 68 | 69 | bool interruptModule() override 70 | { 71 | //if the module is asked to stop ask the asynchrnous thread to stop 72 | input_port.stop(); 73 | erosloop.join(); 74 | output_port.close(); 75 | return true; 76 | } 77 | 78 | //synchronous thread 79 | virtual bool updateModule() 80 | { 81 | 82 | //static cv::Mat cv_image(res.height, res.width, CV_8U); 83 | static cv::Mat eros8U; 84 | 85 | eros.getSurface().convertTo(eros8U, CV_8U); 86 | 87 | cv::GaussianBlur(eros8U, eros8U, cv::Size(5, 5), 0, 0); 88 | 89 | output_port.setEnvelope(yarpstamp); 90 | output_port.prepare().copy(yarp::cv::fromCvMat(eros8U)); 91 | output_port.write(); 92 | return true; 93 | } 94 | 95 | //asynchronous thread run forever 96 | void events2eros() { 97 | 98 | while (input_port.isRunning()) { 99 | ev::info packet_info = input_port.readAll(true); 100 | for(auto &v : input_port) 101 | eros.update(v.x, v.y); 102 | } 103 | } 104 | 105 | }; 106 | 107 | int main(int argc, char * argv[]) 108 | { 109 | /* prepare and configure the resource finder */ 110 | yarp::os::ResourceFinder rf; 111 | rf.configure( argc, argv ); 112 | 113 | /* create the module */ 114 | eroser instance; 115 | return instance.runModule(rf); 116 | } -------------------------------------------------------------------------------- /example/movenet/evaluate.py: -------------------------------------------------------------------------------- 1 | """ 2 | @Fire 3 | https://github.com/fire717 4 | """ 5 | import os, argparse 6 | import random 7 | import sys 8 | 9 | sys.path.append('.') 10 | sys.path.append('../../../hpe-core') 11 | from pycore.moveenet import init, Data, MoveNet, Task 12 | 13 | from config import cfg 14 | from pycore.moveenet.utils.utils import arg_parser 15 | 16 | 17 | def main(cfg): 18 | init(cfg) 19 | 20 | model = MoveNet(num_classes=cfg["num_classes"], 21 | width_mult=cfg["width_mult"], 22 | mode='train') 23 | 24 | data = Data(cfg) 25 | data_loader = data.getEvalDataloader() 26 | 27 | run_task = Task(cfg, model) 28 | 29 | run_task.modelLoad("models/e97_valacc0.81209.pth") 30 | 31 | run_task.evaluate(data_loader, fastmode=True) 32 | # run_task.infer_video(data_loader,'/home/ggoyal/data/h36m/tester/out.avi') 33 | 34 | 35 | if __name__ == '__main__': 36 | cfg = arg_parser(cfg) 37 | main(cfg) 38 | -------------------------------------------------------------------------------- /example/movenet/models/dhp19_allcams_e33_valacc0.87996.pth: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/event-driven-robotics/hpe-core/178ac06fbf35f4b6ea9aca1a2a35bb6906b35213/example/movenet/models/dhp19_allcams_e33_valacc0.87996.pth -------------------------------------------------------------------------------- /example/movenet/models/dhp19_frontcams_e88_valacc0.97142.pth: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/event-driven-robotics/hpe-core/178ac06fbf35f4b6ea9aca1a2a35bb6906b35213/example/movenet/models/dhp19_frontcams_e88_valacc0.97142.pth -------------------------------------------------------------------------------- /example/movenet/models/dhp19_sidecams_e44_valacc0.87217.pth: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/event-driven-robotics/hpe-core/178ac06fbf35f4b6ea9aca1a2a35bb6906b35213/example/movenet/models/dhp19_sidecams_e44_valacc0.87217.pth -------------------------------------------------------------------------------- /example/movenet/models/e97_valacc0.81209.pth: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/event-driven-robotics/hpe-core/178ac06fbf35f4b6ea9aca1a2a35bb6906b35213/example/movenet/models/e97_valacc0.81209.pth -------------------------------------------------------------------------------- /example/movenet/models/h36m_finetuned.pth: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/event-driven-robotics/hpe-core/178ac06fbf35f4b6ea9aca1a2a35bb6906b35213/example/movenet/models/h36m_finetuned.pth -------------------------------------------------------------------------------- /example/movenet/models/h36m_only-trained.pth: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/event-driven-robotics/hpe-core/178ac06fbf35f4b6ea9aca1a2a35bb6906b35213/example/movenet/models/h36m_only-trained.pth -------------------------------------------------------------------------------- /example/movenet/models/mpii_pre-trained.pth: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/event-driven-robotics/hpe-core/178ac06fbf35f4b6ea9aca1a2a35bb6906b35213/example/movenet/models/mpii_pre-trained.pth -------------------------------------------------------------------------------- /example/movenet/models/upper.pth: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/event-driven-robotics/hpe-core/178ac06fbf35f4b6ea9aca1a2a35bb6906b35213/example/movenet/models/upper.pth -------------------------------------------------------------------------------- /example/movenet/predict.py: -------------------------------------------------------------------------------- 1 | """ 2 | @Fire 3 | https://github.com/fire717 4 | """ 5 | 6 | from pycore.moveenet import init, Data, MoveNet, Task 7 | 8 | from config import cfg 9 | from pycore.moveenet.utils.utils import arg_parser 10 | 11 | 12 | # Script to create and save as images all the various outputs of the model 13 | 14 | 15 | def main(cfg): 16 | init(cfg) 17 | 18 | model = MoveNet(num_classes=cfg["num_classes"], 19 | width_mult=cfg["width_mult"], 20 | mode='train') 21 | 22 | data = Data(cfg) 23 | test_loader = data.getTestDataloader() 24 | 25 | run_task = Task(cfg, model) 26 | run_task.modelLoad("models/h36m_finetuned.pth") 27 | 28 | run_task.predict(test_loader, cfg['predict_output_path']) 29 | 30 | if __name__ == '__main__': 31 | cfg = arg_parser(cfg) 32 | main(cfg) 33 | -------------------------------------------------------------------------------- /example/movenet/requirements.txt: -------------------------------------------------------------------------------- 1 | numpy 2 | pandas 3 | opencv-python 4 | torch 5 | torchvision 6 | albumentations 7 | Pillow 8 | torchsummary 9 | onnxruntime 10 | tensorboard 11 | bimvee 12 | -------------------------------------------------------------------------------- /example/movenet/scripts/data/delImg.py: -------------------------------------------------------------------------------- 1 | """ 2 | @Fire 3 | https://github.com/fire717 4 | """ 5 | import os 6 | import json 7 | import pickle 8 | import cv2 9 | import numpy as np 10 | import random 11 | 12 | 13 | 14 | 15 | 16 | imgs = os.listdir("imgs") 17 | print("total imgs: ", len(imgs)) 18 | 19 | shows = os.listdir("show") 20 | print("total shows: ", len(shows)) 21 | 22 | 23 | with open("data_all_new.json",'r') as f: 24 | data = json.loads(f.readlines()[0]) 25 | print("total labels: ",len(data)) 26 | 27 | 28 | new_data = [] 29 | for d in data: 30 | name = d['img_name'] 31 | if name not in shows: 32 | if name in imgs: 33 | os.rename(os.path.join("imgs",name),os.path.join("del",name)) 34 | else: 35 | new_data.append(d) 36 | 37 | 38 | print("total new_data: ", len(new_data)) 39 | with open("data_all_new.json",'w') as f: 40 | json.dump(new_data, f, ensure_ascii=False) -------------------------------------------------------------------------------- /example/movenet/scripts/data/findImgNolabel.py: -------------------------------------------------------------------------------- 1 | """ 2 | @Fire 3 | https://github.com/fire717 4 | """ 5 | 6 | 7 | import os 8 | import json 9 | 10 | 11 | 12 | 13 | 14 | read_dir = "show" 15 | img_names = os.listdir(read_dir) 16 | print("len img: ",len(img_names)) 17 | 18 | 19 | 20 | with open("data_all_new.json",'r') as f: 21 | data = json.loads(f.readlines()[0]) 22 | ##print(data[0]) 23 | print("len label: ", len(data)) 24 | 25 | data_names = set([item['img_name'] for item in data]) 26 | 27 | 28 | for i,img_name in enumerate(img_names): 29 | if i%10000==0: 30 | print(i) 31 | 32 | if img_name not in data_names: 33 | print(img_name) 34 | 35 | 36 | 37 | 38 | 39 | 40 | -------------------------------------------------------------------------------- /example/movenet/scripts/data/make_handlabel_data_7keypooints.py: -------------------------------------------------------------------------------- 1 | """ 2 | @Fire 3 | https://github.com/fire717 4 | """ 5 | import os 6 | import json 7 | import pickle 8 | import cv2 9 | import numpy as np 10 | import glob 11 | 12 | 13 | 14 | 15 | read_dir = "label5" 16 | save_dir = "croped" 17 | 18 | 19 | output_name = 'croped/%s.json' % read_dir 20 | output_img_dir = "croped/imgs" 21 | 22 | 23 | if __name__ == '__main__': 24 | 25 | 26 | imgs = glob.glob(read_dir+'/*.jpg') 27 | print(len(imgs)) 28 | 29 | new_label = [] 30 | for i, img_path in enumerate(imgs): 31 | 32 | img_name = os.path.basename(img_path) 33 | img = cv2.imread(img_path) 34 | h,w = img.shape[:2] 35 | 36 | 37 | label_path = img_path[:-3]+'txt' 38 | 39 | with open(label_path, 'r') as f: 40 | lines = f.readlines() 41 | 42 | if len(lines)!=8: 43 | continue 44 | 45 | keypoints = [] 46 | for line in lines[1:]: 47 | 48 | x,y = [float(x) for x in line.strip().split(' ')[:2]] 49 | keypoints.extend([x,y,2]) 50 | 51 | # center = [(keypoints[2*3]+keypoints[4*3])/2, 52 | # (keypoints[2*3+1]+keypoints[4*3+1])/2] 53 | 54 | min_key_x = np.min(np.array(keypoints)[[0,3,6,9,12,15,18]]) 55 | max_key_x = np.max(np.array(keypoints)[[0,3,6,9,12,15,18]]) 56 | min_key_y = np.min(np.array(keypoints)[[1,4,7,10,13,16,19]]) 57 | max_key_y = np.max(np.array(keypoints)[[1,4,7,10,13,16,19]]) 58 | center = [(min_key_x+max_key_x)/2, (min_key_y+max_key_y)/2] 59 | 60 | 61 | save_item = { 62 | "img_name":img_name, 63 | "keypoints":keypoints, 64 | "center":center, 65 | "other_centers":[], 66 | "other_keypoints":[[] for _ in range(7)], 67 | } 68 | # print(save_item) 69 | new_label.append(save_item) 70 | 71 | cv2.imwrite(os.path.join(output_img_dir, img_name), img) 72 | 73 | 74 | 75 | 76 | with open(output_name,'w') as f: 77 | json.dump(new_label, f, ensure_ascii=False) 78 | print('Total write ', len(new_label)) -------------------------------------------------------------------------------- /example/movenet/scripts/data/mergeJson.py: -------------------------------------------------------------------------------- 1 | """ 2 | @Fire 3 | https://github.com/fire717 4 | """ 5 | import os 6 | import json 7 | import pickle 8 | import cv2 9 | import numpy as np 10 | import random 11 | 12 | 13 | read_list = ["13821708-1-64.json", 14 | "254962538-1-64.json", 15 | "301370759-1-64.json", 16 | "347686742-1-64.json", 17 | "386530533-1-64.json", 18 | "390420891-1-64.json", 19 | "label5.json"]# 20 | 21 | data_all = [] 22 | for name in read_list: 23 | with open(name,'r') as f: 24 | data = json.loads(f.readlines()[0]) 25 | print(name, len(data)) 26 | 27 | for d in data: 28 | data_all.append(d) 29 | 30 | 31 | print("total: ", len(data_all)) 32 | random.shuffle(data_all) 33 | with open("video_all4.json",'w') as f: 34 | json.dump(data_all, f, ensure_ascii=False) -------------------------------------------------------------------------------- /example/movenet/scripts/data/moveDifferent.py: -------------------------------------------------------------------------------- 1 | """ 2 | @Fire 3 | https://github.com/fire717 4 | """ 5 | 6 | 7 | import os 8 | 9 | 10 | def getAllName(file_dir, tail_list = ['.jpg','.png','.jpeg']): 11 | L=[] 12 | for root, dirs, files in os.walk(file_dir): 13 | for file in files: 14 | if os.path.splitext(file)[1] in tail_list: 15 | L.append(os.path.join(root, file)) 16 | return L 17 | 18 | 19 | 20 | 21 | 22 | def main(dir_path, label_path, save_dir): 23 | # make all 24 | 25 | img_names = getAllName(dir_path) 26 | print("total img_names: ", len(img_names)) 27 | 28 | 29 | label_names = getAllName(label_path) 30 | print("total label_names: ", len(label_names)) 31 | label_names = set([os.path.basename(name) for name in label_names]) 32 | 33 | 34 | 35 | for i,img_name in enumerate(img_names): 36 | 37 | if i%5000==0: 38 | print(i, len(img_names)) 39 | 40 | name = os.path.basename(img_name) 41 | 42 | 43 | if name in label_names: 44 | os.rename(img_name, os.path.join(save_dir,name)) 45 | 46 | 47 | 48 | 49 | 50 | 51 | 52 | if __name__ == '__main__': 53 | 54 | dir_path = "show" 55 | label_path = "exam" 56 | save_dir = "tmp" 57 | 58 | print("Strat: ", dir_path) 59 | main(dir_path, label_path, save_dir) 60 | print("------------------") -------------------------------------------------------------------------------- /example/movenet/scripts/data/moveSame.py: -------------------------------------------------------------------------------- 1 | """ 2 | @Fire 3 | https://github.com/fire717 4 | """ 5 | 6 | 7 | import os 8 | 9 | 10 | def getAllName(file_dir, tail_list = ['.jpg','.png','.jpeg']): 11 | L=[] 12 | for root, dirs, files in os.walk(file_dir): 13 | for file in files: 14 | if os.path.splitext(file)[1] in tail_list: 15 | L.append(os.path.join(root, file)) 16 | return L 17 | 18 | 19 | 20 | 21 | 22 | def main(read_dir, img_dir, label_dir, save_dir): 23 | # make all 24 | 25 | move_names = os.listdir(read_dir) 26 | basenames = set([x.split('.')[0] for x in move_names]) 27 | print(len(basenames)) 28 | 29 | 30 | img_names = os.listdir(img_dir) 31 | for img_name in img_names: 32 | if img_name.split('.')[0] in basenames: 33 | os.rename(os.path.join(img_dir,img_name), os.path.join(save_dir,img_name)) 34 | 35 | 36 | txt_names = os.listdir(label_dir) 37 | for txt_name in txt_names: 38 | if txt_name.split('.')[0] in basenames: 39 | os.rename(os.path.join(label_dir,txt_name), os.path.join(save_dir,txt_name)) 40 | 41 | 42 | 43 | 44 | 45 | 46 | 47 | 48 | if __name__ == '__main__': 49 | 50 | read_dir = "tmp" 51 | 52 | img_dir = "../crop_imgs/70713034_nb2-1-32" 53 | label_dir = "txt" 54 | save_dir = "clean" 55 | 56 | 57 | main(read_dir, img_dir, label_dir, save_dir) 58 | print("------------------") -------------------------------------------------------------------------------- /example/movenet/scripts/data/resize.py: -------------------------------------------------------------------------------- 1 | """ 2 | @Fire 3 | https://github.com/fire717 4 | """ 5 | import os 6 | import cv2 7 | import numpy as np 8 | from PIL import Image 9 | 10 | read_dir = "imgs" 11 | save_dir = "imgs192pil" 12 | 13 | 14 | 15 | if __name__ == "__main__": 16 | 17 | 18 | img_names = os.listdir(read_dir) 19 | print("total: ", len(img_names)) 20 | 21 | for i,img_name in enumerate(img_names): 22 | if i%5000==0: 23 | print(i) 24 | img_path = os.path.join(read_dir, img_name) 25 | save_path = os.path.join(save_dir, img_name) 26 | 27 | 28 | img = cv2.imread(img_path) 29 | 30 | # img = cv2.resize(img, (192,192)) 31 | 32 | img = Image.fromarray(img) 33 | img = img.resize((192,192)) 34 | img = np.array(img) 35 | 36 | cv2.imwrite(save_path, img) 37 | -------------------------------------------------------------------------------- /example/movenet/scripts/data/show_crop.py: -------------------------------------------------------------------------------- 1 | """ 2 | @Fire 3 | https://github.com/fire717 4 | """ 5 | import os 6 | import json 7 | import pickle 8 | import cv2 9 | import numpy as np 10 | 11 | 12 | img_dir = "imgs" 13 | save_dir = "show" 14 | 15 | with open(r"video_all4.json",'r') as f: 16 | data = json.loads(f.readlines()[0]) 17 | print("total: ", len(data)) 18 | 19 | for item in data: 20 | """ 21 | save_item = { 22 | "img_name":save_name, 23 | "keypoints":save_keypoints, 24 | "center":save_center, 25 | "bbox":save_bbox, 26 | "other_centers":other_centers, 27 | "other_keypoints":other_keypoints, 28 | } 29 | """ 30 | 31 | img_name = item['img_name'] 32 | img = cv2.imread(os.path.join(img_dir, img_name)) 33 | h,w = img.shape[:2] 34 | 35 | save_center = item['center'] 36 | save_keypoints = item['keypoints'] 37 | # save_bbox = item['bbox'] 38 | other_centers = item['other_centers'] 39 | other_keypoints = item['other_keypoints'] 40 | 41 | cv2.circle(img, (int(save_center[0]*w), int(save_center[1]*h)), 4, (0,255,0), 3) 42 | for show_kid in range(len(save_keypoints)//3): 43 | if save_keypoints[show_kid*3+2]==1: 44 | color = (255,0,0) 45 | elif save_keypoints[show_kid*3+2]==2: 46 | color = (0,0,255) 47 | else: 48 | continue 49 | cv2.circle(img, (int(save_keypoints[show_kid*3]*w), 50 | int(save_keypoints[show_kid*3+1]*h)), 3, color, 2) 51 | # cv2.rectangle(img, (int(save_bbox[0]*w), int(save_bbox[1]*h)), 52 | # (int(save_bbox[2]*w), int(save_bbox[3]*h)), (0,255,0), 2) 53 | for show_c in other_centers: 54 | cv2.circle(img, (int(show_c[0]*w), int(show_c[1]*h)), 4, (0,255,255), 3) 55 | for show_ks in other_keypoints: 56 | for show_k in show_ks: 57 | cv2.circle(img, (int(show_k[0]*w), int(show_k[1]*h)), 3, (255,255,0), 2) 58 | 59 | cv2.imwrite(os.path.join(save_dir, img_name), img) -------------------------------------------------------------------------------- /example/movenet/scripts/data/split_trainval.py: -------------------------------------------------------------------------------- 1 | """ 2 | @Fire 3 | https://github.com/fire717 4 | """ 5 | import os 6 | import json 7 | import pickle 8 | import cv2 9 | import numpy as np 10 | import random 11 | 12 | 13 | 14 | with open(r"data_all_new.json",'r') as f: 15 | data = json.loads(f.readlines()[0]) 16 | print("total: ", len(data)) 17 | print(data[0]) 18 | 19 | random.shuffle(data) 20 | print(data[0]) 21 | 22 | val_count = 600 23 | ratio = val_count/len(data) 24 | 25 | 26 | data_train = [] 27 | data_val = [] 28 | for d in data: 29 | if random.random()>ratio: 30 | data_train.append(d) 31 | else: 32 | data_val.append(d) 33 | 34 | print(len(data_train), len(data_val)) 35 | with open("train.json",'w') as f: 36 | json.dump(data_train, f, ensure_ascii=False) 37 | 38 | with open("val.json",'w') as f: 39 | json.dump(data_val, f, ensure_ascii=False) -------------------------------------------------------------------------------- /example/movenet/scripts/data/video2img.py: -------------------------------------------------------------------------------- 1 | """ 2 | @Fire 3 | https://github.com/fire717 4 | """ 5 | import os 6 | import cv2 7 | 8 | 9 | def video2img(video_path, save_dir): 10 | cap = cv2.VideoCapture(video_path) 11 | 12 | basename = os.path.basename(video_path)[:-4] 13 | save_dir = os.path.join(save_dir,basename) 14 | if not os.path.exists(save_dir): 15 | os.makedirs(save_dir) 16 | 17 | idx = 0 18 | while(cap.isOpened()): 19 | if idx%1000==0: 20 | print(idx) 21 | 22 | ret, frame = cap.read() 23 | if not ret or frame is None: 24 | break 25 | 26 | if idx%4==1: 27 | idx+=1 28 | continue 29 | 30 | save_name = os.path.join(save_dir,basename+"_%d.jpg" % idx) 31 | cv2.imwrite(save_name, frame) 32 | 33 | idx+=1 34 | 35 | 36 | video_dir = './video2/' 37 | save_dir = './imgs/' 38 | 39 | video_names = os.listdir(video_dir) 40 | print("Total video :", len(video_names)) 41 | 42 | for i,video_name in enumerate(video_names): 43 | print("start %d/%d :%s " % (i+1, len(video_names),video_name)) 44 | #video_name = '86460431_nb2-1-64.flv' 45 | 46 | video_path = os.path.join(video_dir, video_name) 47 | video2img(video_path, save_dir) 48 | 49 | -------------------------------------------------------------------------------- /example/movenet/scripts/my_weight_center.npy: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/event-driven-robotics/hpe-core/178ac06fbf35f4b6ea9aca1a2a35bb6906b35213/example/movenet/scripts/my_weight_center.npy -------------------------------------------------------------------------------- /example/movenet/scripts/split_trainval.py: -------------------------------------------------------------------------------- 1 | """ 2 | @Fire 3 | https://github.com/fire717 4 | """ 5 | import os 6 | import json 7 | import pickle 8 | import cv2 9 | import numpy as np 10 | import random 11 | 12 | 13 | def read_data(path): 14 | with open(path, 'r') as f: 15 | data = json.loads(f.readlines()[0]) 16 | print("total: ", len(data)) 17 | return data 18 | 19 | 20 | def fix_data(data): 21 | fixed_data = [] 22 | for d in data: 23 | if type(d) is dict: 24 | fixed_data.append(d) 25 | elif type(d) is list: 26 | fixed_data.extend(d) 27 | print('files are concatenating correctly:', len(fixed_data)) 28 | return fixed_data 29 | 30 | 31 | def file_exists_check(data, path): 32 | data_fixed = [] 33 | for d in data: 34 | file = os.path.join(path, d["img_name"]) 35 | if os.path.exists(file): 36 | data_fixed.append(d) 37 | print('files that exist:', len(data_fixed)) 38 | return data_fixed 39 | 40 | 41 | def split(data, val_split=20, mode='ratio', val_subs=None): 42 | data_train = [] 43 | data_val = [] 44 | if mode == 'ratio': 45 | random.shuffle(data) 46 | val_files_num = int((val_split / 100) * len(data)) 47 | 48 | print("Number of validation files", val_files_num) 49 | print("Percentage of validation files", val_split) 50 | 51 | data_val = data[:val_files_num] 52 | data_train = data[val_files_num:] 53 | 54 | elif mode == 'subject': 55 | 56 | for d in data: 57 | if d["img_name"].split('_')[0] in val_subs: 58 | data_val.append(d) 59 | else: 60 | data_train.append(d) 61 | random.shuffle(data_val) 62 | random.shuffle(data_train) 63 | 64 | return data_train, data_val 65 | 66 | 67 | path = "/home/ggoyal/data/h36m/training/poses_full_clean.json" 68 | # path = r"/home/ggoyal/data/h36m/training/poses.json" 69 | data = read_data(path) 70 | # data = fix_data(data) 71 | # img_path = '/home/ggoyal/data/h36m/training/h36m_EROS/' 72 | # data = file_exists_check(data, img_path) 73 | 74 | subs = ['S9', 'S11'] 75 | val_split = 20 # (percentage for validation) 76 | data_train, data_val = split(data, mode='subject', val_subs=subs) 77 | # data_train, data_val = split(data, val_split=20) 78 | 79 | print(len(data), len(data_train), len(data_val)) 80 | # with open("/home/ggoyal/data/h36m/training/poses_full_clean.json", 'w') as f: 81 | # json.dump(data, f, ensure_ascii=False) 82 | 83 | with open("/home/ggoyal/data/h36m/training/train_subject.json", 'w') as f: 84 | json.dump(data_train, f, ensure_ascii=False) 85 | 86 | with open("/home/ggoyal/data/h36m/training/val_subject.json", 'w') as f: 87 | json.dump(data_val, f, ensure_ascii=False) 88 | -------------------------------------------------------------------------------- /example/movenet/yarpmanagerapplication.xml: -------------------------------------------------------------------------------- 1 | 2 | movenet-yarp 3 | 4 | 5 | 6 | 7 | 8 | yarpserver 9 | --write 10 | localhost 11 | 12 | 13 | 14 | atis-bridge-sdk 15 | --s 60 --filter 0.01 16 | localhost 17 | 18 | 19 | 20 | eros-framer 21 | 22 | localhost 23 | 24 | 25 | 26 | python3 /usr/local/hpe-core/example/movenet/run-model.py 27 | --name /movenet 28 | localhost 29 | 30 | 31 | 32 | /atis3/AE:o 33 | /eroser/AE:i 34 | fast_tcp 35 | 36 | 37 | 38 | /eroser/img:o 39 | /movenet/img:i 40 | fast_tcp 41 | 42 | 43 | 44 | -------------------------------------------------------------------------------- /example/op_detector_example_module/.gitignore: -------------------------------------------------------------------------------- 1 | build/ 2 | .vscode/ 3 | -------------------------------------------------------------------------------- /example/op_detector_example_module/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | # requires minimum cmake version 2 | cmake_minimum_required(VERSION 3.16.0) 3 | 4 | # produce the cmake var PROJECT_NAME 5 | project(op_detector_example_module) 6 | 7 | find_package(YARP COMPONENTS os sig REQUIRED) 8 | find_package(hpe-core REQUIRED) 9 | find_package(event-driven REQUIRED) 10 | 11 | add_executable(${PROJECT_NAME} ${PROJECT_NAME}.cpp) 12 | 13 | target_link_libraries(${PROJECT_NAME} YARP::YARP_OS 14 | YARP::YARP_sig 15 | hpe-core::hpe-core) 16 | 17 | add_executable(e2vid_framer e2vid_framer.cpp) 18 | 19 | target_link_libraries(e2vid_framer YARP::YARP_OS 20 | YARP::YARP_sig 21 | ev::event-driven 22 | hpe-core::hpe-core) 23 | 24 | install(TARGETS ${PROJECT_NAME} e2vid_framer DESTINATION ${CMAKE_INSTALL_BINDIR}) -------------------------------------------------------------------------------- /example/op_detector_example_module/README.md: -------------------------------------------------------------------------------- 1 | # Online OpenPose Example 2 | A yarp application for online human pose estimation. The `YARP dataplayer` streams events to `e2vid_framer`, which creates 3 | batches of events and sends them to `E2Vid`. `E2Vid` predicts grayscale frames and sends them to `OpenPose` for pose estimation. 4 | Raw events, grayscale frames and poses are sent to `vFramer` for the final visualization. 5 | 6 | The application has been designed to run using docker for simple set-up of the environment. 7 | 8 | ## Files Description 9 | - `Dockerfile`: file containing instructions for building a `Docker` image able to run `OpenPose` and `E2Vid` 10 | - `e2vid_example_module.py`: python `yarp` module running `E2Vid` 11 | - `e2vid_framer.cpp`: c++ `yarp` module creating batches of events that are sent to `E2Vid` 12 | - `op_detector_example_module.cpp`: c++ `yarp` module running `OpenPose` 13 | - `/conf/yarpapp_demo*.xml`: `yarp` applications configuration files 14 | - `/shell_scripts/launch_yarpview.sh`: bash script to be run outside `Docker`; installs `yarp` if missing, configures `yarpserver` and runs `yarpview` 15 | 16 | The example contains also two c++ wrappers that call python code using Python's c++ api, `/wrappers/e2vid.cpp` and 17 | `/wrappers/e2vid.h`. Currently, it seems that PyTorch's `torch.device()` fails if yarp is included in c++. Nonetheless, 18 | the code can be used as an example on how to execute python scripts from c++. 19 | 20 | ## Installation 21 | The software was tested on Ubuntu 20.04.2 LTS with an Nvidia GPU. 22 | 23 | - Install the latest [Nvidia driver](https://github.com/NVIDIA/nvidia-docker/wiki/Frequently-Asked-Questions#how-do-i-install-the-nvidia-driver) 24 | - Install [Docker Engine](https://docs.docker.com/engine/install/ubuntu) 25 | - Install [Nvidia Docker Toolkit](https://docs.nvidia.com/datacenter/cloud-native/container-toolkit/install-guide.html#docker) 26 | - Download the repository and build the Docker image 27 | ```shell 28 | $ cd 29 | $ git clone git@github.com:event-driven-robotics/hpe-core.git 30 | $ cd hpe-core/example/op_detector_example_module 31 | $ docker build -t op-yarp - < Dockerfile 32 | ``` 33 | :bulb: `` is the parent directory in which the repository is cloned 34 | 35 | ## Live Atis Camera Usage 36 | - Run the Docker container and, inside it, run the yarp manager and server 37 | ```shell 38 | $ xhost local:docker 39 | $ docker run -it --privileged -v /dev/bus/usb:/dev/bus/usb -v /tmp/.X11-unix/:/tmp/.X11-unix -e DISPLAY=unix$DISPLAY --runtime=nvidia --network host 40 | $ yarpmanager & 41 | $ yarpserver & 42 | ``` 43 | In the ``yarpmanager`` window, load the configuration file ``yarpapp_demo_atis.xml`` (located in folder 44 | ``/usr/local/hpe-core/example/op_detector_example_module/conf``) and select the app ``e2vid_op_demo``. 45 | 46 | The terminal window will show ``yarpserver``'s IP address (e.g. ``172.17.0.2``). This might be needed 47 | for the next step. 48 | 49 | - Install (if not present already) and configure ``yarp`` on the local machine 50 | ```shell 51 | # install yarp 52 | $ sudo sh -c 'echo "deb http://www.icub.org/ubuntu focal contrib/science" > /etc/apt/sources.list.d/icub.list' 53 | $ sudo apt-key adv --keyserver keyserver.ubuntu.com --recv-keys 57A5ACB6110576A6 54 | $ sudo apt-get update 55 | $ sudo apt-get install -y yarp 56 | 57 | # make yarpserver in the Docker container visible to local yarp 58 | $ yarp conf 10000 # e.g. 172.17.0.2 59 | $ yarp check 60 | $ yarp detect 61 | ``` 62 | 63 | - Run ``yarpview`` on the local machine (``yarpview`` cannot be currently run in the Docker container; this will be fixed in 64 | a future release) 65 | ```shell 66 | $ yarpview --name /img_vis --x 30 --y 30 --h 720 --w 960 --synch --compact 67 | ``` 68 | 69 | - In the ``yarpmanager`` window, load the configuration file ``yarpapp_demo_atis.xml`` and select the app ``e2vid_op_demo`` 70 | 71 | - Run all components by clicking on the green button ``Run all`` 72 | 73 | - Setup Docker's image for running ATIS Gen3 camera by using [this](https://github.com/event-driven-robotics/atis-gen3-docker/tree/a7edfb2d5813b5edfdc68986a6384ec73cbc6af2) guide 74 | 75 | - Once the camera is connected and running, activate all YARP connections by clicking on the green button ``Connect all`` in ``yarpmanager``'s GUI. 76 | 77 | ## OpenPose Parameters 78 | List of available body models, joints and indices available [here](https://github.com/CMU-Perceptual-Computing-Lab/openpose/blob/master/src/openpose/pose/poseParameters.cpp). 79 | -------------------------------------------------------------------------------- /example/op_detector_example_module/conf/yarpapp_demo.xml: -------------------------------------------------------------------------------- 1 | 2 | e2vid_op_demo_dataset 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | yarpdataplayer 12 | 13 | localhost 14 | 15 | 16 | 17 | /usr/local/hpe-core/example/op_detector_example_module/build/e2vid_framer 18 | localhost 19 | 20 | 21 | 22 | /usr/local/hpe-core/example/op_detector_example_module/build/op_detector_example_module 23 | --model-folder /openpose/models --no_display true 24 | localhost 25 | 26 | 27 | 28 | python3 /usr/local/hpe-core/example/op_detector_example_module/e2vid_example_module.py 29 | localhost 30 | 31 | 32 | 33 | vFramerLite 34 | --displays "(/events (F AE ISO))" --height 240 --width 304 35 | localhost 36 | 37 | 38 | 39 | 40 | 41 | 42 | /zynqGrabber/AE:o 43 | /e2vidPacker/AE:i 44 | fast_tcp 45 | 46 | 47 | 48 | /e2vidPacker/AE:o 49 | /e2vid_example_module/AE:i 50 | fast_tcp 51 | 52 | 53 | 54 | /e2vid_example_module/img:o 55 | /op_detector_example_module/img:i 56 | fast_tcp 57 | 58 | 59 | 60 | /op_detector_example_module/img:o 61 | /vFramer/events/frame:i 62 | fast_tcp 63 | 64 | 65 | 66 | /zynqGrabber/AE:o 67 | /vFramer/events/AE:i 68 | fast_tcp 69 | 70 | 71 | 72 | /vFramer/events/image:o 73 | /img_vis 74 | fast_tcp 75 | 76 | 77 | 78 | 79 | -------------------------------------------------------------------------------- /example/op_detector_example_module/conf/yarpapp_demo_atis.xml: -------------------------------------------------------------------------------- 1 | 2 | e2vid_op_demo_atis_camera 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | /usr/local/hpe-core/example/op_detector_example_module/build/e2vid_framer 12 | --window 100000 13 | localhost 14 | 15 | 16 | 17 | /usr/local/hpe-core/example/op_detector_example_module/build/op_detector_example_module 18 | --model-folder /openpose/models --no_display true 19 | localhost 20 | 21 | 22 | 23 | python3 /usr/local/hpe-core/example/op_detector_example_module/e2vid_example_module.py 24 | --sensor_width 640 --sensor_height 480 25 | localhost 26 | 27 | 28 | 29 | vFramerLite 30 | --displays "(/events (F AE ISO))" --height 480 --width 640 31 | localhost 32 | 33 | 34 | 35 | 36 | 37 | 38 | /atis3/AE:o 39 | /e2vidPacker/AE:i 40 | fast_tcp 41 | 42 | 43 | 44 | /e2vidPacker/AE:o 45 | /e2vid_example_module/AE:i 46 | fast_tcp 47 | 48 | 49 | 50 | /e2vid_example_module/img:o 51 | /op_detector_example_module/img:i 52 | fast_tcp 53 | 54 | 55 | 56 | /op_detector_example_module/img:o 57 | /vFramer/events/frame:i 58 | fast_tcp 59 | 60 | 61 | 62 | /atis3/AE:o 63 | /vFramer/events/AE:i 64 | fast_tcp 65 | 66 | 67 | 68 | /vFramer/events/image:o 69 | /img_vis 70 | fast_tcp 71 | 72 | 73 | 74 | 75 | -------------------------------------------------------------------------------- /example/op_detector_example_module/e2vid/e2vid.py: -------------------------------------------------------------------------------- 1 | 2 | import os 3 | import torch 4 | 5 | from image_reconstructor import ImageReconstructor 6 | from utils.inference_utils import events_to_voxel_grid, events_to_voxel_grid_pytorch 7 | from utils.loading_utils import load_model, get_device 8 | from utils.timers import Timer 9 | 10 | 11 | # global variables 12 | model = None 13 | 14 | 15 | def init_model(config): 16 | global model 17 | model = E2Vid(config) 18 | 19 | 20 | def predict_grayscale_frame(event_window): 21 | global model 22 | return model.predict_grayscale_frame(event_window) 23 | 24 | 25 | class E2Vid: 26 | 27 | def __init__(self, config): 28 | 29 | self.width = config.sensor_width 30 | self.height = config.sensor_height 31 | print('Sensor size: {} x {}'.format(self.width, self.height)) 32 | 33 | self.device = get_device(config.use_gpu) 34 | 35 | self.model = load_model(os.path.join(os.getenv('E2VID_PYTHON_DIR'), 'pretrained/E2VID_lightweight.pth.tar')) 36 | self.model = self.model.to(self.device) 37 | self.model.eval() 38 | 39 | self.reconstructor = ImageReconstructor(self.model, self.height, self.width, self.model.num_bins, config) 40 | 41 | N = config.window_size 42 | if not config.fixed_duration: 43 | if N is None: 44 | N = int(self.width * self.height * config.num_events_per_pixel) 45 | print( 46 | 'Will use {} events per tensor (automatically estimated with num_events_per_pixel={:0.2f}).'.format( 47 | N, config.num_events_per_pixel)) 48 | else: 49 | print('Will use {} events per tensor (user-specified)'.format(N)) 50 | mean_num_events_per_pixel = float(N) / float(self.width * self.height) 51 | if mean_num_events_per_pixel < 0.1: 52 | print('!!Warning!! the number of events used ({}) seems to be low compared to the sensor size. \ 53 | The reconstruction results might be suboptimal.'.format(N)) 54 | elif mean_num_events_per_pixel > 1.5: 55 | print('!!Warning!! the number of events used ({}) seems to be high compared to the sensor size. \ 56 | The reconstruction results might be suboptimal.'.format(N)) 57 | 58 | initial_offset = config.skipevents 59 | sub_offset = config.suboffset 60 | 61 | self.start_index = initial_offset + sub_offset 62 | 63 | self.compute_voxel_grid_on_cpu = config.compute_voxel_grid_on_cpu 64 | if self.compute_voxel_grid_on_cpu: 65 | print('Will compute voxel grid on CPU.') 66 | 67 | def model_share_memory(self): 68 | self.model.share_memory() 69 | 70 | def predict_grayscale_frame(self, event_window): 71 | 72 | last_timestamp = event_window[-1, 0] 73 | 74 | with Timer('Building event tensor'): 75 | if self.compute_voxel_grid_on_cpu: 76 | event_tensor = events_to_voxel_grid(event_window, 77 | num_bins=self.model.num_bins, 78 | width=self.width, 79 | height=self.height) 80 | event_tensor = torch.from_numpy(event_tensor) 81 | else: 82 | event_tensor = events_to_voxel_grid_pytorch(event_window, 83 | num_bins=self.model.num_bins, 84 | width=self.width, 85 | height=self.height, 86 | device=self.device) 87 | 88 | num_events_in_window = event_window.shape[0] 89 | grayscale_frame = self.reconstructor.update_reconstruction(event_tensor, 90 | self.start_index + num_events_in_window, 91 | last_timestamp) 92 | 93 | self.start_index += num_events_in_window 94 | 95 | return grayscale_frame 96 | -------------------------------------------------------------------------------- /example/op_detector_example_module/e2vid/image_reconstructor.py: -------------------------------------------------------------------------------- 1 | 2 | import torch 3 | from model.model import * 4 | from utils.inference_utils import CropParameters, EventPreprocessor, IntensityRescaler, ImageFilter, ImageDisplay, ImageWriter, UnsharpMaskFilter 5 | from utils.inference_utils import upsample_color_image, merge_channels_into_color_image # for color reconstruction 6 | from utils.timers import CudaTimer, cuda_timers 7 | 8 | 9 | class ImageReconstructor: 10 | def __init__(self, model, height, width, num_bins, options): 11 | 12 | self.model = model 13 | self.use_gpu = options.use_gpu 14 | self.device = torch.device('cuda:0') if self.use_gpu else torch.device('cpu') 15 | self.height = height 16 | self.width = width 17 | self.num_bins = num_bins 18 | 19 | self.initialize(self.height, self.width, options) 20 | 21 | def initialize(self, height, width, options): 22 | print('== Image reconstruction == ') 23 | print('Image size: {}x{}'.format(self.height, self.width)) 24 | 25 | self.no_recurrent = options.no_recurrent 26 | if self.no_recurrent: 27 | print('!!Recurrent connection disabled!!') 28 | 29 | self.perform_color_reconstruction = options.color # whether to perform color reconstruction (only use this with the DAVIS346color) 30 | if self.perform_color_reconstruction: 31 | if options.auto_hdr: 32 | print('!!Warning: disabling auto HDR for color reconstruction!!') 33 | options.auto_hdr = False # disable auto_hdr for color reconstruction (otherwise, each channel will be normalized independently) 34 | 35 | self.crop = CropParameters(self.width, self.height, self.model.num_encoders) 36 | 37 | self.last_states_for_each_channel = {'grayscale': None} 38 | 39 | if self.perform_color_reconstruction: 40 | self.crop_halfres = CropParameters(int(width / 2), int(height / 2), 41 | self.model.num_encoders) 42 | for channel in ['R', 'G', 'B', 'W']: 43 | self.last_states_for_each_channel[channel] = None 44 | 45 | self.event_preprocessor = EventPreprocessor(options) 46 | self.intensity_rescaler = IntensityRescaler(options) 47 | self.image_filter = ImageFilter(options) 48 | self.unsharp_mask_filter = UnsharpMaskFilter(options, device=self.device) 49 | self.image_writer = ImageWriter(options) 50 | self.image_display = ImageDisplay(options) 51 | 52 | def update_reconstruction(self, event_tensor, event_tensor_id, stamp=None): 53 | with torch.no_grad(): 54 | 55 | with CudaTimer('Reconstruction'): 56 | 57 | with CudaTimer('NumPy (CPU) -> Tensor (GPU)'): 58 | events = event_tensor.unsqueeze(dim=0) 59 | events = events.to(self.device) 60 | 61 | events = self.event_preprocessor(events) 62 | 63 | # Resize tensor to [1 x C x crop_size x crop_size] by applying zero padding 64 | events_for_each_channel = {'grayscale': self.crop.pad(events)} 65 | reconstructions_for_each_channel = {} 66 | if self.perform_color_reconstruction: 67 | events_for_each_channel['R'] = self.crop_halfres.pad(events[:, :, 0::2, 0::2]) 68 | events_for_each_channel['G'] = self.crop_halfres.pad(events[:, :, 0::2, 1::2]) 69 | events_for_each_channel['W'] = self.crop_halfres.pad(events[:, :, 1::2, 0::2]) 70 | events_for_each_channel['B'] = self.crop_halfres.pad(events[:, :, 1::2, 1::2]) 71 | 72 | # Reconstruct new intensity image for each channel (grayscale + RGBW if color reconstruction is enabled) 73 | for channel in events_for_each_channel.keys(): 74 | with CudaTimer('Inference'): 75 | new_predicted_frame, states = self.model(events_for_each_channel[channel], 76 | self.last_states_for_each_channel[channel]) 77 | 78 | if self.no_recurrent: 79 | self.last_states_for_each_channel[channel] = None 80 | else: 81 | self.last_states_for_each_channel[channel] = states 82 | 83 | # Output reconstructed image 84 | crop = self.crop if channel == 'grayscale' else self.crop_halfres 85 | 86 | # Unsharp mask (on GPU) 87 | new_predicted_frame = self.unsharp_mask_filter(new_predicted_frame) 88 | 89 | # Intensity rescaler (on GPU) 90 | new_predicted_frame = self.intensity_rescaler(new_predicted_frame) 91 | 92 | with CudaTimer('Tensor (GPU) -> NumPy (CPU)'): 93 | reconstructions_for_each_channel[channel] = new_predicted_frame[0, 0, crop.iy0:crop.iy1, 94 | crop.ix0:crop.ix1].cpu().numpy() 95 | 96 | if self.perform_color_reconstruction: 97 | out = merge_channels_into_color_image(reconstructions_for_each_channel) 98 | else: 99 | out = reconstructions_for_each_channel['grayscale'] 100 | 101 | # Post-processing, e.g bilateral filter (on CPU) 102 | out = self.image_filter(out) 103 | 104 | return self.image_display.crop_outer_border(out, self.image_display.border) 105 | -------------------------------------------------------------------------------- /example/op_detector_example_module/e2vid_framer.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | #include 4 | #include 5 | #include 6 | 7 | using namespace ev; 8 | using namespace yarp::os; 9 | using namespace yarp::sig; 10 | 11 | 12 | class e2vidPacker : public RFModule, public Thread { 13 | 14 | private: 15 | deque window_queue; 16 | vReadPort > input_port; 17 | vWritePort output_port; 18 | Stamp yarpstamp; 19 | std::mutex m; 20 | 21 | bool send_update{false}; 22 | int window_size; 23 | 24 | public: 25 | 26 | virtual bool configure(yarp::os::ResourceFinder& rf) 27 | { 28 | //set the module name used to name ports 29 | setName((rf.check("name", Value("/e2vidPacker")).asString()).c_str()); 30 | 31 | /* initialize yarp network */ 32 | if (!yarp::os::Network::checkNetwork(2)) { 33 | std::cout << "Could not connect to YARP" << std::endl; 34 | return false; 35 | } 36 | 37 | //open io ports 38 | if(!input_port.open(getName("/AE:i"))) { 39 | yError() << "Could not open input port"; 40 | return false; 41 | } 42 | 43 | if(!output_port.open(getName("/AE:o"))) { 44 | yError() << "Could not open output port"; 45 | return false; 46 | } 47 | 48 | //read flags and parameters 49 | window_size = rf.check("window", Value(7500)).asInt(); 50 | 51 | //start the asynchronous and synchronous threads 52 | return Thread::start(); 53 | } 54 | 55 | virtual double getPeriod() 56 | { 57 | return 0.2; //period of synchrnous thread 58 | } 59 | 60 | bool interruptModule() 61 | { 62 | //if the module is asked to stop ask the asynchrnous thread to stop 63 | return Thread::stop(); 64 | } 65 | 66 | void onStop() 67 | { 68 | //when the asynchrnous thread is asked to stop, close ports and do 69 | //other clean up 70 | input_port.close(); 71 | output_port.close(); 72 | } 73 | 74 | //synchronous thread 75 | virtual bool updateModule() 76 | { 77 | 78 | m.lock(); 79 | deque fakeq = window_queue; 80 | m.unlock(); 81 | if(send_update && fakeq.size()) 82 | output_port.write(fakeq, yarpstamp); 83 | send_update = false; 84 | 85 | return Thread::isRunning(); 86 | } 87 | 88 | //asynchronous thread run forever 89 | void run() { 90 | 91 | while (true) { 92 | //if(input_port.queryunprocessed() > 10) 93 | // yInfo() << "delay" << input_port.queryunprocessed() << "packets"; 94 | const vector* q = input_port.read(yarpstamp); 95 | if(!q || Thread::isStopping()) return; 96 | 97 | m.lock(); 98 | for (auto& qi : *q) 99 | window_queue.push_back(qi); 100 | 101 | int ntoerase = window_queue.size() - window_size; 102 | if(ntoerase > 0) 103 | window_queue.erase(window_queue.begin(), window_queue.begin()+ntoerase); 104 | send_update = true; 105 | //while(window_queue.size() > window_size) 106 | // window_queue.pop_front(); 107 | m.unlock(); 108 | } 109 | } 110 | }; 111 | 112 | int main(int argc, char * argv[]) 113 | { 114 | /* prepare and configure the resource finder */ 115 | yarp::os::ResourceFinder rf; 116 | rf.configure( argc, argv ); 117 | 118 | /* create the module */ 119 | e2vidPacker instance; 120 | return instance.runModule(rf); 121 | } 122 | -------------------------------------------------------------------------------- /example/op_detector_example_module/op_detector_example_module.cpp: -------------------------------------------------------------------------------- 1 | 2 | #include 3 | #include 4 | #include 5 | #include 6 | #include 7 | #include 8 | 9 | using namespace yarp::os; 10 | using namespace yarp::sig; 11 | 12 | class OPDetectorExampleModule : public RFModule { 13 | 14 | private: 15 | 16 | BufferedPort> input_port; 17 | BufferedPort> output_port_frame; 18 | BufferedPort output_port_skeleton; 19 | 20 | std::string models_path; 21 | std::string pose_model; 22 | 23 | hpecore::OpenPoseDetector detector; 24 | 25 | public: 26 | 27 | OPDetectorExampleModule() {} 28 | 29 | virtual bool configure(yarp::os::ResourceFinder& rf) 30 | { 31 | if (!yarp::os::Network::checkNetwork(2.0)) { 32 | std::cout << "Could not connect to YARP" << std::endl; 33 | return false; 34 | } 35 | //set the module name used to name ports 36 | setName((rf.check("name", Value("/op_detector_example_module")).asString()).c_str()); 37 | 38 | //open io ports 39 | if(!input_port.open(getName() + "/img:i")) { 40 | yError() << "Could not open input port"; 41 | return false; 42 | } 43 | 44 | if(!output_port_frame.open(getName() + "/img:o")) { 45 | yError() << "Could not open output frame port"; 46 | return false; 47 | } 48 | 49 | if(!output_port_skeleton.open(getName() + "/skl:o")) { 50 | yError() << "Could not open output skeleton port"; 51 | return false; 52 | } 53 | 54 | //read flags and parameters 55 | std::string default_models_path = "/openpose/models"; 56 | models_path = rf.check("models_path", Value(default_models_path)).asString(); 57 | 58 | // list of body parts and indexes available here, https://github.com/CMU-Perceptual-Computing-Lab/openpose/blob/master/src/openpose/pose/poseParameters.cpp 59 | // std::string default_pose_model = "BODY_25"; 60 | std::string default_pose_model = "COCO"; 61 | // std::string default_pose_model = "MPI_15"; 62 | pose_model = rf.check("pose_model", Value(default_pose_model)).asString(); 63 | 64 | detector.init(models_path, pose_model); 65 | 66 | return true; 67 | } 68 | 69 | virtual double getPeriod() 70 | { 71 | //run the module as fast as possible. Only as fast as new images are 72 | //available and then limited by how fast OpenPose takes to run 73 | return 0; 74 | } 75 | 76 | bool interruptModule() 77 | { 78 | //if the module is asked to stop ask the asynchronous thread to stop 79 | input_port.interrupt(); 80 | output_port_frame.interrupt(); 81 | output_port_skeleton.interrupt(); 82 | return true; 83 | } 84 | 85 | bool close() 86 | { 87 | //when the asynchronous thread is asked to stop, close ports and do other clean up 88 | detector.stop(); 89 | input_port.close(); 90 | output_port_frame.close(); 91 | output_port_skeleton.close(); 92 | return true; 93 | } 94 | 95 | //synchronous thread 96 | virtual bool updateModule() 97 | { 98 | // read greyscale image from yarp 99 | ImageOf* img_yarp = input_port.read(); 100 | 101 | Stamp timestamp; 102 | input_port.getEnvelope(timestamp); 103 | 104 | if (img_yarp == nullptr) 105 | return false; 106 | 107 | double tic = Time::now(); 108 | static double t_accum = 0.0; 109 | static int t_count = 0; 110 | 111 | //convert image to OpenCV RGB format 112 | cv::Mat img_cv = yarp::cv::toCvMat(*img_yarp); 113 | cv::Mat rgbimage; 114 | cv::cvtColor(img_cv, rgbimage, cv::COLOR_GRAY2BGR); 115 | 116 | //call the openpose detector 117 | hpecore::skeleton13 pose = detector.detect(rgbimage); 118 | 119 | //calculate the running frequency 120 | t_accum += Time::now() - tic; 121 | t_count++; 122 | if(t_accum > 2.0) { 123 | yInfo() << "Running happily at an upper bound of" << (int)(t_count / t_accum) << "Hz"; 124 | t_accum = 0.0; 125 | t_count = 0; 126 | } 127 | 128 | // write openpose's output frame to the output port 129 | output_port_frame.prepare().copy(yarp::cv::fromCvMat(rgbimage)); 130 | output_port_frame.setEnvelope(timestamp); 131 | output_port_frame.write(); 132 | 133 | // write openpose's output skeleton to the output port 134 | 135 | // create a Bottle containing the list of joints coordinates 136 | Bottle coordinates_bottle; 137 | for(auto &t : pose) 138 | { 139 | coordinates_bottle.addInt32(t.u); 140 | coordinates_bottle.addInt32(t.v); 141 | } 142 | 143 | // add the Bottle with the list of coordinates to the output_port Bottle 144 | Bottle& output_bottle = output_port_skeleton.prepare(); 145 | output_bottle.clear(); 146 | output_bottle.addString("SKLT"); 147 | output_bottle.addList() = coordinates_bottle; 148 | output_port_skeleton.setEnvelope(timestamp); 149 | output_port_skeleton.write(); 150 | 151 | // //visualisation 152 | // cv::imshow("OpenPose", rgbimage); 153 | // cv::waitKey(1); 154 | 155 | return true; 156 | } 157 | }; 158 | 159 | int main(int argc, char * argv[]) 160 | { 161 | /* prepare and configure the resource finder */ 162 | yarp::os::ResourceFinder rf; 163 | rf.setVerbose( false ); 164 | rf.configure( argc, argv ); 165 | 166 | /* create the module */ 167 | OPDetectorExampleModule instance; 168 | return instance.runModule(rf); 169 | } 170 | -------------------------------------------------------------------------------- /example/reprojection_test/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | # requires minimum cmake version 2 | cmake_minimum_required(VERSION 3.5) 3 | 4 | # produce the cmake var PROJECT_NAME 5 | project(reproj-test) 6 | 7 | #find_package(YCM REQUIRED) 8 | find_package(hpe-core REQUIRED) 9 | 10 | #default the install location to that of event-driven 11 | 12 | add_executable(${PROJECT_NAME} test.cpp) 13 | 14 | target_link_libraries(${PROJECT_NAME} PRIVATE hpe-core::hpe-core) 15 | 16 | 17 | -------------------------------------------------------------------------------- /example/reprojection_test/test.cpp: -------------------------------------------------------------------------------- 1 | /* BSD 3-Clause License 2 | 3 | Copyright (c) 2023, Event Driven Perception for Robotics 4 | All rights reserved. 5 | 6 | Redistribution and use in source and binary forms, with or without 7 | modification, are permitted provided that the following conditions are met: 8 | 9 | 1. Redistributions of source code must retain the above copyright notice, this 10 | list of conditions and the following disclaimer. 11 | 12 | 2. Redistributions in binary form must reproduce the above copyright notice, 13 | this list of conditions and the following disclaimer in the documentation 14 | and/or other materials provided with the distribution. 15 | 16 | 3. Neither the name of the copyright holder nor the names of its 17 | contributors may be used to endorse or promote products derived from 18 | this software without specific prior written permission. 19 | 20 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 21 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 22 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 23 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE 24 | FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL 25 | DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR 26 | SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 27 | CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, 28 | OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE 29 | OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. */ 30 | 31 | #include 32 | #include 33 | #include 34 | 35 | int main(int argc, char * argv[]) 36 | { 37 | static const int w = 640; 38 | static const int h = 480; 39 | static const int w2 = 960; 40 | static const int h2 = 540; 41 | 42 | static constexpr double theta = 45 * M_PI / 180.0; 43 | 44 | 45 | 46 | hpecore::skeletonCFT mycft; 47 | 48 | 49 | 50 | mycft.setCam1Parameters({w, h, w/2, h/2}, {320, 320, -0.2, 0}); 51 | mycft.setCam2Parameters({w2, h2, w2/2, h2/2}, {400, 400, -0.2, 0}); 52 | mycft.setExtrinsicTransform({cos(theta), 0, -sin(theta), 2, 53 | 0, 1, 0, 0.2, 54 | sin(theta), 0, cos(theta), 1, 55 | 0, 0, 0, 1}); 56 | 57 | //mycft.setExtrinsicTransform({0.999946, 0.0046135, 0.00935247, 0.019063, -0.0047823, 0.999825, 0.0181072, 0.0977093, -0.00926729, -0.0181509, 0.999792, 0.114073, 0, 0, 0, 1}); 58 | 59 | cv::Mat img = cv::Mat::zeros(h, w, CV_8UC3); 60 | cv::Mat img2 = cv::Mat::zeros(h2, w2, CV_8UC3); 61 | //cv::Mat output_image = cv::Mat::zeros(w, h, CV_8U); 62 | 63 | hpecore::skeleton13 js = {0}; 64 | js[0] = {308, 89}; js[1] = {279, 113}; js[2] = {323, 119}; 65 | js[3] = {323, 119}; js[4] = {267, 144}; js[5] = {334, 170}; 66 | js[6] = {328, 209}; js[7] = {292, 211}; js[8] = {308, 122}; 67 | js[9] = {341, 213}; js[10] = {293, 301}; js[11] = {326, 300}; 68 | js[12] = {282, 391}; 69 | 70 | auto out = mycft.cft(js, 3); 71 | 72 | hpecore::drawSkeleton(img, js, {0, 0, 200}); 73 | hpecore::drawSkeleton(img2, out, {200, 0, 200}); 74 | 75 | 76 | 77 | cv::imshow("Transform", img); 78 | cv::imshow("Transform2", img2); 79 | cv::waitKey(10000); 80 | 81 | return 0; 82 | } -------------------------------------------------------------------------------- /example/yarp-glhpe/.gitignore: -------------------------------------------------------------------------------- 1 | venv/ 2 | build/ 3 | tester.py 4 | app_yarp-glhpe_local.xml 5 | test_eval_glhpe.py 6 | -------------------------------------------------------------------------------- /example/yarp-glhpe/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | # requires minimum cmake version 2 | cmake_minimum_required(VERSION 3.5) 3 | 4 | # produce the cmake var PROJECT_NAME 5 | project(glhpe-framer) 6 | 7 | #find_package(YCM REQUIRED) 8 | find_package(YARP COMPONENTS os sig REQUIRED) 9 | find_package(event-driven REQUIRED) 10 | find_package(hpe-core REQUIRED) 11 | 12 | #default the install location to that of event-driven 13 | 14 | add_executable(${PROJECT_NAME} glhpe-framer.cpp) 15 | 16 | target_link_libraries(${PROJECT_NAME} PRIVATE YARP::YARP_os 17 | YARP::YARP_init 18 | ev::event-driven 19 | hpe-core::hpe-core) 20 | 21 | install(TARGETS ${PROJECT_NAME} DESTINATION ${CMAKE_INSTALL_BINDIR}) 22 | 23 | -------------------------------------------------------------------------------- /example/yarp-glhpe/README.md: -------------------------------------------------------------------------------- 1 | 2 | # GL-HPE Example 3 | Online setup of the [Lifting events to 3D HPE](https://github.com/IIT-PAVIS/lifting_events_to_3d_hpe) program with a YARP input setup. 4 | 5 | 6 | The application has been designed to run using docker for simple set-up of the environment. 7 | 8 | ## Installation 9 | The software was tested on Ubuntu 20.04.2 LTS without GPU support. 10 | 11 | - Download the repository and build the Docker image 12 | ```shell 13 | $ cd 14 | $ git clone git@github.com:event-driven-robotics/hpe-core.git 15 | $ cd hpe-core/example/yarp_glhpe 16 | $ docker build -t gl_hpe:yarp - < Dockerfile 17 | ``` 18 | :bulb: `` is the parent directory in which the repository is cloned 19 | 20 | ## Usage 21 | - Download the pre-trained model from [here](https://drive.google.com/drive/folders/1AgsQl6sTJBygPvgbdR1e9IfVAYxupMGI) and store it into folder `/path/to/pre/trained/model/folder` 22 | - Run the Docker container 23 | ```shell 24 | $ xhost + 25 | $ docker run -it -v /tmp/.X11-unix/:/tmp/.X11-unix -v /path/to/pre/trained/model/folder:/usr/local/code/gl_hpe/checkpoint/ -e DISPLAY=unix$DISPLAY gl_hpe:yarp bash 26 | ``` 27 | 28 | - At the terminal inside the container run the following commands 29 | ```shell 30 | $ yarpserver & 31 | $ yarpmanager 32 | ``` 33 | :warning: the `&` runs the process in the background enabling a single terminal to run both processes. 34 | 35 | - In the `yarpmanager`, load the application by opening `/usr/local/code/hpe-core/example/yarp-glhpe/app_yarp-glhpe.xml` 36 | and run all modules (the first time the python script `yarp-glhpe/run-model.py` runs, it downloads an additional pre-trained 37 | model for the backbone CNN which, according to the connection speed, might take several minutes and prevent pose prediction 38 | until it has finished) 39 | 40 | - In the `yarpdataplayer` GUI use the drop-down menus to load the test dataset by opening folder `/usr/local/code/hpe-core/example/test_dataset` and play it 41 | 42 | - Connect all connections in the `yarpmanager` 43 | 44 | - A new window will pop up and display the detected skeleton overlaid on the event frames 45 | -------------------------------------------------------------------------------- /example/yarp-glhpe/app_yarp-glhpe.xml: -------------------------------------------------------------------------------- 1 | 2 | yarp-glhpe 3 | 4 | 5 | 6 | 7 | 8 | yarpview 9 | --name /yarpview/img:i --synch 10 | localhost 11 | 12 | 13 | 14 | /usr/local/code/hpe-core/example/yarp-glhpe/build/./glhpe-framer 15 | --name /glhpe-framer 16 | localhost 17 | 18 | 19 | 20 | python3 /usr/local/code/hpe-core/example/yarp-glhpe/run-model.py 21 | --name /glhpeModule 22 | localhost 23 | 24 | 25 | 26 | yarpdataplayer 27 | --name /yarpdataplayer 28 | localhost 29 | 30 | 31 | 32 | /file/ch3dvs:o 33 | /glhpe-framer/AE:i 34 | fast_tcp 35 | 36 | 37 | 38 | /glhpe-framer/img:o 39 | /glhpeModule/img:i 40 | fast_tcp 41 | 42 | 43 | 44 | /glhpe-framer/img:o 45 | /yarpview/img:i 46 | fast_tcp 47 | 48 | 49 | 50 | -------------------------------------------------------------------------------- /example/yarp-glhpe/glhpe-framer.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | #include 4 | #include 5 | #include 6 | #include 7 | 8 | using namespace ev; 9 | using namespace yarp::os; 10 | using namespace yarp::sig; 11 | 12 | 13 | class glhpewindower : public RFModule, public Thread { 14 | 15 | private: 16 | deque window_queue; 17 | vReadPort > input_port; 18 | BufferedPort > output_port; 19 | std::mutex m; 20 | 21 | int window_size; 22 | resolution res; 23 | Stamp yarpstamp; 24 | 25 | public: 26 | 27 | glhpewindower() {} 28 | 29 | virtual bool configure(yarp::os::ResourceFinder& rf) 30 | { 31 | //set the module name used to name ports 32 | setName((rf.check("name", Value("/glhpewindow")).asString()).c_str()); 33 | 34 | /* initialize yarp network */ 35 | yarp::os::Network yarp; 36 | if(!yarp.checkNetwork(2.0)) { 37 | std::cout << "Could not connect to YARP" << std::endl; 38 | return false; 39 | } 40 | 41 | //open io ports 42 | if(!input_port.open(getName("/AE:i"))) { 43 | yError() << "Could not open input port"; 44 | return false; 45 | } 46 | 47 | if(!output_port.open(getName("/img:o"))) { 48 | yError() << "Could not open output port"; 49 | return false; 50 | } 51 | 52 | //read flags and parameters 53 | window_size = rf.check("window", Value(7500)).asInt(); 54 | res.height = rf.check("height", Value(300)).asInt(); 55 | res.width = rf.check("width", Value(400)).asInt(); 56 | 57 | //start the asynchronous and synchronous threads 58 | return Thread::start(); 59 | } 60 | 61 | virtual double getPeriod() 62 | { 63 | return 0.1; //period of synchrnous thread 64 | } 65 | 66 | bool interruptModule() 67 | { 68 | //if the module is asked to stop ask the asynchrnous thread to stop 69 | return Thread::stop(); 70 | } 71 | 72 | void onStop() 73 | { 74 | //when the asynchrnous thread is asked to stop, close ports and do 75 | //other clean up 76 | input_port.close(); 77 | output_port.close(); 78 | } 79 | 80 | //synchronous thread 81 | virtual bool updateModule() 82 | { 83 | //add any synchronous operations here, visualisation, debug out prints 84 | //ImageOf &image = output_port.prepare(); 85 | //image.resize(res.width, res.height); 86 | //image.zero(); 87 | 88 | cv::Mat cv_image(res.height, res.width, CV_8U); 89 | 90 | m.lock(); 91 | hpecore::createCountImage(window_queue, cv_image); 92 | m.unlock(); 93 | hpecore::varianceNormalisation(cv_image); 94 | 95 | output_port.setEnvelope(yarpstamp); 96 | output_port.prepare().copy(yarp::cv::fromCvMat(cv_image)); 97 | output_port.write(); 98 | return Thread::isRunning(); 99 | } 100 | 101 | //asynchronous thread run forever 102 | void run() { 103 | 104 | while (true) { 105 | const vector* q = input_port.read(yarpstamp); 106 | if(!q || Thread::isStopping()) return; 107 | 108 | m.lock(); 109 | for (auto& qi : *q) 110 | window_queue.push_back(qi); 111 | 112 | while(window_queue.size() > window_size) 113 | window_queue.pop_front(); 114 | m.unlock(); 115 | } 116 | } 117 | }; 118 | 119 | int main(int argc, char * argv[]) 120 | { 121 | /* initialize yarp network */ 122 | yarp::os::Network yarp; 123 | if(!yarp.checkNetwork(2)) { 124 | std::cout << "Could not connect to YARP" << std::endl; 125 | return false; 126 | } 127 | 128 | /* prepare and configure the resource finder */ 129 | yarp::os::ResourceFinder rf; 130 | rf.configure( argc, argv ); 131 | 132 | /* create the module */ 133 | glhpewindower instance; 134 | return instance.runModule(rf); 135 | } 136 | -------------------------------------------------------------------------------- /pycore/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/event-driven-robotics/hpe-core/178ac06fbf35f4b6ea9aca1a2a35bb6906b35213/pycore/__init__.py -------------------------------------------------------------------------------- /pycore/moveenet/__init__.py: -------------------------------------------------------------------------------- 1 | """ 2 | @Fire 3 | https://github.com/fire717 4 | """ 5 | import os 6 | 7 | from pycore.moveenet.data.data import Data 8 | from pycore.moveenet.models.movenet_mobilenetv2 import MoveNet 9 | from pycore.moveenet.task.task import Task 10 | 11 | 12 | from pycore.moveenet.utils.utils import setRandomSeed, printDash 13 | 14 | 15 | def init(cfg): 16 | 17 | if cfg["cfg_verbose"]: 18 | printDash() 19 | print(cfg) 20 | printDash() 21 | 22 | 23 | 24 | os.environ["CUDA_VISIBLE_DEVICES"] = cfg['GPU_ID'] 25 | setRandomSeed(cfg['random_seed']) 26 | 27 | 28 | # 29 | # if not os.path.exists(cfg['save_dir']): 30 | # os.makedirs(cfg['save_dir']) -------------------------------------------------------------------------------- /pycore/moveenet/config.py: -------------------------------------------------------------------------------- 1 | """ 2 | @Fire 3 | https://github.com/fire717 4 | """ 5 | 6 | cfg = { 7 | ##### Global Setting 8 | 'GPU_ID': '0,1', 9 | "num_workers": 4, 10 | "random_seed": 42, 11 | "cfg_verbose": True, 12 | "save_dir": '', 13 | "num_classes": 13, 14 | "width_mult": 1.0, 15 | "img_size": 192, 16 | 'label': '', 17 | 18 | ##### Train Setting 19 | 'pre-separated_data': True, 20 | 'training_data_split': 80, 21 | "dataset": '', 22 | 'balance_data': False, 23 | 'log_interval': 10, 24 | 'save_best_only': False, 25 | 26 | 'pin_memory': True, 27 | 'newest_ckpt': '', 28 | 'th': 50, # percentage of headsize 29 | 'from_scratch': True, 30 | 31 | ##### Train Hyperparameters 32 | 'learning_rate': 0.001, # 1.25e-4 33 | 'batch_size': 64, 34 | 'epochs': 300, 35 | 'optimizer': 'Adam', # Adam SGD 36 | 'scheduler': 'MultiStepLR-70,100-0.1', # default SGDR-5-2 CVPR step-4-0.8 MultiStepLR 37 | # multistepLR-<<>milestones>-<> 38 | 'weight_decay': 0.001, # 5.e-4, # 0.0001, 39 | 'class_weight': None, # [1., 1., 1., 1., 1., 1., 1., ] 40 | 'clip_gradient': 5, # 1, 41 | 'w_heatmap': 1, 42 | 'w_bone': 20, 43 | 'w_center': 1, 44 | 'w_reg': 3, 45 | 'w_offset': 1, 46 | 47 | ##### File paths 48 | 'predict_output_path': '', 49 | 'results_path': '', 50 | "img_path": '', 51 | "test_img_path": '', 52 | "eval_img_path": '', 53 | "eval_outputs": '', 54 | "eval_label_path": '', 55 | 'train_label_path': '', 56 | 'val_label_path': '', 57 | 'ckpt': '' 58 | } 59 | 60 | -------------------------------------------------------------------------------- /pycore/moveenet/data/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/event-driven-robotics/hpe-core/178ac06fbf35f4b6ea9aca1a2a35bb6906b35213/pycore/moveenet/data/__init__.py -------------------------------------------------------------------------------- /pycore/moveenet/data/center_weight_origin.npy: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/event-driven-robotics/hpe-core/178ac06fbf35f4b6ea9aca1a2a35bb6906b35213/pycore/moveenet/data/center_weight_origin.npy -------------------------------------------------------------------------------- /pycore/moveenet/data/data.py: -------------------------------------------------------------------------------- 1 | """ 2 | @Fire 3 | https://github.com/fire717 4 | """ 5 | import os 6 | import random 7 | import numpy as np 8 | import json 9 | import copy 10 | 11 | from pycore.moveenet.data.data_tools import getDataLoader, getFileNames 12 | from pycore.moveenet.task.task_tools import movenetDecode 13 | 14 | 15 | class Data(): 16 | def __init__(self, cfg): 17 | 18 | self.cfg = cfg 19 | 20 | def dataBalance(self, data_list): 21 | """ 22 | item = { 23 | "img_name":save_name, 24 | "keypoints":save_keypoints, 25 | [左手腕,左手肘,左肩,头,右肩,右手肘,右手腕] 26 | "center":save_center, 27 | "other_centers":other_centers, 28 | "other_keypoints":other_keypoints, 29 | } 30 | """ 31 | new_data_list = copy.deepcopy(data_list) 32 | 33 | count1 = 0 34 | count2 = 0 35 | count3 = 0 36 | count4 = 0 37 | for item in data_list: 38 | keypoints = item['keypoints'] 39 | 40 | kpt_np = np.array(keypoints).reshape((-1, 3)) 41 | kpt_np_valid = kpt_np[kpt_np[:, 2] > 0] 42 | 43 | w = np.max(kpt_np_valid[:, 0]) - np.min(kpt_np_valid[:, 0]) 44 | h = np.max(kpt_np_valid[:, 1]) - np.min(kpt_np_valid[:, 1]) 45 | 46 | if (kpt_np[1][1] > kpt_np[0][1] and kpt_np[1][1] > kpt_np[2][1]) or \ 47 | (kpt_np[5][1] > kpt_np[6][1] and kpt_np[5][1] > kpt_np[4][1]): 48 | count1 += 1 49 | print(item) 50 | for i in range(2): 51 | new_data_list.append(item) 52 | 53 | if kpt_np[2][0] - kpt_np[4][0] < \ 54 | max(kpt_np[1][1] - kpt_np[2][1], kpt_np[5][1] - kpt_np[4][1]): 55 | count2 += 1 56 | 57 | for i in range(2): 58 | new_data_list.append(item) 59 | 60 | if (kpt_np[1][1] < kpt_np[2][1]) or \ 61 | (kpt_np[5][1] < kpt_np[4][1]): 62 | count3 += 1 63 | 64 | for i in range(5): 65 | new_data_list.append(item) 66 | 67 | if h < w: 68 | count4 += 1 69 | for i in range(3): 70 | new_data_list.append(item) 71 | 72 | print(count1, count2, count3, count4) 73 | 74 | random.shuffle(new_data_list) 75 | return new_data_list 76 | 77 | 78 | def getEvalDataloader(self): 79 | with open(self.cfg['eval_label_path'], 'r') as f: 80 | data_label_list = json.loads(f.readlines()[0]) 81 | 82 | print("[INFO] Total images: ", len(data_label_list)) 83 | 84 | input_data = [data_label_list] 85 | data_loader = getDataLoader("eval", 86 | input_data, 87 | self.cfg) 88 | return data_loader 89 | 90 | def getTestDataloader(self): 91 | data_names = getFileNames(self.cfg['test_img_path']) 92 | test_loader = getDataLoader("test", 93 | data_names, 94 | self.cfg) 95 | return test_loader 96 | -------------------------------------------------------------------------------- /pycore/moveenet/loss/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/event-driven-robotics/hpe-core/178ac06fbf35f4b6ea9aca1a2a35bb6906b35213/pycore/moveenet/loss/__init__.py -------------------------------------------------------------------------------- /pycore/moveenet/models/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/event-driven-robotics/hpe-core/178ac06fbf35f4b6ea9aca1a2a35bb6906b35213/pycore/moveenet/models/__init__.py -------------------------------------------------------------------------------- /pycore/moveenet/task/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/event-driven-robotics/hpe-core/178ac06fbf35f4b6ea9aca1a2a35bb6906b35213/pycore/moveenet/task/__init__.py -------------------------------------------------------------------------------- /pycore/moveenet/utils/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/event-driven-robotics/hpe-core/178ac06fbf35f4b6ea9aca1a2a35bb6906b35213/pycore/moveenet/utils/__init__.py -------------------------------------------------------------------------------- /pycore/moveenet/utils/metrics.py: -------------------------------------------------------------------------------- 1 | """ 2 | @Fire 3 | https://github.com/fire717 4 | """ 5 | import numpy as np 6 | 7 | # from config import cfg 8 | 9 | 10 | def getDist(pre, labels,num_classes = 13): 11 | """ 12 | input: 13 | pre: [batchsize, 14] 14 | labels: [batchsize, 14] 15 | return: 16 | dist: [batchsize, 7] 17 | """ 18 | pre = pre.reshape([-1, num_classes, 2]) 19 | labels = labels.reshape([-1, num_classes, 2]) 20 | res = np.power(pre[:, :, 0] - labels[:, :, 0], 2) + np.power(pre[:, :, 1] - labels[:, :, 1], 2) 21 | return res 22 | 23 | 24 | def getAccRight(dist, th): 25 | """ 26 | input: 27 | dist: [batchsize, 7] 28 | 29 | return: 30 | dist: [7,] right count of every point 31 | """ 32 | res = np.zeros(dist.shape[1], dtype=np.int64) 33 | for i in range(dist.shape[1]): 34 | res[i] = sum(dist[:, i] < th) 35 | 36 | return res 37 | 38 | 39 | def myAcc(output, target, th=0.5, num_classes = 13): 40 | """ 41 | return [7,] ndarray 42 | """ 43 | # print(output.shape) 44 | # 64, 7, 40, 40 gaussian 45 | # (64, 14) !gaussian 46 | # b 47 | # if hm_type == 'gaussian': 48 | if len(output.shape) == 4: 49 | output = heatmap2locate(output) 50 | target = heatmap2locate(target) 51 | 52 | # offset方式还原坐标 53 | # [h, ls, rs, lb, rb, lr, rr] 54 | # output[:,6:10] = output[:,6:10]+output[:,2:6] 55 | # output[:,10:14] = output[:,10:14]+output[:,6:10] 56 | 57 | dist = getDist(output, target,num_classes) 58 | cate_acc = getAccRight(dist,th) 59 | return cate_acc 60 | 61 | 62 | def pck(output, target, limb_length, threshold=None, num_classes=13, mode='head'): 63 | if output.size % 3 == 0: 64 | dim = 3 65 | else: 66 | dim = 2 67 | if threshold is None: 68 | if mode == 'head': # for MPII dataset 69 | threshold = 0.5 70 | elif mode == 'torso': # for H36M and DHP19 71 | threshold = 0.2 72 | else: 73 | print("Invalid accuracy model") 74 | return None 75 | 76 | if len(output.shape) == 4: 77 | output = heatmap2locate(output) 78 | target = heatmap2locate(target) 79 | 80 | pck={} 81 | # print(torso_diameter) 82 | # compute PCK's threshold as percentage of head size in pixels for each pose 83 | 84 | 85 | # compute euclidean distances between joints 86 | output = output.reshape((-1,num_classes,dim))[:,:,:2] 87 | target = target.reshape((-1,num_classes,2)) 88 | distances = np.linalg.norm( output - target , axis=2) 89 | 90 | try: 91 | thresholds_val = limb_length * threshold 92 | except TypeError: 93 | print('The data type of the length of thresholding limb is incompatible:', type(limb_length)) 94 | print('All thresholds in the batch set to zero.') 95 | thresholds_val = np.zeros([output.shape[0]]) 96 | 97 | 98 | # compute correct keypoints 99 | th_head_expanded = thresholds_val.unsqueeze(1).expand(-1,distances.shape[1]) 100 | correct_keypoints = (distances <= th_head_expanded.numpy()).astype(int) 101 | 102 | # remove not annotated keypoints from pck computation 103 | correct_keypoints = correct_keypoints * (target[:, :, 0] != -1).astype(int) 104 | annotated_keypoints_num_samples = np.sum((target[:, :, 0] != -1).astype(int), axis=1) 105 | annotated_keypoints_num_joints = np.sum((target[:, :, 0] != -1).astype(int), axis=0) 106 | # print("correct_keypoints: ",correct_keypoints.shape) 107 | # print("annotated_keypoints_num: ",annotated_keypoints_num.shape) 108 | 109 | # compute pck in all different formats 110 | pck_per_joint = np.sum(correct_keypoints, axis=0) / annotated_keypoints_num_joints 111 | pck_per_sample = np.sum(correct_keypoints, axis=1) / annotated_keypoints_num_samples 112 | # pck_per_keypoint = sum(sum(correct_keypoints))/ sum(annotated_keypoints_num_joints) 113 | pck["correct_per_sample"] = np.sum(correct_keypoints, axis=1) 114 | pck["correct_per_joint"] = np.sum(correct_keypoints, axis=0) 115 | pck["per_joint_mean"] = np.mean(pck_per_joint) 116 | pck["per_sample_mean"] = np.mean(pck_per_sample) 117 | pck["total_keypoints"] = sum(annotated_keypoints_num_joints) 118 | pck["anno_keypoints_per_joint"] = annotated_keypoints_num_joints 119 | pck["anno_keypoints_per_sample"] = annotated_keypoints_num_samples 120 | pck["total_correct"] = sum(sum(correct_keypoints)) 121 | 122 | # print(pck) 123 | # print(pck_joints) 124 | 125 | return pck 126 | -------------------------------------------------------------------------------- /pycore/movenet_rgb/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/event-driven-robotics/hpe-core/178ac06fbf35f4b6ea9aca1a2a35bb6906b35213/pycore/movenet_rgb/__init__.py -------------------------------------------------------------------------------- /pycore/movenet_rgb/constants.py: -------------------------------------------------------------------------------- 1 | 2 | # Dictionary that maps from joint names to keypoint indices. 3 | 4 | KEYPOINT_DICT = { 5 | 'nose': 0, 6 | 'left_eye': 1, 7 | 'right_eye': 2, 8 | 'left_ear': 3, 9 | 'right_ear': 4, 10 | 'left_shoulder': 5, 11 | 'right_shoulder': 6, 12 | 'left_elbow': 7, 13 | 'right_elbow': 8, 14 | 'left_wrist': 9, 15 | 'right_wrist': 10, 16 | 'left_hip': 11, 17 | 'right_hip': 12, 18 | 'left_knee': 13, 19 | 'right_knee': 14, 20 | 'left_ankle': 15, 21 | 'right_ankle': 16 22 | } 23 | 24 | 25 | # Maps bones to a matplotlib color name. 26 | KEYPOINT_EDGE_INDS_TO_COLOR = { 27 | (0, 1): 'm', 28 | (0, 2): 'c', 29 | (1, 3): 'm', 30 | (2, 4): 'c', 31 | (0, 5): 'm', 32 | (0, 6): 'c', 33 | (5, 7): 'm', 34 | (7, 9): 'm', 35 | (6, 8): 'c', 36 | (8, 10): 'c', 37 | (5, 6): 'y', 38 | (5, 11): 'm', 39 | (6, 12): 'c', 40 | (11, 12): 'y', 41 | (11, 13): 'm', 42 | (13, 15): 'm', 43 | (12, 14): 'c', 44 | (14, 16): 'c' 45 | } -------------------------------------------------------------------------------- /pycore/movenet_rgb/run_movenet.py: -------------------------------------------------------------------------------- 1 | import tensorflow as tf 2 | import tensorflow_hub as hub 3 | 4 | import numpy as np 5 | import argparse 6 | import cv2, csv, time, os 7 | from funcs import movenet, _keypoints_and_edges_for_display, draw_prediction_on_image 8 | 9 | # from datasets.h36m.utils.parsing import movenet_to_hpecore 10 | 11 | from pycore.moveenet.visualization.visualization import add_skeleton, movenet_to_hpecore 12 | from pycore.moveenet.utils.utils import ensure_loc 13 | from datasets.utils.export import str2bool 14 | 15 | def get_movenet_13(pose_17): 16 | assert pose_17.shape == (17,2) 17 | pose_13 = pose_17[4:,:] 18 | pose_13[0,:] = pose_17[0,:] 19 | return pose_13 20 | 21 | def write_results(path, row): 22 | # Write a data point into a csvfile 23 | with open(path, 'a') as f: 24 | writer = csv.writer(f, delimiter=' ') 25 | writer.writerow(row) 26 | 27 | 28 | def create_row(ts, skt, delay=0.0): 29 | # Function to create a row to be written into a csv file. 30 | row = [] 31 | ts = float(ts) 32 | row.extend([ts, delay]) 33 | row.extend(skt) 34 | return row 35 | 36 | def main(args): 37 | model_name = "movenet_lightning" #@param ["movenet_lightning", "movenet_thunder", "movenet_lightning_f16.tflite", "movenet_thunder_f16.tflite", "movenet_lightning_int8.tflite", "movenet_thunder_int8.tflite"] 38 | 39 | if "movenet_lightning" in model_name: 40 | module = hub.load("https://tfhub.dev/google/movenet/singlepose/lightning/4") 41 | input_size = 192 42 | elif "movenet_thunder" in model_name: 43 | module = hub.load("https://tfhub.dev/google/movenet/singlepose/thunder/4") 44 | input_size = 256 45 | else: 46 | raise ValueError("Unsupported model name: %s" % model_name) 47 | 48 | # if args.dev: 49 | # video_path = "/home/ggoyal/data/h36m_cropped/cropped_video/cam2_S9_Directions.mp4" 50 | # write_csv = "/home/ggoyal/data/results/tester/cam2_S9_Directions/movenet_rgb.csv" 51 | # else: 52 | video_path=args.input 53 | write_csv = args.output 54 | cap = cv2.VideoCapture(video_path) 55 | fps = cap.get(cv2.CAP_PROP_FPS) 56 | 57 | # Check if camera opened successfully 58 | if (cap.isOpened() == False): 59 | print("Error opening video stream or file") 60 | filename = os.path.basename(video_path).split('.')[0] 61 | # Read until video is completed 62 | fi = 0 63 | while (cap.isOpened()): 64 | # Capture frame-by-frame 65 | ret, frame = cap.read() 66 | if ret == True: 67 | height, width, _ = frame.shape 68 | image = tf.convert_to_tensor(frame, dtype=tf.uint8) 69 | # Resize and pad the image to keep the aspect ratio and fit the expected size. 70 | input_image = tf.expand_dims(image, axis=0) 71 | input_image = tf.image.resize(input_image, [input_size, input_size]) 72 | ts = cap.get(cv2.CAP_PROP_POS_MSEC)/1000 73 | 74 | start_sample = time.time() 75 | keypoints_with_scores = movenet(input_image, module) 76 | (keypoint_locs, keypoint_edges, 77 | edge_colors) = _keypoints_and_edges_for_display( 78 | keypoints_with_scores, height, width,0) 79 | keypoint_locs_13 = get_movenet_13(keypoint_locs) 80 | kps_hpecore = movenet_to_hpecore(keypoint_locs_13) 81 | kps_pre_hpecore = np.reshape(kps_hpecore, [-1]) 82 | if args.dev or args.save_image: 83 | for i in range(len(keypoint_locs_13[:])): 84 | frame = add_skeleton(frame, kps_pre_hpecore, (0, 0, 255), True, normalised=False) 85 | # pre = keypoint_locs_13 86 | # x = int(pre[i,0]) 87 | # y = int(pre[i,1]) 88 | # cv2.circle(frame, (x, y), 3, (0, 0, 255), 3) # predicted keypoints in red 89 | if args.dev: 90 | cv2.imshow('Frame', frame) 91 | if cv2.waitKey(25) & 0xFF == ord('q'): 92 | break 93 | if args.save_image: 94 | ensure_loc(os.path.dirname(args.save_image)) 95 | cv2.imwrite(os.path.join(args.save_image, f'{filename}_{fi:04d}.jpg'), frame) 96 | 97 | if args.output: 98 | 99 | row = create_row(ts, kps_pre_hpecore, delay=time.time() - start_sample) 100 | ensure_loc(os.path.dirname(write_csv)) 101 | write_results(write_csv, row) 102 | fi+=1 103 | 104 | # Break the loop 105 | else: 106 | break 107 | if args.stop: 108 | if fi > args.stop: 109 | break 110 | 111 | # When everything done, release the video capture object 112 | cap.release() 113 | 114 | # Closes all the frames 115 | cv2.destroyAllWindows() 116 | 117 | 118 | if __name__ == '__main__': 119 | 120 | parser = argparse.ArgumentParser() 121 | parser.add_argument('-input', help='Path to sample', default='', type=str) 122 | parser.add_argument('-output', help='Path to csv file', default=None, type=str) 123 | parser.add_argument('-save_image', help='Path to image folder', default=None, type=str) 124 | parser.add_argument("-dev", type=str2bool, nargs='?', const=True, default=False, help="Set for visualisation mode.") 125 | parser.add_argument("-stop", type=str, default=None, help="early stop.") 126 | 127 | args = parser.parse_args() 128 | main(args) --------------------------------------------------------------------------------