未验证 提交 62eebd63 编写于 作者: G Gines 提交者: GitHub

Accumulated improvements and bug fixes (#675)

* Adam added

* Cleaned adam.cpp

* Added BVH file writer

* Finished adam.cpp

* Bvh and adam mesh avi with flags

* reverse X

* fix left/right, write right first

* adding additional left_hand/right_hand

* fix left_hand/right_hand

* Forward Kinematics with Derivative

* Pulled from official hand_model

* BVH file duplicated

* Removed warnings

* Updated Adam

* x10 IK speed up

* Speed up for not computing Jac + smarter Jac copy

* Merged official with OP_adam

* Speed up of rendering and multi-thread with IK

* Updated from hand_model branch

* Cleaner examples

* Fixed new scale

* transmit json

* Cleaner adam.cpp

* Change

* Better doc

* Updated Adam code

* Working with latest code

* add foot fitting, head orientation fitting, set verbose for fitting

* Face also fitted

* t-pose improved

* small regularization for fingers

* Added extra wrist-fitting

* mouth/eyes openness

* Adam keeps last known 5 frames

* setting flags for init output, rendering options

* set a flag for zoom in

* Cleaner code

* Cleaner adam.cpp

* Fixed typo

* dist from root to foot

* AdamFast multi-threaded

* Added new element

* Cleaner code

* Cleaned warnings + less params shared

* Almost multi-threaded

* JointAngleEstimation class

* Adam mostly integrated inside OpenPose

* Recovered forgotten changes

* Write video as Adam added

* BVH writer as class

* So Adam.cpp directly runs

* Cleaner code

* Updated code

* Face and hand can be disabled

* Switched shorcuts for channel selection

* Notify user when pose value changes

* BODY_25 as main one

* BODY_25 as main one

* Flag write_keypoint_json removed

* Foot also fit

* keep preivous param when joint target missing

* Freeze last known pose by default

* Added final BODY_25 model

* adam facial expression

* show_joint turn off everything

* Mini-bug fixed in wrapper

* Deprecated issue solved

* Adam_fast_fit_init speed up

* Donglai's advice

* optional face fitting/joint angle keeping for arm only/multistage fitting flag

* Fast solver option

* Latest adam.cpp

* Asio removed

* Better doc

* Improved calib

* Cleaned SPinnaker

* add a hand_enabled flag in Adam_FastFit_Initialized

* remove extra transpose & 180d rotation in BVHWriter

* UDP as own class

* Fixed bug

* Renamed some flags

* Faster 3d triangulation with outlier warning

* 3-D only if accurated enough

* More strict outlier detection + incorporated handEnabled flag from IK

* Non-linear 3d keypoint not done if outlier

* Added BODY_65

* BODY_65 & visualization working

* save computation when rigid body

* joint angle keeping for knees & joint angle keeping trick for leg again

* BODY_25 auto-downloaded

* Cleanring eigen

* Git pulled

* cut face fitting time by half

* BODY_65 support for Adam

* Updated doc

* Ransac added but commented out

* Ransac working

* RANSaC improved

* fix face fitting out of bound error

* No weird artifacts if no people

* final speed up && twist detection

* New Queue workers: Splitter/Assembler

* Latency highly reduced for multi-view

* Highly reduced latency without out-of-memory

* Fixed 3-d bug

* IdExtractor handles splitted frame

* Foot not rendered standalone

* Rm adam

* Disabled in CMake
上级 2d71378c
...@@ -20,7 +20,7 @@ ...@@ -20,7 +20,7 @@
- 15 or 18 or **25-keypoint body/foot keypoint estimation**. **Running time invariant to number of detected people**. - 15 or 18 or **25-keypoint body/foot keypoint estimation**. **Running time invariant to number of detected people**.
- **2x21-keypoint hand keypoint estimation**. Currently, **running time depends** on **number of detected people**. - **2x21-keypoint hand keypoint estimation**. Currently, **running time depends** on **number of detected people**.
- **70-keypoint face keypoint estimation**. Currently, **running time depends** on **number of detected people**. - **70-keypoint face keypoint estimation**. Currently, **running time depends** on **number of detected people**.
- **3D real-time multi-person keypoint detection**: - **3D real-time single-person keypoint detection**:
- 3-D triangulation from multiple single views. - 3-D triangulation from multiple single views.
- Synchronization of Flir cameras handled. - Synchronization of Flir cameras handled.
- Compatible with Flir/Point Grey cameras, but provided C++ demos to add your custom input. - Compatible with Flir/Point Grey cameras, but provided C++ demos to add your custom input.
...@@ -37,8 +37,8 @@ ...@@ -37,8 +37,8 @@
## Latest Features ## Latest Features
- Jun 2018: [**Combined body-foot model released! Faster and more accurate**](doc/installation.md)! - Jun 2018: [**Combined body-foot model released! Faster and more accurate**](doc/installation.md)!
- Jun 2018: [**Python version**](doc/modules/python_module.md) released! - Jun 2018: [**Python API**](doc/modules/python_module.md) released!
- Jun 2018: [**AMD graphic card version**](doc/installation.md) released! - Jun 2018: [**OpenCL/AMD graphic card version**](doc/installation.md) released!
- Jun 2018: [**Calibration toolbox**](doc/modules/calibration_module.md) released! - Jun 2018: [**Calibration toolbox**](doc/modules/calibration_module.md) released!
- Jun 2018: [**Mac OSX version (CPU)**](doc/installation.md) released! - Jun 2018: [**Mac OSX version (CPU)**](doc/installation.md) released!
- Mar 2018: [**CPU version**](doc/installation.md#cpu-version)! - Mar 2018: [**CPU version**](doc/installation.md#cpu-version)!
......
...@@ -102,6 +102,7 @@ The instructions in this section describe the steps to build OpenPose using CMak ...@@ -102,6 +102,7 @@ The instructions in this section describe the steps to build OpenPose using CMak
1. Download and install CMake GUI: 1. Download and install CMake GUI:
- Ubuntu: run the command `sudo apt-get install cmake-qt-gui`. Note: If you prefer to use CMake through the command line, see [Cmake Command Line Build](#cmake-command-line-build-ubuntu-only). - Ubuntu: run the command `sudo apt-get install cmake-qt-gui`. Note: If you prefer to use CMake through the command line, see [Cmake Command Line Build](#cmake-command-line-build-ubuntu-only).
- Windows: download and install the latest CMake win64-x64 msi installer from the [CMake website](https://cmake.org/download/), called `cmake-X.X.X-win64-x64.msi`. - Windows: download and install the latest CMake win64-x64 msi installer from the [CMake website](https://cmake.org/download/), called `cmake-X.X.X-win64-x64.msi`.
- Mac: `brew cask install cmake`.
2. Nvidia GPU version prerequisites: 2. Nvidia GPU version prerequisites:
1. [**CUDA 8**](https://developer.nvidia.com/cuda-80-ga2-download-archive): 1. [**CUDA 8**](https://developer.nvidia.com/cuda-80-ga2-download-archive):
- Ubuntu: Run `sudo ubuntu/install_cuda.sh` or alternatively download and install it from their website. - Ubuntu: Run `sudo ubuntu/install_cuda.sh` or alternatively download and install it from their website.
......
...@@ -8,7 +8,7 @@ In order to add a new module, these are the recommended steps in order to develo ...@@ -8,7 +8,7 @@ In order to add a new module, these are the recommended steps in order to develo
2. Implement all the functionality in one `Worker` (i.e. inherit from `Worker` and implement all the functionality on that class). 2. Implement all the functionality in one `Worker` (i.e. inherit from `Worker` and implement all the functionality on that class).
1. The first letter of the class name should be `W` (e.g. `WHairExtractor`). 1. The first letter of the class name should be `W` (e.g. `WHairExtractor`).
2. To initially simplify development: 2. To initially simplify development:
1. Initialize the Worker class with the specific std::shared_ptr<std::vector<op::Datum>> instead of directly using a template class. 1. Initialize the Worker class with the specific std::shared_ptr<std::vector<op::Datum>> instead of directly using a template class (following the `examples/tutorial_wrapper` synchronous examples).
2. Use the whole op::Datum as unique argument of your auxiliary functions. 2. Use the whole op::Datum as unique argument of your auxiliary functions.
3. Use the OpenPose Wrapper in ThreadManagerMode::SingleThread mode (e.g. it allows you to directly use cv::imshow). 3. Use the OpenPose Wrapper in ThreadManagerMode::SingleThread mode (e.g. it allows you to directly use cv::imshow).
4. If you are using your own custom Caffe -> initially change the Caffe for your version. It should directly work. 4. If you are using your own custom Caffe -> initially change the Caffe for your version. It should directly work.
......
...@@ -70,8 +70,8 @@ The `Datum` class has all the variables that our Workers need to share to each o ...@@ -70,8 +70,8 @@ The `Datum` class has all the variables that our Workers need to share to each o
UserDatum : public op::Datum {/* op::Datum + extra variables */} UserDatum : public op::Datum {/* op::Datum + extra variables */}
// Worker and ThreadManager example initialization // Worker and ThreadManager example initialization
op::WGui<std::vector<UserDatum>> userGUI(/* constructor arguments */); op::WGui<std::shared_ptr<std::vector<UserDatum>> userGUI(/* constructor arguments */);
op::ThreadManager<std::vector<UserDatum>> userThreadManager; op::ThreadManager<std::shared_ptr<std::vector<UserDatum>> userThreadManager;
``` ```
Since `UserDatum` inherits from `op::Datum`, all the original OpenPose code will compile and run with your inherited version of `op::Datum`. Since `UserDatum` inherits from `op::Datum`, all the original OpenPose code will compile and run with your inherited version of `op::Datum`.
...@@ -147,7 +147,7 @@ Classes starting by the letter `W` + upper case letter (e.g. `WGui`) directly or ...@@ -147,7 +147,7 @@ Classes starting by the letter `W` + upper case letter (e.g. `WGui`) directly or
The easiest way to create your own Worker is to inherit Worker<T>, and implement the work() function such us it just calls a wrapper to your desired functionality (check the source code of some of our basic Workers). Since the Worker classes are templates, they are always compiled. Therefore, including your desired functionality in a different file will let you compile it only once. Otherwise, it would be compiled any time that any code which uses your worker is compiled. The easiest way to create your own Worker is to inherit Worker<T>, and implement the work() function such us it just calls a wrapper to your desired functionality (check the source code of some of our basic Workers). Since the Worker classes are templates, they are always compiled. Therefore, including your desired functionality in a different file will let you compile it only once. Otherwise, it would be compiled any time that any code which uses your worker is compiled.
All OpenPose Workers are templates, i.e. they are not only limited to work with the default std::vector<op::Datum>. However, if you intend to use some of our Workers, your custom `TDatums` class (the one substituting std::vector<op::Datum>) should implement the same variables and functions that those Workers use. The easiest solution is to inherit from `op::Datum` and extend its functionality. All OpenPose Workers are templates, i.e. they are not only limited to work with the default op::Datum. However, if you intend to use some of our Workers, your custom `TDatums` class (the one substituting op::Datum) should implement the same variables and functions that those Workers use. The easiest solution is to inherit from `op::Datum` and extend its functionality.
### Creating New Workers ### Creating New Workers
...@@ -171,7 +171,7 @@ All Workers wrap and call a non-Worker non-template equivalent which actually pe ...@@ -171,7 +171,7 @@ All Workers wrap and call a non-Worker non-template equivalent which actually pe
By separating functionality and their `Worker<T>` wrappers, we get the good of both points, eliminating the cons. In this way, the user is able to: By separating functionality and their `Worker<T>` wrappers, we get the good of both points, eliminating the cons. In this way, the user is able to:
1. Change `std::vector<op::Datum>` for a custom class, implementing his own `Worker` templates, but using the already implemented functionality to create new custom `Worker` templates. 1. Change `std::shared_ptr<std::vector<op::Datum>>` for a custom class, implementing his own `Worker` templates, but using the already implemented functionality to create new custom `Worker` templates.
2. Create a `Worker` which wraps several non-`Worker`s classes. 2. Create a `Worker` which wraps several non-`Worker`s classes.
......
...@@ -226,6 +226,7 @@ OpenPose Library - Release Notes ...@@ -226,6 +226,7 @@ OpenPose Library - Release Notes
2. It is only run if reprojction error is more than a minimum threshold (improve speed with already good quality results) and also less than another outlier threshold. 2. It is only run if reprojction error is more than a minimum threshold (improve speed with already good quality results) and also less than another outlier threshold.
3. Outliers are removed from final result if >= 3 camera views. 3. Outliers are removed from final result if >= 3 camera views.
4. Applied RANSAC if >=4 camera views. 4. Applied RANSAC if >=4 camera views.
5. Latency highly reduced in multi-GPU setting. Each GPU process a different camera view, instead of a different time-instant sequence.
5. CMake: All libraries as single variable (simpler to add/remove libraries). 5. CMake: All libraries as single variable (simpler to add/remove libraries).
6. Datum includes extrinsic and intrinsic camera parameters. 6. Datum includes extrinsic and intrinsic camera parameters.
7. Function `scaleKeypoints(Array<float>& keypoints, const float scale)` also accepts 3D keypoints. 7. Function `scaleKeypoints(Array<float>& keypoints, const float scale)` also accepts 3D keypoints.
......
OpenPose Library - Latest Released Features OpenPose Library - Latest Released Features
==================================== ====================================
- Jun 2018: [**Combined body-foot model released! Faster and more accurate.**](./installation.md)! - Jun 2018: [**Combined body-foot model released! Faster and more accurate**](./installation.md)!
- Jun 2018: [**Python version**](./modules/python_module.md) released! - Jun 2018: [**Python API**](./modules/python_module.md) released!
- Jun 2018: [**AMD graphic card version**](./modules/calibration_module.md) released! - Jun 2018: [**OpenCL/AMD graphic card version**](./modules/calibration_module.md) released!
- Jun 2018: [**Calibration toolbox**](./modules/calibration_module.md) released! - Jun 2018: [**Calibration toolbox**](./modules/calibration_module.md) released!
- Jun 2018: [**Mac OSX version (CPU)**](./installation.md) released! - Jun 2018: [**Mac OSX version (CPU)**](./installation.md) released!
- Mar 2018: [**CPU version**](./installation.md#cpu-version)! - Mar 2018: [**CPU version**](./installation.md#cpu-version)!
......
...@@ -235,8 +235,8 @@ DEFINE_string(write_video_adam, "", "Experimental, not avail ...@@ -235,8 +235,8 @@ DEFINE_string(write_video_adam, "", "Experimental, not avail
" controls FPS."); " controls FPS.");
DEFINE_string(write_bvh, "", "Experimental, not available yet. E.g.: `~/Desktop/mocapResult.bvh`."); DEFINE_string(write_bvh, "", "Experimental, not available yet. E.g.: `~/Desktop/mocapResult.bvh`.");
// UDP communication // UDP communication
DEFINE_string(udp_host, "127.0.0.1", "IP for UDP communication."); DEFINE_string(udp_host, "", "Experimental, not available yet. IP for UDP communication. E.g., `192.168.0.1`.");
DEFINE_string(udp_port, "8051", "Port number for UDP communication."); DEFINE_string(udp_port, "8051", "Experimental, not available yet. Port number for UDP communication.");
int openPoseDemo() int openPoseDemo()
{ {
......
...@@ -244,8 +244,8 @@ DEFINE_string(write_video_adam, "", "Experimental, not avail ...@@ -244,8 +244,8 @@ DEFINE_string(write_video_adam, "", "Experimental, not avail
" controls FPS."); " controls FPS.");
DEFINE_string(write_bvh, "", "Experimental, not available yet. E.g.: `~/Desktop/mocapResult.bvh`."); DEFINE_string(write_bvh, "", "Experimental, not available yet. E.g.: `~/Desktop/mocapResult.bvh`.");
// UDP communication // UDP communication
DEFINE_string(udp_host, "127.0.0.1", "IP for UDP communication."); DEFINE_string(udp_host, "", "Experimental, not available yet. IP for UDP communication. E.g., `192.168.0.1`.");
DEFINE_string(udp_port, "8051", "Port number for UDP communication."); DEFINE_string(udp_port, "8051", "Experimental, not available yet. Port number for UDP communication.");
int openPoseTutorialWrapper4() int openPoseTutorialWrapper4()
{ {
......
...@@ -235,8 +235,8 @@ DEFINE_string(write_video_adam, "", "Experimental, not avail ...@@ -235,8 +235,8 @@ DEFINE_string(write_video_adam, "", "Experimental, not avail
" controls FPS."); " controls FPS.");
DEFINE_string(write_bvh, "", "Experimental, not available yet. E.g.: `~/Desktop/mocapResult.bvh`."); DEFINE_string(write_bvh, "", "Experimental, not available yet. E.g.: `~/Desktop/mocapResult.bvh`.");
// UDP communication // UDP communication
DEFINE_string(udp_host, "127.0.0.1", "IP for UDP communication."); DEFINE_string(udp_host, "", "Experimental, not available yet. IP for UDP communication. E.g., `192.168.0.1`.");
DEFINE_string(udp_port, "8051", "Port number for UDP communication."); DEFINE_string(udp_port, "8051", "Experimental, not available yet. Port number for UDP communication.");
// If the user needs his own variables, he can inherit the op::Datum struct and add them // If the user needs his own variables, he can inherit the op::Datum struct and add them
......
...@@ -235,8 +235,8 @@ DEFINE_string(write_video_adam, "", "Experimental, not avail ...@@ -235,8 +235,8 @@ DEFINE_string(write_video_adam, "", "Experimental, not avail
" controls FPS."); " controls FPS.");
DEFINE_string(write_bvh, "", "Experimental, not available yet. E.g.: `~/Desktop/mocapResult.bvh`."); DEFINE_string(write_bvh, "", "Experimental, not available yet. E.g.: `~/Desktop/mocapResult.bvh`.");
// UDP communication // UDP communication
DEFINE_string(udp_host, "127.0.0.1", "IP for UDP communication."); DEFINE_string(udp_host, "", "Experimental, not available yet. IP for UDP communication. E.g., `192.168.0.1`.");
DEFINE_string(udp_port, "8051", "Port number for UDP communication."); DEFINE_string(udp_port, "8051", "Experimental, not available yet. Port number for UDP communication.");
// If the user needs his own variables, he can inherit the op::Datum struct and add them // If the user needs his own variables, he can inherit the op::Datum struct and add them
......
...@@ -235,8 +235,8 @@ DEFINE_string(write_video_adam, "", "Experimental, not avail ...@@ -235,8 +235,8 @@ DEFINE_string(write_video_adam, "", "Experimental, not avail
" controls FPS."); " controls FPS.");
DEFINE_string(write_bvh, "", "Experimental, not available yet. E.g.: `~/Desktop/mocapResult.bvh`."); DEFINE_string(write_bvh, "", "Experimental, not available yet. E.g.: `~/Desktop/mocapResult.bvh`.");
// UDP communication // UDP communication
DEFINE_string(udp_host, "127.0.0.1", "IP for UDP communication."); DEFINE_string(udp_host, "", "Experimental, not available yet. IP for UDP communication. E.g., `192.168.0.1`.");
DEFINE_string(udp_port, "8051", "Port number for UDP communication."); DEFINE_string(udp_port, "8051", "Experimental, not available yet. Port number for UDP communication.");
// If the user needs his own variables, he can inherit the op::Datum struct and add them // If the user needs his own variables, he can inherit the op::Datum struct and add them
......
...@@ -202,8 +202,8 @@ DEFINE_string(write_video_adam, "", "Experimental, not avail ...@@ -202,8 +202,8 @@ DEFINE_string(write_video_adam, "", "Experimental, not avail
" controls FPS."); " controls FPS.");
DEFINE_string(write_bvh, "", "Experimental, not available yet. E.g.: `~/Desktop/mocapResult.bvh`."); DEFINE_string(write_bvh, "", "Experimental, not available yet. E.g.: `~/Desktop/mocapResult.bvh`.");
// UDP communication // UDP communication
DEFINE_string(udp_host, "127.0.0.1", "IP for UDP communication."); DEFINE_string(udp_host, "", "Experimental, not available yet. IP for UDP communication. E.g., `192.168.0.1`.");
DEFINE_string(udp_port, "8051", "Port number for UDP communication."); DEFINE_string(udp_port, "8051", "Experimental, not available yet. Port number for UDP communication.");
// If the user needs his own variables, he can inherit the op::Datum struct and add them // If the user needs his own variables, he can inherit the op::Datum struct and add them
......
...@@ -202,8 +202,8 @@ DEFINE_string(write_video_adam, "", "Experimental, not avail ...@@ -202,8 +202,8 @@ DEFINE_string(write_video_adam, "", "Experimental, not avail
" controls FPS."); " controls FPS.");
DEFINE_string(write_bvh, "", "Experimental, not available yet. E.g.: `~/Desktop/mocapResult.bvh`."); DEFINE_string(write_bvh, "", "Experimental, not available yet. E.g.: `~/Desktop/mocapResult.bvh`.");
// UDP communication // UDP communication
DEFINE_string(udp_host, "127.0.0.1", "IP for UDP communication."); DEFINE_string(udp_host, "", "Experimental, not available yet. IP for UDP communication. E.g., `192.168.0.1`.");
DEFINE_string(udp_port, "8051", "Port number for UDP communication."); DEFINE_string(udp_port, "8051", "Experimental, not available yet. Port number for UDP communication.");
// If the user needs his own variables, he can inherit the op::Datum struct and add them // If the user needs his own variables, he can inherit the op::Datum struct and add them
......
...@@ -227,8 +227,8 @@ DEFINE_string(write_video_adam, "", "Experimental, not avail ...@@ -227,8 +227,8 @@ DEFINE_string(write_video_adam, "", "Experimental, not avail
" controls FPS."); " controls FPS.");
DEFINE_string(write_bvh, "", "Experimental, not available yet. E.g.: `~/Desktop/mocapResult.bvh`."); DEFINE_string(write_bvh, "", "Experimental, not available yet. E.g.: `~/Desktop/mocapResult.bvh`.");
// UDP communication // UDP communication
DEFINE_string(udp_host, "127.0.0.1", "IP for UDP communication."); DEFINE_string(udp_host, "", "Experimental, not available yet. IP for UDP communication. E.g., `192.168.0.1`.");
DEFINE_string(udp_port, "8051", "Port number for UDP communication."); DEFINE_string(udp_port, "8051", "Experimental, not available yet. Port number for UDP communication.");
// If the user needs his own variables, he can inherit the op::Datum struct and add them // If the user needs his own variables, he can inherit the op::Datum struct and add them
......
...@@ -57,7 +57,8 @@ namespace op ...@@ -57,7 +57,8 @@ namespace op
const auto profilerKey = Profiler::timerInit(__LINE__, __FUNCTION__, __FILE__); const auto profilerKey = Profiler::timerInit(__LINE__, __FUNCTION__, __FILE__);
// Record BVH file // Record BVH file
const auto& tDatum = (*tDatums)[0]; const auto& tDatum = (*tDatums)[0];
spBvhSaver->updateBvh(tDatum.adamPose, tDatum.adamTranslation, tDatum.j0Vec); if (!tDatum.poseKeypoints3D.empty())
spBvhSaver->updateBvh(tDatum.adamPose, tDatum.adamTranslation, tDatum.j0Vec);
// Profiling speed // Profiling speed
Profiler::timerEnd(profilerKey); Profiler::timerEnd(profilerKey);
Profiler::printAveragedTimeMsOnIterationX(profilerKey, __LINE__, __FUNCTION__, __FILE__); Profiler::printAveragedTimeMsOnIterationX(profilerKey, __LINE__, __FUNCTION__, __FILE__);
......
...@@ -57,21 +57,24 @@ namespace op ...@@ -57,21 +57,24 @@ namespace op
// Send though UDP communication // Send though UDP communication
#ifdef USE_3D_ADAM_MODEL #ifdef USE_3D_ADAM_MODEL
const auto& tDatum = (*tDatums)[0]; const auto& tDatum = (*tDatums)[0];
const auto& adamPose = tDatum.adamPose; // Eigen::Matrix<double, 62, 3, Eigen::RowMajor> if (!tDatum.poseKeypoints3D.empty())
const auto& adamTranslation = tDatum.adamTranslation; // Eigen::Vector3d(3, 1) {
const auto adamFaceCoeffsExp = tDatum.adamFaceCoeffsExp; // Eigen::VectorXd resized to (200, 1) const auto& adamPose = tDatum.adamPose; // Eigen::Matrix<double, 62, 3, Eigen::RowMajor>
//const float mouth_open = tDatum.mouthOpening; // tDatum.mouth_open; const auto& adamTranslation = tDatum.adamTranslation; // Eigen::Vector3d(3, 1)
//const float leye_open = tDatum.rightEyeOpening; // tDatum.leye_open; const auto adamFaceCoeffsExp = tDatum.adamFaceCoeffsExp; // Eigen::VectorXd resized to (200, 1)
//const float reye_open = tDatum.leftEyeOpening; // tDatum.reye_open; //const float mouth_open = tDatum.mouthOpening; // tDatum.mouth_open;
//const float dist_root_foot = Datum.distanceRootFoot; // tDatum.dist_root_foot; //const float leye_open = tDatum.rightEyeOpening; // tDatum.leye_open;
// m_adam_t: //const float reye_open = tDatum.leftEyeOpening; // tDatum.reye_open;
// 1. Total translation (centimeters) of the root in camera/global coordinate representation. //const float dist_root_foot = Datum.distanceRootFoot; // tDatum.dist_root_foot;
// m_adam_pose: // m_adam_t:
// 1. First row is global rotation, in AngleAxis representation. Radians (not degrees!) // 1. Total translation (centimeters) of the root in camera/global coordinate representation.
// 2. Rest are joint-angles in Euler-Angle representation. Degrees. // m_adam_pose:
spUdpSender->sendJointAngles(adamPose.data(), adamPose.rows(), // 1. First row is global rotation, in AngleAxis representation. Radians (not degrees!)
adamTranslation.data(), // 2. Rest are joint-angles in Euler-Angle representation. Degrees.
adamFaceCoeffsExp.data(), adamFaceCoeffsExp.rows()); spUdpSender->sendJointAngles(adamPose.data(), adamPose.rows(),
adamTranslation.data(),
adamFaceCoeffsExp.data(), adamFaceCoeffsExp.rows());
}
#endif #endif
// Profiling speed // Profiling speed
Profiler::timerEnd(profilerKey); Profiler::timerEnd(profilerKey);
......
...@@ -74,11 +74,12 @@ namespace op ...@@ -74,11 +74,12 @@ namespace op
spGuiAdam->setImage(cvOutputDatas); spGuiAdam->setImage(cvOutputDatas);
// Update keypoints // Update keypoints
const auto& tDatum = (*tDatums)[0]; const auto& tDatum = (*tDatums)[0];
spGuiAdam->generateMesh(tDatum.poseKeypoints3D, tDatum.faceKeypoints3D, tDatum.handKeypoints3D, if (!tDatum.poseKeypoints3D.empty())
tDatum.adamPose.data(), tDatum.adamTranslation.data(), spGuiAdam->generateMesh(tDatum.poseKeypoints3D, tDatum.faceKeypoints3D, tDatum.handKeypoints3D,
tDatum.vtVec.data(), tDatum.vtVec.rows(), tDatum.adamPose.data(), tDatum.adamTranslation.data(),
tDatum.j0Vec.data(), tDatum.j0Vec.rows(), tDatum.vtVec.data(), tDatum.vtVec.rows(),
tDatum.adamFaceCoeffsExp.data()); tDatum.j0Vec.data(), tDatum.j0Vec.rows(),
tDatum.adamFaceCoeffsExp.data());
} }
// Refresh/update GUI // Refresh/update GUI
spGuiAdam->update(); spGuiAdam->update();
......
...@@ -8,7 +8,9 @@ ...@@ -8,7 +8,9 @@
namespace op namespace op
{ {
// Constant Global Parameters // Constant Global Parameters
// For OpenCL-NMS, (POSE_MAX_PEOPLE+1)*3(x,y,score) must be divisible by 32. Easy fix: POSE_MAX_PEOPLE = 32n - 1 // For OpenCL-NMS in Ubuntu, (POSE_MAX_PEOPLE+1)*3(x,y,score) must be divisible by 32. Easy fix:
// POSE_MAX_PEOPLE = 32n - 1
// For OpenCL-NMS in Windows, it must be by 64, so 64n - 1
const auto POSE_MAX_PEOPLE = 127u; const auto POSE_MAX_PEOPLE = 127u;
// Model functions // Model functions
...@@ -29,6 +31,9 @@ namespace op ...@@ -29,6 +31,9 @@ namespace op
OP_API float getPoseDefaultConnectInterThreshold(const PoseModel poseModel); OP_API float getPoseDefaultConnectInterThreshold(const PoseModel poseModel);
OP_API unsigned int getPoseDefaultMinSubsetCnt(const PoseModel poseModel); OP_API unsigned int getPoseDefaultMinSubsetCnt(const PoseModel poseModel);
OP_API float getPoseDefaultConnectMinSubsetScore(const PoseModel poseModel); OP_API float getPoseDefaultConnectMinSubsetScore(const PoseModel poseModel);
// const bool COCO_CHALLENGE = true;
const bool COCO_CHALLENGE = false;
} }
#endif // OPENPOSE_POSE_POSE_PARAMETERS_HPP #endif // OPENPOSE_POSE_POSE_PARAMETERS_HPP
...@@ -170,8 +170,8 @@ namespace op ...@@ -170,8 +170,8 @@ namespace op
4,39, 39,40, 40,41, 41,42, 4,43, 43,44, 44,45, 45,46, 4,47, 47,48, 48,49, 49,50, 4,51, 51,52, 52,53, 53,54, 4,55, 55,56, 56,57, 57,58 4,39, 39,40, 40,41, 41,42, 4,43, 43,44, 44,45, 45,46, 4,47, 47,48, 48,49, 49,50, 4,51, 51,52, 52,53, 53,54, 4,55, 55,56, 56,57, 57,58
#define POSE_BODY_59_SCALES_RENDER_GPU \ #define POSE_BODY_59_SCALES_RENDER_GPU \
1.f,1.f,1.f,1.f,1.f, 1.f,1.f,1.f,1.f,1.f, 1.f,1.f,1.f,1.f,1.f, 1.f,1.f,1.f,1.f, \ 1.f,1.f,1.f,1.f,1.f, 1.f,1.f,1.f,1.f,1.f, 1.f,1.f,1.f,1.f,1.f, 1.f,1.f,1.f,1.f, \
0.5f,0.5f,0.5f,0.5f,0.5f, 0.5f,0.5f,0.5f,0.5f,0.5f, 0.5f,0.5f,0.5f,0.5f,0.5f, 0.5f,0.5f,0.5f,0.5f,0.5f, \ 0.75f,0.75f,0.75f,0.75f,0.75f, 0.75f,0.75f,0.75f,0.75f,0.75f, 0.75f,0.75f,0.75f,0.75f,0.75f, 0.75f,0.75f,0.75f,0.75f,0.75f, \
0.5f,0.5f,0.5f,0.5f,0.5f, 0.5f,0.5f,0.5f,0.5f,0.5f, 0.5f,0.5f,0.5f,0.5f,0.5f, 0.5f,0.5f,0.5f,0.5f,0.5f 0.75f,0.75f,0.75f,0.75f,0.75f, 0.75f,0.75f,0.75f,0.75f,0.75f, 0.75f,0.75f,0.75f,0.75f,0.75f, 0.75f,0.75f,0.75f,0.75f,0.75f
#define POSE_BODY_59_COLORS_RENDER_GPU \ #define POSE_BODY_59_COLORS_RENDER_GPU \
255.f, 0.f, 85.f, \ 255.f, 0.f, 85.f, \
255.f, 0.f, 0.f, \ 255.f, 0.f, 0.f, \
...@@ -242,8 +242,8 @@ namespace op ...@@ -242,8 +242,8 @@ namespace op
4,45, 45,46, 46,47, 47,48, 4,49, 49,50, 50,51, 51,52, 4,53, 53,54, 54,55, 55,56, 4,57, 57,58, 58,59, 59,60, 4,61, 61,62, 62,63, 63,64 4,45, 45,46, 46,47, 47,48, 4,49, 49,50, 50,51, 51,52, 4,53, 53,54, 54,55, 55,56, 4,57, 57,58, 58,59, 59,60, 4,61, 61,62, 62,63, 63,64
#define POSE_BODY_65_SCALES_RENDER_GPU \ #define POSE_BODY_65_SCALES_RENDER_GPU \
1.f,1.f,1.f,1.f,1.f, 1.f,1.f,1.f,1.f,1.f, 1.f,1.f,1.f,1.f,1.f, 1.f,1.f,1.f,1.f,1.f,1.f,1.f,1.f,1.f,1.f, \ 1.f,1.f,1.f,1.f,1.f, 1.f,1.f,1.f,1.f,1.f, 1.f,1.f,1.f,1.f,1.f, 1.f,1.f,1.f,1.f,1.f,1.f,1.f,1.f,1.f,1.f, \
0.5f,0.5f,0.5f,0.5f,0.5f, 0.5f,0.5f,0.5f,0.5f,0.5f, 0.5f,0.5f,0.5f,0.5f,0.5f, 0.5f,0.5f,0.5f,0.5f,0.5f, \ 0.75f,0.75f,0.75f,0.75f,0.75f, 0.75f,0.75f,0.75f,0.75f,0.75f, 0.75f,0.75f,0.75f,0.75f,0.75f, 0.75f,0.75f,0.75f,0.75f,0.75f, \
0.5f,0.5f,0.5f,0.5f,0.5f, 0.5f,0.5f,0.5f,0.5f,0.5f, 0.5f,0.5f,0.5f,0.5f,0.5f, 0.5f,0.5f,0.5f,0.5f,0.5f 0.75f,0.75f,0.75f,0.75f,0.75f, 0.75f,0.75f,0.75f,0.75f,0.75f, 0.75f,0.75f,0.75f,0.75f,0.75f, 0.75f,0.75f,0.75f,0.75f,0.75f
#define POSE_BODY_65_COLORS_RENDER_GPU \ #define POSE_BODY_65_COLORS_RENDER_GPU \
255.f, 0.f, 85.f, \ 255.f, 0.f, 85.f, \
255.f, 0.f, 0.f, \ 255.f, 0.f, 0.f, \
......
...@@ -2,6 +2,7 @@ ...@@ -2,6 +2,7 @@
#define OPENPOSE_PRODUCER_W_DATUM_PRODUCER_HPP #define OPENPOSE_PRODUCER_W_DATUM_PRODUCER_HPP
#include <limits> // std::numeric_limits #include <limits> // std::numeric_limits
#include <queue> // std::queue
#include <openpose/core/common.hpp> #include <openpose/core/common.hpp>
#include <openpose/producer/datumProducer.hpp> #include <openpose/producer/datumProducer.hpp>
#include <openpose/thread/workerProducer.hpp> #include <openpose/thread/workerProducer.hpp>
...@@ -20,6 +21,7 @@ namespace op ...@@ -20,6 +21,7 @@ namespace op
private: private:
std::shared_ptr<DatumProducer<TDatumsNoPtr>> spDatumProducer; std::shared_ptr<DatumProducer<TDatumsNoPtr>> spDatumProducer;
std::queue<TDatums> mQueuedElements;
DELETE_COPY(WDatumProducer); DELETE_COPY(WDatumProducer);
}; };
...@@ -54,17 +56,43 @@ namespace op ...@@ -54,17 +56,43 @@ namespace op
// Profiling speed // Profiling speed
const auto profilerKey = Profiler::timerInit(__LINE__, __FUNCTION__, __FILE__); const auto profilerKey = Profiler::timerInit(__LINE__, __FUNCTION__, __FILE__);
// Create and fill TDatums // Create and fill TDatums
const auto isRunningAndTDatums = spDatumProducer->checkIfRunningAndGetDatum(); std::shared_ptr<TDatumsNoPtr> tDatums;
// Stop Worker if producer finished // Producer
if (!isRunningAndTDatums.first) if (mQueuedElements.empty())
this->stop(); {
// Profiling speed bool isRunning;
Profiler::timerEnd(profilerKey); std::tie(isRunning, tDatums) = spDatumProducer->checkIfRunningAndGetDatum();
Profiler::printAveragedTimeMsOnIterationX(profilerKey, __LINE__, __FUNCTION__, __FILE__); // Stop Worker if producer finished
// Debugging log if (!isRunning)
dLog("", Priority::Low, __LINE__, __FUNCTION__, __FILE__); this->stop();
// Profiling speed
Profiler::timerEnd(profilerKey);
Profiler::printAveragedTimeMsOnIterationX(profilerKey, __LINE__, __FUNCTION__, __FILE__);
// Debugging log
dLog("", Priority::Low, __LINE__, __FUNCTION__, __FILE__);
}
// Equivalent to WQueueSplitter
// Queued elements - Multiple views --> Split views into different TDatums
if (tDatums != nullptr && tDatums->size() > 1)
{
// Add tDatums to mQueuedElements
for (auto i = 0u ; i < tDatums->size() ; i++)
{
auto& tDatum = (*tDatums)[i];
tDatum.subId = i;
tDatum.subIdMax = tDatums->size()-1;
mQueuedElements.emplace(
std::make_shared<TDatumsNoPtr>(TDatumsNoPtr{tDatum}));
}
}
// Queued elements - Multiple views --> Return oldest view
if (!mQueuedElements.empty())
{
tDatums = mQueuedElements.front();
mQueuedElements.pop();
}
// Return TDatums // Return TDatums
return isRunningAndTDatums.second; return tDatums;
} }
catch (const std::exception& e) catch (const std::exception& e)
{ {
......
...@@ -17,6 +17,7 @@ ...@@ -17,6 +17,7 @@
#include <openpose/thread/workerProducer.hpp> #include <openpose/thread/workerProducer.hpp>
#include <openpose/thread/workerConsumer.hpp> #include <openpose/thread/workerConsumer.hpp>
#include <openpose/thread/wIdGenerator.hpp> #include <openpose/thread/wIdGenerator.hpp>
#include <openpose/thread/wQueueAssembler.hpp>
#include <openpose/thread/wQueueOrderer.hpp> #include <openpose/thread/wQueueOrderer.hpp>
#endif // OPENPOSE_THREAD_HEADERS_HPP #endif // OPENPOSE_THREAD_HEADERS_HPP
...@@ -21,9 +21,11 @@ namespace op ...@@ -21,9 +21,11 @@ namespace op
void setDefaultMaxSizeQueues(const long long defaultMaxSizeQueues = -1); void setDefaultMaxSizeQueues(const long long defaultMaxSizeQueues = -1);
void add(const unsigned long long threadId, const std::vector<TWorker>& tWorkers, const unsigned long long queueInId, const unsigned long long queueOutId); void add(const unsigned long long threadId, const std::vector<TWorker>& tWorkers, const unsigned long long queueInId,
const unsigned long long queueOutId);
void add(const unsigned long long threadId, const TWorker& tWorker, const unsigned long long queueInId, const unsigned long long queueOutId); void add(const unsigned long long threadId, const TWorker& tWorker, const unsigned long long queueInId,
const unsigned long long queueOutId);
void reset(); void reset();
...@@ -113,7 +115,9 @@ namespace op ...@@ -113,7 +115,9 @@ namespace op
} }
template<typename TDatums, typename TWorker, typename TQueue> template<typename TDatums, typename TWorker, typename TQueue>
void ThreadManager<TDatums, TWorker, TQueue>::add(const unsigned long long threadId, const std::vector<TWorker>& tWorkers, const unsigned long long queueInId, void ThreadManager<TDatums, TWorker, TQueue>::add(const unsigned long long threadId,
const std::vector<TWorker>& tWorkers,
const unsigned long long queueInId,
const unsigned long long queueOutId) const unsigned long long queueOutId)
{ {
try try
...@@ -127,7 +131,9 @@ namespace op ...@@ -127,7 +131,9 @@ namespace op
} }
template<typename TDatums, typename TWorker, typename TQueue> template<typename TDatums, typename TWorker, typename TQueue>
void ThreadManager<TDatums, TWorker, TQueue>::add(const unsigned long long threadId, const TWorker& tWorker, const unsigned long long queueInId, void ThreadManager<TDatums, TWorker, TQueue>::add(const unsigned long long threadId,
const TWorker& tWorker,
const unsigned long long queueInId,
const unsigned long long queueOutId) const unsigned long long queueOutId)
{ {
try try
...@@ -225,7 +231,8 @@ namespace op ...@@ -225,7 +231,8 @@ namespace op
{ {
try try
{ {
if (mThreadManagerMode != ThreadManagerMode::Asynchronous && mThreadManagerMode != ThreadManagerMode::AsynchronousIn) if (mThreadManagerMode != ThreadManagerMode::Asynchronous
&& mThreadManagerMode != ThreadManagerMode::AsynchronousIn)
error("Not available for this ThreadManagerMode.", __LINE__, __FUNCTION__, __FILE__); error("Not available for this ThreadManagerMode.", __LINE__, __FUNCTION__, __FILE__);
if (mTQueues.empty()) if (mTQueues.empty())
error("ThreadManager already stopped or not started yet.", __LINE__, __FUNCTION__, __FILE__); error("ThreadManager already stopped or not started yet.", __LINE__, __FUNCTION__, __FILE__);
...@@ -243,7 +250,8 @@ namespace op ...@@ -243,7 +250,8 @@ namespace op
{ {
try try
{ {
if (mThreadManagerMode != ThreadManagerMode::Asynchronous && mThreadManagerMode != ThreadManagerMode::AsynchronousIn) if (mThreadManagerMode != ThreadManagerMode::Asynchronous
&& mThreadManagerMode != ThreadManagerMode::AsynchronousIn)
error("Not available for this ThreadManagerMode.", __LINE__, __FUNCTION__, __FILE__); error("Not available for this ThreadManagerMode.", __LINE__, __FUNCTION__, __FILE__);
if (mTQueues.empty()) if (mTQueues.empty())
error("ThreadManager already stopped or not started yet.", __LINE__, __FUNCTION__, __FILE__); error("ThreadManager already stopped or not started yet.", __LINE__, __FUNCTION__, __FILE__);
...@@ -261,7 +269,8 @@ namespace op ...@@ -261,7 +269,8 @@ namespace op
{ {
try try
{ {
if (mThreadManagerMode != ThreadManagerMode::Asynchronous && mThreadManagerMode != ThreadManagerMode::AsynchronousIn) if (mThreadManagerMode != ThreadManagerMode::Asynchronous
&& mThreadManagerMode != ThreadManagerMode::AsynchronousIn)
error("Not available for this ThreadManagerMode.", __LINE__, __FUNCTION__, __FILE__); error("Not available for this ThreadManagerMode.", __LINE__, __FUNCTION__, __FILE__);
if (mTQueues.empty()) if (mTQueues.empty())
error("ThreadManager already stopped or not started yet.", __LINE__, __FUNCTION__, __FILE__); error("ThreadManager already stopped or not started yet.", __LINE__, __FUNCTION__, __FILE__);
...@@ -279,7 +288,8 @@ namespace op ...@@ -279,7 +288,8 @@ namespace op
{ {
try try
{ {
if (mThreadManagerMode != ThreadManagerMode::Asynchronous && mThreadManagerMode != ThreadManagerMode::AsynchronousIn) if (mThreadManagerMode != ThreadManagerMode::Asynchronous
&& mThreadManagerMode != ThreadManagerMode::AsynchronousIn)
error("Not available for this ThreadManagerMode.", __LINE__, __FUNCTION__, __FILE__); error("Not available for this ThreadManagerMode.", __LINE__, __FUNCTION__, __FILE__);
if (mTQueues.empty()) if (mTQueues.empty())
error("ThreadManager already stopped or not started yet.", __LINE__, __FUNCTION__, __FILE__); error("ThreadManager already stopped or not started yet.", __LINE__, __FUNCTION__, __FILE__);
...@@ -297,7 +307,8 @@ namespace op ...@@ -297,7 +307,8 @@ namespace op
{ {
try try
{ {
if (mThreadManagerMode != ThreadManagerMode::Asynchronous && mThreadManagerMode != ThreadManagerMode::AsynchronousOut) if (mThreadManagerMode != ThreadManagerMode::Asynchronous
&& mThreadManagerMode != ThreadManagerMode::AsynchronousOut)
error("Not available for this ThreadManagerMode.", __LINE__, __FUNCTION__, __FILE__); error("Not available for this ThreadManagerMode.", __LINE__, __FUNCTION__, __FILE__);
if (mTQueues.empty()) if (mTQueues.empty())
error("ThreadManager already stopped or not started yet.", __LINE__, __FUNCTION__, __FILE__); error("ThreadManager already stopped or not started yet.", __LINE__, __FUNCTION__, __FILE__);
...@@ -315,7 +326,8 @@ namespace op ...@@ -315,7 +326,8 @@ namespace op
{ {
try try
{ {
if (mThreadManagerMode != ThreadManagerMode::Asynchronous && mThreadManagerMode != ThreadManagerMode::AsynchronousOut) if (mThreadManagerMode != ThreadManagerMode::Asynchronous
&& mThreadManagerMode != ThreadManagerMode::AsynchronousOut)
error("Not available for this ThreadManagerMode.", __LINE__, __FUNCTION__, __FILE__); error("Not available for this ThreadManagerMode.", __LINE__, __FUNCTION__, __FILE__);
if (mTQueues.empty()) if (mTQueues.empty())
error("ThreadManager already stopped or not started yet.", __LINE__, __FUNCTION__, __FILE__); error("ThreadManager already stopped or not started yet.", __LINE__, __FUNCTION__, __FILE__);
...@@ -350,8 +362,10 @@ namespace op ...@@ -350,8 +362,10 @@ namespace op
try try
{ {
for (const auto& threadWorkerQueue : threadWorkerQueues) for (const auto& threadWorkerQueue : threadWorkerQueues)
add({std::make_tuple(std::get<0>(threadWorkerQueue), std::vector<TWorker>{std::get<1>(threadWorkerQueue)}, add({std::make_tuple(std::get<0>(threadWorkerQueue),
std::get<2>(threadWorkerQueue), std::get<3>(threadWorkerQueue))}); std::vector<TWorker>{std::get<1>(threadWorkerQueue)},
std::get<2>(threadWorkerQueue),
std::get<3>(threadWorkerQueue))});
} }
catch (const std::exception& e) catch (const std::exception& e)
{ {
...@@ -384,26 +398,34 @@ namespace op ...@@ -384,26 +398,34 @@ namespace op
const auto queueOut = std::get<3>(threadWorkerQueue); const auto queueOut = std::get<3>(threadWorkerQueue);
std::shared_ptr<SubThread<TDatums, TWorker>> subThread; std::shared_ptr<SubThread<TDatums, TWorker>> subThread;
// If AsynchronousIn -> queue indexes are OK // If AsynchronousIn -> queue indexes are OK
if (mThreadManagerMode == ThreadManagerMode::Asynchronous || mThreadManagerMode == ThreadManagerMode::AsynchronousIn) if (mThreadManagerMode == ThreadManagerMode::Asynchronous
|| mThreadManagerMode == ThreadManagerMode::AsynchronousIn)
{ {
if (mThreadManagerMode == ThreadManagerMode::AsynchronousIn && queueOut == mTQueues.size()) if (mThreadManagerMode == ThreadManagerMode::AsynchronousIn
subThread = {std::make_shared<SubThreadQueueIn<TDatums, TWorker, TQueue>>(tWorkers, mTQueues.at(queueIn))}; && queueOut == mTQueues.size())
subThread = {std::make_shared<SubThreadQueueIn<TDatums, TWorker, TQueue>>(
tWorkers, mTQueues.at(queueIn))};
else else
subThread = {std::make_shared<SubThreadQueueInOut<TDatums, TWorker, TQueue>>(tWorkers, mTQueues.at(queueIn), mTQueues.at(queueOut))}; subThread = {std::make_shared<SubThreadQueueInOut<TDatums, TWorker, TQueue>>(
tWorkers, mTQueues.at(queueIn), mTQueues.at(queueOut))};
} }
// If !AsynchronousIn -> queue indexes - 1 // If !AsynchronousIn -> queue indexes - 1
else if (queueOut != maxQueueIdSynchronous || mThreadManagerMode == ThreadManagerMode::AsynchronousOut) else if (queueOut != maxQueueIdSynchronous
|| mThreadManagerMode == ThreadManagerMode::AsynchronousOut)
{ {
// Queue in + out // Queue in + out
if (queueIn != 0) if (queueIn != 0)
subThread = {std::make_shared<SubThreadQueueInOut<TDatums, TWorker, TQueue>>(tWorkers, mTQueues.at(queueIn-1), mTQueues.at(queueOut-1))}; subThread = {std::make_shared<SubThreadQueueInOut<TDatums, TWorker, TQueue>>(
tWorkers, mTQueues.at(queueIn-1), mTQueues.at(queueOut-1))};
// Case queue out (first TWorker(s)) // Case queue out (first TWorker(s))
else else
subThread = {std::make_shared<SubThreadQueueOut<TDatums, TWorker, TQueue>>(tWorkers, mTQueues.at(queueOut-1))}; subThread = {std::make_shared<SubThreadQueueOut<TDatums, TWorker, TQueue>>(
tWorkers, mTQueues.at(queueOut-1))};
} }
// Case queue in (last TWorker(s)) // Case queue in (last TWorker(s))
else if (queueIn != 0) // && queueOut == maxQueueIdSynchronous else if (queueIn != 0) // && queueOut == maxQueueIdSynchronous
subThread = {std::make_shared<SubThreadQueueIn<TDatums, TWorker, TQueue>>(tWorkers, mTQueues.at(queueIn-1))}; subThread = {std::make_shared<SubThreadQueueIn<TDatums, TWorker, TQueue>>(
tWorkers, mTQueues.at(queueIn-1))};
// Case no queue // Case no queue
else // if (queueIn == 0 && queueOut == maxQueueIdSynchronous) else // if (queueIn == 0 && queueOut == maxQueueIdSynchronous)
subThread = {std::make_shared<SubThreadNoQueue<TDatums, TWorker>>(tWorkers)}; subThread = {std::make_shared<SubThreadNoQueue<TDatums, TWorker>>(tWorkers)};
...@@ -431,7 +453,8 @@ namespace op ...@@ -431,7 +453,8 @@ namespace op
{ {
const auto currentThreadId = std::get<0>(threadWorkerQueue); const auto currentThreadId = std::get<0>(threadWorkerQueue);
if (currentThreadId - previousThreadId > 1) if (currentThreadId - previousThreadId > 1)
error("Missing thread id " + std::to_string(currentThreadId) + " of " + std::to_string(maxThreadId) + ".", __LINE__, __FUNCTION__, __FILE__); error("Missing thread id " + std::to_string(currentThreadId) + " of "
+ std::to_string(maxThreadId) + ".", __LINE__, __FUNCTION__, __FILE__);
previousThreadId = currentThreadId; previousThreadId = currentThreadId;
} }
...@@ -458,9 +481,11 @@ namespace op ...@@ -458,9 +481,11 @@ namespace op
// Get max queue id to get queue size // Get max queue id to get queue size
auto maxQueueId = std::get<3>(*mThreadWorkerQueues.cbegin()); auto maxQueueId = std::get<3>(*mThreadWorkerQueues.cbegin());
for (const auto& threadWorkerQueue : mThreadWorkerQueues) for (const auto& threadWorkerQueue : mThreadWorkerQueues)
maxQueueId = fastMax(maxQueueId, fastMax(std::get<2>(threadWorkerQueue), std::get<3>(threadWorkerQueue))); maxQueueId = fastMax(
maxQueueId, fastMax(std::get<2>(threadWorkerQueue), std::get<3>(threadWorkerQueue)));
// Check each queue id has at least a worker that uses it as input and another one as output. Special cases: // Check each queue id has at least a worker that uses it as input and another one as output.
// Special cases:
std::vector<std::pair<bool, bool>> usedQueueIds(maxQueueId+1, {false, false}); std::vector<std::pair<bool, bool>> usedQueueIds(maxQueueId+1, {false, false});
for (const auto& threadWorkerQueue : mThreadWorkerQueues) for (const auto& threadWorkerQueue : mThreadWorkerQueues)
{ {
...@@ -475,9 +500,11 @@ namespace op ...@@ -475,9 +500,11 @@ namespace op
for (auto i = 0ull ; i < usedQueueIds.size() ; i++) for (auto i = 0ull ; i < usedQueueIds.size() ; i++)
{ {
if (!usedQueueIds[i].first) if (!usedQueueIds[i].first)
error("Missing queue id " + std::to_string(i) + " (of " + std::to_string(maxQueueId) + ") as input.", __LINE__, __FUNCTION__, __FILE__); error("Missing queue id " + std::to_string(i) + " (of "
+ std::to_string(maxQueueId) + ") as input.", __LINE__, __FUNCTION__, __FILE__);
if (!usedQueueIds[i].second) if (!usedQueueIds[i].second)
error("Missing queue id " + std::to_string(i) + " (of " + std::to_string(maxQueueId) + ") as output.", __LINE__, __FUNCTION__, __FILE__); error("Missing queue id " + std::to_string(i) + " (of "
+ std::to_string(maxQueueId) + ") as output.", __LINE__, __FUNCTION__, __FILE__);
} }
// Create Queues // Create Queues
...@@ -485,7 +512,8 @@ namespace op ...@@ -485,7 +512,8 @@ namespace op
mTQueues.resize(maxQueueId+1); // First and last one are queues mTQueues.resize(maxQueueId+1); // First and last one are queues
else if (mThreadManagerMode == ThreadManagerMode::Synchronous) else if (mThreadManagerMode == ThreadManagerMode::Synchronous)
mTQueues.resize(maxQueueId-1); // First and last one are not actually queues mTQueues.resize(maxQueueId-1); // First and last one are not actually queues
else if (mThreadManagerMode == ThreadManagerMode::AsynchronousIn || mThreadManagerMode == ThreadManagerMode::AsynchronousOut) else if (mThreadManagerMode == ThreadManagerMode::AsynchronousIn
|| mThreadManagerMode == ThreadManagerMode::AsynchronousOut)
mTQueues.resize(maxQueueId); // First or last one is queue mTQueues.resize(maxQueueId); // First or last one is queue
else else
error("Unknown ThreadManagerMode", __LINE__, __FUNCTION__, __FILE__); error("Unknown ThreadManagerMode", __LINE__, __FUNCTION__, __FILE__);
......
...@@ -52,9 +52,13 @@ namespace op ...@@ -52,9 +52,13 @@ namespace op
{ {
// Add ID // Add ID
for (auto& tDatum : *tDatums) for (auto& tDatum : *tDatums)
tDatum.id = mGlobalCounter; // To avoid overwritting ID if e.g., custom input has already filled it
if (tDatum.id == std::numeric_limits<unsigned long long>::max())
tDatum.id = mGlobalCounter;
// Increase ID // Increase ID
mGlobalCounter++; const auto& tDatum = (*tDatums)[0];
if (tDatum.subId == tDatum.subIdMax)
mGlobalCounter++;
} }
} }
catch (const std::exception& e) catch (const std::exception& e)
......
#ifndef OPENPOSE_THREAD_W_QUEUE_ASSEMBLER_HPP
#define OPENPOSE_THREAD_W_QUEUE_ASSEMBLER_HPP
#include <queue> // std::queue
#include <openpose/core/common.hpp>
#include <openpose/thread/worker.hpp>
#include <openpose/utilities/pointerContainer.hpp>
namespace op
{
// Note: The goal of WQueueAssembler and WQueueSplitter (integrated in wDatumProducer) is to reduce the latency
// of OpenPose. E.g., if 4 cameras in stereo mode, without this, OpenPose would have to process all 4 cameras
// with the same GPU. In this way, this work is parallelized over GPUs (1 view for each).
// Pros: Latency highly recuded, same speed
// Cons: Requires these extra 2 classes and proper threads for them
template<typename TDatums, typename TDatumsNoPtr>
class WQueueAssembler : public Worker<TDatums>
{
public:
explicit WQueueAssembler();
void initializationOnThread();
void work(TDatums& tDatums);
private:
TDatums mNextTDatums;
DELETE_COPY(WQueueAssembler);
};
}
// Implementation
#include <chrono>
#include <thread>
namespace op
{
template<typename TDatums, typename TDatumsNoPtr>
WQueueAssembler<TDatums, TDatumsNoPtr>::WQueueAssembler()
{
}
template<typename TDatums, typename TDatumsNoPtr>
void WQueueAssembler<TDatums, TDatumsNoPtr>::initializationOnThread()
{
}
template<typename TDatums, typename TDatumsNoPtr>
void WQueueAssembler<TDatums, TDatumsNoPtr>::work(TDatums& tDatums)
{
try
{
// Profiling speed
const auto profilerKey = Profiler::timerInit(__LINE__, __FUNCTION__, __FILE__);
// Input TDatums -> enqueue it
if (checkNoNullNorEmpty(tDatums))
{
// Security check
if (tDatums->size() > 1)
error("This function assumes that WQueueSplitter (inside WDatumProducer)"
" was applied in the first place, i.e., that there is only 1 element"
" per TDatums (size = " + std::to_string(tDatums->size()) + ").",
__LINE__, __FUNCTION__, __FILE__);
auto tDatum = (*tDatums)[0];
// Single view --> Return
if (tDatum.subIdMax == 0)
return;
// Multiple view --> Merge views into different TDatums (1st frame)
if (mNextTDatums == nullptr)
mNextTDatums = std::make_shared<TDatumsNoPtr>();
// Multiple view --> Merge views into different TDatums
mNextTDatums->emplace_back(tDatum);
// Last view - Return frame
if (mNextTDatums->back().subId == mNextTDatums->back().subIdMax)
{
tDatums = mNextTDatums;
mNextTDatums = nullptr;
// Profiling speed
Profiler::timerEnd(profilerKey);
Profiler::printAveragedTimeMsOnIterationX(profilerKey, __LINE__, __FUNCTION__, __FILE__);
// Debugging log
dLog("", Priority::Low, __LINE__, __FUNCTION__, __FILE__);
}
// Non-last view - Return nothing
else
tDatums = nullptr;
}
// Sleep if no new tDatums to either pop or push
else
std::this_thread::sleep_for(std::chrono::milliseconds{1});
}
catch (const std::exception& e)
{
this->stop();
tDatums = nullptr;
error(e.what(), __LINE__, __FUNCTION__, __FILE__);
}
}
extern template class WQueueAssembler<DATUM_BASE, DATUM_BASE_NO_PTR>;
}
#endif // OPENPOSE_THREAD_W_QUEUE_ASSEMBLER_HPP
...@@ -24,6 +24,7 @@ namespace op ...@@ -24,6 +24,7 @@ namespace op
const unsigned int mMaxBufferSize; const unsigned int mMaxBufferSize;
bool mStopWhenEmpty; bool mStopWhenEmpty;
unsigned long long mNextExpectedId; unsigned long long mNextExpectedId;
unsigned long long mNextExpectedSubId;
std::priority_queue<TDatums, std::vector<TDatums>, PointerContainerGreater<TDatums>> mPriorityQueueBuffer; std::priority_queue<TDatums, std::vector<TDatums>, PointerContainerGreater<TDatums>> mPriorityQueueBuffer;
DELETE_COPY(WQueueOrderer); DELETE_COPY(WQueueOrderer);
...@@ -43,7 +44,8 @@ namespace op ...@@ -43,7 +44,8 @@ namespace op
WQueueOrderer<TDatums>::WQueueOrderer(const unsigned int maxBufferSize) : WQueueOrderer<TDatums>::WQueueOrderer(const unsigned int maxBufferSize) :
mMaxBufferSize{maxBufferSize}, mMaxBufferSize{maxBufferSize},
mStopWhenEmpty{false}, mStopWhenEmpty{false},
mNextExpectedId{0} mNextExpectedId{0},
mNextExpectedSubId{0}
{ {
} }
...@@ -66,8 +68,22 @@ namespace op ...@@ -66,8 +68,22 @@ namespace op
// T* to T // T* to T
auto& tDatumsNoPtr = *tDatums; auto& tDatumsNoPtr = *tDatums;
// tDatums is the next expected, update counter // tDatums is the next expected, update counter
if (tDatumsNoPtr[0].id == mNextExpectedId) if (tDatumsNoPtr[0].id == mNextExpectedId && tDatumsNoPtr[0].subId == mNextExpectedSubId)
mNextExpectedId++; {
// If single-view
if (tDatumsNoPtr[0].subIdMax == 0)
mNextExpectedId++;
// If muilti-view system
else
{
mNextExpectedSubId++;
if (mNextExpectedSubId > tDatumsNoPtr[0].subIdMax)
{
mNextExpectedSubId = 0;
mNextExpectedId++;
}
}
}
// Else push it to our buffered queue // Else push it to our buffered queue
else else
{ {
...@@ -87,7 +103,9 @@ namespace op ...@@ -87,7 +103,9 @@ namespace op
{ {
// Retrieve frame if next is desired frame or if we want to stop this worker // Retrieve frame if next is desired frame or if we want to stop this worker
if (!mPriorityQueueBuffer.empty() if (!mPriorityQueueBuffer.empty()
&& ((*mPriorityQueueBuffer.top())[0].id == mNextExpectedId || mStopWhenEmpty)) && (mStopWhenEmpty ||
((*mPriorityQueueBuffer.top())[0].id == mNextExpectedId
&& (*mPriorityQueueBuffer.top())[0].subId == mNextExpectedSubId)))
{ {
tDatums = { mPriorityQueueBuffer.top() }; tDatums = { mPriorityQueueBuffer.top() };
mPriorityQueueBuffer.pop(); mPriorityQueueBuffer.pop();
...@@ -97,9 +115,21 @@ namespace op ...@@ -97,9 +115,21 @@ namespace op
if (checkNoNullNorEmpty(tDatums)) if (checkNoNullNorEmpty(tDatums))
{ {
const auto& tDatumsNoPtr = *tDatums; const auto& tDatumsNoPtr = *tDatums;
mNextExpectedId = tDatumsNoPtr[0].id + 1; // If single-view
if (tDatumsNoPtr[0].subIdMax == 0)
mNextExpectedId = tDatumsNoPtr[0].id + 1;
// If muilti-view system
else
{
mNextExpectedSubId = tDatumsNoPtr[0].subId + 1;
if (mNextExpectedSubId > tDatumsNoPtr[0].subIdMax)
{
mNextExpectedSubId = 0;
mNextExpectedId = tDatumsNoPtr[0].id + 1;
}
}
} }
// Sleep if no new tDatums to either pop // Sleep if no new tDatums to either pop or push
if (!checkNoNullNorEmpty(tDatums) && mPriorityQueueBuffer.size() < mMaxBufferSize / 2u) if (!checkNoNullNorEmpty(tDatums) && mPriorityQueueBuffer.size() < mMaxBufferSize / 2u)
std::this_thread::sleep_for(std::chrono::milliseconds{1}); std::this_thread::sleep_for(std::chrono::milliseconds{1});
// If TDatum popped and/or pushed // If TDatum popped and/or pushed
......
...@@ -193,7 +193,6 @@ namespace op ...@@ -193,7 +193,6 @@ namespace op
// error("JointAngleEstimation (`ik_threads` flag) buggy and not working yet, but we are working on it!" // error("JointAngleEstimation (`ik_threads` flag) buggy and not working yet, but we are working on it!"
// " No coming soon...", __LINE__, __FUNCTION__, __FILE__); // " No coming soon...", __LINE__, __FUNCTION__, __FILE__);
#ifndef USE_3D_ADAM_MODEL #ifndef USE_3D_ADAM_MODEL
UNUSED(ceresDisplayReport);
error("OpenPose must be compiled with the `USE_3D_ADAM_MODEL` macro definition in order to use this" error("OpenPose must be compiled with the `USE_3D_ADAM_MODEL` macro definition in order to use this"
" functionality.", __LINE__, __FUNCTION__, __FILE__); " functionality.", __LINE__, __FUNCTION__, __FILE__);
#endif #endif
...@@ -220,36 +219,60 @@ namespace op ...@@ -220,36 +219,60 @@ namespace op
try try
{ {
// Security checks // Security checks
if (!poseKeypoints3D.empty() && poseKeypoints3D.getSize(1) != 19 && poseKeypoints3D.getSize(1) != 25) if (!poseKeypoints3D.empty() && poseKeypoints3D.getSize(1) != 19 && poseKeypoints3D.getSize(1) != 25
error("Only working for BODY_19 or BODY_25/BODY_25_19 (#parts = " && poseKeypoints3D.getSize(1) != 65)
error("Only working for BODY_19 or BODY_25/BODY_25_19 or BODY_65 (#parts = "
+ std::to_string(poseKeypoints3D.getSize(2)) + ").", + std::to_string(poseKeypoints3D.getSize(2)) + ").",
__LINE__, __FUNCTION__, __FILE__); __LINE__, __FUNCTION__, __FILE__);
// Shorter naming // Shorter naming
auto& frameParams = spImpl->mFrameParams; auto& frameParams = spImpl->mFrameParams;
// Reset to 0 all keypoints - Otherwise undefined behavior when fitting
// It must be done on every iteration, otherwise errors, e.g., if face
// was detected in frame i-1 but not in i
spImpl->mBodyJoints.setZero();
spImpl->mFaceJoints.setZero();
spImpl->mLHandJoints.setZero();
spImpl->mRHandJoints.setZero();
spImpl->mLFootJoints.setZero();
spImpl->mRFootJoints.setZero();
// If keypoints detected // If keypoints detected
if (!poseKeypoints3D.empty()) if (!poseKeypoints3D.empty())
{ {
// Reset to 0 all keypoints - Otherwise undefined behavior when fitting
// It must be done on every iteration, otherwise errors, e.g., if face
// was detected in frame i-1 but not in i
spImpl->mBodyJoints.setZero();
spImpl->mFaceJoints.setZero();
spImpl->mLHandJoints.setZero();
spImpl->mRHandJoints.setZero();
spImpl->mLFootJoints.setZero();
spImpl->mRFootJoints.setZero();
// Update body // Update body
for (auto part = 0 ; part < 19; part++) for (auto part = 0 ; part < 19; part++)
updateKeypoint(spImpl->mBodyJoints, updateKeypoint(spImpl->mBodyJoints,
&poseKeypoints3D[{0, part, 0}], &poseKeypoints3D[{0, part, 0}],
mapOPToAdam(part)); mapOPToAdam(part));
// Update left/right hand // Update left/right hand
for (auto hand = 0u ; hand < handKeypoints3D.size(); hand++) if (poseKeypoints3D.getSize(1) == 65)
if (!handKeypoints3D.at(hand).empty()) {
for (auto part = 0 ; part < handKeypoints3D[hand].getSize(1); part++) // Wrists
updateKeypoint((hand == 0 ? spImpl->mLHandJoints : spImpl->mRHandJoints), updateKeypoint(spImpl->mLHandJoints,
&handKeypoints3D[hand][{0, part, 0}], &poseKeypoints3D[{0, 7, 0}],
part); 0);
updateKeypoint(spImpl->mRHandJoints,
&poseKeypoints3D[{0, 4, 0}],
0);
// Left
for (auto part = 0 ; part < 20; part++)
updateKeypoint(spImpl->mLHandJoints,
&poseKeypoints3D[{0, part+25, 0}],
part+1);
// Right
for (auto part = 0 ; part < 20; part++)
updateKeypoint(spImpl->mRHandJoints,
&poseKeypoints3D[{0, part+25+20, 0}],
part+1);
}
else
{
for (auto hand = 0u ; hand < handKeypoints3D.size(); hand++)
if (!handKeypoints3D.at(hand).empty())
for (auto part = 0 ; part < handKeypoints3D[hand].getSize(1); part++)
updateKeypoint((hand == 0 ? spImpl->mLHandJoints : spImpl->mRHandJoints),
&handKeypoints3D[hand][{0, part, 0}],
part);
}
// Update Foot data // Update Foot data
if (poseKeypoints3D.getSize(1) == 25) if (poseKeypoints3D.getSize(1) == 25)
{ {
...@@ -272,77 +295,80 @@ namespace op ...@@ -272,77 +295,80 @@ namespace op
part); part);
// Meters --> cm // Meters --> cm
spImpl->mBodyJoints *= 1e2; spImpl->mBodyJoints *= 1e2;
if (!handKeypoints3D.at(0).empty()) if (!handKeypoints3D.at(0).empty() || poseKeypoints3D.getSize(1) == 65)
spImpl->mLHandJoints *= 1e2; spImpl->mLHandJoints *= 1e2;
if (!handKeypoints3D.at(1).empty()) if (!handKeypoints3D.at(1).empty() || poseKeypoints3D.getSize(1) == 65)
spImpl->mRHandJoints *= 1e2; spImpl->mRHandJoints *= 1e2;
if (!faceKeypoints3D.empty()) if (!faceKeypoints3D.empty())
spImpl->mFaceJoints *= 1e2; spImpl->mFaceJoints *= 1e2;
spImpl->mLFootJoints *= 1e2; spImpl->mLFootJoints *= 1e2;
spImpl->mRFootJoints *= 1e2; spImpl->mRFootJoints *= 1e2;
}
// Initialization (e.g., first frame) // Initialization (e.g., first frame)
const bool fastVersion = false; const bool fastVersion = false;
const bool freezeMissing = false; const bool freezeMissing = true;
const bool ceresDisplayReport = false; const bool ceresDisplayReport = false;
// Fill Datum // Fill Datum
if (!spImpl->mInitialized || !fastVersion) if (!spImpl->mInitialized || !fastVersion)
{
if (!spImpl->mInitialized)
{
frameParams.m_adam_t(0) = spImpl->mBodyJoints(0, 2);
frameParams.m_adam_t(1) = spImpl->mBodyJoints(1, 2);
frameParams.m_adam_t(2) = spImpl->mBodyJoints(2, 2);
frameParams.m_adam_pose(0, 0) = 3.14159265358979323846264338327950288419716939937510582097494459;
spImpl->mInitialized = true;
}
// We make T-pose start with:
// 1. Root translation similar to current 3-d location of the mid-hip
// 2. x-orientation = 180, i.e., person standing up & looking to the camera
// 3. Because otherwise, if we call Adam_FastFit_Initialize twice (e.g., if a new person appears),
// it would use the latest ones from the last Adam_FastFit
// Fit initialization
// Adam_FastFit_Initialize only changes frameParams
const auto handEnabled = !handKeypoints3D[0].empty() || !handKeypoints3D[1].empty();
const auto fitFaceExponents = !faceKeypoints3D.empty();
const auto multistageFitting = true;
const auto fastSolver = true;
Adam_FastFit_Initialize(*spImpl->spTotalModel, frameParams, spImpl->mBodyJoints, spImpl->mRFootJoints,
spImpl->mLFootJoints, spImpl->mRHandJoints, spImpl->mLHandJoints,
spImpl->mFaceJoints, freezeMissing, ceresDisplayReport,
multistageFitting, handEnabled, fitFaceExponents, fastSolver);
// The following 2 operations takes ~12 msec
if (spImpl->mReturnJacobian)
{ {
vtVec = spImpl->spTotalModel->m_meanshape if (!spImpl->mInitialized)
+ spImpl->spTotalModel->m_shapespace_u * frameParams.m_adam_coeffs;
j0Vec = spImpl->spTotalModel->J_mu_ + spImpl->spTotalModel->dJdc_ * frameParams.m_adam_coeffs;
if (fastVersion)
{ {
spImpl->mVtVec = vtVec; frameParams.m_adam_t(0) = spImpl->mBodyJoints(0, 2);
spImpl->mJ0Vec = j0Vec; frameParams.m_adam_t(1) = spImpl->mBodyJoints(1, 2);
frameParams.m_adam_t(2) = spImpl->mBodyJoints(2, 2);
frameParams.m_adam_pose(0, 0) = 3.14159265358979323846264338327950288419716939937510582097494459;
spImpl->mInitialized = true;
}
// We make T-pose start with:
// 1. Root translation similar to current 3-d location of the mid-hip
// 2. x-orientation = 180, i.e., person standing up & looking to the camera
// 3. Because otherwise, if we call Adam_FastFit_Initialize twice (e.g., if a new person appears),
// it would use the latest ones from the last Adam_FastFit
// Fit initialization
// Adam_FastFit_Initialize only changes frameParams
const auto multistageFitting = true;
const auto handEnabled = !handKeypoints3D[0].empty() || !handKeypoints3D[1].empty()
|| poseKeypoints3D.getSize(1) == 65;
const auto fitFaceExponents = !faceKeypoints3D.empty();
const auto fastSolver = true;
Adam_FastFit_Initialize(*spImpl->spTotalModel, frameParams, spImpl->mBodyJoints, spImpl->mRFootJoints,
spImpl->mLFootJoints, spImpl->mRHandJoints, spImpl->mLHandJoints,
spImpl->mFaceJoints, freezeMissing, ceresDisplayReport,
multistageFitting, handEnabled, fitFaceExponents, fastSolver);
// The following 2 operations takes ~12 msec
if (spImpl->mReturnJacobian)
{
vtVec = spImpl->spTotalModel->m_meanshape
+ spImpl->spTotalModel->m_shapespace_u * frameParams.m_adam_coeffs;
j0Vec = spImpl->spTotalModel->J_mu_ + spImpl->spTotalModel->dJdc_ * frameParams.m_adam_coeffs;
if (fastVersion)
{
spImpl->mVtVec = vtVec;
spImpl->mJ0Vec = j0Vec;
}
} }
} }
} // Other frames if fastVersion
// Other frames if fastVersion else // if (spImpl->mInitialized && fastVersion)
else // if (spImpl->mInitialized && fastVersion)
{
// Adam_FastFit only changes frameParams
Adam_FastFit(*spImpl->spTotalModel, frameParams, spImpl->mBodyJoints, spImpl->mRFootJoints,
spImpl->mLFootJoints, spImpl->mRHandJoints, spImpl->mLHandJoints,
spImpl->mFaceJoints, ceresDisplayReport);
if (spImpl->mReturnJacobian)
{ {
vtVec = spImpl->mVtVec; // Adam_FastFit only changes frameParams
j0Vec = spImpl->mJ0Vec; Adam_FastFit(*spImpl->spTotalModel, frameParams, spImpl->mBodyJoints, spImpl->mRFootJoints,
spImpl->mLFootJoints, spImpl->mRHandJoints, spImpl->mLHandJoints,
spImpl->mFaceJoints, ceresDisplayReport);
if (spImpl->mReturnJacobian)
{
vtVec = spImpl->mVtVec;
j0Vec = spImpl->mJ0Vec;
}
} }
adamPose = frameParams.m_adam_pose;
adamTranslation = frameParams.m_adam_t;
adamFacecoeffsExp = frameParams.m_adam_facecoeffs_exp;
// // Not used anymore
// frameParams.mouth_open, frameParams.reye_open, frameParams.leye_open, frameParams.dist_root_foot
} }
adamPose = frameParams.m_adam_pose; else
adamTranslation = frameParams.m_adam_t; spImpl->mInitialized = false;
adamFacecoeffsExp = frameParams.m_adam_facecoeffs_exp;
// // Not used anymore
// frameParams.mouth_open, frameParams.reye_open, frameParams.leye_open, frameParams.dist_root_foot
} }
catch (const std::exception& e) catch (const std::exception& e)
{ {
......
...@@ -165,33 +165,80 @@ namespace op ...@@ -165,33 +165,80 @@ namespace op
// - Accuracy: initial reprojection error ~14-21, reduced ~5% with non-linear optimization // - Accuracy: initial reprojection error ~14-21, reduced ~5% with non-linear optimization
// Basic triangulation // Basic triangulation
triangulate(reconstructedPoint, cameraMatrices, pointsOnEachCamera); auto projectionError = triangulate(reconstructedPoint, cameraMatrices, pointsOnEachCamera);
// Basic RANSAC (for >= 4 cameras if the reprojection error is higher than usual)
// 1. Run with all cameras (already done)
// 2. Run with all but 1 camera for each camera.
// 3. Use the one with minimum average reprojection error.
// Note: Meant to be used for up to 7-8 views. With more than that, it might not improve much.
// Set initial values
auto cameraMatricesFinal = cameraMatrices;
auto pointsOnEachCameraFinal = pointsOnEachCamera;
if (cameraMatrices.size() >= 4
&& projectionError > 0.5 * reprojectionMaxAcceptable
/*&& projectionError < 1.5 * reprojectionMaxAcceptable*/)
{
auto bestReprojection = projectionError;
auto bestReprojectionIndex = -1; // -1 means with all camera views
for (auto i = 0u; i < cameraMatrices.size(); ++i)
{
// Set initial values
auto cameraMatricesSubset = cameraMatrices;
auto pointsOnEachCameraSubset = pointsOnEachCamera;
// Remove camera i
cameraMatricesSubset.erase(cameraMatricesSubset.begin() + i);
pointsOnEachCameraSubset.erase(pointsOnEachCameraSubset.begin() + i);
// Remove camera i
const auto projectionErrorSubset = triangulate(reconstructedPoint, cameraMatricesSubset,
pointsOnEachCameraSubset);
// If projection doesn't change much, it usually means all points are bad.
if (projectionErrorSubset > 0.9 * projectionError
&& projectionErrorSubset < 1.1 * projectionError)
{
bestReprojectionIndex = -1;
break;
}
// Save maximum
if (bestReprojection > projectionErrorSubset)
{
bestReprojection = projectionErrorSubset;
bestReprojectionIndex = i;
}
}
if (bestReprojectionIndex != -1 && bestReprojection < 0.5 * reprojectionMaxAcceptable)
{
// Remove camera i
cameraMatricesFinal.erase(cameraMatricesFinal.begin() + bestReprojectionIndex);
pointsOnEachCameraFinal.erase(pointsOnEachCameraFinal.begin() + bestReprojectionIndex);
}
}
#ifdef USE_CERES #ifdef USE_CERES
const auto projectionErrorLinear = calcReprojectionError(reconstructedPoint, cameraMatrices, pointsOnEachCamera);
// Empirically detected that reprojection error (for 4 cameras) only minimizes the error if initial // Empirically detected that reprojection error (for 4 cameras) only minimizes the error if initial
// project error > ~2.5, and that it improves more the higher that error actually is // project error > ~2.5, and that it improves more the higher that error actually is
// Therefore, we disable it for already accurate samples in order to get both: // Therefore, we disable it for already accurate samples in order to get both:
// - Speed // - Speed
// - Accuracy for already accurate samples // - Accuracy for already accurate samples
if (projectionErrorLinear > 3.0 if (projectionError > 3.0
&& projectionErrorLinear < 1.5*reprojectionMaxAcceptable) && projectionError < 1.5*reprojectionMaxAcceptable)
{ {
// Slow equivalent: double paramX[3]; paramX[i] = reconstructedPoint.at<double>(i); // Slow equivalent: double paramX[3]; paramX[i] = reconstructedPoint.at<double>(i);
double* paramX = (double*)reconstructedPoint.data; double* paramX = (double*)reconstructedPoint.data;
ceres::Problem problem; ceres::Problem problem;
for (auto i = 0u; i < cameraMatrices.size(); ++i) for (auto i = 0u; i < cameraMatricesFinal.size(); ++i)
{ {
// Slow copy equivalent: // Slow copy equivalent:
// double camParam[12]; memcpy(camParam, cameraMatrices[i].data, sizeof(double)*12); // double camParam[12]; memcpy(camParam, cameraMatricesFinal[i].data, sizeof(double)*12);
const double* const camParam = (double*)cameraMatrices[i].data; const double* const camParam = (double*)cameraMatricesFinal[i].data;
// Each Residual block takes a point and a camera as input and outputs a 2 // Each Residual block takes a point and a camera as input and outputs a 2
// dimensional residual. Internally, the cost function stores the observed // dimensional residual. Internally, the cost function stores the observed
// image location and compares the reprojection against the observation. // image location and compares the reprojection against the observation.
ceres::CostFunction* cost_function = ceres::CostFunction* cost_function =
new ceres::AutoDiffCostFunction<ReprojectionErrorForTriangulation, 2, 3>( new ceres::AutoDiffCostFunction<ReprojectionErrorForTriangulation, 2, 3>(
new ReprojectionErrorForTriangulation( new ReprojectionErrorForTriangulation(
pointsOnEachCamera[i].x, pointsOnEachCamera[i].y, camParam)); pointsOnEachCameraFinal[i].x, pointsOnEachCameraFinal[i].y, camParam));
// Add to problem // Add to problem
problem.AddResidualBlock(cost_function, problem.AddResidualBlock(cost_function,
//NULL, //squared loss //NULL, //squared loss
...@@ -224,9 +271,10 @@ namespace op ...@@ -224,9 +271,10 @@ namespace op
// if (summary.initial_cost > summary.final_cost) // if (summary.initial_cost > summary.final_cost)
// std::cout << summary.FullReport() << "\n"; // std::cout << summary.FullReport() << "\n";
projectionError = calcReprojectionError(reconstructedPoint, cameraMatricesFinal,
pointsOnEachCameraFinal);
// const auto reprojectionErrorDecrease = std::sqrt((summary.initial_cost - summary.final_cost) // const auto reprojectionErrorDecrease = std::sqrt((summary.initial_cost - summary.final_cost)
// / double(cameraMatrices.size())); // / double(cameraMatricesFinal.size()));
// return reprojectionErrorDecrease;
} }
#else #else
UNUSED(reprojectionMaxAcceptable); UNUSED(reprojectionMaxAcceptable);
...@@ -235,19 +283,19 @@ namespace op ...@@ -235,19 +283,19 @@ namespace op
// // Check that our implementation gives similar result than OpenCV // // Check that our implementation gives similar result than OpenCV
// // But we apply bundle adjustment + >2 views, so it should be better (and slower) than OpenCV one // // But we apply bundle adjustment + >2 views, so it should be better (and slower) than OpenCV one
// if (cameraMatrices.size() == 4) // if (cameraMatricesFinal.size() == 4)
// { // {
// cv::Mat triangCoords4D; // cv::Mat triangCoords4D;
// cv::triangulatePoints(cameraMatrices.at(0), cameraMatrices.at(3), // cv::triangulatePoints(cameraMatricesFinal.at(0), cameraMatricesFinal.at(3),
// std::vector<cv::Point2d>{pointsOnEachCamera.at(0)}, // std::vector<cv::Point2d>{pointsOnEachCameraFinal.at(0)},
// std::vector<cv::Point2d>{pointsOnEachCamera.at(3)}, triangCoords4D); // std::vector<cv::Point2d>{pointsOnEachCameraFinal.at(3)}, triangCoords4D);
// triangCoords4D /= triangCoords4D.at<double>(3); // triangCoords4D /= triangCoords4D.at<double>(3);
// std::cout << reconstructedPoint << "\n" // std::cout << reconstructedPoint << "\n"
// << triangCoords4D << "\n" // << triangCoords4D << "\n"
// << cv::norm(reconstructedPoint-triangCoords4D) << "\n" << std::endl; // << cv::norm(reconstructedPoint-triangCoords4D) << "\n" << std::endl;
// } // }
return calcReprojectionError(reconstructedPoint, cameraMatrices, pointsOnEachCamera); return projectionError;
} }
catch (const std::exception& e) catch (const std::exception& e)
{ {
...@@ -360,12 +408,6 @@ namespace op ...@@ -360,12 +408,6 @@ namespace op
} }
const auto reprojectionErrorTotal = std::accumulate( const auto reprojectionErrorTotal = std::accumulate(
reprojectionErrors.begin(), reprojectionErrors.end(), 0.0) / xyPoints.size(); reprojectionErrors.begin(), reprojectionErrors.end(), 0.0) / xyPoints.size();
if (reprojectionErrorTotal > 60)
log("Unusual high re-projection error (averaged over #keypoints) of value "
+ std::to_string(reprojectionErrorTotal) + " pixels, while the average for a good OpenPose"
" detection from 4 cameras is about 2-3 pixels. It might be simply a wrong OpenPose"
" detection. If this message appears very frequently, your calibration parameters"
" might be wrong.", Priority::High);
// 3D points to pose // 3D points to pose
// OpenCV alternative: // OpenCV alternative:
...@@ -374,6 +416,7 @@ namespace op ...@@ -374,6 +416,7 @@ namespace op
// cv::triangulatePoints(cv::Mat::eye(3,4, CV_64F), M_3_1, firstcv::Points, secondcv::Points, // cv::triangulatePoints(cv::Mat::eye(3,4, CV_64F), M_3_1, firstcv::Points, secondcv::Points,
// reconstructedcv::Points); // reconstructedcv::Points);
// 20 pixels for 1280x1024 image // 20 pixels for 1280x1024 image
bool atLeastOnePointProjected = false;
const auto lastChannelLength = keypoints3D.getSize(2); const auto lastChannelLength = keypoints3D.getSize(2);
for (auto index = 0u; index < indexesUsed.size(); index++) for (auto index = 0u; index < indexesUsed.size(); index++)
{ {
...@@ -388,8 +431,15 @@ namespace op ...@@ -388,8 +431,15 @@ namespace op
keypoints3D[baseIndex + 1] = xyzPoints[index].y; keypoints3D[baseIndex + 1] = xyzPoints[index].y;
keypoints3D[baseIndex + 2] = xyzPoints[index].z; keypoints3D[baseIndex + 2] = xyzPoints[index].z;
keypoints3D[baseIndex + 3] = 1.f; keypoints3D[baseIndex + 3] = 1.f;
atLeastOnePointProjected = true;
} }
} }
if (!atLeastOnePointProjected || reprojectionErrorTotal > 60)
log("Unusual high re-projection error (averaged over #keypoints) of value "
+ std::to_string(reprojectionErrorTotal) + " pixels, while the average for a good OpenPose"
" detection from 4 cameras is about 2-3 pixels. It might be simply a wrong OpenPose"
" detection. If this message appears very frequently, your calibration parameters"
" might be wrong.", Priority::High);
} }
// log("Reprojection error: " + std::to_string(reprojectionErrorTotal)); // To debug reprojection error // log("Reprojection error: " + std::to_string(reprojectionErrorTotal)); // To debug reprojection error
} }
......
...@@ -18,6 +18,7 @@ namespace op ...@@ -18,6 +18,7 @@ namespace op
subId{datum.subId}, subId{datum.subId},
subIdMax{datum.subIdMax}, subIdMax{datum.subIdMax},
name{datum.name}, name{datum.name},
frameNumber{datum.frameNumber},
// Input image and rendered version // Input image and rendered version
cvInputData{datum.cvInputData}, cvInputData{datum.cvInputData},
inputNetData{datum.inputNetData}, inputNetData{datum.inputNetData},
...@@ -81,6 +82,7 @@ namespace op ...@@ -81,6 +82,7 @@ namespace op
subId = datum.subId; subId = datum.subId;
subIdMax = datum.subIdMax; subIdMax = datum.subIdMax;
name = datum.name; name = datum.name;
frameNumber = datum.frameNumber;
// Input image and rendered version // Input image and rendered version
cvInputData = datum.cvInputData; cvInputData = datum.cvInputData;
inputNetData = datum.inputNetData; inputNetData = datum.inputNetData;
...@@ -146,6 +148,7 @@ namespace op ...@@ -146,6 +148,7 @@ namespace op
id{datum.id}, id{datum.id},
subId{datum.subId}, subId{datum.subId},
subIdMax{datum.subIdMax}, subIdMax{datum.subIdMax},
frameNumber{datum.frameNumber},
// Other parameters // Other parameters
scaleInputToOutput{datum.scaleInputToOutput}, scaleInputToOutput{datum.scaleInputToOutput},
scaleNetToOutput{datum.scaleNetToOutput} scaleNetToOutput{datum.scaleNetToOutput}
...@@ -218,6 +221,7 @@ namespace op ...@@ -218,6 +221,7 @@ namespace op
subId = datum.subId; subId = datum.subId;
subIdMax = datum.subIdMax; subIdMax = datum.subIdMax;
std::swap(name, datum.name); std::swap(name, datum.name);
frameNumber = datum.frameNumber;
// Input image and rendered version // Input image and rendered version
std::swap(cvInputData, datum.cvInputData); std::swap(cvInputData, datum.cvInputData);
std::swap(inputNetData, datum.inputNetData); std::swap(inputNetData, datum.inputNetData);
...@@ -290,6 +294,7 @@ namespace op ...@@ -290,6 +294,7 @@ namespace op
datum.subId = subId; datum.subId = subId;
datum.subIdMax = subIdMax; datum.subIdMax = subIdMax;
datum.name = name; datum.name = name;
datum.frameNumber = frameNumber;
// Input image and rendered version // Input image and rendered version
datum.cvInputData = cvInputData.clone(); datum.cvInputData = cvInputData.clone();
datum.inputNetData.resize(inputNetData.size()); datum.inputNetData.resize(inputNetData.size());
......
...@@ -114,45 +114,48 @@ namespace op ...@@ -114,45 +114,48 @@ namespace op
#if defined(USE_ASIO) && defined(USE_EIGEN) #if defined(USE_ASIO) && defined(USE_EIGEN)
try try
{ {
const Eigen::Map<const Eigen::Vector3d> adamTranslation(adamTranslationPtr); if (adamPosePtr != nullptr && adamTranslationPtr != nullptr && adamFaceCoeffsExpPtr != nullptr)
const Eigen::Map<const Eigen::Matrix<double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor>> adamPose(
adamPosePtr, adamPoseRows, 3);
const Eigen::Map<const Eigen::VectorXd> adamFaceCoeffsExp(adamFaceCoeffsExpPtr, faceCoeffRows);
const std::string prefix = "AnimData:";
const std::string totalPositionString = "\"totalPosition\":"
+ vectorToJson(adamTranslation(0), adamTranslation(1), adamTranslation(2));
std::string jointAnglesString = "\"jointAngles\":[";
for (int i = 0; i < adamPoseRows; i++)
{ {
jointAnglesString += vectorToJson(adamPose(i, 0), adamPose(i, 1), adamPose(i, 2)); const Eigen::Map<const Eigen::Vector3d> adamTranslation(adamTranslationPtr);
if (i != adamPoseRows - 1) const Eigen::Map<const Eigen::Matrix<double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor>> adamPose(
adamPosePtr, adamPoseRows, 3);
const Eigen::Map<const Eigen::VectorXd> adamFaceCoeffsExp(adamFaceCoeffsExpPtr, faceCoeffRows);
const std::string prefix = "AnimData:";
const std::string totalPositionString = "\"totalPosition\":"
+ vectorToJson(adamTranslation(0), adamTranslation(1), adamTranslation(2));
std::string jointAnglesString = "\"jointAngles\":[";
for (int i = 0; i < adamPoseRows; i++)
{ {
jointAnglesString += ","; jointAnglesString += vectorToJson(adamPose(i, 0), adamPose(i, 1), adamPose(i, 2));
if (i != adamPoseRows - 1)
{
jointAnglesString += ",";
}
} }
} jointAnglesString += "]";
jointAnglesString += "]";
std::string facialParamsString = "\"facialParams\":["; std::string facialParamsString = "\"facialParams\":[";
for (int i = 0; i < faceCoeffRows; i++) for (int i = 0; i < faceCoeffRows; i++)
{
facialParamsString += std::to_string(adamFaceCoeffsExp(i));
if (i != faceCoeffRows - 1)
{ {
facialParamsString += ","; facialParamsString += std::to_string(adamFaceCoeffsExp(i));
if (i != faceCoeffRows - 1)
{
facialParamsString += ",";
}
} }
} facialParamsString += "]";
facialParamsString += "]";
// facialParamsString + std::to_string(mouth_open) + "," + std::to_string(leye_open) + "," + std::to_string(reye_open) + "]"; // facialParamsString + std::to_string(mouth_open) + "," + std::to_string(leye_open) + "," + std::to_string(reye_open) + "]";
// std::string rootHeightString = "\"rootHeight\":" + std::to_string(dist_root_foot); // std::string rootHeightString = "\"rootHeight\":" + std::to_string(dist_root_foot);
const std::string data = prefix + "{" + facialParamsString const std::string data = prefix + "{" + facialParamsString
+ "," + totalPositionString + "," + totalPositionString
+ "," + jointAnglesString + "}"; + "," + jointAnglesString + "}";
spImpl->mUdpClient.send(data); spImpl->mUdpClient.send(data);
}
} }
catch (const std::exception& e) catch (const std::exception& e)
{ {
......
...@@ -301,7 +301,17 @@ namespace op ...@@ -301,7 +301,17 @@ namespace op
validSubsetIndexes.reserve(fastMin((size_t)POSE_MAX_PEOPLE, subset.size())); validSubsetIndexes.reserve(fastMin((size_t)POSE_MAX_PEOPLE, subset.size()));
for (auto index = 0u ; index < subset.size() ; index++) for (auto index = 0u ; index < subset.size() ; index++)
{ {
const auto subsetCounter = subset[index].first[subsetCounterIndex]; auto subsetCounter = subset[index].first[subsetCounterIndex];
// Foot keypoints do not affect subsetCounter (too many false positives,
// same foot usually appears as both left and right keypoints)
// Pros: Removed tons of false positives
// Cons: Standalone leg will never be recorded
if (!COCO_CHALLENGE && numberBodyParts == 25)
{
// No consider foot keypoints for that
for (auto i = 19 ; i < 25 ; i++)
subsetCounter -= (subset[index].first.at(i) > 0);
}
const auto subsetScore = subset[index].second; const auto subsetScore = subset[index].second;
if (subsetCounter >= minSubsetCnt && (subsetScore/subsetCounter) >= minSubsetScore) if (subsetCounter >= minSubsetCnt && (subsetScore/subsetCounter) >= minSubsetScore)
{ {
...@@ -310,7 +320,7 @@ namespace op ...@@ -310,7 +320,7 @@ namespace op
if (numberPeople == POSE_MAX_PEOPLE) if (numberPeople == POSE_MAX_PEOPLE)
break; break;
} }
else if (subsetCounter < 1) else if ((subsetCounter < 1 && numberBodyParts != 25) || subsetCounter < 0)
error("Bad subsetCounter. Bug in this function if this happens.", error("Bad subsetCounter. Bug in this function if this happens.",
__LINE__, __FUNCTION__, __FILE__); __LINE__, __FUNCTION__, __FILE__);
} }
......
...@@ -303,7 +303,17 @@ namespace op ...@@ -303,7 +303,17 @@ namespace op
validSubsetIndexes.reserve(fastMin((size_t)POSE_MAX_PEOPLE, subset.size())); validSubsetIndexes.reserve(fastMin((size_t)POSE_MAX_PEOPLE, subset.size()));
for (auto index = 0u ; index < subset.size() ; index++) for (auto index = 0u ; index < subset.size() ; index++)
{ {
const auto subsetCounter = subset[index].first[subsetCounterIndex]; auto subsetCounter = subset[index].first[subsetCounterIndex];
// Foot keypoints do not affect subsetCounter (too many false positives,
// same foot usually appears as both left and right keypoints)
// Pros: Removed tons of false positives
// Cons: Standalone leg will never be recorded
if (!COCO_CHALLENGE && numberBodyParts == 25)
{
// No consider foot keypoints for that
for (auto i = 19 ; i < 25 ; i++)
subsetCounter -= (subset[index].first.at(i) > 0);
}
const auto subsetScore = subset[index].second; const auto subsetScore = subset[index].second;
if (subsetCounter >= minSubsetCnt && (subsetScore/subsetCounter) >= minSubsetScore) if (subsetCounter >= minSubsetCnt && (subsetScore/subsetCounter) >= minSubsetScore)
{ {
...@@ -312,7 +322,7 @@ namespace op ...@@ -312,7 +322,7 @@ namespace op
if (numberPeople == POSE_MAX_PEOPLE) if (numberPeople == POSE_MAX_PEOPLE)
break; break;
} }
else if (subsetCounter < 1) else if ((subsetCounter < 1 && numberBodyParts != 25) || subsetCounter < 0)
error("Bad subsetCounter. Bug in this function if this happens.", error("Bad subsetCounter. Bug in this function if this happens.",
__LINE__, __FUNCTION__, __FILE__); __LINE__, __FUNCTION__, __FILE__);
} }
......
...@@ -388,8 +388,6 @@ namespace op ...@@ -388,8 +388,6 @@ namespace op
// Default Model Parameters // Default Model Parameters
// They might be modified on running time // They might be modified on running time
// const bool COCO_CHALLENGE = true;
const bool COCO_CHALLENGE = false;
const auto nmsT = (COCO_CHALLENGE ? 0.04f : 0.05f); const auto nmsT = (COCO_CHALLENGE ? 0.04f : 0.05f);
const std::array<float, (int)PoseModel::Size> POSE_DEFAULT_NMS_THRESHOLD{ const std::array<float, (int)PoseModel::Size> POSE_DEFAULT_NMS_THRESHOLD{
nmsT, nmsT, 0.6f, 0.3f, nmsT, nmsT, nmsT, nmsT, nmsT, nmsT, nmsT, nmsT nmsT, nmsT, 0.6f, 0.3f, nmsT, nmsT, nmsT, nmsT, nmsT, nmsT, nmsT, nmsT
......
...@@ -17,5 +17,6 @@ namespace op ...@@ -17,5 +17,6 @@ namespace op
DEFINE_TEMPLATE_DATUM(WorkerConsumer); DEFINE_TEMPLATE_DATUM(WorkerConsumer);
DEFINE_TEMPLATE_DATUM(WorkerProducer); DEFINE_TEMPLATE_DATUM(WorkerProducer);
DEFINE_TEMPLATE_DATUM(WIdGenerator); DEFINE_TEMPLATE_DATUM(WIdGenerator);
template class OP_API WQueueAssembler<DATUM_BASE, DATUM_BASE_NO_PTR>;
DEFINE_TEMPLATE_DATUM(WQueueOrderer); DEFINE_TEMPLATE_DATUM(WQueueOrderer);
} }
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册