提交 05a05730 编写于 作者: G gineshidalgo99

Camera resolution works for flir camera, render pose CPU for 3d by default

上级 9b525050
......@@ -43,9 +43,10 @@ This demo assumes n arbitrary stereo cameras from the FLIR company (formerly Poi
- (Ubuntu-only) Open your USB ports following section `Configuring USBFS` in [http://www.ptgrey.com/KB/10685](http://www.ptgrey.com/KB/10685).
- Install the Spinnaker SDK for your operating system: [https://www.ptgrey.com/support/downloads](https://www.ptgrey.com/support/downloads).
2. Fujinon 3 MP Varifocal Lens (3.8-13mm, 3.4x Zoom) for each camera.
- E.g. [https://www.bhphotovideo.com/c/product/736855-REG/Fujinon_DV3_4X3_8SA_1_3_MP_Varifocal_Lens.html](https://www.bhphotovideo.com/c/product/736855-REG/Fujinon_DV3_4X3_8SA_1_3_MP_Varifocal_Lens.html).
- E.g., [https://www.bhphotovideo.com/c/product/736855-REG/Fujinon_DV3_4X3_8SA_1_3_MP_Varifocal_Lens.html](https://www.bhphotovideo.com/c/product/736855-REG/Fujinon_DV3_4X3_8SA_1_3_MP_Varifocal_Lens.html).
3. 4-Port PCI Express (PCIe) USB 3.0 Card Adapter with 4 dedicated channels.
- E.g. [https://www.startech.com/Cards-Adapters/USB-3.0/Cards/PCI-Express-USB-3-Card-4-Dedicated-Channels-4-Port~PEXUSB3S44V](https://www.startech.com/Cards-Adapters/USB-3.0/Cards/PCI-Express-USB-3-Card-4-Dedicated-Channels-4-Port~PEXUSB3S44V).
- E.g., the 4 Ext Quad Bus version, PCI Express, from: [https://www.amazon.com/Express-SuperSpeed-Adapter-Dedicated-Channels/dp/B00HJZEA2S/ref=sr_1_1?ie=UTF8&qid=1492197599&sr=8-1&keywords=4%2BPort%2BPCI%2BExpress%2B(PCIe)%2Bdedicated%2Bports&th=1](https://www.amazon.com/Express-SuperSpeed-Adapter-Dedicated-Channels/dp/B00HJZEA2S/ref=sr_1_1?ie=UTF8&qid=1492197599&sr=8-1&keywords=4%2BPort%2BPCI%2BExpress%2B(PCIe)%2Bdedicated%2Bports&th=1).
- Alternative: [https://www.startech.com/Cards-Adapters/USB-3.0/Cards/PCI-Express-USB-3-Card-4-Dedicated-Channels-4-Port~PEXUSB3S44V](https://www.startech.com/Cards-Adapters/USB-3.0/Cards/PCI-Express-USB-3-Card-4-Dedicated-Channels-4-Port~PEXUSB3S44V).
4. USB 3.0 cable for each FLIR camera.
- From their official website: [https://www.ptgrey.com/5-meter-type-a-to-micro-b-locking-usb-30-cable](https://www.ptgrey.com/5-meter-type-a-to-micro-b-locking-usb-30-cable).
......@@ -73,7 +74,7 @@ In order to verify that the camera parameters introduced by the user are sorted
## Installing the OpenPose 3-D Reconstruction Module
Check the [doc/installation.md#openpose-3d-reconstruction-module](./quick_start.md#openpose-3d-reconstruction-module) for installation steps.
Check the [doc/installation.md#3d-reconstruction-module](./quick_start.md#3d-reconstruction-module) for installation steps.
......
......@@ -136,7 +136,7 @@ Each flag is divided into flag name, default value, and description.
- DEFINE_int32(profile_speed, 1000, "If PROFILER_ENABLED was set in CMake or Makefile.config files, OpenPose will show some runtime statistics at this frame number.");
2. Producer
- DEFINE_int32(camera, -1, "The camera index for cv::VideoCapture. Integer in the range [0, 9]. Select a negative number (by default), to auto-detect and open the first available camera.");
- DEFINE_string(camera_resolution, "1280x720", "Size of the camera frames to ask for.");
- DEFINE_string(camera_resolution, "-1x-1", "Set the camera resolution (either `--camera` or `--flir_camera`). `-1x-1` will use the default 1280x720 for `--camera`, or the maximum flir camera resolution available for `--flir_camera`");
- DEFINE_double(camera_fps, 30.0, "Frame rate for the webcam (only used when saving video from webcam). Set this value to the minimum value between the OpenPose displayed speed and the webcam real frame rate.");
- DEFINE_string(video, "", "Use a video file instead of the camera. Use `examples/media/video.avi` for our default example video.");
- DEFINE_string(image_dir, "", "Process a directory of images. Use `examples/media/` for our default example folder with 20 images. Read all standard formats (jpg, png, bmp, etc.).");
......
......@@ -9,6 +9,7 @@ OpenPose - Frequently Asked Question (FAQ)
4. [Vide/Webcam Not Working](#video-webcam-not-working)
5. [Cannot Find OpenPose.dll Error](#cannot-find-openpose.dll-error-windows)
6. [Free Invalid Pointer Error](#free-invalid-pointer-error)
7. [Source Directory does not Contain CMakeLists.txt (Windows)](#source-directory-does-not-contain-cmakelists.txt-windows)
......@@ -66,3 +67,10 @@ Note: OpenPose library is not an executable, but a library. So instead clicking
**Q: I am getting an error of the type: munmap_chunk()/free/invalid pointer.**
**A**: In order to run OpenCV 3.X and Caffe simultaneously, [OpenCV must be compiled without `WITH_GTK` and with `WITH_QT` flags](https://github.com/BVLC/caffe/issues/5282#issuecomment-306063718). On Ubuntu 16.04 the qt5 package is "qt5-default" and the OpenCV cmake option is WITH_QT.
### Source Directory does not Contain CMakeLists.txt (Windows)
**Q: I am getting an error of the type: `The source directory {path to file} does not contain a CMakeLists.txt file.`.**
**A**: You might not have writing access to that folder. If you are in Windows, you should not try to install it in `Program Files`.
......@@ -12,7 +12,7 @@ OpenPose - Installation
8. [Uninstallation](#uninstallation)
9. [Optional Settings](#optional-settings)
1. [MPI Model](#mpi-model)
2. [OpenPose 3D Reconstruction Module](#openpose-3d-reconstruction-module)
2. [3D Reconstruction Module](#3d-reconstruction-module)
3. [Compiling without cuDNN](#compiling-without-cudnn)
4. [Custom Caffe (Ubuntu Only)](#custom-caffe-ubuntu-only)
5. [Custom OpenCV (Ubuntu Only)](#custom-opencv-ubuntu-only)
......@@ -214,7 +214,7 @@ By default, the body MPI model is not downloaded. You can download it by turning
#### OpenPose 3D Reconstruction Module
#### 3D Reconstruction Module
You can include the 3D reconstruction module by:
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.
......
......@@ -45,7 +45,9 @@ DEFINE_int32(profile_speed, 1000, "If PROFILER_ENABLED was
// Producer
DEFINE_int32(camera, -1, "The camera index for cv::VideoCapture. Integer in the range [0, 9]. Select a negative"
" number (by default), to auto-detect and open the first available camera.");
DEFINE_string(camera_resolution, "1280x720", "Size of the camera frames to ask for.");
DEFINE_string(camera_resolution, "-1x-1", "Set the camera resolution (either `--camera` or `--flir_camera`). `-1x-1` will use the"
" default 1280x720 for `--camera`, or the maximum flir camera resolution available for"
" `--flir_camera`");
DEFINE_double(camera_fps, 30.0, "Frame rate for the webcam (only used when saving video from webcam). Set this value to the"
" minimum value between the OpenPose displayed speed and the webcam real frame rate.");
DEFINE_string(video, "", "Use a video file instead of the camera. Use `examples/media/video.avi` for our default"
......@@ -266,7 +268,8 @@ int openPoseDemo()
// Pose configuration (use WrapperStructPose{} for default and recommended configuration)
const op::WrapperStructPose wrapperStructPose{!FLAGS_body_disable, netInputSize, outputSize, keypointScale,
FLAGS_num_gpu, FLAGS_num_gpu_start, FLAGS_scale_number,
(float)FLAGS_scale_gap, op::flagsToRenderMode(FLAGS_render_pose),
(float)FLAGS_scale_gap,
op::flagsToRenderMode(FLAGS_render_pose, FLAGS_3d, FLAGS_render_pose),
poseModel, !FLAGS_disable_blending, (float)FLAGS_alpha_pose,
(float)FLAGS_alpha_heatmap, FLAGS_part_to_show, FLAGS_model_folder,
heatMapTypes, heatMapScale, FLAGS_part_candidates,
......@@ -274,13 +277,13 @@ int openPoseDemo()
enableGoogleLogging, FLAGS_3d, FLAGS_identification};
// Face configuration (use op::WrapperStructFace{} to disable it)
const op::WrapperStructFace wrapperStructFace{FLAGS_face, faceNetInputSize,
op::flagsToRenderMode(FLAGS_face_render, FLAGS_render_pose),
op::flagsToRenderMode(FLAGS_face_render, FLAGS_3d, FLAGS_render_pose),
(float)FLAGS_face_alpha_pose, (float)FLAGS_face_alpha_heatmap,
(float)FLAGS_face_render_threshold};
// Hand configuration (use op::WrapperStructHand{} to disable it)
const op::WrapperStructHand wrapperStructHand{FLAGS_hand, handNetInputSize, FLAGS_hand_scale_number,
(float)FLAGS_hand_scale_range, FLAGS_hand_tracking,
op::flagsToRenderMode(FLAGS_hand_render, FLAGS_render_pose),
op::flagsToRenderMode(FLAGS_hand_render, FLAGS_3d, FLAGS_render_pose),
(float)FLAGS_hand_alpha_pose, (float)FLAGS_hand_alpha_heatmap,
(float)FLAGS_hand_render_threshold};
// Producer (use default to disable any input)
......
......@@ -54,7 +54,9 @@ DEFINE_int32(profile_speed, 1000, "If PROFILER_ENABLED was
// Producer
DEFINE_int32(camera, -1, "The camera index for cv::VideoCapture. Integer in the range [0, 9]. Select a negative"
" number (by default), to auto-detect and open the first available camera.");
DEFINE_string(camera_resolution, "1280x720", "Size of the camera frames to ask for.");
DEFINE_string(camera_resolution, "-1x-1", "Set the camera resolution (either `--camera` or `--flir_camera`). `-1x-1` will use the"
" default 1280x720 for `--camera`, or the maximum flir camera resolution available for"
" `--flir_camera`");
DEFINE_double(camera_fps, 30.0, "Frame rate for the webcam (only used when saving video from webcam). Set this value to the"
" minimum value between the OpenPose displayed speed and the webcam real frame rate.");
DEFINE_string(video, "", "Use a video file instead of the camera. Use `examples/media/video.avi` for our default"
......
......@@ -31,7 +31,9 @@ DEFINE_int32(logging_level, 3, "The logging level. Inte
// Producer
DEFINE_int32(camera, -1, "The camera index for cv::VideoCapture. Integer in the range [0, 9]. Select a negative"
" number (by default), to auto-detect and open the first available camera.");
DEFINE_string(camera_resolution, "1280x720", "Size of the camera frames to ask for.");
DEFINE_string(camera_resolution, "-1x-1", "Set the camera resolution (either `--camera` or `--flir_camera`). `-1x-1` will use the"
" default 1280x720 for `--camera`, or the maximum flir camera resolution available for"
" `--flir_camera`");
DEFINE_double(camera_fps, 30.0, "Frame rate for the webcam (only used when saving video from webcam). Set this value to the"
" minimum value between the OpenPose displayed speed and the webcam real frame rate.");
DEFINE_string(video, "", "Use a video file instead of the camera. Use `examples/media/video.avi` for our default"
......
......@@ -32,7 +32,9 @@ DEFINE_int32(logging_level, 3, "The logging level. Inte
// Producer
DEFINE_int32(camera, -1, "The camera index for cv::VideoCapture. Integer in the range [0, 9]. Select a negative"
" number (by default), to auto-detect and open the first available camera.");
DEFINE_string(camera_resolution, "1280x720", "Size of the camera frames to ask for.");
DEFINE_string(camera_resolution, "-1x-1", "Set the camera resolution (either `--camera` or `--flir_camera`). `-1x-1` will use the"
" default 1280x720 for `--camera`, or the maximum flir camera resolution available for"
" `--flir_camera`");
DEFINE_double(camera_fps, 30.0, "Frame rate for the webcam (only used when saving video from webcam). Set this value to the"
" minimum value between the OpenPose displayed speed and the webcam real frame rate.");
DEFINE_string(video, "", "Use a video file instead of the camera. Use `examples/media/video.avi` for our default"
......
......@@ -44,7 +44,9 @@ DEFINE_int32(profile_speed, 1000, "If PROFILER_ENABLED was
// Producer
DEFINE_int32(camera, -1, "The camera index for cv::VideoCapture. Integer in the range [0, 9]. Select a negative"
" number (by default), to auto-detect and open the first available camera.");
DEFINE_string(camera_resolution, "1280x720", "Size of the camera frames to ask for.");
DEFINE_string(camera_resolution, "-1x-1", "Set the camera resolution (either `--camera` or `--flir_camera`). `-1x-1` will use the"
" default 1280x720 for `--camera`, or the maximum flir camera resolution available for"
" `--flir_camera`");
DEFINE_double(camera_fps, 30.0, "Frame rate for the webcam (only used when saving video from webcam). Set this value to the"
" minimum value between the OpenPose displayed speed and the webcam real frame rate.");
DEFINE_string(video, "", "Use a video file instead of the camera. Use `examples/media/video.avi` for our default"
......
......@@ -18,7 +18,7 @@ namespace op
/**
* Constructor of FlirReader. It opens all the available FLIR cameras
*/
explicit FlirReader(const std::string& cameraParametersPath);
explicit FlirReader(const std::string& cameraParametersPath, const Point<int>& cameraResolution);
~FlirReader();
......
......@@ -15,7 +15,7 @@ namespace op
/**
* Constructor of SpinnakerWrapper. It opens all the available FLIR cameras
*/
explicit SpinnakerWrapper(const std::string& cameraParameterPath);
explicit SpinnakerWrapper(const std::string& cameraParameterPath, const Point<int>& cameraResolution);
~SpinnakerWrapper();
......
......@@ -23,7 +23,7 @@ namespace op
OP_API std::shared_ptr<Producer> flagsToProducer(const std::string& imageDirectory, const std::string& videoPath,
const std::string& ipCameraPath, const int webcamIndex,
const bool flirCamera = false,
const std::string& webcamResolution = "1280x720",
const std::string& cameraResolution = "-1x-1",
const double webcamFps = 30.,
const std::string& cameraParameterPath = "models/cameraParameters/",
const unsigned int imageDirectoryStereo = 1);
......@@ -32,7 +32,8 @@ namespace op
const bool heatMapsAddBkg = false,
const bool heatMapsAddPAFs = false);
OP_API RenderMode flagsToRenderMode(const int renderFlag, const int renderPoseFlag = -2);
OP_API RenderMode flagsToRenderMode(const int renderFlag, const bool gpuBuggy = false,
const int renderPoseFlag = -2);
OP_API DisplayMode flagsToDisplayMode(const int display, const bool enabled3d);
......
......@@ -95,7 +95,7 @@ namespace op
// GPU ID
mGpuID = gpuID;
#else
UNUSED(mGpuID);
UNUSED(gpuID);
#endif
// Array sizes
upImpl->mTopSize = std::array<int, 4>{topBlob->shape(0), topBlob->shape(1),
......
......@@ -86,7 +86,7 @@ namespace op
// GPU ID
mGpuID = gpuID;
#else
UNUSED(mGpuID);
UNUSED(gpuID);
#endif
#else
UNUSED(bottom);
......
......@@ -275,7 +275,7 @@ namespace op
glTranslatef(-gMouseXPan, gMouseYPan, -gMouseZPan);
renderFloor();
// renderFloor(); // Disabled, how to know where the floor is?
std::unique_lock<std::mutex> lock{gKeypoints3D.mutex};
if (gKeypoints3D.validKeypoints)
{
......
......@@ -4,14 +4,16 @@
namespace op
{
FlirReader::FlirReader(const std::string& cameraParametersPath) :
FlirReader::FlirReader(const std::string& cameraParametersPath, const Point<int>& cameraResolution) :
Producer{ProducerType::FlirCamera},
mSpinnakerWrapper{cameraParametersPath},
mSpinnakerWrapper{cameraParametersPath, cameraResolution},
mFrameNameCounter{0}
{
try
{
// Get resolution
const auto resolution = mSpinnakerWrapper.getResolution();
// Set resolution
set(CV_CAP_PROP_FRAME_WIDTH, resolution.x);
set(CV_CAP_PROP_FRAME_HEIGHT, resolution.y);
}
......@@ -140,7 +142,7 @@ namespace op
return -1.;
else
{
log("Unknown property", Priority::Max, __LINE__, __FUNCTION__, __FILE__);
log("Unknown property.", Priority::Max, __LINE__, __FUNCTION__, __FILE__);
return -1.;
}
}
......@@ -164,7 +166,7 @@ namespace op
else if (capProperty == CV_CAP_PROP_FRAME_COUNT || capProperty == CV_CAP_PROP_FPS)
log("This property is read-only.", Priority::Max, __LINE__, __FUNCTION__, __FILE__);
else
log("Unknown property", Priority::Max, __LINE__, __FUNCTION__, __FILE__);
log("Unknown property.", Priority::Max, __LINE__, __FUNCTION__, __FILE__);
}
catch (const std::exception& e)
{
......
......@@ -334,7 +334,7 @@ namespace op
#endif
};
SpinnakerWrapper::SpinnakerWrapper(const std::string& cameraParameterPath)
SpinnakerWrapper::SpinnakerWrapper(const std::string& cameraParameterPath, const Point<int>& resolution)
#ifdef WITH_FLIR_CAMERA
: upImpl{new ImplSpinnakerWrapper{}}
#endif
......@@ -342,6 +342,9 @@ namespace op
#ifdef WITH_FLIR_CAMERA
try
{
// Clean previous unclosed builds (e.g. if core dumped in the previous code using the cameras)
release();
upImpl->mInitialized = true;
// Print application build information
......@@ -485,6 +488,44 @@ namespace op
log("Camera " + std::to_string(i) + " acquisition mode set to continuous...", Priority::High);
// Set camera resolution
// Retrieve GenICam nodemap
auto& iNodeMap = cameraPtr->GetNodeMap();
// Set offset
Spinnaker::GenApi::CIntegerPtr ptrOffsetX = iNodeMap.GetNode("OffsetX");
ptrOffsetX->SetValue(0);
Spinnaker::GenApi::CIntegerPtr ptrOffsetY = iNodeMap.GetNode("OffsetY");
ptrOffsetY->SetValue(0);
// Set resolution
if (resolution.x > 0 && resolution.y > 0)
{
// WARNING: setting the obset would require auto-change in the camera matrix parameters
// Set offset
// const Spinnaker::GenApi::CIntegerPtr ptrWidthMax = iNodeMap.GetNode("WidthMax");
// const Spinnaker::GenApi::CIntegerPtr ptrHeightMax = iNodeMap.GetNode("HeightMax");
// ptrOffsetX->SetValue((ptrWidthMax->GetValue() - resolution.x) / 2);
// ptrOffsetY->SetValue((ptrHeightMax->GetValue() - resolution.y) / 2);
// Set Width
Spinnaker::GenApi::CIntegerPtr ptrWidth = iNodeMap.GetNode("Width");
ptrWidth->SetValue(resolution.x);
// Set width
Spinnaker::GenApi::CIntegerPtr ptrHeight = iNodeMap.GetNode("Height");
ptrHeight->SetValue(resolution.y);
}
else
{
const Spinnaker::GenApi::CIntegerPtr ptrWidthMax = iNodeMap.GetNode("WidthMax");
const Spinnaker::GenApi::CIntegerPtr ptrHeightMax = iNodeMap.GetNode("HeightMax");
// Set Width
Spinnaker::GenApi::CIntegerPtr ptrWidth = iNodeMap.GetNode("Width");
ptrWidth->SetValue(ptrWidthMax->GetValue());
// Set width
Spinnaker::GenApi::CIntegerPtr ptrHeight = iNodeMap.GetNode("Height");
ptrHeight->SetValue(ptrHeightMax->GetValue());
log("Choosing maximum resolution for flir camera (" + std::to_string(ptrWidth->GetValue())
+ " x " + std::to_string(ptrHeight->GetValue()) + ").", Priority::High);
}
// Begin acquiring images
cameraPtr->BeginAcquisition();
......@@ -523,6 +564,7 @@ namespace op
upImpl->mResolution = Point<int>{cvMats[0].cols, cvMats[0].rows};
log("\nRunning for all cameras...\n\n*** IMAGE ACQUISITION ***\n", Priority::High);
}
catch (const Spinnaker::Exception& e)
{
......@@ -649,14 +691,13 @@ namespace op
// GetByIndex(); this is an alternative to retrieving cameras as
// Spinnaker::CameraPtr objects that can be quick and easy for small tasks.
//
for (auto i = 0; i < upImpl->mCameraList.GetSize(); i++)
upImpl->mCameraList.GetByIndex(i)->EndAcquisition();
for (auto i = 0; i < upImpl->mCameraList.GetSize(); i++)
{
// Select camera
auto cameraPtr = upImpl->mCameraList.GetByIndex(i);
cameraPtr->EndAcquisition();
// Retrieve GenICam nodemap
auto& iNodeMap = cameraPtr->GetNodeMap();
......@@ -689,6 +730,29 @@ namespace op
log("Cameras released! Exiting program.", Priority::High);
}
else
{
// Open general system
auto systemPtr = Spinnaker::System::GetInstance();
auto cameraList = systemPtr->GetCameras();
if (cameraList.GetSize() > 0)
{
for (int i = 0; i < cameraList.GetSize(); i++)
{
// Select camera
auto cameraPtr = cameraList.GetByIndex(i);
// Begin
cameraPtr->Init();
cameraPtr->BeginAcquisition();
// End
cameraPtr->EndAcquisition();
cameraPtr->DeInit();
}
}
cameraList.Clear();
systemPtr->ReleaseInstance();
}
}
catch (const Spinnaker::Exception& e)
{
......
......@@ -136,7 +136,7 @@ namespace op
std::shared_ptr<Producer> flagsToProducer(const std::string& imageDirectory, const std::string& videoPath,
const std::string& ipCameraPath, const int webcamIndex,
const bool flirCamera, const std::string& webcamResolution,
const bool flirCamera, const std::string& cameraResolution,
const double webcamFps, const std::string& cameraParameterPath,
const unsigned int imageDirectoryStereo)
{
......@@ -152,16 +152,22 @@ namespace op
return std::make_shared<VideoReader>(videoPath);
else if (type == ProducerType::IPCamera)
return std::make_shared<IpCameraReader>(ipCameraPath);
else if (type == ProducerType::FlirCamera)
return std::make_shared<FlirReader>(cameraParameterPath);
else if (type == ProducerType::Webcam)
// Flir camera
if (type == ProducerType::FlirCamera)
{
// cameraFrameSize
const auto webcamFrameSize = op::flagsToPoint(webcamResolution, "1280x720");
const auto cameraFrameSize = op::flagsToPoint(cameraResolution, "-1x-1");
return std::make_shared<FlirReader>(cameraParameterPath, cameraFrameSize);
}
// Webcam
if (type == ProducerType::Webcam)
{
// cameraFrameSize
const auto cameraFrameSize = op::flagsToPoint(cameraResolution, "1280x720");
if (webcamIndex >= 0)
{
const auto throwExceptionIfNoOpened = true;
return std::make_shared<WebcamReader>(webcamIndex, webcamFrameSize, webcamFps,
return std::make_shared<WebcamReader>(webcamIndex, cameraFrameSize, webcamFps,
throwExceptionIfNoOpened);
}
else
......@@ -170,7 +176,7 @@ namespace op
std::shared_ptr<WebcamReader> webcamReader;
for (auto index = 0 ; index < 10 ; index++)
{
webcamReader = std::make_shared<WebcamReader>(index, webcamFrameSize, webcamFps,
webcamReader = std::make_shared<WebcamReader>(index, cameraFrameSize, webcamFps,
throwExceptionIfNoOpened);
if (webcamReader->isOpened())
{
......@@ -214,7 +220,7 @@ namespace op
}
}
RenderMode flagsToRenderMode(const int renderFlag, const int renderPoseFlag)
RenderMode flagsToRenderMode(const int renderFlag, const bool gpuBuggy, const int renderPoseFlag)
{
try
{
......@@ -222,7 +228,7 @@ namespace op
if (renderFlag == -1 && renderPoseFlag == -2)
{
#ifdef USE_CUDA
return RenderMode::Gpu;
return (gpuBuggy ? RenderMode::Cpu : RenderMode::Gpu);
#else
return RenderMode::Cpu;
#endif
......
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册