提交 9e1d6e41 编写于 作者: G gineshidalgo99

3D updating bug fixed, dlog in experimental module

上级 4986dadd
......@@ -144,7 +144,8 @@ if (${GPU_MODE} MATCHES "CUDA")
endif (${GPU_MODE} MATCHES "CUDA")
# Suboptions for OpenPose 3D Reconstruction demo
option(BUILD_MODULE_3D "Build OpenPose 3D Reconstruction module." OFF)
option(WITH_3D_RENDERER "Add OpenPose 3D renderer module (it requires FreeGLUT library)." OFF)
option(WITH_FLIR_CAMERA "Add FLIR (formerly Point Grey) camera code (requires Spinnaker SDK already installed)." OFF)
# Download the models
option(DOWNLOAD_COCO_MODEL "Download COCO model." ON)
......@@ -171,10 +172,14 @@ if (${GPU_MODE} MATCHES "CUDA")
endif ()
# Adding 3D
if (BUILD_MODULE_3D)
if (WITH_3D_RENDERER)
# OpenPose flags
add_definitions(-DBUILD_MODULE_3D)
endif (BUILD_MODULE_3D)
add_definitions(-DWITH_3D_RENDERER)
endif (WITH_3D_RENDERER)
if (WITH_FLIR_CAMERA)
# OpenPose flags
add_definitions(-DWITH_FLIR_CAMERA)
endif (WITH_FLIR_CAMERA)
if (UNIX AND NOT APPLE)
if (${GPU_MODE} MATCHES "CUDA")
......@@ -193,19 +198,21 @@ if (UNIX AND NOT APPLE)
endif (OpenCV_CONFIG_FILE)
# 3D
if (BUILD_MODULE_3D)
if (WITH_3D_RENDERER)
# GLUT
find_package(GLUT REQUIRED)
endif (WITH_3D_RENDERER)
if (WITH_FLIR_CAMERA)
# Spinnaker
find_package(Spinnaker)
if (NOT SPINNAKER_FOUND)
message(FATAL_ERROR "Spinnaker not found. Either turn off the `BUILD_MODULE_3D` option or specify the path of
Spinnaker includes and libs.")
message(FATAL_ERROR "Spinnaker not found. Either turn off the `WITH_FLIR_CAMERA` option or specify the path to
the Spinnaker includes and libs.")
endif (NOT SPINNAKER_FOUND)
# Otherwise error if 3D module enabled, and then disabled (with Spinnaker not installed)
else (BUILD_MODULE_3D)
else (WITH_FLIR_CAMERA)
set(SPINNAKER_LIB "")
endif (BUILD_MODULE_3D)
endif (WITH_FLIR_CAMERA)
# OpenMP
if (${GPU_MODE} MATCHES "CPU_ONLY")
......@@ -271,9 +278,9 @@ if (WIN32)
download_zip("opencv_310.zip" ${OP_WIN_URL} ${FIND_LIB_PREFIX} 1e5240a64b814b3c0b822f136be78ad7)
download_zip("caffe3rdparty_2017_07_14.zip" ${OP_WIN_URL} ${FIND_LIB_PREFIX} ec0f800c8fb337e33304f3375bd06a80)
download_zip("caffe_2018_01_18.zip" ${OP_WIN_URL} ${FIND_LIB_PREFIX} 4b8e548cc7ea20abea472950dd5301bd)
if (BUILD_MODULE_3D)
if (WITH_3D_RENDERER)
download_zip("freeglut_2018_01_14.zip" ${OP_WIN_URL} ${FIND_LIB_PREFIX} BB182187285E06880F0EDE3A39530091)
endif (BUILD_MODULE_3D)
endif (WITH_3D_RENDERER)
message(STATUS "Windows dependencies downloaded.")
find_library(OpenCV_LIBS opencv_world310 HINTS ${FIND_LIB_PREFIX}/opencv/x64/vc14/lib)
......@@ -284,20 +291,24 @@ if (WIN32)
find_library(OpenCV_LIBS opencv_world310 HINTS ${FIND_LIB_PREFIX}/opencv/x64/vc14/lib)
find_library(Caffe_LIB caffe HINTS ${FIND_LIB_PREFIX}/caffe/lib)
find_library(Caffe_Proto_LIB caffeproto HINTS ${FIND_LIB_PREFIX}/caffe/lib)
if (BUILD_MODULE_3D)
find_library(SPINNAKER_LIB spinnaker_v140 HINTS ${FIND_LIB_PREFIX}/spinnaker/lib)
if (WITH_3D_RENDERER)
find_library(GLUT_LIBRARY freeglut HINTS ${FIND_LIB_PREFIX}/freeglut/lib)
message(STATUS "\${GLUT_LIBRARY} = ${GLUT_LIBRARY}")
endif (BUILD_MODULE_3D)
endif (WITH_3D_RENDERER)
if (WITH_FLIR_CAMERA)
find_library(SPINNAKER_LIB spinnaker_v140 HINTS ${FIND_LIB_PREFIX}/spinnaker/lib)
endif (WITH_FLIR_CAMERA)
set(Caffe_LIBS ${Caffe_LIB};${Caffe_Proto_LIB})
set(OpenCV_INCLUDE_DIRS "3rdparty/windows/opencv/include")
set(Caffe_INCLUDE_DIRS "3rdparty/windows/caffe/include;3rdparty/windows/caffe/include2")
set(Boost_INCLUDE_DIRS "3rdparty/windows/caffe3rdparty/include/boost-1_61")
set(WINDOWS_INCLUDE_DIRS "3rdparty/windows/caffe3rdparty/include")
if (BUILD_MODULE_3D)
set(SPINNAKER_INCLUDE_DIRS "3rdparty/windows/spinnaker/include")
if (WITH_3D_RENDERER)
set(GLUT_INCLUDE_DIRS "3rdparty/windows/freeglut/include")
endif (BUILD_MODULE_3D)
endif (WITH_3D_RENDERER)
if (WITH_FLIR_CAMERA)
set(SPINNAKER_INCLUDE_DIRS "3rdparty/windows/spinnaker/include")
endif (WITH_FLIR_CAMERA)
set(Caffe_FOUND 1)
endif (WIN32)
......@@ -445,9 +456,12 @@ if (${GPU_MODE} MATCHES "CUDA")
${CUDA_INCLUDE_DIRS})
endif ()
# 3D
if (BUILD_MODULE_3D)
include_directories(${GLUT_INCLUDE_DIRS} ${SPINNAKER_INCLUDE_DIRS})
endif (BUILD_MODULE_3D)
if (WITH_3D_RENDERER)
include_directories(${GLUT_INCLUDE_DIRS})
endif (WITH_3D_RENDERER)
if (WITH_FLIR_CAMERA)
include_directories(${SPINNAKER_INCLUDE_DIRS})
endif (WITH_FLIR_CAMERA)
# Windows includes
if (WIN32)
include_directories(
......
......@@ -198,7 +198,7 @@ By default, the body MPI model is not downloaded. You can download it by turning
#### OpenPose 3D Reconstruction Module and Demo
You can include the 3D reconstruction module by:
1. Install the FLIR camera driver and software, Spinnaker SDK. It is a propietary software, so we cannot provide direct download link.
1. Install the FLIR camera software, Spinnaker SDK. It is a propietary software, so we cannot provide direct download link. Note: You might skip this step if you intend to use the 3-D OpenPose module with a different camera brand.
1. Ubuntu: Get and install the latest Spinnaker SKD version in their default path. OpenPose will automatically find it. Otherwise, set the right path with CMake.
2. Windows: Donwload the latest Spinnaker SKD version from [https://www.ptgrey.com/support/downloads](https://www.ptgrey.com/support/downloads).
- Copy `{PointGreyParentDirectory}\Point Grey Research\Spinnaker\bin64\vs2015\` as `{OpenPoseDirectory}\3rdparty\windows\spinnaker\bin\`. You can remove all the *.exe files.
......@@ -216,7 +216,7 @@ You can include the 3D reconstruction module by:
- Copy `{freeglutParentDirectory}\freeglut\bin\x64\` as `{OpenPoseDirectory}\3rdparty\windows\freeglut\bin\`.
- Copy `{freeglutParentDirectory}\freeglut\include\` as `{OpenPoseDirectory}\3rdparty\windows\freeglut\include\`.
- Copy `{freeglutParentDirectory}\freeglut\lib\x64\` as `{OpenPoseDirectory}\3rdparty\windows\freeglut\lib\`.
3. Follow the CMake installation steps, and set the `BUILD_MODULE_3D` option.
3. Follow the CMake installation steps. In addition, set the `WITH_FLIR_CAMERA` (only if Spinnaker was installed) and `WITH_3D_RENDERER` options.
4. In Windows, after openning the OpenPose visual studio solution:
1. Right-click on `Solution 'OpenPose'` of the `Solution Explorer` window, usually placed at the top-right part of the VS screen.
2. Click on `Properties`. Go to `Configuration Properties` -> `Configuration` and check `Build` for the `OpenPose3DReconstruction` project.
......
......@@ -8,7 +8,8 @@
4. [Camera Calibration](#camera-calibration)
5. [Camera Ordering](#camera-ordering)
6. [Installing the OpenPose 3-D Reconstruction Module](#installing-the-openpose-3-d-reconstruction-module)
7. [Known Bug](#known-bug)
7. [Using a Different Camera Brand](#using-a-different-camera-brand)
8. [Known Bug](#known-bug)
......@@ -87,6 +88,11 @@ It should be similar to the following image.
## Using a Different Camera Brand
You can copy and modify the OpenPose 3-D demo to use any camera brand, by modifying the frames producer. For that, you would need to provide your custom code to retrieve synchronized images from your cameras, as well as their intrinsic and extrinsic camera parameters.
## Known Bug
FreeGLUT is a quite light library. Due to that, there is a known bug in the 3D module:
......
add_subdirectory(experimental_3d)
add_subdirectory(openpose)
add_subdirectory(tutorial_add_module)
add_subdirectory(tutorial_pose)
add_subdirectory(tutorial_thread)
add_subdirectory(tutorial_wrapper)
if (BUILD_MODULE_3D)
add_subdirectory(experimental_3d)
endif (BUILD_MODULE_3D)
if (UNIX AND NOT APPLE)
add_subdirectory(tests)
endif (UNIX AND NOT APPLE)
......@@ -206,7 +206,7 @@ int openpose()
// Initializing the user custom classes
// Frames producer (e.g. video, webcam, ...)
auto wPointGrey = std::make_shared<op::WPointGrey>();
auto wFlirReader = std::make_shared<op::WFlirReader>();
// Processing
auto wReconstruction3D = std::make_shared<op::WReconstruction3D>();
// GUI (Display)
......@@ -215,7 +215,7 @@ int openpose()
op::Wrapper<std::vector<op::Datum3D>> opWrapper;
// Add custom input
const auto workerInputOnNewThread = true;
opWrapper.setWorkerInput(wPointGrey, workerInputOnNewThread);
opWrapper.setWorkerInput(wFlirReader, workerInputOnNewThread);
// Add custom processing
const auto workerProcessingOnNewThread = true;
opWrapper.setWorkerPostProcessing(wReconstruction3D, workerProcessingOnNewThread);
......
......@@ -14,6 +14,7 @@ namespace op
Array<float> faceKeypoints3D;
Array<float> leftHandKeypoints3D;
Array<float> rightHandKeypoints3D;
cv::Mat cameraParameterMatrix;
};
}
......
......@@ -7,22 +7,25 @@
namespace op
{
// Following OpenPose `tutorial_wrapper/` examples, we create our own class inherited from WorkerProducer.
// This worker:
// 1. Set hardware trigger and the buffer to get the latest obtained frame.
// 2. Read images from FLIR cameras.
// 3. Turn them into std::vector<cv::Mat>.
// 4. Return the resulting images wrapped into a std::shared_ptr<std::vector<Datum3D>>.
// The HW trigger + reading FLIR camera code is highly based on the Spinnaker SDK examples `AcquisitionMultipleCamera`
// and specially `Trigger`
// (located in `src/`). See them for more details about the cameras.
// See `examples/tutorial_wrapper/` for more details about inhering the WorkerProducer class.
class OP_API WPointGrey : public WorkerProducer<std::shared_ptr<std::vector<Datum3D>>>
/**
* FLIR (Point-Grey) camera producer
* Following OpenPose `tutorial_wrapper/` examples, we create our own class inherited from WorkerProducer.
* This worker:
* 1. Set hardware trigger and the buffer to get the latest obtained frame.
* 2. Read images from FLIR cameras.
* 3. Turn them into std::vector<cv::Mat>.
* 4. Return the resulting images wrapped into a std::shared_ptr<std::vector<Datum3D>>.
* The HW trigger + reading FLIR camera code is highly based on the Spinnaker SDK examples
* `AcquisitionMultipleCamera` and specially `Trigger`
* (located in `src/`). See them for more details about the cameras.
* See `examples/tutorial_wrapper/` for more details about inhering the WorkerProducer class.
*/
class OP_API WFlirReader : public WorkerProducer<std::shared_ptr<std::vector<Datum3D>>>
{
public:
WPointGrey();
WFlirReader();
~WPointGrey();
~WFlirReader();
void initializationOnThread();
......@@ -31,8 +34,8 @@ namespace op
private:
// PIMPL idiom
// http://www.cppsamples.com/common-tasks/pimpl.html
struct ImplWPointGrey;
std::unique_ptr<ImplWPointGrey> upImpl;
struct ImplWFlirReader;
std::unique_ptr<ImplWFlirReader> upImpl;
};
}
......
......@@ -5,8 +5,8 @@
#include <openpose/experimental/3d/cameraParameters.hpp>
// Datum3D
#include <openpose/experimental/3d/datum3D.hpp>
// PointGrey cameras
#include <openpose/experimental/3d/pointGrey.hpp>
// Flir (Point-Grey) cameras
#include <openpose/experimental/3d/flirReader.hpp>
// 3D reconstruction
#include <openpose/experimental/3d/reconstruction3D.hpp>
// OpenGL Renderer
......
......@@ -9,11 +9,11 @@ namespace op
{
// Following OpenPose `tutorial_wrapper/` examples, we create our own class inherited from Worker.
// This worker will do 3-D reconstruction
// We apply the simple Direct linear transformation (DLT) algorithm, asumming each keypoint (e.g. right hip) is seen
// by all the cameras.
// We apply the simple Direct linear transformation (DLT) algorithm, asumming each keypoint (e.g. right hip) is
// seen by all the cameras.
// No non-linear minimization used, and if some camera misses the point, it is not reconstructed.
// See `examples/tutorial_wrapper/` for more details about inhering the Worker class and using it for post-processing
// purposes.
// See `examples/tutorial_wrapper/` for more details about inhering the Worker class and using it for
// post-processing purposes.
class OP_API WReconstruction3D : public Worker<std::shared_ptr<std::vector<Datum3D>>>
{
public:
......
......@@ -15,8 +15,8 @@ namespace op
{
public:
/**
* Constructor of ImageDirectoryReader. It sets the image directory path from which the images will be loaded and
* generates a std::vector<std::string> with the list of images on that directory.
* Constructor of ImageDirectoryReader. It sets the image directory path from which the images will be loaded
* and generates a std::vector<std::string> with the list of images on that directory.
* @param imageDirectoryPath const std::string parameter with the folder path containing the images.
*/
explicit ImageDirectoryReader(const std::string& imageDirectoryPath);
......
set(SOURCES_OP_3D
cameraParameters.cpp
pointGrey.cpp
flirReader.cpp
reconstruction3D.cpp
renderer.cpp)
......
#include <chrono>
#include <thread>
#include <opencv2/imgproc/imgproc.hpp>
#ifdef BUILD_MODULE_3D
#ifdef WITH_FLIR_CAMERA
#include <Spinnaker.h>
#endif
#include <openpose/experimental/3d/cameraParameters.hpp>
#include <openpose/utilities/check.hpp>
#include <openpose/experimental/3d/pointGrey.hpp>
#include <openpose/experimental/3d/flirReader.hpp>
namespace op
{
#ifdef BUILD_MODULE_3D
#ifdef WITH_FLIR_CAMERA
/*
* This function converts between Spinnaker::ImagePtr container to cv::Mat container used in OpenCV.
*/
cv::Mat pointGreyToCvMat(const Spinnaker::ImagePtr &imagePtr)
cv::Mat flirReaderToCvMat(const Spinnaker::ImagePtr &imagePtr)
{
try
{
......@@ -266,10 +266,10 @@ namespace op
for (auto i = 0u; i < imagePtrs.size(); i++)
{
// Baseline
// cvMats.emplace_back(pointGreyToCvMat(imagePtrs.at(i)).clone());
// cvMats.emplace_back(flirReaderToCvMat(imagePtrs.at(i)).clone());
// Undistort
// http://docs.opencv.org/2.4/modules/imgproc/doc/geometric_transformations.html#undistort
auto auxCvMat = pointGreyToCvMat(imagePtrs.at(i));
auto auxCvMat = flirReaderToCvMat(imagePtrs.at(i));
cvMats.emplace_back();
cv::undistort(auxCvMat, cvMats[i], getIntrinsics(i), getDistorsion(i));
}
......@@ -321,29 +321,29 @@ namespace op
}
#endif
struct WPointGrey::ImplWPointGrey
struct WFlirReader::ImplWFlirReader
{
#ifdef BUILD_MODULE_3D
#ifdef WITH_FLIR_CAMERA
bool mInitialized;
Spinnaker::CameraList mCameraList;
Spinnaker::SystemPtr mSystemPtr;
ImplWPointGrey() :
ImplWFlirReader() :
mInitialized{false}
{
}
#endif
};
WPointGrey::WPointGrey()
#ifdef BUILD_MODULE_3D
: upImpl{new ImplWPointGrey{}}
WFlirReader::WFlirReader()
#ifdef WITH_FLIR_CAMERA
: upImpl{new ImplWFlirReader{}}
#endif
{
try
{
#ifndef BUILD_MODULE_3D
error("OpenPose must be compiled with `BUILD_MODULE_3D` in order to use this class.",
#ifndef WITH_FLIR_CAMERA
error("OpenPose must be compiled with `WITH_FLIR_CAMERA` in order to use this class.",
__LINE__, __FUNCTION__, __FILE__);
#endif
}
......@@ -353,9 +353,9 @@ namespace op
}
}
WPointGrey::~WPointGrey()
WFlirReader::~WFlirReader()
{
#ifdef BUILD_MODULE_3D
#ifdef WITH_FLIR_CAMERA
try
{
if (upImpl->mInitialized)
......@@ -417,9 +417,9 @@ namespace op
#endif
}
void WPointGrey::initializationOnThread()
void WFlirReader::initializationOnThread()
{
#ifdef BUILD_MODULE_3D
#ifdef WITH_FLIR_CAMERA
try
{
upImpl->mInitialized = true;
......@@ -600,13 +600,15 @@ namespace op
#endif
}
std::shared_ptr<std::vector<Datum3D>> WPointGrey::workProducer()
std::shared_ptr<std::vector<Datum3D>> WFlirReader::workProducer()
{
try
{
#ifdef BUILD_MODULE_3D
#ifdef WITH_FLIR_CAMERA
try
{
// Debugging log
dLog("", Priority::Low, __LINE__, __FUNCTION__, __FILE__);
// Profiling speed
const auto profilerKey = Profiler::timerInit(__LINE__, __FUNCTION__, __FILE__);
// Get image from each camera
......@@ -616,7 +618,8 @@ namespace op
for (auto i = 0u ; i < cvMats.size() ; i++)
{
datums3d->at(i).cvInputData = cvMats.at(i);
datums3d->at(i).cvOutputData = (*datums3d)[i].cvInputData;
(*datums3d)[i].cvOutputData = (*datums3d)[i].cvInputData;
(*datums3d)[i].cameraParameterMatrix = getM(i);
}
// Profiling speed
if (!cvMats.empty())
......@@ -624,6 +627,8 @@ namespace op
Profiler::timerEnd(profilerKey);
Profiler::printAveragedTimeMsOnIterationX(profilerKey, __LINE__, __FUNCTION__, __FILE__);
}
// Debugging log
dLog("", Priority::Low, __LINE__, __FUNCTION__, __FILE__);
// Return Datum
return datums3d;
}
......@@ -634,7 +639,7 @@ namespace op
return nullptr;
}
#else
error("OpenPose must be compiled with `BUILD_MODULE_3D` in order to use this class.",
error("OpenPose must be compiled with `WITH_FLIR_CAMERA` in order to use this class.",
__LINE__, __FUNCTION__, __FILE__);
return nullptr;
#endif
......
#include <opencv2/opencv.hpp>
#include <openpose/experimental/3d/cameraParameters.hpp>
#include <openpose/experimental/3d/reconstruction3D.hpp>
namespace op
......@@ -7,7 +6,7 @@ namespace op
double calcReprojectionError(const cv::Mat& X, const std::vector<cv::Mat>& M, const std::vector<cv::Point2d>& pt2D)
{
auto averageError = 0.;
for(unsigned int i = 0 ; i < M.size() ; i++)
for (auto i = 0u ; i < M.size() ; i++)
{
cv::Mat imageX = M[i] * X;
imageX /= imageX.at<double>(2,0);
......@@ -31,7 +30,8 @@ namespace op
cv::Mat A = cv::Mat::zeros(numberCameras*2, 4, CV_64F);
for (auto i = 0 ; i < numberCameras ; i++)
{
cv::Mat temp = pointOnEachCamera[i].x*matrixEachCamera[i].rowRange(2,3) - matrixEachCamera[i].rowRange(0,1);
cv::Mat temp = pointOnEachCamera[i].x*matrixEachCamera[i].rowRange(2,3)
- matrixEachCamera[i].rowRange(0,1);
temp.copyTo(A.rowRange(i*2,i*2+1));
temp = pointOnEachCamera[i].y*matrixEachCamera[i].rowRange(2,3) - matrixEachCamera[i].rowRange(1,2);
temp.copyTo(A.rowRange(i*2+1,i*2+2));
......@@ -42,7 +42,7 @@ namespace op
X /= X.at<double>(3);
}
// TODO: ask Hanbyul for the missing function: TriangulationOptimization
// TODO: ask for the missing function: TriangulationOptimization
double triangulateWithOptimization(cv::Mat& X, const std::vector<cv::Mat>& matrixEachCamera,
const std::vector<cv::Point2d>& pointOnEachCamera)
{
......@@ -57,7 +57,8 @@ namespace op
return 0.;
}
void reconstructArray(Array<float>& keypoints3D, const std::vector<Array<float>>& keypointsVector)
void reconstructArray(Array<float>& keypoints3D, const std::vector<Array<float>>& keypointsVector,
const std::vector<cv::Mat>& matrixEachCamera)
{
// Get number body parts
auto detectionMissed = false;
......@@ -106,7 +107,7 @@ namespace op
for (auto i = 0u; i < xyPoints.size(); i++)
{
cv::Mat X;
triangulateWithOptimization(X, getMs(), xyPoints[i]);
triangulateWithOptimization(X, matrixEachCamera, xyPoints[i]);
xyzPoints[i] = cv::Point3d{ X.at<double>(0), X.at<double>(1), X.at<double>(2) };
}
......@@ -143,10 +144,13 @@ namespace op
// datum.poseKeypoints: Array<float> with the estimated pose
try
{
// Debugging log
dLog("", Priority::Low, __LINE__, __FUNCTION__, __FILE__);
// Profiling speed
const auto profilerKey = Profiler::timerInit(__LINE__, __FUNCTION__, __FILE__);
if (datumsPtr != nullptr && !datumsPtr->empty())
{
std::vector<cv::Mat> matrixEachCamera;
std::vector<Array<float>> poseKeypointVector;
std::vector<Array<float>> faceKeypointVector;
std::vector<Array<float>> leftHandKeypointVector;
......@@ -157,18 +161,21 @@ namespace op
faceKeypointVector.emplace_back(datumsElement.faceKeypoints);
leftHandKeypointVector.emplace_back(datumsElement.handKeypoints[0]);
rightHandKeypointVector.emplace_back(datumsElement.handKeypoints[1]);
matrixEachCamera.emplace_back(datumsElement.cameraParameterMatrix);
}
// Pose 3-D reconstruction
reconstructArray(datumsPtr->at(0).poseKeypoints3D, poseKeypointVector);
reconstructArray(datumsPtr->at(0).poseKeypoints3D, poseKeypointVector, matrixEachCamera);
// Face 3-D reconstruction
reconstructArray(datumsPtr->at(0).faceKeypoints3D, faceKeypointVector);
reconstructArray(datumsPtr->at(0).faceKeypoints3D, faceKeypointVector, matrixEachCamera);
// Left hand 3-D reconstruction
reconstructArray(datumsPtr->at(0).leftHandKeypoints3D, leftHandKeypointVector);
reconstructArray(datumsPtr->at(0).leftHandKeypoints3D, leftHandKeypointVector, matrixEachCamera);
// Right hand 3-D reconstruction
reconstructArray(datumsPtr->at(0).rightHandKeypoints3D, rightHandKeypointVector);
reconstructArray(datumsPtr->at(0).rightHandKeypoints3D, rightHandKeypointVector, matrixEachCamera);
// Profiling speed
Profiler::timerEnd(profilerKey);
Profiler::printAveragedTimeMsOnIterationX(profilerKey, __LINE__, __FUNCTION__, __FILE__);
// Debugging log
dLog("", Priority::Low, __LINE__, __FUNCTION__, __FILE__);
}
}
catch (const std::exception& e)
......
#include <mutex>
#include <stdio.h>
#ifdef BUILD_MODULE_3D
#ifdef WITH_3D_RENDERER
#include <GL/glut.h>
#include <GL/freeglut_ext.h> // glutLeaveMainLoop
#include <GL/freeglut_std.h>
......@@ -15,7 +15,7 @@ namespace op
{
const bool LOG_VERBOSE_3D_RENDERER = false;
#ifdef BUILD_MODULE_3D
#ifdef WITH_3D_RENDERER
struct Keypoints3D
{
Array<float> mPoseKeypoints;
......@@ -206,7 +206,7 @@ namespace op
}
// this is the actual idle function
void idleFunc()
void idleFunction()
{
glutPostRedisplay();
glutSwapBuffers();
......@@ -381,8 +381,7 @@ namespace op
char *my_argv[] = { NULL };
int my_argc = 0;
glutInit(&my_argc, my_argv);
// setup the size, position, and display mode for new windows
// Setup the size, position, and display mode for new windows
glutInitWindowSize(1280, 720);
glutInitWindowPosition(200, 0);
// glutSetOption(GLUT_MULTISAMPLE,8);
......@@ -390,14 +389,14 @@ namespace op
// button, but it does not work (tested in Ubuntu)
// https://stackoverflow.com/questions/3799803/is-it-possible-to-make-a-window-withouth-a-top-in-glut
glutInitDisplayMode(GLUT_RGBA | GLUT_DOUBLE | GLUT_DEPTH | GLUT_MULTISAMPLE);
// create and set up a window
// Create and set up a window
glutCreateWindow(GUI_NAME.c_str());
initGraphics();
glutDisplayFunc(renderMain);
glutMouseFunc(mouseButton);
glutMotionFunc(mouseMotion);
glutIdleFunc(idleFunc);
// Only required if glutMainLoop() called
// glutIdleFunc(idleFunction);
// Full screen would fix the problem of disabling `x` button
// glutFullScreen();
// Key presses
......@@ -414,12 +413,12 @@ namespace op
{
try
{
#ifdef BUILD_MODULE_3D
#ifdef WITH_3D_RENDERER
// Update sPoseModel
sPoseModel = poseModel;
#else
UNUSED(poseModel);
error("OpenPose must be compiled with `BUILD_MODULE_3D` in order to use this class.",
error("OpenPose must be compiled with `WITH_3D_RENDERER` in order to use this class.",
__LINE__, __FUNCTION__, __FILE__);
#endif
}
......@@ -433,7 +432,7 @@ namespace op
{
try
{
#ifdef BUILD_MODULE_3D
#ifdef WITH_3D_RENDERER
glutLeaveMainLoop();
#endif
}
......@@ -445,7 +444,7 @@ namespace op
void WRender3D::initializationOnThread()
{
#ifdef BUILD_MODULE_3D
#ifdef WITH_3D_RENDERER
try
{
// Init display
......@@ -462,9 +461,11 @@ namespace op
void WRender3D::workConsumer(const std::shared_ptr<std::vector<Datum3D>>& datumsPtr)
{
#ifdef BUILD_MODULE_3D
#ifdef WITH_3D_RENDERER
try
{
// Debugging log
dLog("", Priority::Low, __LINE__, __FUNCTION__, __FILE__);
// Profiling speed
const auto profilerKey = Profiler::timerInit(__LINE__, __FUNCTION__, __FILE__);
// User's displaying/saving/other processing here
......@@ -504,9 +505,12 @@ namespace op
this->stop();
// OpenCL - Run main loop event
// It is run outside loop, or it would get visually stuck if loop to slow
idleFunction();
glutMainLoopEvent();
// This alternative can only be called once, and it will block the thread until program exit
// glutMainLoop();
// Debugging log
dLog("", Priority::Low, __LINE__, __FUNCTION__, __FILE__);
}
catch (const std::exception& e)
{
......
......@@ -10,8 +10,11 @@ namespace op
try
{
// Get files on directory with the desired extensions
const std::vector<std::string> extensions{"bmp", "dib", "pbm", "pgm", "ppm", "sr", "ras", // Completely supported by OpenCV
"jpg", "jpeg", "png"}; // Most of them supported by OpenCV
const std::vector<std::string> extensions{
// Completely supported by OpenCV
"bmp", "dib", "pbm", "pgm", "ppm", "sr", "ras",
// Most of them supported by OpenCV
"jpg", "jpeg", "png"};
const auto imagePaths = getFilesOnDirectory(imageDirectoryPath, extensions);
// Check #files > 0
......@@ -45,7 +48,8 @@ namespace op
try
{
auto frame = loadImage(mFilePaths.at(mFrameNameCounter++).c_str(), CV_LOAD_IMAGE_COLOR);
// Check frame integrity. This function also checks width/height changes. However, if it is performed after setWidth/setHeight this is performed over the new resolution (so they always match).
// Check frame integrity. This function also checks width/height changes. However, if it is performed
// after setWidth/setHeight this is performed over the new resolution (so they always match).
checkFrameIntegrity(frame);
// Update size, since images might have different size between each one of them
mResolution = Point<int>{frame.cols, frame.rows};
......
......@@ -53,7 +53,8 @@ DEEP_NET := caffe
CAFFE_DIR := 3rdparty/caffe/distribute
# OpenPose 3-D Reconstruction
# BUILD_MODULE_3D := 1
# WITH_3D_RENDERER := 1
# WITH_FLIR_CAMERA := 1
# Spinnaker directory
SPINNAKER_DIR := /usr/include/spinnaker
......
......@@ -59,7 +59,8 @@ DEEP_NET := caffe
CAFFE_DIR := 3rdparty/caffe/distribute
# OpenPose 3-D Reconstruction
# BUILD_MODULE_3D := 1
# WITH_3D_RENDERER := 1
# WITH_FLIR_CAMERA := 1
# Spinnaker directory
SPINNAKER_DIR := /usr/include/spinnaker
......
......@@ -53,7 +53,8 @@ DEEP_NET := caffe
CAFFE_DIR := 3rdparty/caffe/distribute
# OpenPose 3-D Reconstruction
# BUILD_MODULE_3D := 1
# WITH_3D_RENDERER := 1
# WITH_FLIR_CAMERA := 1
# Spinnaker directory
SPINNAKER_DIR := /usr/include/spinnaker
......
......@@ -59,7 +59,8 @@ DEEP_NET := caffe
CAFFE_DIR := 3rdparty/caffe/distribute
# OpenPose 3-D Reconstruction
# BUILD_MODULE_3D := 1
# WITH_3D_RENDERER := 1
# WITH_FLIR_CAMERA := 1
# Spinnaker directory
SPINNAKER_DIR := /usr/include/spinnaker
......
......@@ -59,7 +59,8 @@ DEEP_NET := caffe
CAFFE_DIR := 3rdparty/caffe/distribute
# OpenPose 3-D Reconstruction
# BUILD_MODULE_3D := 1
# WITH_3D_RENDERER := 1
# WITH_FLIR_CAMERA := 1
# Spinnaker directory
SPINNAKER_DIR := /usr/include/spinnaker
......
......@@ -71,17 +71,23 @@ else
endif
# Spinnaker
BUILD_MODULE_3D ?= 0
ifneq ($(BUILD_MODULE_3D), 0)
COMMON_FLAGS += -DBUILD_MODULE_3D
# Spinnaker SDK
LIBRARIES += Spinnaker
INCLUDE_DIRS += $(SPINNAKER_DIR)
# 3-D
# 3-D renderer
WITH_3D_RENDERER ?= 0
ifneq ($(WITH_3D_RENDERER), 0)
COMMON_FLAGS += -DWITH_3D_RENDERER
# FreeGLUT
LIBRARIES += glut
# LIBRARIES += GLU GL glut
endif
# Spinnaker SDK
WITH_FLIR_CAMERA ?= 0
ifneq ($(WITH_FLIR_CAMERA), 0)
COMMON_FLAGS += -DWITH_FLIR_CAMERA
# Spinnaker SDK
LIBRARIES += Spinnaker
INCLUDE_DIRS += $(SPINNAKER_DIR)
endif
##############################
# Get all source files
......
......@@ -125,8 +125,8 @@
<ClInclude Include="..\..\include\openpose\core\wScaleAndSizeExtractor.hpp" />
<ClInclude Include="..\..\include\openpose\experimental\3d\cameraParameters.hpp" />
<ClInclude Include="..\..\include\openpose\experimental\3d\datum3D.hpp" />
<ClInclude Include="..\..\include\openpose\experimental\3d\flirReader.hpp" />
<ClInclude Include="..\..\include\openpose\experimental\3d\headers.hpp" />
<ClInclude Include="..\..\include\openpose\experimental\3d\pointGrey.hpp" />
<ClInclude Include="..\..\include\openpose\experimental\3d\reconstruction3D.hpp" />
<ClInclude Include="..\..\include\openpose\experimental\3d\renderer.hpp" />
<ClInclude Include="..\..\include\openpose\experimental\headers.hpp" />
......@@ -284,7 +284,7 @@
<ClCompile Include="..\..\src\openpose\core\resizeAndMergeCaffe.cpp" />
<ClCompile Include="..\..\src\openpose\core\scaleAndSizeExtractor.cpp" />
<ClCompile Include="..\..\src\openpose\experimental\3d\cameraParameters.cpp" />
<ClCompile Include="..\..\src\openpose\experimental\3d\pointGrey.cpp" />
<ClCompile Include="..\..\src\openpose\experimental\3d\flirReader.cpp" />
<ClCompile Include="..\..\src\openpose\experimental\3d\reconstruction3D.cpp" />
<ClCompile Include="..\..\src\openpose\experimental\3d\renderer.cpp" />
<ClCompile Include="..\..\src\openpose\experimental\tracking\defineTemplates.cpp" />
......
......@@ -560,10 +560,10 @@
<ClInclude Include="..\..\include\openpose\experimental\3d\datum3D.hpp">
<Filter>Header Files\experimental\3d</Filter>
</ClInclude>
<ClInclude Include="..\..\include\openpose\experimental\3d\headers.hpp">
<ClInclude Include="..\..\include\openpose\experimental\3d\flirReader.hpp">
<Filter>Header Files\experimental\3d</Filter>
</ClInclude>
<ClInclude Include="..\..\include\openpose\experimental\3d\pointGrey.hpp">
<ClInclude Include="..\..\include\openpose\experimental\3d\headers.hpp">
<Filter>Header Files\experimental\3d</Filter>
</ClInclude>
<ClInclude Include="..\..\include\openpose\experimental\3d\reconstruction3D.hpp">
......@@ -657,7 +657,7 @@
<ClCompile Include="..\..\src\openpose\experimental\3d\cameraParameters.cpp">
<Filter>Source Files\experimental\3d</Filter>
</ClCompile>
<ClCompile Include="..\..\src\openpose\experimental\3d\pointGrey.cpp">
<ClCompile Include="..\..\src\openpose\experimental\3d\flirReader.cpp">
<Filter>Source Files\experimental\3d</Filter>
</ClCompile>
<ClCompile Include="..\..\src\openpose\experimental\3d\reconstruction3D.cpp">
......
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册