Repository: OpenGP/htrack
Branch: master
Commit: 7cfef0328f1a
Files: 273
Total size: 2.6 MB
Directory structure:
gitextract_0a61e4qc/
├── .gitignore
├── CMakeLists.txt
├── COPYING.txt
├── README.md
├── apps/
│ ├── CMakeLists.txt
│ ├── colorpick/
│ │ ├── CMakeLists.txt
│ │ └── colorpick.cpp
│ ├── helloworld/
│ │ ├── CMakeLists.txt
│ │ └── main.cpp
│ ├── helloworld_atb/
│ │ ├── CMakeLists.txt
│ │ ├── main.cpp
│ │ └── main_new.cpp
│ ├── helloworld_cublas/
│ │ ├── CMakeLists.txt
│ │ ├── gnuplot_i.h
│ │ ├── main_performance.cpp
│ │ └── main_simple.cpp
│ ├── helloworld_cudagl/
│ │ ├── CMakeLists.txt
│ │ └── main.cpp
│ ├── helloworld_librealsense/
│ │ ├── CMakeLists.txt
│ │ └── main.cpp
│ ├── helloworld_opencv/
│ │ ├── CMakeLists.txt
│ │ └── main.cpp
│ ├── helloworld_openmp/
│ │ ├── CMakeLists.txt
│ │ └── main.cpp
│ ├── helloworld_openni/
│ │ ├── CMakeLists.txt
│ │ └── main.cpp
│ ├── helloworld_qglviewer/
│ │ ├── CMakeLists.txt
│ │ └── main.cpp
│ ├── helloworld_qtopengl/
│ │ ├── CMakeLists.txt
│ │ └── main.cpp
│ ├── helloworld_realsense/
│ │ ├── CMakeLists.txt
│ │ └── main.cpp
│ ├── helloworld_thrust/
│ │ ├── CMakeLists.txt
│ │ └── main.cu
│ ├── htrack_atb/
│ │ ├── AntTweakBarEventFilter.h
│ │ ├── CMakeLists.txt
│ │ └── main.cpp
│ ├── htrack_qt/
│ │ ├── CMakeLists.txt
│ │ ├── Main_window.cpp
│ │ ├── Main_window.h
│ │ ├── OpenGL_viewer.cpp
│ │ ├── OpenGL_viewer.h
│ │ └── main.cpp
│ └── synthgen/
│ └── synthgen.cpp
├── cmake/
│ ├── CompileSynthgen.cmake
│ ├── ConfigureAntTweakBar.cmake
│ ├── ConfigureCUDA.cmake
│ ├── ConfigureCompiler.cmake
│ ├── ConfigureCudaOctree.cmake
│ ├── ConfigureEigen.cmake
│ ├── ConfigureGLEW.cmake
│ ├── ConfigureGLFW.cmake
│ ├── ConfigureLibRealSense.cmake
│ ├── ConfigureOpenCV.cmake
│ ├── ConfigureOpenGL.cmake
│ ├── ConfigureOpenGP.cmake
│ ├── ConfigureOpenMP.cmake
│ ├── ConfigureOpenNI.cmake
│ ├── ConfigureQGLViewer.cmake
│ ├── ConfigureQt.cmake
│ ├── ConfigureRealSense.cmake
│ ├── ConfigureSensor.cmake
│ ├── ConfigureSoftKinetic.cmake
│ ├── FindAntTweakBar.cmake
│ ├── FindEigen3.cmake
│ ├── FindGLEW.cmake
│ ├── FindGLFW.cmake
│ ├── FindGLM.cmake
│ ├── FindOpenCV2.cmake
│ ├── FindOpenGP.cmake
│ ├── FindOpenNI2.cmake
│ ├── FindQGLViewer.cmake
│ └── FindSoftKinetic.cmake
├── cudax/
│ ├── CMakeLists.txt
│ ├── CublasHelper.h
│ ├── CudaHelper.h
│ ├── CudaTimer.h
│ ├── KinectCamera.h
│ ├── Kinematic.h
│ ├── MeshGrid.h
│ ├── OpenCVOutputBuffer.h
│ ├── PixelIndexer.h
│ ├── Timer.h
│ ├── cuda_glm.h
│ ├── externs.h
│ ├── functors/
│ │ ├── ClosestPoint.h
│ │ ├── ComputeJacobianRow.h
│ │ ├── ComputeJacobianRowDepth.h
│ │ ├── ComputeJacobianRowExtraClosedForm.h
│ │ ├── ComputeJacobianRowPush.h
│ │ ├── ComputeJacobianRowSilho.h
│ │ ├── CopyOver.h
│ │ ├── ImageGradient.h
│ │ ├── ImageGradientDepth.h
│ │ ├── ImageHighlighter.h
│ │ ├── IsMatchingDepth.h
│ │ ├── IsSilhouette.h
│ │ ├── IsSilhouetteBoundary.h
│ │ ├── IsTopLeft3x3Block.h
│ │ └── SkeletonJacobian.h
│ ├── helper_cuda.h
│ ├── kernel.cu
│ ├── kernel.h
│ ├── kernel_debug.h
│ ├── kernel_init.h
│ ├── kernel_upload.h
│ └── outer_product.cu
├── matlab/
│ ├── ik_alignment/
│ │ ├── FKObject.m
│ │ └── PiecewiseRigidAlignment2D.m
│ └── is_tracking_lost/
│ ├── andrew_ng_logistic_regression.m
│ ├── data.txt
│ ├── main.m
│ └── readme.txt
├── openni/
│ ├── include/
│ │ ├── Driver/
│ │ │ ├── OniDriverAPI.h
│ │ │ └── OniDriverTypes.h
│ │ ├── Linux-x86/
│ │ │ └── OniPlatformLinux-x86.h
│ │ ├── NiTE.h
│ │ ├── NiteCAPI.h
│ │ ├── NiteCEnums.h
│ │ ├── NiteCTypes.h
│ │ ├── NiteEnums.h
│ │ ├── NiteVersion.h
│ │ ├── OniCAPI.h
│ │ ├── OniCEnums.h
│ │ ├── OniCProperties.h
│ │ ├── OniCTypes.h
│ │ ├── OniEnums.h
│ │ ├── OniPlatform.h
│ │ ├── OniProperties.h
│ │ ├── OniVersion.h
│ │ ├── OpenNI.h
│ │ └── PS1080.h
│ └── lib/
│ └── OpenNI2/
│ └── Drivers/
│ └── libFreenectDriver.so.vga
├── tracker/
│ ├── CMakeLists.txt
│ ├── Calibration/
│ │ ├── Calibration.cpp
│ │ ├── Calibration.h
│ │ ├── Skeleton_IO.cpp
│ │ ├── Skeleton_IO.h
│ │ └── default.calib
│ ├── Data/
│ │ ├── Camera.cpp
│ │ ├── Camera.h
│ │ ├── DataFrame.h
│ │ ├── DataStream.cpp
│ │ ├── DataStream.h
│ │ ├── SolutionStream.h
│ │ ├── TextureColor8UC3.h
│ │ └── TextureDepth16UC1.h
│ ├── DataStructure/
│ │ ├── CustomJointInfo.h
│ │ ├── SkeletonSerializer.cpp
│ │ └── SkeletonSerializer.h
│ ├── Detection/
│ │ ├── DetectionStream.h
│ │ ├── FindFingers.cpp
│ │ ├── FindFingers.h
│ │ ├── QianDetection.cpp
│ │ ├── QianDetection.h
│ │ ├── TrivialDetector.cpp
│ │ ├── TrivialDetector.h
│ │ └── matlab_helpers.h
│ ├── Energy/
│ │ ├── Collision.cpp
│ │ ├── Collision.h
│ │ ├── Damping.cpp
│ │ ├── Damping.h
│ │ ├── Energy.cpp
│ │ ├── Energy.h
│ │ ├── Fitting/
│ │ │ ├── DistanceTransform.h
│ │ │ ├── Settings.h
│ │ │ └── TrackingMonitor.h
│ │ ├── Fitting.cpp
│ │ ├── Fitting.h
│ │ ├── JointLimits.cpp
│ │ ├── JointLimits.h
│ │ ├── PoseSpace.cpp
│ │ ├── PoseSpace.h
│ │ ├── PoseSpace_PCA/
│ │ │ ├── Limits
│ │ │ ├── P
│ │ │ ├── Sigma
│ │ │ ├── fingers/
│ │ │ │ ├── Limits
│ │ │ │ ├── P
│ │ │ │ ├── Sigma
│ │ │ │ └── mu
│ │ │ ├── mu
│ │ │ └── thumb/
│ │ │ ├── Limits
│ │ │ ├── P
│ │ │ ├── Sigma
│ │ │ └── mu
│ │ ├── Temporal.cpp
│ │ ├── Temporal.h
│ │ ├── Wristband.cpp
│ │ └── Wristband.h
│ ├── ForwardDeclarations.h
│ ├── HandFinder/
│ │ ├── HandFinder.cpp
│ │ ├── HandFinder.h
│ │ ├── connectedComponents.cpp
│ │ ├── connectedComponents.h
│ │ └── wristband.txt
│ ├── Legacy/
│ │ ├── LegacyTracker.cpp
│ │ ├── LegacyTracker.h
│ │ ├── algorithm/
│ │ │ ├── Detector.h
│ │ │ ├── ICP.cpp
│ │ │ └── ICP.h
│ │ ├── fingerfist.mat
│ │ ├── geometry/
│ │ │ ├── Cylinders.cpp
│ │ │ ├── Cylinders.h
│ │ │ ├── Effector.cpp
│ │ │ ├── Effector.h
│ │ │ ├── Joint.cpp
│ │ │ ├── Joint.h
│ │ │ ├── Mapping.cpp
│ │ │ ├── Mapping.h
│ │ │ ├── Skeleton.cpp
│ │ │ └── Skeleton.h
│ │ ├── math/
│ │ │ ├── Gauss_newton.h
│ │ │ ├── Inverse_kinematics.cpp
│ │ │ ├── Inverse_kinematics.h
│ │ │ ├── MathUtils.cpp
│ │ │ ├── MathUtils.h
│ │ │ ├── PCA.cpp
│ │ │ └── PCA.h
│ │ └── util/
│ │ ├── PostureFile.h
│ │ ├── Util.cpp
│ │ ├── Util.h
│ │ └── openmp_helpers.h
│ ├── OffscreenRender/
│ │ ├── CustomFrameBuffer.h
│ │ ├── OffscreenRenderer.cpp
│ │ └── OffscreenRenderer.h
│ ├── OpenGL/
│ │ ├── CylindersRenderer/
│ │ │ ├── Cylinders_FB_fshader.glsl
│ │ │ ├── Cylinders_FB_vshader.glsl
│ │ │ ├── Cylinders_fshader.glsl
│ │ │ ├── Cylinders_renderer.cpp
│ │ │ ├── Cylinders_renderer.h
│ │ │ ├── Cylinders_vshader.glsl
│ │ │ └── icopill.h
│ │ ├── KinectDataRenderer/
│ │ │ ├── KinectDataRenderer.cpp
│ │ │ ├── KinectDataRenderer.h
│ │ │ ├── KinectDataRenderer_fshader.glsl
│ │ │ └── KinectDataRenderer_vshader.glsl
│ │ ├── ObjectRenderer.cpp
│ │ ├── ObjectRenderer.h
│ │ ├── QuadRenderer/
│ │ │ ├── QuadRenderer.cpp
│ │ │ ├── QuadRenderer.h
│ │ │ ├── QuadRenderer_color_fshader.glsl
│ │ │ ├── QuadRenderer_depth_fshader.glsl
│ │ │ └── QuadRenderer_vshader.glsl
│ │ └── shaders.qrc
│ ├── Sensor/
│ │ ├── Sensor.h
│ │ ├── Sensor_depthsensegrabber.cpp
│ │ ├── Sensor_librealsense.cpp
│ │ ├── Sensor_openni.cpp
│ │ ├── Sensor_realsense.cpp
│ │ └── Sensor_softkin.cpp
│ ├── Tracker.h
│ ├── TwSettings.cpp
│ ├── TwSettings.h
│ ├── Types.h
│ ├── Worker.cpp
│ └── Worker.h
└── util/
├── CMakeLists.txt
├── MLogger.h
├── MLogger_Eigen.h
├── OpenGL32Format.h
├── Sleeper.h
├── assertf.h
├── check_error_gl.h
├── eigen_opengl_helpers.h
├── gl_wrapper.h
├── mylogger.h
├── opencv_wrapper.h
├── opengl_helper.h
├── qfile_helper.h
├── qt2eigen.h
├── rand.h
├── singleton.h
└── tictoc.h
================================================
FILE CONTENTS
================================================
================================================
FILE: .gitignore
================================================
*.txt.user
*-build
#################
## openFrameworks
#################
[Bb]in/*
![Bb]in/data/
[Bb]uild/
[Oo]bj/
*.o
[Dd]ebug*/
[Rr]elease*/
*.mode*
*.app/
*.pyc
*.log
#################
## Code::Blocks
#################
*.cbp
*.depend
*.layout
############
## Windows
############
# Windows image file caches
Thumbs.db
# Folder config file
Desktop.ini
*~
================================================
FILE: CMakeLists.txt
================================================
cmake_minimum_required(VERSION 2.8)
project(htrack)
#--- Gets rid of annoying CMake 3 warnings
if(NOT (CMAKE_MAJOR_VERSION LESS 3))
cmake_policy(SET CMP0043 OLD)
cmake_policy(SET CMP0020 OLD)
cmake_policy(SET CMP0005 OLD)
endif()
#--- Where to find the FindPackageName.cmake
set(CMAKE_MODULE_PATH ${CMAKE_SOURCE_DIR}/cmake)
#--- Where exes/libs will be deployed
set(LIBRARY_OUTPUT_PATH ${PROJECT_BINARY_DIR})
set(EXECUTABLE_OUTPUT_PATH ${PROJECT_BINARY_DIR})
set(CMAKE_RUNTIME_OUTPUT_DIRECTORY_DEBUG ${PROJECT_BINARY_DIR})
set(CMAKE_LIBRARY_OUTPUT_DIRECTORY_DEBUG ${PROJECT_BINARY_DIR})
set(CMAKE_RUNTIME_OUTPUT_DIRECTORY_RELEASE ${PROJECT_BINARY_DIR})
set(CMAKE_LIBRARY_OUTPUT_DIRECTORY_RELEASE ${PROJECT_BINARY_DIR})
#--- Compiler setup
include(cmake/ConfigureCompiler.cmake)
#--- Configure the libraries
include(cmake/ConfigureQt.cmake)
include(cmake/ConfigureOpenGL.cmake)
include(cmake/ConfigureGLEW.cmake)
include(cmake/ConfigureEigen.cmake)
include(cmake/ConfigureOpenCV.cmake)
include(cmake/ConfigureOpenNI.cmake)
include(cmake/ConfigureRealSense.cmake)
include(cmake/ConfigureLibRealSense.cmake)
include(cmake/ConfigureSoftKinetic.cmake)
include(cmake/ConfigureCUDA.cmake)
include(cmake/ConfigureAntTweakBar.cmake)
#--- sub-projects
add_subdirectory(util)
add_subdirectory(cudax)
add_subdirectory(tracker)
#--- Choose which sensor to use
include(cmake/ConfigureSensor.cmake)
add_definitions(${DEFINITION_SENSOR})
add_subdirectory(apps/htrack_atb)
add_subdirectory(apps/htrack_qt)
add_subdirectory(apps/colorpick)
#add_subdirectory(apps/synthgen) #<<< NOT READY
================================================
FILE: COPYING.txt
================================================
GNU LESSER GENERAL PUBLIC LICENSE
Version 3, 29 June 2007
Copyright (C) 2007 Free Software Foundation, Inc.
Everyone is permitted to copy and distribute verbatim copies
of this license document, but changing it is not allowed.
This version of the GNU Lesser General Public License incorporates
the terms and conditions of version 3 of the GNU General Public
License, supplemented by the additional permissions listed below.
0. Additional Definitions.
As used herein, "this License" refers to version 3 of the GNU Lesser
General Public License, and the "GNU GPL" refers to version 3 of the GNU
General Public License.
"The Library" refers to a covered work governed by this License,
other than an Application or a Combined Work as defined below.
An "Application" is any work that makes use of an interface provided
by the Library, but which is not otherwise based on the Library.
Defining a subclass of a class defined by the Library is deemed a mode
of using an interface provided by the Library.
A "Combined Work" is a work produced by combining or linking an
Application with the Library. The particular version of the Library
with which the Combined Work was made is also called the "Linked
Version".
The "Minimal Corresponding Source" for a Combined Work means the
Corresponding Source for the Combined Work, excluding any source code
for portions of the Combined Work that, considered in isolation, are
based on the Application, and not on the Linked Version.
The "Corresponding Application Code" for a Combined Work means the
object code and/or source code for the Application, including any data
and utility programs needed for reproducing the Combined Work from the
Application, but excluding the System Libraries of the Combined Work.
1. Exception to Section 3 of the GNU GPL.
You may convey a covered work under sections 3 and 4 of this License
without being bound by section 3 of the GNU GPL.
2. Conveying Modified Versions.
If you modify a copy of the Library, and, in your modifications, a
facility refers to a function or data to be supplied by an Application
that uses the facility (other than as an argument passed when the
facility is invoked), then you may convey a copy of the modified
version:
a) under this License, provided that you make a good faith effort to
ensure that, in the event an Application does not supply the
function or data, the facility still operates, and performs
whatever part of its purpose remains meaningful, or
b) under the GNU GPL, with none of the additional permissions of
this License applicable to that copy.
3. Object Code Incorporating Material from Library Header Files.
The object code form of an Application may incorporate material from
a header file that is part of the Library. You may convey such object
code under terms of your choice, provided that, if the incorporated
material is not limited to numerical parameters, data structure
layouts and accessors, or small macros, inline functions and templates
(ten or fewer lines in length), you do both of the following:
a) Give prominent notice with each copy of the object code that the
Library is used in it and that the Library and its use are
covered by this License.
b) Accompany the object code with a copy of the GNU GPL and this license
document.
4. Combined Works.
You may convey a Combined Work under terms of your choice that,
taken together, effectively do not restrict modification of the
portions of the Library contained in the Combined Work and reverse
engineering for debugging such modifications, if you also do each of
the following:
a) Give prominent notice with each copy of the Combined Work that
the Library is used in it and that the Library and its use are
covered by this License.
b) Accompany the Combined Work with a copy of the GNU GPL and this license
document.
c) For a Combined Work that displays copyright notices during
execution, include the copyright notice for the Library among
these notices, as well as a reference directing the user to the
copies of the GNU GPL and this license document.
d) Do one of the following:
0) Convey the Minimal Corresponding Source under the terms of this
License, and the Corresponding Application Code in a form
suitable for, and under terms that permit, the user to
recombine or relink the Application with a modified version of
the Linked Version to produce a modified Combined Work, in the
manner specified by section 6 of the GNU GPL for conveying
Corresponding Source.
1) Use a suitable shared library mechanism for linking with the
Library. A suitable mechanism is one that (a) uses at run time
a copy of the Library already present on the user's computer
system, and (b) will operate properly with a modified version
of the Library that is interface-compatible with the Linked
Version.
e) Provide Installation Information, but only if you would otherwise
be required to provide such information under section 6 of the
GNU GPL, and only to the extent that such information is
necessary to install and execute a modified version of the
Combined Work produced by recombining or relinking the
Application with a modified version of the Linked Version. (If
you use option 4d0, the Installation Information must accompany
the Minimal Corresponding Source and Corresponding Application
Code. If you use option 4d1, you must provide the Installation
Information in the manner specified by section 6 of the GNU GPL
for conveying Corresponding Source.)
5. Combined Libraries.
You may place library facilities that are a work based on the
Library side by side in a single library together with other library
facilities that are not Applications and are not covered by this
License, and convey such a combined library under terms of your
choice, if you do both of the following:
a) Accompany the combined library with a copy of the same work based
on the Library, uncombined with any other library facilities,
conveyed under the terms of this License.
b) Give prominent notice with the combined library that part of it
is a work based on the Library, and explaining where to find the
accompanying uncombined form of the same work.
6. Revised Versions of the GNU Lesser General Public License.
The Free Software Foundation may publish revised and/or new versions
of the GNU Lesser General Public License from time to time. Such new
versions will be similar in spirit to the present version, but may
differ in detail to address new problems or concerns.
Each version is given a distinguishing version number. If the
Library as you received it specifies that a certain numbered version
of the GNU Lesser General Public License "or any later version"
applies to it, you have the option of following the terms and
conditions either of that published version or of any later version
published by the Free Software Foundation. If the Library as you
received it does not specify a version number of the GNU Lesser
General Public License, you may choose any version of the GNU Lesser
General Public License ever published by the Free Software Foundation.
If the Library as you received it specifies that a proxy can decide
whether future versions of the GNU Lesser General Public License shall
apply, that proxy's public statement of acceptance of any version is
permanent authorization for you to choose that version for the
Library.
================================================
FILE: README.md
================================================
# Robust Articulated-ICP for Real-Time Hand Tracking
- **YouTube Video**: https://youtu.be/rm3YnClSmIQ
- **Paper PDF**: http://infoscience.epfl.ch/record/206951/files/htrack.pdf
## Disclaimer
To obtain the results shown in the video (or as seen in the live demo sessions at SGP'15) proper hardware is necessary:
- **Ubuntu 14.04** (on windows/osx the OS interferes with GPU on Compute/Graphics context switches)
- Intel Core **i7 @4GhZ**
- CUDA Graphic card (**NVIDIA GTX980** used in our demo)
- **Senz3D** depth camera (SENSOR_DEPTHSENSEGRABBER, use SoftKinetic or Intel/Creative)
Other notes:
- note the software must be compiled in **64bits**!
- **Wristband** color calibration (make sure the wristband is detected robustly otherwise the tracking might not perform as effectively, you can check this by enabling "show wband" in the htrack_atb application)
## BibTex
@article{htrack_sgp15,
author = {Andrea Tagliasacchi and Matthias Schr{\"o}der and Anastasia Tkach and
Sofien Bouaziz and Mario Botsch and Mark Pauly},
title = {Robust Articulated-ICP for Real-Time Hand Tracking},
journal = {Symposium on Geometry Processing (Computer Graphics Forum)},
month = July,
year = 2015}
## News
- July 8th 2015: we won the **Best Paper Award** at the Symposium on Geometry Processing (SGP) 2015!
- June 12th 2015: official code release (in sync with CVPR'15 HANDS workshop)
## Acknowledgements
- Thanks to "Tu-Hoa Pham" for his pull request that improved the SoftKinetic (Senz3D) Sensor!
================================================
FILE: apps/CMakeLists.txt
================================================
cmake_minimum_required(VERSION 2.8)
project(htrack-helloworlds)
#--- Gets rid of annoying CMake 3 warnings
if(NOT (CMAKE_MAJOR_VERSION LESS 3))
cmake_policy(SET CMP0043 OLD)
cmake_policy(SET CMP0020 OLD)
cmake_policy(SET CMP0005 OLD)
endif()
#--- Helloworld applications
add_subdirectory(helloworld)
add_subdirectory(helloworld_opencv)
add_subdirectory(helloworld_qtopengl)
add_subdirectory(helloworld_atb) # only for htrack-atb
add_subdirectory(helloworld_cudagl)
add_subdirectory(helloworld_cublas)
add_subdirectory(helloworld_thrust)
add_subdirectory(helloworld_openmp) # linux-only
add_subdirectory(helloworld_qglviewer) # only for htrack-qt
#--- Sensors Testing
add_subdirectory(helloworld_realsense) # windows only!!
add_subdirectory(helloworld_openni) # any os
================================================
FILE: apps/colorpick/CMakeLists.txt
================================================
#--- This project needs this extra library
#include(../../cmake/ConfigureQGLViewer.cmake)
INCLUDE_DIRECTORIES(../../) #< #include "tracker/..."
file(GLOB_RECURSE SRC "*.cpp")
file(GLOB_RECURSE HDR "*.h")
add_executable(colorpick ${HDR} ${SRC})
target_link_libraries(colorpick htracksdk ${LIBRARIES})
================================================
FILE: apps/colorpick/colorpick.cpp
================================================
// based on http://pastebin.com/EHz2a0YP
#include
#include
#include
#include
#include
#include
#include "tracker/Legacy/util/Util.h"
using namespace cv;
using namespace std;
//-----------------------------------------------------------------//
cv::Mat image, sel, src, hsv;
Scalar cMin(179,255,255), cMax(0,0,0);
bool selecting = false;
char w1[20] = "Color picker";
char w2[20] = "Picked color";
char w3[20] = "Segments";
//-----------------------------------------------------------------//
void filter()
{
// range based color classification
cv::Mat bw;
cv::inRange(hsv, cMin, cMax, bw);
cv::cvtColor(bw, sel, CV_GRAY2BGR);
cv::imshow(w2, sel);
// segmentation with opening and contours
cv::RNG rng(12345);
cv::Mat output;
vector > contours;
vector hierarchy;
cv::Mat kernel = getStructuringElement(MORPH_ELLIPSE, Size(4,4));
cv::morphologyEx(bw, output, MORPH_OPEN, kernel);
cv::findContours(output, contours, hierarchy, CV_RETR_LIST, CV_CHAIN_APPROX_SIMPLE);
cv::Mat drawing = cv::Mat::zeros(output.size(), CV_8UC3);
for(int i = 0; i < contours.size(); ++i)
{
Scalar color = Scalar(rng.uniform(0,255), rng.uniform(0,255), rng.uniform(0,255));
drawContours(drawing, contours, i, color, CV_FILLED);
Moments m = moments(contours[i]);
Point2f mp = Point2f(m.m10/m.m00, m.m01/m.m00);
double a = contourArea(contours[i]);
if(a > 2000)
{
Scalar color = Scalar(255,255,255);
drawContours(drawing, contours, i, color);
line(drawing, mp + Point2f(-4,-4), mp + Point2f( 4, 4), color);
line(drawing, mp + Point2f( 4,-4), mp + Point2f(-4, 4), color);
}
}
imshow(w3, drawing);
}
//-----------------------------------------------------------------//
static void onMouse(int event, int x, int y, int f, void *)
{
std::cout << "## UPDATED" << std::endl;
image = src.clone();
Vec3b pix = hsv.at(y,x);
int H = pix.val[0];
int S = pix.val[1];
int V = pix.val[2];
//--
if(event == EVENT_LBUTTONDOWN)
selecting = true;
else if(event == EVENT_LBUTTONUP)
selecting = false;
if(selecting)
{
if(H < cMin[0])
cMin[0] = H;
if(S < cMin[1])
cMin[1] = S;
if(V < cMin[2])
cMin[2] = V;
if(H > cMax[0])
cMax[0] = H;
if(S > cMax[1])
cMax[1] = S;
if(V > cMax[2])
cMax[2] = V;
filter();
}
//--
Scalar bgr = cvc(hsv2rgb(cvc(cv::Scalar(H,S,V))), true);
rectangle(image, Point(3,5), Point(13,15), bgr, -1);
stringstream s;
s << "HSV=(" << H << ", " << S << ", " << V << ")";
putText(image, s.str().c_str(), Point(17,15), FONT_HERSHEY_SIMPLEX, .6, Scalar(0,0,0), 2);
putText(image, s.str().c_str(), Point(17,15), FONT_HERSHEY_SIMPLEX, .6, Scalar(255,255,255));
//--
bgr = cvc(hsv2rgb(cvc(cMin)), true);
rectangle(image, Point(3,25), Point(13,35), bgr, -1);
s.str("");
s.clear();
s << "hsv_min=" << cMin[0] << ", " << cMin[1] << ", " << cMin[2];
std::cout << s.str() << std::endl;
putText(image, s.str().c_str(), Point(17,35), FONT_HERSHEY_SIMPLEX, .6, Scalar(0,0,0), 2);
putText(image, s.str().c_str(), Point(17,35), FONT_HERSHEY_SIMPLEX, .6, Scalar(255,255,255));
//--
bgr = cvc(hsv2rgb(cvc(cMax)), true);
rectangle(image, Point(3,45), Point(13,55), bgr, -1);
s.str("");
s.clear();
s << "hsv_max=" << cMax[0] << ", " << cMax[1] << ", " << cMax[2];
std::cout << s.str() << std::endl;
putText(image, s.str().c_str(), Point(17,55), FONT_HERSHEY_SIMPLEX, .6, Scalar(0,0,0), 2);
putText(image, s.str().c_str(), Point(17,55), FONT_HERSHEY_SIMPLEX, .6, Scalar(255,255,255));
//--
s.str("");
s.clear();
s << "range:";
putText(image, s.str().c_str(), Point(255,25), FONT_HERSHEY_SIMPLEX, .6, Scalar(0,0,0), 2);
putText(image, s.str().c_str(), Point(255,25), FONT_HERSHEY_SIMPLEX, .6, Scalar(255,255,255));
double n = 57.0f;
for(double i = 0; i < n; ++i)
{
// note: red hues wrap around, 1D linear interpolation
// doesn't include all possible HSV combinations
double w = i / n;
Scalar col = (1.0-w)*cMin + w*cMax;
bgr = cvc(hsv2rgb(cvc(col)), true);
rectangle(image, Point(255+i,35), Point(256+i,45), bgr, -1);
}
//--
imshow(w1, image);
imshow(w2, sel);
}
//-----------------------------------------------------------------//
int main(int argc, char **argv)
{
// TODO use camera images for input
cout << "Color picker" << endl
<< "------------" << endl
<< "Pass image file as command line argument" << endl
<< "Click to select colors" << endl
<< "Press SPACE to reset min/max" << endl
<< "Press Q or ESC to quit" << endl << endl;
if(argc < 2)
{
cout << "No file specified" << endl;
return 0;
}
src = imread(argv[1]);
if(!src.data)
{
cout << "Could not read file" << endl;
return 0;
}
namedWindow(w1, WINDOW_AUTOSIZE);
cvtColor(src, hsv, CV_BGR2HSV);
filter();
imshow(w1, src);
imshow(w2, sel);
setMouseCallback(w1, onMouse, 0);
for(;;)
{
char key = waitKey(20);
if(key == 0x71 || key == 0x1b)
break;
else if(key == 0x20)
{
cMin = Scalar(179,255,255);
cMax = Scalar(0,0,0);
filter();
}
}
return 0;
}
================================================
FILE: apps/helloworld/CMakeLists.txt
================================================
cmake_minimum_required(VERSION 2.8)
get_filename_component(FOLDERNAME ${CMAKE_CURRENT_LIST_DIR} NAME)
project(${FOLDERNAME})
file(GLOB_RECURSE SOURCES "*.cpp")
file(GLOB_RECURSE HEADERS "*.h")
file(GLOB_RECURSE SHADERS "*.glsl")
add_executable(${FOLDERNAME} ${SOURCES} ${HEADERS} ${SHADERS})
target_link_libraries(${FOLDERNAME} ${COMMON_LIBS})
================================================
FILE: apps/helloworld/main.cpp
================================================
#include
int main(int /*argc*/, char ** /*argv*/)
{
std::cout << "hello world!" << std::endl;
return 0;
}
================================================
FILE: apps/helloworld_atb/CMakeLists.txt
================================================
cmake_minimum_required(VERSION 2.8)
get_filename_component(PROJECT ${CMAKE_CURRENT_LIST_DIR} NAME)
project(${PROJECT})
set(CMAKE_MODULE_PATH ${CMAKE_CURRENT_LIST_DIR}/../../cmake)
include(../../cmake/ConfigureCompiler.cmake)
include(../../cmake/ConfigureQt.cmake)
include(../../cmake/ConfigureOpenGL.cmake)
include(../../cmake/ConfigureAntTweakBar.cmake)
INCLUDE_DIRECTORIES(../../)
#set(CMAKE_BUILD_TYPE "Release")
set(CMAKE_BUILD_TYPE "Debug")
list(APPEND SOURCES ../../tracker/TwSettings.cpp)
add_executable(${PROJECT} main.cpp ${SOURCES})
target_link_libraries(${PROJECT} ${LIBRARIES})
#set(EXECUTABLE_OUTPUT_PATH ${CMAKE_SOURCE_DIR})
================================================
FILE: apps/helloworld_atb/main.cpp
================================================
#include
#include
#include
#include
#include
#include "../htrack_atb/AntTweakBarEventFilter.h"
#include "tracker/TwSettings.h"
float v1;
float g1_v1;
float g1_v2;
#include "AntTweakBar.h"
/// Format class to enable OpenGL4 core profile
class OpenGLFormat : public QGLFormat{
public:
OpenGLFormat(){
setVersion(3,2);
setProfile(QGLFormat::CoreProfile);
setSampleBuffers(false); ///< no anti-aliasing
// setSamples(1); ///< no anti-aliasing
}
};
class GLWidget : public QGLWidget{
QOpenGLVertexArrayObject vao;
public:
GLWidget():QGLWidget(OpenGLFormat()){
std::cout << "OpenGL " << this->format().majorVersion() << "." << this->format().minorVersion() << std::endl;
this->installEventFilter( new AntTweakBarEventFilter(this) ); ///< all actions pass through filter
}
~GLWidget(){
TwTerminate();
}
void initializeGL(){
bool success = vao.create();
if(!success) exit(EXIT_FAILURE);
vao.bind();
tw_settings->tw_init(this->width(), this->height());
tw_settings->tw_add(v1, "v1", "min=.5 max=50 step=0.4");
tw_settings->tw_add(g1_v1, "g1_v1", "group=g1");
tw_settings->tw_add(g1_v2, "g1_v2", "group=g1");
}
void paintGL() {
glClearColor(0,1,0,1); ///< green
glClear(GL_COLOR_BUFFER_BIT);
tw_settings->tw_draw();
// TwWindowSize(this->width(), this->height());
TwDraw();
}
};
int main(int argc, char* argv[]){
QApplication app(argc, argv);
GLWidget glarea;
glarea.show();
return app.exec();
}
================================================
FILE: apps/helloworld_atb/main_new.cpp
================================================
#include
#include
#include
#include
#include
#include
#include "gui/AntTweakBarEventFilter.h"
#include "AntTweakBar.h"
TwBar* _bar = NULL;
float v1;
float g1_v1;
float g1_v2;
class GLWidget : public QOpenGLWidget{
QOpenGLVertexArrayObject vao;
public:
GLWidget():QOpenGLWidget(){
std::cout << "OpenGL " << this->format().majorVersion() << "." << this->format().minorVersion() << std::endl;
this->installEventFilter( new AntTweakBarEventFilter(this) ); ///< all actions pass through filter
}
~GLWidget(){
TwTerminate();
}
void initializeGL(){
bool success = vao.create();
if(!success) exit(EXIT_FAILURE);
vao.bind();
TwInit(TW_OPENGL_CORE, NULL);
TwWindowSize(this->width()*2, this->height()*2);
_bar = TwNewBar ("Settings");
TwAddVarRW(_bar, "p", TW_TYPE_FLOAT, &v1, "min=.5 max=50 step=0.4");
TwAddVarRW(_bar, "V1", TW_TYPE_FLOAT, &g1_v1, " group=g1 ");
TwAddVarRW(_bar, "V2", TW_TYPE_FLOAT, &g1_v2, " group=g1 ");
glViewport(0, 0, this->width(), this->height());
}
void paintGL() {
glViewport(0,0,this->width(), this->height());
glClearColor(0,1,0,1); ///< green
glClear(GL_COLOR_BUFFER_BIT);
TwDraw();
}
};
int main(int argc, char* argv[]){
QApplication app(argc, argv);
QSurfaceFormat format;
format.setVersion(4, 3);
format.setProfile(QSurfaceFormat::CoreProfile);
format.setDepthBufferSize(24);
format.setStencilBufferSize(8);
QSurfaceFormat::setDefaultFormat(format);
GLWidget glarea;
glarea.show();
return app.exec();
}
================================================
FILE: apps/helloworld_cublas/CMakeLists.txt
================================================
cmake_minimum_required(VERSION 2.8)
get_filename_component(PROJECT ${CMAKE_CURRENT_LIST_DIR} NAME)
project(${PROJECT})
set(CMAKE_MODULE_PATH ${CMAKE_CURRENT_LIST_DIR}/../../cmake)
include(../../cmake/ConfigureCompiler.cmake)
include(../../cmake/ConfigureQt.cmake)
include(../../cmake/ConfigureCUDA.cmake)
include(../../cmake/ConfigureEigen.cmake)
include_directories(../../)
#--- only compile a tiny fraction of cudax
set(CUDAX_CU "../../cudax/outer_product.cu")
cuda_add_library(cudax STATIC ${CUDAX_CU})
list(APPEND LIBRARIES cudax)
#--- exec1
add_executable(${PROJECT}_simple main_simple.cpp)
target_link_libraries(${PROJECT}_simple ${LIBRARIES})
#--- exec2 (needs gnuplot!)
if(UNIX AND NOT APPLE)
add_executable(${PROJECT}_perfomance main_performance.cpp)
target_link_libraries(${PROJECT}_perfomance ${LIBRARIES})
endif()
================================================
FILE: apps/helloworld_cublas/gnuplot_i.h
================================================
////////////////////////////////////////////////////////////////////////////////
///
/// \brief A C++ interface to gnuplot.
///
///
/// The interface uses pipes and so won't run on a system that doesn't have
/// POSIX pipe support Tested on Windows (MinGW and Visual C++) and Linux (GCC)
///
/// Version history:
/// 0. C interface
/// by N. Devillard (27/01/03)
/// 1. C++ interface: direct translation from the C interface
/// by Rajarshi Guha (07/03/03)
/// 2. corrections for Win32 compatibility
/// by V. Chyzhdzenka (20/05/03)
/// 3. some member functions added, corrections for Win32 and Linux
/// compatibility
/// by M. Burgis (10/03/08)
///
/// Requirements:
/// * gnuplot has to be installed (http://www.gnuplot.info/download.html)
/// * for Windows: set Path-Variable for Gnuplot path
/// (e.g. C:/program files/gnuplot/bin)
/// or set Gnuplot path with:
/// Gnuplot::set_GNUPlotPath(const std::string &path);
///
////////////////////////////////////////////////////////////////////////////////
#ifndef _GNUPLOT_PIPES_H_
#define _GNUPLOT_PIPES_H_
#include
#include
#include
#include
#include // for std::ostringstream
#include
#include
#include // for getenv()
#include // for std::list
#if defined(WIN32) || defined(_WIN32) || defined(__WIN32__) || defined(__TOS_WIN__)
//defined for 32 and 64-bit environments
#include // for _access(), _mktemp()
#define GP_MAX_TMP_FILES 27 // 27 temporary files it's Microsoft restriction
#elif defined(unix) || defined(__unix) || defined(__unix__) || defined(__APPLE__)
//all UNIX-like OSs (Linux, *BSD, MacOSX, Solaris, ...)
#include // for access(), mkstemp()
#define GP_MAX_TMP_FILES 64
#else
#error unsupported or unknown operating system
#endif
//declare classes in global namespace
class GnuplotException : public std::runtime_error
{
public:
GnuplotException(const std::string &msg) : std::runtime_error(msg) {}
};
class Gnuplot
{
private:
//----------------------------------------------------------------------------------
// member data
///\brief pointer to the stream that can be used to write to the pipe
FILE *gnucmd;
///\brief validation of gnuplot session
bool valid;
///\brief true = 2d, false = 3d
bool two_dim;
///\brief number of plots in session
int nplots;
///\brief functions and data are displayed in a defined styles
std::string pstyle;
///\brief interpolate and approximate data in defined styles (e.g. spline)
std::string smooth;
///\brief list of created tmpfiles
std::vector tmpfile_list;
//----------------------------------------------------------------------------------
// static data
///\brief number of all tmpfiles (number of tmpfiles restricted)
static int tmpfile_num;
///\brief name of executed GNUPlot file
static std::string m_sGNUPlotFileName;
///\brief gnuplot path
static std::string m_sGNUPlotPath;
///\brief standart terminal, used by showonscreen
static std::string terminal_std;
//----------------------------------------------------------------------------------
// member functions (auxiliary functions)
// ---------------------------------------------------
///\brief get_program_path(); and popen();
///
/// \param --> void
///
/// \return <-- void
// ---------------------------------------------------
void init();
// ---------------------------------------------------
///\brief creates tmpfile and returns its name
///
/// \param tmp --> points to the tempfile
///
/// \return <-- the name of the tempfile
// ---------------------------------------------------
std::string create_tmpfile(std::ofstream &tmp);
//----------------------------------------------------------------------------------
///\brief gnuplot path found?
///
/// \param ---
///
/// \return <-- found the gnuplot path (yes == true, no == false)
// ---------------------------------------------------------------------------------
static bool get_program_path();
// ---------------------------------------------------------------------------------
///\brief checks if file is available
///
/// \param filename --> the filename
/// \param mode --> the mode [optional,default value = 0]
///
/// \return file exists (yes == true, no == false)
// ---------------------------------------------------------------------------------
bool file_available(const std::string &filename);
// ---------------------------------------------------------------------------------
///\brief checks if file exists
///
/// \param filename --> the filename
/// \param mode --> the mode [optional,default value = 0]
///
/// \return file exists (yes == true, no == false)
// ---------------------------------------------------------------------------------
static bool file_exists(const std::string &filename, int mode=0);
public:
// ----------------------------------------------------------------------------
/// \brief optional function: set Gnuplot path manual
/// attention: for windows: path with slash '/' not backslash '\'
///
/// \param path --> the gnuplot path
///
/// \return true on success, false otherwise
// ----------------------------------------------------------------------------
static bool set_GNUPlotPath(const std::string &path);
// ----------------------------------------------------------------------------
/// optional: set standart terminal, used by showonscreen
/// defaults: Windows - win, Linux - x11, Mac - aqua
///
/// \param type --> the terminal type
///
/// \return ---
// ----------------------------------------------------------------------------
static void set_terminal_std(const std::string &type);
//-----------------------------------------------------------------------------
// constructors
// ----------------------------------------------------------------------------
///\brief set a style during construction
Gnuplot(const std::string &style = "points");
/// plot a single std::vector at one go
Gnuplot(const std::vector &x,
const std::string &title = "",
const std::string &style = "points",
const std::string &labelx = "x",
const std::string &labely = "y");
/// plot pairs std::vector at one go
Gnuplot(const std::vector &x,
const std::vector &y,
const std::string &title = "",
const std::string &style = "points",
const std::string &labelx = "x",
const std::string &labely = "y");
/// plot triples std::vector at one go
Gnuplot(const std::vector &x,
const std::vector &y,
const std::vector &z,
const std::string &title = "",
const std::string &style = "points",
const std::string &labelx = "x",
const std::string &labely = "y",
const std::string &labelz = "z");
/// destructor: needed to delete temporary files
~Gnuplot();
//----------------------------------------------------------------------------------
/// send a command to gnuplot
Gnuplot& cmd(const std::string &cmdstr);
// -------------------------------------------------------------------------
///\brief Sends a command to an active gnuplot session, identical to cmd()
/// send a command to gnuplot using the << operator
///
/// \param cmdstr --> the command string
///
/// \return <-- a reference to the gnuplot object
// -------------------------------------------------------------------------
inline Gnuplot& operator<<(const std::string &cmdstr)
{
cmd(cmdstr);
return(*this);
}
//--------------------------------------------------------------------------
// show on screen or write to file
/// sets terminal type to terminal_std
Gnuplot& showonscreen(); // window output is set by default (win/x11/aqua)
/// Saves a gnuplot to a file named filename. Defaults to saving pdf
Gnuplot& savetofigure(const std::string &filename,
const std::string &terminal="ps");
//--------------------------------------------------------------------------
// set and unset
/// set line style (some of these styles require additional information):
/// lines, points, linespoints, impulses, dots, steps, fsteps, histeps,
/// boxes, histograms, filledcurves
Gnuplot& set_style(const std::string &stylestr = "points");
/// interpolation and approximation of data, arguments:
/// csplines, bezier, acsplines (for data values > 0), sbezier, unique, frequency
/// (works only with plot_x, plot_xy, plotfile_x, plotfile_xy
/// (if smooth is set, set_style has no effekt on data plotting)
Gnuplot& set_smooth(const std::string &stylestr = "csplines");
// ----------------------------------------------------------------------
/// \brief unset smooth
/// attention: smooth is not set by default
///
/// \param ---
///
/// \return <-- a reference to a gnuplot object
// ----------------------------------------------------------------------
inline Gnuplot& unset_smooth()
{
smooth = "";
return *this;
};
/// scales the size of the points used in plots
Gnuplot& set_pointsize(const double pointsize = 1.0);
/// turns grid on/off
inline Gnuplot& set_grid()
{
cmd("set grid");
return *this;
};
/// grid is not set by default
inline Gnuplot& unset_grid()
{
cmd("unset grid");
return *this;
};
// -----------------------------------------------
/// set the mulitplot mode
///
/// \param ---
///
/// \return <-- reference to the gnuplot object
// -----------------------------------------------
inline Gnuplot& set_multiplot()
{
cmd("set multiplot") ;
return *this;
};
// -----------------------------------------------
/// unsets the mulitplot mode
///
/// \param ---
///
/// \return <-- reference to the gnuplot object
// -----------------------------------------------
inline Gnuplot& unset_multiplot()
{
cmd("unset multiplot");
return *this;
};
/// set sampling rate of functions, or for interpolating data
Gnuplot& set_samples(const int samples = 100);
/// set isoline density (grid) for plotting functions as surfaces (for 3d plots)
Gnuplot& set_isosamples(const int isolines = 10);
// --------------------------------------------------------------------------
/// enables/disables hidden line removal for surface plotting (for 3d plot)
///
/// \param ---
///
/// \return <-- reference to the gnuplot object
// --------------------------------------------------------------------------
Gnuplot& set_hidden3d()
{
cmd("set hidden3d");
return *this;
};
// ---------------------------------------------------------------------------
/// hidden3d is not set by default
///
/// \param ---
///
/// \return <-- reference to the gnuplot object
// ---------------------------------------------------------------------------
inline Gnuplot& unset_hidden3d()
{
cmd("unset hidden3d");
return *this;
};
/// enables/disables contour drawing for surfaces (for 3d plot)
/// base, surface, both
Gnuplot& set_contour(const std::string &position = "base");
// --------------------------------------------------------------------------
/// contour is not set by default, it disables contour drawing for surfaces
///
/// \param ---
///
/// \return <-- reference to the gnuplot object
// ------------------------------------------------------------------
inline Gnuplot& unset_contour()
{
cmd("unset contour");
return *this;
};
// ------------------------------------------------------------
/// enables/disables the display of surfaces (for 3d plot)
///
/// \param ---
///
/// \return <-- reference to the gnuplot object
// ------------------------------------------------------------------
inline Gnuplot& set_surface()
{
cmd("set surface");
return *this;
};
// ----------------------------------------------------------
/// surface is set by default,
/// it disables the display of surfaces (for 3d plot)
///
/// \param ---
///
/// \return <-- reference to the gnuplot object
// ------------------------------------------------------------------
inline Gnuplot& unset_surface()
{
cmd("unset surface");
return *this;
}
/// switches legend on/off
/// position: inside/outside, left/center/right, top/center/bottom, nobox/box
Gnuplot& set_legend(const std::string &position = "default");
// ------------------------------------------------------------------
/// \brief Switches legend off
/// attention:legend is set by default
///
/// \param ---
///
/// \return <-- reference to the gnuplot object
// ------------------------------------------------------------------
inline Gnuplot& unset_legend()
{
cmd("unset key");
return *this;
}
// -----------------------------------------------------------------------
/// \brief sets and clears the title of a gnuplot session
///
/// \param title --> the title of the plot [optional, default == ""]
///
/// \return <-- reference to the gnuplot object
// -----------------------------------------------------------------------
inline Gnuplot& set_title(const std::string &title = "")
{
std::string cmdstr;
cmdstr = "set title \"";
cmdstr+=title;
cmdstr+="\"";
*this<set_title();
return *this;
}
/// set x axis label
Gnuplot& set_ylabel(const std::string &label = "x");
/// set y axis label
Gnuplot& set_xlabel(const std::string &label = "y");
/// set z axis label
Gnuplot& set_zlabel(const std::string &label = "z");
/// set axis - ranges
Gnuplot& set_xrange(const double iFrom,
const double iTo);
/// set y-axis - ranges
Gnuplot& set_yrange(const double iFrom,
const double iTo);
/// set z-axis - ranges
Gnuplot& set_zrange(const double iFrom,
const double iTo);
/// autoscale axis (set by default) of xaxis
///
/// \param ---
///
/// \return <-- reference to the gnuplot object
// -----------------------------------------------
inline Gnuplot& set_xautoscale()
{
cmd("set xrange restore");
cmd("set autoscale x");
return *this;
};
// -----------------------------------------------
/// autoscale axis (set by default) of yaxis
///
/// \param ---
///
/// \return <-- reference to the gnuplot object
// -----------------------------------------------
inline Gnuplot& set_yautoscale()
{
cmd("set yrange restore");
cmd("set autoscale y");
return *this;
};
// -----------------------------------------------
/// autoscale axis (set by default) of zaxis
///
/// \param ---
///
/// \return <-- reference to the gnuplot object
// -----------------------------------------------
inline Gnuplot& set_zautoscale()
{
cmd("set zrange restore");
cmd("set autoscale z");
return *this;
};
/// turns on/off log scaling for the specified xaxis (logscale is not set by default)
Gnuplot& set_xlogscale(const double base = 10);
/// turns on/off log scaling for the specified yaxis (logscale is not set by default)
Gnuplot& set_ylogscale(const double base = 10);
/// turns on/off log scaling for the specified zaxis (logscale is not set by default)
Gnuplot& set_zlogscale(const double base = 10);
// -----------------------------------------------
/// turns off log scaling for the x axis
///
/// \param ---
///
/// \return <-- reference to the gnuplot object
// -----------------------------------------------
inline Gnuplot& unset_xlogscale()
{
cmd("unset logscale x");
return *this;
};
// -----------------------------------------------
/// turns off log scaling for the y axis
///
/// \param ---
///
/// \return <-- reference to the gnuplot object
// -----------------------------------------------
inline Gnuplot& unset_ylogscale()
{
cmd("unset logscale y");
return *this;
};
// -----------------------------------------------
/// turns off log scaling for the z axis
///
/// \param ---
///
/// \return <-- reference to the gnuplot object
// -----------------------------------------------
inline Gnuplot& unset_zlogscale()
{
cmd("unset logscale z");
return *this;
};
/// set palette range (autoscale by default)
Gnuplot& set_cbrange(const double iFrom, const double iTo);
//--------------------------------------------------------------------------
// plot
/// plot a single std::vector: x
/// from file
Gnuplot& plotfile_x(const std::string &filename,
const unsigned int column = 1,
const std::string &title = "");
/// from std::vector
template
Gnuplot& plot_x(const X& x, const std::string &title = "");
/// plot x,y pairs: x y
/// from file
Gnuplot& plotfile_xy(const std::string &filename,
const unsigned int column_x = 1,
const unsigned int column_y = 2,
const std::string &title = "");
/// from data
template
Gnuplot& plot_xy(const X& x, const Y& y, const std::string &title = "");
/// plot x,y pairs with dy errorbars: x y dy
/// from file
Gnuplot& plotfile_xy_err(const std::string &filename,
const unsigned int column_x = 1,
const unsigned int column_y = 2,
const unsigned int column_dy = 3,
const std::string &title = "");
/// from data
template
Gnuplot& plot_xy_err(const X &x, const Y &y, const E &dy,
const std::string &title = "");
/// plot x,y,z triples: x y z
/// from file
Gnuplot& plotfile_xyz(const std::string &filename,
const unsigned int column_x = 1,
const unsigned int column_y = 2,
const unsigned int column_z = 3,
const std::string &title = "");
/// from std::vector
template
Gnuplot& plot_xyz(const X &x,
const Y &y,
const Z &z,
const std::string &title = "");
/// plot an equation of the form: y = ax + b, you supply a and b
Gnuplot& plot_slope(const double a,
const double b,
const std::string &title = "");
/// plot an equation supplied as a std::string y=f(x), write only the
/// function f(x) not y the independent variable has to be x
/// binary operators: ** exponentiation, * multiply, / divide, + add, -
/// substract, % modulo
/// unary operators: - minus, ! factorial
/// elementary functions: rand(x), abs(x), sgn(x), ceil(x), floor(x),
/// int(x), imag(x), real(x), arg(x), sqrt(x), exp(x), log(x), log10(x),
/// sin(x), cos(x), tan(x), asin(x), acos(x), atan(x), atan2(y,x),
/// sinh(x), cosh(x), tanh(x), asinh(x), acosh(x), atanh(x)
/// special functions: erf(x), erfc(x), inverf(x), gamma(x), igamma(a,x),
/// lgamma(x), ibeta(p,q,x), besj0(x), besj1(x), besy0(x), besy1(x),
/// lambertw(x)
/// statistical fuctions: norm(x), invnorm(x)
Gnuplot& plot_equation(const std::string &equation,
const std::string &title = "");
/// plot an equation supplied as a std::string z=f(x,y), write only the
/// function f(x,y) not z the independent variables have to be x and y
Gnuplot& plot_equation3d(const std::string &equation,
const std::string &title = "");
/// plot image
Gnuplot& plot_image(const unsigned char *ucPicBuf,
const unsigned int iWidth,
const unsigned int iHeight,
const std::string &title = "");
//--------------------------------------------------------------------------
///\brief replot repeats the last plot or splot command.
/// this can be useful for viewing a plot with different set options,
/// or when generating the same plot for several devices (showonscreen,
// savetofigure)
///
/// \param ---
///
/// \return ---
//--------------------------------------------------------------------------
inline Gnuplot& replot(void)
{
if (nplots > 0) cmd("replot");
return *this;
};
/// resets a gnuplot session (next plot will erase previous ones)
Gnuplot& reset_plot();
/// resets a gnuplot session and sets all variables to default
Gnuplot& reset_all();
/// deletes temporary files
void remove_tmpfiles();
// -------------------------------------------------------------------
/// \brief Is the gnuplot session valid ??
///
///
/// \param ---
///
/// \return true if valid, false if not
// -------------------------------------------------------------------
inline bool is_valid()
{
return(valid);
};
};
//------------------------------------------------------------------------------
//
// initialize static data
//
int Gnuplot::tmpfile_num = 0;
#if defined(WIN32) || defined(_WIN32) || defined(__WIN32__) || defined(__TOS_WIN__)
std::string Gnuplot::m_sGNUPlotFileName = "pgnuplot.exe";
std::string Gnuplot::m_sGNUPlotPath = "C:/program files/gnuplot/bin/";
#elif defined(unix) || defined(__unix) || defined(__unix__) || defined(__APPLE__)
std::string Gnuplot::m_sGNUPlotFileName = "gnuplot";
std::string Gnuplot::m_sGNUPlotPath = "/usr/local/bin/";
#endif
#if defined(WIN32) || defined(_WIN32) || defined(__WIN32__) || defined(__TOS_WIN__)
std::string Gnuplot::terminal_std = "windows";
#elif ( defined(unix) || defined(__unix) || defined(__unix__) ) && !defined(__APPLE__)
std::string Gnuplot::terminal_std = "x11";
#elif defined(__APPLE__)
std::string Gnuplot::terminal_std = "aqua";
#endif
//------------------------------------------------------------------------------
//
// constructor: set a style during construction
//
inline Gnuplot::Gnuplot(const std::string &style)
:gnucmd(NULL) ,valid(false) ,two_dim(false) ,nplots(0)
{
init();
set_style(style);
}
//------------------------------------------------------------------------------
//
// constructor: open a new session, plot a signal (x)
//
inline Gnuplot::Gnuplot(const std::vector &x,
const std::string &title,
const std::string &style,
const std::string &labelx,
const std::string &labely)
:gnucmd(NULL) ,valid(false) ,two_dim(false) ,nplots(0)
{
init();
set_style(style);
set_xlabel(labelx);
set_ylabel(labely);
plot_x(x,title);
}
//------------------------------------------------------------------------------
//
// constructor: open a new session, plot a signal (x,y)
//
inline Gnuplot::Gnuplot(const std::vector &x,
const std::vector &y,
const std::string &title,
const std::string &style,
const std::string &labelx,
const std::string &labely)
:gnucmd(NULL) ,valid(false) ,two_dim(false) ,nplots(0)
{
init();
set_style(style);
set_xlabel(labelx);
set_ylabel(labely);
plot_xy(x,y,title);
}
//------------------------------------------------------------------------------
//
// constructor: open a new session, plot a signal (x,y,z)
//
inline Gnuplot::Gnuplot(const std::vector &x,
const std::vector &y,
const std::vector &z,
const std::string &title,
const std::string &style,
const std::string &labelx,
const std::string &labely,
const std::string &labelz)
:gnucmd(NULL) ,valid(false) ,two_dim(false) ,nplots(0)
{
init();
set_style(style);
set_xlabel(labelx);
set_ylabel(labely);
set_zlabel(labelz);
plot_xyz(x,y,z,title);
}
//------------------------------------------------------------------------------
//
/// Plots a 2d graph from a list of doubles: x
//
template
Gnuplot& Gnuplot::plot_x(const X& x, const std::string &title)
{
if (x.size() == 0)
{
throw GnuplotException("std::vector too small");
return *this;
}
std::ofstream tmp;
std::string name = create_tmpfile(tmp);
if (name == "")
return *this;
//
// write the data to file
//
for (unsigned int i = 0; i < x.size(); i++)
tmp << x[i] << std::endl;
tmp.flush();
tmp.close();
plotfile_x(name, 1, title);
return *this;
}
//------------------------------------------------------------------------------
//
/// Plots a 2d graph from a list of doubles: x y
//
template
Gnuplot& Gnuplot::plot_xy(const X& x, const Y& y, const std::string &title)
{
if (x.size() == 0 || y.size() == 0)
{
throw GnuplotException("std::vectors too small");
return *this;
}
if (x.size() != y.size())
{
throw GnuplotException("Length of the std::vectors differs");
return *this;
}
std::ofstream tmp;
std::string name = create_tmpfile(tmp);
if (name == "")
return *this;
//
// write the data to file
//
for (unsigned int i = 0; i < x.size(); i++)
tmp << x[i] << " " << y[i] << std::endl;
tmp.flush();
tmp.close();
plotfile_xy(name, 1, 2, title);
return *this;
}
///-----------------------------------------------------------------------------
///
/// plot x,y pairs with dy errorbars
///
template
Gnuplot& Gnuplot::plot_xy_err(const X &x,
const Y &y,
const E &dy,
const std::string &title)
{
if (x.size() == 0 || y.size() == 0 || dy.size() == 0)
{
throw GnuplotException("std::vectors too small");
return *this;
}
if (x.size() != y.size() || y.size() != dy.size())
{
throw GnuplotException("Length of the std::vectors differs");
return *this;
}
std::ofstream tmp;
std::string name = create_tmpfile(tmp);
if (name == "")
return *this;
//
// write the data to file
//
for (unsigned int i = 0; i < x.size(); i++)
tmp << x[i] << " " << y[i] << " " << dy[i] << std::endl;
tmp.flush();
tmp.close();
// Do the actual plot
plotfile_xy_err(name, 1, 2, 3, title);
return *this;
}
//------------------------------------------------------------------------------
//
// Plots a 3d graph from a list of doubles: x y z
//
template
Gnuplot& Gnuplot::plot_xyz(const X &x,
const Y &y,
const Z &z,
const std::string &title)
{
if (x.size() == 0 || y.size() == 0 || z.size() == 0)
{
throw GnuplotException("std::vectors too small");
return *this;
}
if (x.size() != y.size() || x.size() != z.size())
{
throw GnuplotException("Length of the std::vectors differs");
return *this;
}
std::ofstream tmp;
std::string name = create_tmpfile(tmp);
if (name == "")
return *this;
//
// write the data to file
//
for (unsigned int i = 0; i < x.size(); i++)
tmp << x[i] << " " << y[i] << " " << z[i] <
void stringtok (Container &container,
std::string const &in,
const char * const delimiters = " \t\n")
{
const std::string::size_type len = in.length();
std::string::size_type i = 0;
while ( i < len )
{
// eat leading whitespace
i = in.find_first_not_of (delimiters, i);
if (i == std::string::npos)
return; // nothing left but white space
// find the end of the token
std::string::size_type j = in.find_first_of (delimiters, i);
// push token
if (j == std::string::npos)
{
container.push_back (in.substr(i));
return;
}
else
container.push_back (in.substr(i, j-i));
// set up for next loop
i = j + 1;
}
return;
}
//------------------------------------------------------------------------------
//
// Destructor: needed to delete temporary files
//
Gnuplot::~Gnuplot()
{
// remove_tmpfiles();
// A stream opened by popen() should be closed by pclose()
#if defined(WIN32) || defined(_WIN32) || defined(__WIN32__) || defined(__TOS_WIN__)
if (_pclose(gnucmd) == -1)
#elif defined(unix) || defined(__unix) || defined(__unix__) || defined(__APPLE__)
if (pclose(gnucmd) == -1)
#endif
std::cerr << "Gnuplot::~Gnuplot: Problem closing communication to gnuplot" << std::endl;
}
//------------------------------------------------------------------------------
//
// Resets a gnuplot session (next plot will erase previous ones)
//
Gnuplot& Gnuplot::reset_plot()
{
// remove_tmpfiles();
nplots = 0;
return *this;
}
//------------------------------------------------------------------------------
//
// resets a gnuplot session and sets all varibles to default
//
Gnuplot& Gnuplot::reset_all()
{
// remove_tmpfiles();
nplots = 0;
cmd("reset");
cmd("clear");
pstyle = "points";
smooth = "";
showonscreen();
return *this;
}
//------------------------------------------------------------------------------
//
// Change the plotting style of a gnuplot session
//
Gnuplot& Gnuplot::set_style(const std::string &stylestr)
{
if (stylestr.find("lines") == std::string::npos &&
stylestr.find("points") == std::string::npos &&
stylestr.find("linespoints") == std::string::npos &&
stylestr.find("impulses") == std::string::npos &&
stylestr.find("dots") == std::string::npos &&
stylestr.find("steps") == std::string::npos &&
stylestr.find("fsteps") == std::string::npos &&
stylestr.find("histeps") == std::string::npos &&
stylestr.find("boxes") == std::string::npos && // 1-4 columns of data are required
stylestr.find("filledcurves") == std::string::npos &&
stylestr.find("histograms") == std::string::npos ) //only for one data column
// stylestr.find("labels") == std::string::npos && // 3 columns of data are required
// stylestr.find("xerrorbars") == std::string::npos && // 3-4 columns of data are required
// stylestr.find("xerrorlines") == std::string::npos && // 3-4 columns of data are required
// stylestr.find("errorbars") == std::string::npos && // 3-4 columns of data are required
// stylestr.find("errorlines") == std::string::npos && // 3-4 columns of data are required
// stylestr.find("yerrorbars") == std::string::npos && // 3-4 columns of data are required
// stylestr.find("yerrorlines") == std::string::npos && // 3-4 columns of data are required
// stylestr.find("boxerrorbars") == std::string::npos && // 3-5 columns of data are required
// stylestr.find("xyerrorbars") == std::string::npos && // 4,6,7 columns of data are required
// stylestr.find("xyerrorlines") == std::string::npos && // 4,6,7 columns of data are required
// stylestr.find("boxxyerrorbars") == std::string::npos && // 4,6,7 columns of data are required
// stylestr.find("financebars") == std::string::npos && // 5 columns of data are required
// stylestr.find("candlesticks") == std::string::npos && // 5 columns of data are required
// stylestr.find("vectors") == std::string::npos &&
// stylestr.find("image") == std::string::npos &&
// stylestr.find("rgbimage") == std::string::npos &&
// stylestr.find("pm3d") == std::string::npos )
{
pstyle = std::string("points");
}
else
{
pstyle = stylestr;
}
return *this;
}
//------------------------------------------------------------------------------
//
// smooth: interpolation and approximation of data
//
Gnuplot& Gnuplot::set_smooth(const std::string &stylestr)
{
if (stylestr.find("unique") == std::string::npos &&
stylestr.find("frequency") == std::string::npos &&
stylestr.find("csplines") == std::string::npos &&
stylestr.find("acsplines") == std::string::npos &&
stylestr.find("bezier") == std::string::npos &&
stylestr.find("sbezier") == std::string::npos )
{
smooth = "";
}
else
{
smooth = stylestr;
}
return *this;
}
//------------------------------------------------------------------------------
//
// sets terminal type to windows / x11
//
Gnuplot& Gnuplot::showonscreen()
{
cmd("set output");
cmd("set terminal " + Gnuplot::terminal_std);
return *this;
}
//------------------------------------------------------------------------------
//
// saves a gnuplot session to a postscript file
//
Gnuplot& Gnuplot::savetofigure(const std::string &filename,
const std::string &terminal)
{
std::ostringstream cmdstr;
cmdstr << "set terminal " << terminal;
cmd(cmdstr.str() );
cmdstr.str(""); // Clear cmdstr
cmdstr << "set output \"" << filename << "\"";
cmd(cmdstr.str());
return *this;
}
//------------------------------------------------------------------------------
//
// Switches legend on
//
Gnuplot& Gnuplot::set_legend(const std::string &position)
{
std::ostringstream cmdstr;
cmdstr << "set key " << position;
cmd(cmdstr.str());
return *this;
}
//------------------------------------------------------------------------------
//
// turns on log scaling for the x axis
//
Gnuplot& Gnuplot::set_xlogscale(const double base)
{
std::ostringstream cmdstr;
cmdstr << "set logscale x " << base;
cmd(cmdstr.str());
return *this;
}
//------------------------------------------------------------------------------
//
// turns on log scaling for the y axis
//
Gnuplot& Gnuplot::set_ylogscale(const double base)
{
std::ostringstream cmdstr;
cmdstr << "set logscale y " << base;
cmd(cmdstr.str());
return *this;
}
//------------------------------------------------------------------------------
//
// turns on log scaling for the z axis
//
Gnuplot& Gnuplot::set_zlogscale(const double base)
{
std::ostringstream cmdstr;
cmdstr << "set logscale z " << base;
cmd(cmdstr.str());
return *this;
}
//------------------------------------------------------------------------------
//
// scales the size of the points used in plots
//
Gnuplot& Gnuplot::set_pointsize(const double pointsize)
{
std::ostringstream cmdstr;
cmdstr << "set pointsize " << pointsize;
cmd(cmdstr.str());
return *this;
}
//------------------------------------------------------------------------------
//
// set isoline density (grid) for plotting functions as surfaces
//
Gnuplot& Gnuplot::set_samples(const int samples)
{
std::ostringstream cmdstr;
cmdstr << "set samples " << samples;
cmd(cmdstr.str());
return *this;
}
//------------------------------------------------------------------------------
//
// set isoline density (grid) for plotting functions as surfaces
//
Gnuplot& Gnuplot::set_isosamples(const int isolines)
{
std::ostringstream cmdstr;
cmdstr << "set isosamples " << isolines;
cmd(cmdstr.str());
return *this;
}
//------------------------------------------------------------------------------
//
// enables contour drawing for surfaces set contour {base | surface | both}
//
Gnuplot& Gnuplot::set_contour(const std::string &position)
{
if (position.find("base") == std::string::npos &&
position.find("surface") == std::string::npos &&
position.find("both") == std::string::npos )
{
cmd("set contour base");
}
else
{
cmd("set contour " + position);
}
return *this;
}
//------------------------------------------------------------------------------
//
// set labels
//
// set the xlabel
Gnuplot& Gnuplot::set_xlabel(const std::string &label)
{
std::ostringstream cmdstr;
cmdstr << "set xlabel \"" << label << "\"";
cmd(cmdstr.str());
return *this;
}
//------------------------------------------------------------------------------
// set the ylabel
//
Gnuplot& Gnuplot::set_ylabel(const std::string &label)
{
std::ostringstream cmdstr;
cmdstr << "set ylabel \"" << label << "\"";
cmd(cmdstr.str());
return *this;
}
//------------------------------------------------------------------------------
// set the zlabel
//
Gnuplot& Gnuplot::set_zlabel(const std::string &label)
{
std::ostringstream cmdstr;
cmdstr << "set zlabel \"" << label << "\"";
cmd(cmdstr.str());
return *this;
}
//------------------------------------------------------------------------------
//
// set range
//
// set the xrange
Gnuplot& Gnuplot::set_xrange(const double iFrom,
const double iTo)
{
std::ostringstream cmdstr;
cmdstr << "set xrange[" << iFrom << ":" << iTo << "]";
cmd(cmdstr.str());
return *this;
}
//------------------------------------------------------------------------------
// set the yrange
//
Gnuplot& Gnuplot::set_yrange(const double iFrom,
const double iTo)
{
std::ostringstream cmdstr;
cmdstr << "set yrange[" << iFrom << ":" << iTo << "]";
cmd(cmdstr.str());
return *this;
}
//------------------------------------------------------------------------------
// set the zrange
//
Gnuplot& Gnuplot::set_zrange(const double iFrom,
const double iTo)
{
std::ostringstream cmdstr;
cmdstr << "set zrange[" << iFrom << ":" << iTo << "]";
cmd(cmdstr.str());
return *this;
}
//------------------------------------------------------------------------------
//
// set the palette range
//
Gnuplot& Gnuplot::set_cbrange(const double iFrom,
const double iTo)
{
std::ostringstream cmdstr;
cmdstr << "set cbrange[" << iFrom << ":" << iTo << "]";
cmd(cmdstr.str());
return *this;
}
//------------------------------------------------------------------------------
//
// Plots a linear equation y=ax+b (where you supply the
// slope a and intercept b)
//
Gnuplot& Gnuplot::plot_slope(const double a,
const double b,
const std::string &title)
{
std::ostringstream cmdstr;
//
// command to be sent to gnuplot
//
if (nplots > 0 && two_dim == true)
cmdstr << "replot ";
else
cmdstr << "plot ";
cmdstr << a << " * x + " << b << " title \"";
if (title == "")
cmdstr << "f(x) = " << a << " * x + " << b;
else
cmdstr << title;
cmdstr << "\" with " << pstyle;
//
// Do the actual plot
//
cmd(cmdstr.str());
return *this;
}
//------------------------------------------------------------------------------
//
// Plot an equation supplied as a std::string y=f(x) (only f(x) expected)
//
Gnuplot& Gnuplot::plot_equation(const std::string &equation,
const std::string &title)
{
std::ostringstream cmdstr;
//
// command to be sent to gnuplot
//
if (nplots > 0 && two_dim == true)
cmdstr << "replot ";
else
cmdstr << "plot ";
cmdstr << equation;
if (title == "")
cmdstr << " notitle";
else
cmdstr << " title \"" << title << "\"";
cmdstr << " with " << pstyle;
//
// Do the actual plot
//
cmd(cmdstr.str());
return *this;
}
//------------------------------------------------------------------------------
//
// plot an equation supplied as a std::string y=(x)
//
Gnuplot& Gnuplot::plot_equation3d(const std::string &equation,
const std::string &title)
{
std::ostringstream cmdstr;
//
// command to be sent to gnuplot
//
if (nplots > 0 && two_dim == false)
cmdstr << "replot ";
else
cmdstr << "splot ";
cmdstr << equation << " title \"";
if (title == "")
cmdstr << "f(x,y) = " << equation;
else
cmdstr << title;
cmdstr << "\" with " << pstyle;
//
// Do the actual plot
//
cmd(cmdstr.str());
return *this;
}
//------------------------------------------------------------------------------
//
// Plots a 2d graph from a list of doubles (x) saved in a file
//
Gnuplot& Gnuplot::plotfile_x(const std::string &filename,
const unsigned int column,
const std::string &title)
{
//
// check if file exists
//
file_available(filename);
std::ostringstream cmdstr;
//
// command to be sent to gnuplot
//
if (nplots > 0 && two_dim == true)
cmdstr << "replot ";
else
cmdstr << "plot ";
cmdstr << "\"" << filename << "\" using " << column;
if (title == "")
cmdstr << " notitle ";
else
cmdstr << " title \"" << title << "\" ";
if(smooth == "")
cmdstr << "with " << pstyle;
else
cmdstr << "smooth " << smooth;
//
// Do the actual plot
//
cmd(cmdstr.str()); //nplots++; two_dim = true; already in cmd();
return *this;
}
//------------------------------------------------------------------------------
//
// Plots a 2d graph from a list of doubles (x y) saved in a file
//
Gnuplot& Gnuplot::plotfile_xy(const std::string &filename,
const unsigned int column_x,
const unsigned int column_y,
const std::string &title)
{
//
// check if file exists
//
file_available(filename);
std::ostringstream cmdstr;
//
// command to be sent to gnuplot
//
if (nplots > 0 && two_dim == true)
cmdstr << "replot ";
else
cmdstr << "plot ";
cmdstr << "\"" << filename << "\" using " << column_x << ":" << column_y;
if (title == "")
cmdstr << " notitle ";
else
cmdstr << " title \"" << title << "\" ";
if(smooth == "")
cmdstr << "with " << pstyle;
else
cmdstr << "smooth " << smooth;
//
// Do the actual plot
//
cmd(cmdstr.str());
return *this;
}
//------------------------------------------------------------------------------
//
// Plots a 2d graph with errorbars from a list of doubles (x y dy) in a file
//
Gnuplot& Gnuplot::plotfile_xy_err(const std::string &filename,
const unsigned int column_x,
const unsigned int column_y,
const unsigned int column_dy,
const std::string &title)
{
//
// check if file exists
//
file_available(filename);
std::ostringstream cmdstr;
//
// command to be sent to gnuplot
//
if (nplots > 0 && two_dim == true)
cmdstr << "replot ";
else
cmdstr << "plot ";
cmdstr << "\"" << filename << "\" using "
<< column_x << ":" << column_y << ":" << column_dy
<< " with errorbars ";
if (title == "")
cmdstr << " notitle ";
else
cmdstr << " title \"" << title << "\" ";
//
// Do the actual plot
//
cmd(cmdstr.str());
return *this;
}
//------------------------------------------------------------------------------
//
// Plots a 3d graph from a list of doubles (x y z) saved in a file
//
Gnuplot& Gnuplot::plotfile_xyz(const std::string &filename,
const unsigned int column_x,
const unsigned int column_y,
const unsigned int column_z,
const std::string &title)
{
//
// check if file exists
//
file_available(filename);
std::ostringstream cmdstr;
//
// command to be sent to gnuplot
//
if (nplots > 0 && two_dim == false)
cmdstr << "replot ";
else
cmdstr << "splot ";
cmdstr << "\"" << filename << "\" using " << column_x << ":" << column_y
<< ":" << column_z;
if (title == "")
cmdstr << " notitle with " << pstyle;
else
cmdstr << " title \"" << title << "\" with " << pstyle;
//
// Do the actual plot
//
cmd(cmdstr.str());
return *this;
}
//------------------------------------------------------------------------------
//
/// * note that this function is not valid for versions of GNUPlot below 4.2
//
Gnuplot& Gnuplot::plot_image(const unsigned char * ucPicBuf,
const unsigned int iWidth,
const unsigned int iHeight,
const std::string &title)
{
std::ofstream tmp;
std::string name = create_tmpfile(tmp);
if (name == "")
return *this;
//
// write the data to file
//
int iIndex = 0;
for(unsigned int iRow = 0; iRow < iHeight; iRow++)
{
for(unsigned int iColumn = 0; iColumn < iWidth; iColumn++)
{
tmp << iColumn << " " << iRow << " "
<< static_cast(ucPicBuf[iIndex++]) << std::endl;
}
}
tmp.flush();
tmp.close();
std::ostringstream cmdstr;
//
// command to be sent to gnuplot
//
if (nplots > 0 && two_dim == true)
cmdstr << "replot ";
else
cmdstr << "plot ";
if (title == "")
cmdstr << "\"" << name << "\" with image";
else
cmdstr << "\"" << name << "\" title \"" << title << "\" with image";
//
// Do the actual plot
//
cmd(cmdstr.str());
return *this;
}
//------------------------------------------------------------------------------
//
// Sends a command to an active gnuplot session
//
Gnuplot& Gnuplot::cmd(const std::string &cmdstr)
{
if( !(valid) )
{
return *this;
}
// int fputs ( const char * str, FILE * stream );
// writes the string str to the stream.
// The function begins copying from the address specified (str) until it
// reaches the terminating null character ('\0'). This final
// null-character is not copied to the stream.
fputs( (cmdstr+"\n").c_str(), gnucmd );
// int fflush ( FILE * stream );
// If the given stream was open for writing and the last i/o operation was
// an output operation, any unwritten data in the output buffer is written
// to the file. If the argument is a null pointer, all open files are
// flushed. The stream remains open after this call.
fflush(gnucmd);
if( cmdstr.find("replot") != std::string::npos )
{
return *this;
}
else if( cmdstr.find("splot") != std::string::npos )
{
two_dim = false;
nplots++;
}
else if( cmdstr.find("plot") != std::string::npos )
{
two_dim = true;
nplots++;
}
return *this;
}
//------------------------------------------------------------------------------
//
// Opens up a gnuplot session, ready to receive commands
//
void Gnuplot::init()
{
// char * getenv ( const char * name ); get value of environment variable
// Retrieves a C string containing the value of the environment variable
// whose name is specified as argument. If the requested variable is not
// part of the environment list, the function returns a NULL pointer.
#if ( defined(unix) || defined(__unix) || defined(__unix__) ) && !defined(__APPLE__)
if (getenv("DISPLAY") == NULL)
{
valid = false;
throw GnuplotException("Can't find DISPLAY variable");
}
#endif
// if gnuplot not available
if (!Gnuplot::get_program_path())
{
valid = false;
throw GnuplotException("Can't find gnuplot");
}
//
// open pipe
//
std::string tmp = Gnuplot::m_sGNUPlotPath + "/" +
Gnuplot::m_sGNUPlotFileName;
// FILE *popen(const char *command, const char *mode);
// The popen() function shall execute the command specified by the string
// command, create a pipe between the calling program and the executed
// command, and return a pointer to a stream that can be used to either read
// from or write to the pipe.
#if defined(WIN32) || defined(_WIN32) || defined(__WIN32__) || defined(__TOS_WIN__)
gnucmd = _popen(tmp.c_str(),"w");
#elif defined(unix) || defined(__unix) || defined(__unix__) || defined(__APPLE__)
gnucmd = popen(tmp.c_str(),"w");
#endif
// popen() shall return a pointer to an open stream that can be used to read
// or write to the pipe. Otherwise, it shall return a null pointer and may
// set errno to indicate the error.
if (!gnucmd)
{
valid = false;
throw GnuplotException("Couldn't open connection to gnuplot");
}
nplots = 0;
valid = true;
smooth = "";
//set terminal type
showonscreen();
return;
}
//------------------------------------------------------------------------------
//
// Find out if a command lives in m_sGNUPlotPath or in PATH
//
bool Gnuplot::get_program_path()
{
//
// first look in m_sGNUPlotPath for Gnuplot
//
std::string tmp = Gnuplot::m_sGNUPlotPath + "/" +
Gnuplot::m_sGNUPlotFileName;
#if defined(WIN32) || defined(_WIN32) || defined(__WIN32__) || defined(__TOS_WIN__)
if ( Gnuplot::file_exists(tmp,0) ) // check existence
#elif defined(unix) || defined(__unix) || defined(__unix__) || defined(__APPLE__)
if ( Gnuplot::file_exists(tmp,1) ) // check existence and execution permission
#endif
{
return true;
}
//
// second look in PATH for Gnuplot
//
char *path;
// Retrieves a C string containing the value of environment variable PATH
path = getenv("PATH");
if (path == NULL)
{
throw GnuplotException("Path is not set");
return false;
}
else
{
std::list ls;
//split path (one long string) into list ls of strings
#if defined(WIN32) || defined(_WIN32) || defined(__WIN32__) || defined(__TOS_WIN__)
stringtok(ls,path,";");
#elif defined(unix) || defined(__unix) || defined(__unix__) || defined(__APPLE__)
stringtok(ls,path,":");
#endif
// scan list for Gnuplot program files
for (std::list::const_iterator i = ls.begin();
i != ls.end(); ++i)
{
tmp = (*i) + "/" + Gnuplot::m_sGNUPlotFileName;
#if defined(WIN32) || defined(_WIN32) || defined(__WIN32__) || defined(__TOS_WIN__)
if ( Gnuplot::file_exists(tmp,0) ) // check existence
#elif defined(unix) || defined(__unix) || defined(__unix__) || defined(__APPLE__)
if ( Gnuplot::file_exists(tmp,1) ) // check existence and execution permission
#endif
{
Gnuplot::m_sGNUPlotPath = *i; // set m_sGNUPlotPath
return true;
}
}
tmp = "Can't find gnuplot neither in PATH nor in \"" +
Gnuplot::m_sGNUPlotPath + "\"";
throw GnuplotException(tmp);
}
}
//------------------------------------------------------------------------------
//
// check if file exists
//
bool Gnuplot::file_exists(const std::string &filename, int mode)
{
if ( mode < 0 || mode > 7)
{
throw std::runtime_error("In function \"Gnuplot::file_exists\": mode\
has to be an integer between 0 and 7");
return false;
}
// int _access(const char *path, int mode);
// returns 0 if the file has the given mode,
// it returns -1 if the named file does not exist or is not accessible in
// the given mode
// mode = 0 (F_OK) (default): checks file for existence only
// mode = 1 (X_OK): execution permission
// mode = 2 (W_OK): write permission
// mode = 4 (R_OK): read permission
// mode = 6 : read and write permission
// mode = 7 : read, write and execution permission
#if defined(WIN32) || defined(_WIN32) || defined(__WIN32__) || defined(__TOS_WIN__)
if (_access(filename.c_str(), mode) == 0)
#elif defined(unix) || defined(__unix) || defined(__unix__) || defined(__APPLE__)
if (access(filename.c_str(), mode) == 0)
#endif
{
return true;
}
else
{
return false;
}
}
bool Gnuplot::file_available(const std::string &filename)
{
std::ostringstream except;
if( Gnuplot::file_exists(filename,0) ) // check existence
{
if( !(Gnuplot::file_exists(filename,4)) ) // check read permission
{
except << "No read permission for File \"" << filename << "\"";
throw GnuplotException( except.str() );
return false;
}
}
else
{
except << "File \"" << filename << "\" does not exist";
throw GnuplotException( except.str() );
return false;
}
return false;
}
//------------------------------------------------------------------------------
//
// Opens a temporary file
//
std::string Gnuplot::create_tmpfile(std::ofstream &tmp)
{
#if defined(WIN32) || defined(_WIN32) || defined(__WIN32__) || defined(__TOS_WIN__)
char name[] = "gnuplotiXXXXXX"; //tmp file in working directory
#elif defined(unix) || defined(__unix) || defined(__unix__) || defined(__APPLE__)
char name[] = "/tmp/gnuplotiXXXXXX"; // tmp file in /tmp
#endif
//
// check if maximum number of temporary files reached
//
if (Gnuplot::tmpfile_num == GP_MAX_TMP_FILES - 1)
{
std::ostringstream except;
except << "Maximum number of temporary files reached ("
<< GP_MAX_TMP_FILES << "): cannot open more files" << std::endl;
throw GnuplotException( except.str() );
}
// int mkstemp(char *name);
// shall replace the contents of the string pointed to by "name" by a unique
// filename, and return a file descriptor for the file open for reading and
// writing. Otherwise, -1 shall be returned if no suitable file could be
// created. The string in template should look like a filename with six
// trailing 'X' s; mkstemp() replaces each 'X' with a character from the
// portable filename character set. The characters are chosen such that the
// resulting name does not duplicate the name of an existing file at the
// time of a call to mkstemp()
//
// open temporary files for output
//
#if defined(WIN32) || defined(_WIN32) || defined(__WIN32__) || defined(__TOS_WIN__)
if (_mktemp(name) == NULL)
#elif defined(unix) || defined(__unix) || defined(__unix__) || defined(__APPLE__)
int tmpfd;
if ((tmpfd = mkstemp(name)) == -1)
#endif
{
std::ostringstream except;
except << "Cannot create temporary file \"" << name << "\"";
throw GnuplotException(except.str());
}
#if defined(unix) || defined(__unix) || defined(__unix__) || defined(__APPLE__)
close(tmpfd);
#endif
tmp.open(name);
if (tmp.bad())
{
std::ostringstream except;
except << "Cannot create temporary file \"" << name << "\"";
throw GnuplotException(except.str());
}
//
// Save the temporary filename
//
tmpfile_list.push_back(name);
Gnuplot::tmpfile_num++;
return name;
}
void Gnuplot::remove_tmpfiles()
{
if ((tmpfile_list).size() > 0)
{
for (unsigned int i = 0; i < tmpfile_list.size(); i++)
{
if( remove( tmpfile_list[i].c_str() ) != 0 )
{
std::ostringstream except;
except << "Cannot remove temporary file \"" << tmpfile_list[i] << "\"";
throw GnuplotException(except.str());
}
}
Gnuplot::tmpfile_num -= static_cast(tmpfile_list.size());
}
}
#endif
================================================
FILE: apps/helloworld_cublas/main_performance.cpp
================================================
#include
#include
#include
#include "util/gl_wrapper.h"
#include "util/OpenGL32Format.h"
#include
#include "thrust/device_vector.h"
#include "thrust/host_vector.h"
#include "thrust/copy.h"
#include "cudax/CublasHelper.h"
#include "cudax/CudaHelper.h"
#include "cudax/CudaTimer.h"
#include "./gnuplot_i.h"
using namespace std;
using namespace cudax;
typedef float Scalar;
typedef Eigen::Matrix Matrix_MxN;
extern "C" void outer_product(float* input, float* output, int rows, int cols);
extern "C" void vector_product(float* J_in, float* e_in, float* Jte_out, int rows, int cols);
//--
extern "C" void outer_product_init(float* input, int rows, int cols);
extern "C" void outer_product_compute(int rows, int cols);
extern "C" void outer_product_copy(float* output);
extern "C" void vector_product_init(float* J_in, float* e_in, int rows, int cols);
extern "C" void vector_product_compute(int rows, int cols);
extern "C" void vector_product_copy(float* Jte_out);
//--
void wait_for_key (){
cout << endl << "Press ENTER to continue..." << endl;
std::cin.clear();
std::cin.ignore(std::cin.rdbuf()->in_avail());
std::cin.get();
return;
}
int main(int argc, char *argv[]){
QApplication app(argc, argv);
OpenGL32Format fmt;
QGLWidget widget(fmt);
widget.makeCurrent();
CudaHelper::init();
CublasHelper::init();
///--- Jacobian multiplication
{
// Matrix dimensions
const int MAX_NUM_CONSTRAINTS = 320*240;
const int NUM_ROWS = 100;
const int NUM_COLS = 26; ///< #DOF 1xhand
// Row major matrix type
typedef Eigen::Matrix Matrix_MxN_RowMajor;
//--- JTJ computation
// Large matrix with MAX_NUM_CONSTRAINTS rows
Matrix_MxN_RowMajor J;
J = Matrix_MxN_RowMajor::Random(MAX_NUM_CONSTRAINTS, NUM_COLS);
// GPU matrix product of the top NUM_ROWS rows
cout << "compute:" << endl;
Matrix_MxN JtJ_gpu(NUM_COLS, NUM_COLS);
#if 1
outer_product_init(J.data(), NUM_ROWS, NUM_COLS);
outer_product_compute(NUM_ROWS, NUM_COLS);
outer_product_copy(JtJ_gpu.data());
#else
outer_product(J.data(), JtJ_gpu.data(), NUM_ROWS, NUM_COLS);
#endif
// CPU matrix product of the top NUM_ROWS rows
Matrix_MxN J_sub = J.block(0, 0, NUM_ROWS, NUM_COLS);
Matrix_MxN JtJ_cpu = J_sub.transpose() * J_sub;
// Print results
cout << "CPU result:" << endl << JtJ_cpu << endl << endl;
cout << "GPU result:" << endl << JtJ_gpu << endl << endl;
cout << "Frobenius norm: " << (JtJ_cpu - JtJ_gpu).norm() << endl << endl;
//--- JTe computation
// Right hand side matrix-vector multiplication
Matrix_MxN_RowMajor e;
e = Matrix_MxN_RowMajor::Random(MAX_NUM_CONSTRAINTS, 1);
Matrix_MxN e_sub = e.block(0, 0, NUM_ROWS, 1);
// GPU matrix-vector product
Matrix_MxN Jte_gpu(NUM_COLS, 1);
#if 1
vector_product_init(J.data(), e.data(), NUM_ROWS, NUM_COLS);
vector_product_compute(NUM_ROWS, NUM_COLS);
vector_product_copy(Jte_gpu.data());
#else
vector_product(J.data(), e.data(), Jte_gpu.data(), NUM_ROWS, NUM_COLS);
#endif
// CPU matrix-vector product
Matrix_MxN Jte_cpu = J_sub.transpose() * e_sub;
// Print results
cout << "CPU result:" << endl << Jte_cpu << endl << endl;
cout << "GPU result:" << endl << Jte_gpu << endl << endl;
cout << "Frobenius norm: " << (Jte_cpu - Jte_gpu).norm() << endl << endl;
//--- Runtimes
// Plot computation time
vector data_x0(MAX_NUM_CONSTRAINTS); // Matrix dimension
vector data_y1(MAX_NUM_CONSTRAINTS); // GPU JTJ runtime
vector data_y2(MAX_NUM_CONSTRAINTS); // CPU JTJ runtime
vector data_y3(MAX_NUM_CONSTRAINTS); // GPU JTe runtime
vector data_y4(MAX_NUM_CONSTRAINTS); // CPU JTe runtime
CudaTimer timer;
for(int i = 0; i < MAX_NUM_CONSTRAINTS; i += 100){
int N = i+1;
float x = (float)N;
//--- JTJ
Matrix_MxN_RowMajor J_test = J.block(0,0,N,NUM_COLS);
Matrix_MxN JtJ_test(NUM_COLS, NUM_COLS);
// GPU
outer_product_init(J_test.data(), N, NUM_COLS);
timer.restart("");
outer_product_compute(N, NUM_COLS);
//outer_product(J_test.data(), JtJ_test.data(), N, NUM_COLS);
float y1 = timer.elapsed();
outer_product_copy(JtJ_test.data());
// CPU
timer.restart("");
Matrix_MxN JtJ_test_cpu = J_test.transpose() * J_test;
float y2 = timer.elapsed();
//cout << "Frobenius norm: " << (JtJ_test - JtJ_test_cpu).norm() << endl << endl;
//--- JTe
Matrix_MxN_RowMajor e_test = e.block(0,0,N,1);
Matrix_MxN Jte_test(NUM_COLS, 1);
// GPU
vector_product_init(J_test.data(), e_test.data(), N, NUM_COLS);
timer.restart("");
vector_product_compute(N, NUM_COLS);
//vector_product(J_test.data(), e_test.data(), Jte_test.data(), N, NUM_COLS);
float y3 = timer.elapsed();
vector_product_copy(Jte_test.data());
// CPU
timer.restart("");
Matrix_MxN Jte_test_cpu = J_test.transpose() * e_test;
float y4 = timer.elapsed();
//cout << "Frobenius norm: " << (Jte_test - Jte_test_cpu).norm() << endl << endl;
data_x0.push_back(x);
data_y1.push_back(y1);
data_y2.push_back(y2);
data_y3.push_back(y3);
data_y4.push_back(y4);
}
try{
Gnuplot::set_terminal_std("qt");
Gnuplot plot("lines");
plot.set_title("Computation time of J^T * J w.r.t. number of rows of J in milliseconds");
plot.set_grid();
plot.plot_xy(data_x0, data_y1, "GPU JTJ");
plot.plot_xy(data_x0, data_y2, "CPU JTJ");
plot.plot_xy(data_x0, data_y3, "GPU JTe");
plot.plot_xy(data_x0, data_y4, "CPU JTe");
cout << "Computation time for "
<< MAX_NUM_CONSTRAINTS << " x "
<< NUM_COLS << " matrix: "
<< data_y1[data_y1.size()-1] << " ms [GPU], "
<< data_y2[data_y2.size()-1] << " ms [CPU]"
<< endl;
wait_for_key(); ///< avoid window closing right away
}catch(GnuplotException &e){
cout << e.what() << endl;
}
}
CublasHelper::cleanup();
exit(0);
return 0;
}
================================================
FILE: apps/helloworld_cublas/main_simple.cpp
================================================
///--- Computes matrix products on GPU
/// this example is broken, but if it runs it's "okay"
/// TODO: matthias, it runs but frobenius is non-zero... why?
#include
#include "util/gl_wrapper.h"
#include "util/OpenGL32Format.h"
#include
#include
#include
#include "cudax/CublasHelper.h"
#include "cudax/CudaHelper.h"
#include "cudax/CublasHelper.h"
using namespace std;
using namespace cudax;
typedef float Scalar;
typedef Eigen::Matrix Matrix_MxN;
extern "C" void outer_product(float* input, float* output, int rows, int cols);
int main(int argc, char *argv[]){
QApplication app(argc, argv);
OpenGL32Format fmt;
QGLWidget widget(fmt);
widget.makeCurrent();
CudaHelper::init();
CublasHelper::init();
{
Matrix_MxN J = Matrix_MxN::Random(100,10);
Matrix_MxN JtJ(J.cols(),J.cols());
outer_product(J.data(), JtJ.data(), J.rows(), J.cols());
cout << J.transpose() * J << endl;
cout << endl << endl;
cout << JtJ << endl;
cout << endl << endl;
cout << "Frobenius norm: " << (J.transpose()*J - JtJ).norm() << endl;
}
CublasHelper::cleanup();
CudaHelper::cleanup();
return 0;
}
================================================
FILE: apps/helloworld_cudagl/CMakeLists.txt
================================================
cmake_minimum_required(VERSION 2.8)
get_filename_component(PROJECTNAME ${CMAKE_CURRENT_LIST_DIR} NAME)
project(${PROJECTNAME})
set(CMAKE_MODULE_PATH ${CMAKE_CURRENT_LIST_DIR}/../../cmake)
include(../../cmake/ConfigureCompiler.cmake)
include(../../cmake/ConfigureQt.cmake)
include(../../cmake/ConfigureOpenGL.cmake)
include(../../cmake/ConfigureGLEW.cmake)
include(../../cmake/ConfigureCUDA.cmake)
include(../../cmake/ConfigureEigen.cmake)
include(../../cmake/ConfigureOpenGL.cmake)
set(CMAKE_BUILD_TYPE "Release")
#set(CMAKE_BUILD_TYPE "Debug")
include_directories(../../) #< #include "tracker/..."
file(GLOB SOURCES "*.h")
file(GLOB HEADERS "*.cpp")
add_executable(${PROJECTNAME} ${SOURCES} ${HEADERS})
target_link_libraries(${PROJECTNAME} ${LIBRARIES})
================================================
FILE: apps/helloworld_cudagl/main.cpp
================================================
// Test the CUDA OpenGL interoperability
//
// Performance on GeForce 650M (OSX):
// [cudaGraphicsGLRegisterImage] 21.8078 ms
// [1000x (w/ offscreen draw)] 1687.07 ms
// [1000x (w/o offscreen draw)] 1438.53 ms
// [cudaGraphicsUnregisterResource] 0.555032 ms
// Performance on GeForce GTX980 and i5@3Ghz (Ubuntu@MIT):
// [cudaGraphicsGLRegisterImage] 170.678 ms
// [1000x (w/ offscreen draw)] 204.626 ms
// [1000x (w/o offscreen draw)] 195.564 ms
// [cudaGraphicsUnregisterResource] 0.12116 ms
// Performance on GeForce GTX980 (Win8.1):
// [cudaGraphicsGLRegisterImage] 109.379 ms
// [1000x (w/ offscreen draw)] 182.223 ms
// [1000x (w/o offscreen draw)] 156.25 ms
// [cudaGraphicsUnregisterResource] 0 ms
#include
#include "util/gl_wrapper.h"
#include "util/tictoc.h"
#include "cudax/CudaHelper.h"
#include
#include
#include
#include "tracker/OffscreenRender/CustomFrameBuffer.h"
///--- Create an OpenGL>3 context
class GLWidget : public QGLWidget{
QOpenGLVertexArrayObject vao;
class OpenGLFormat : public QGLFormat{
public:
OpenGLFormat(){
setVersion(3,2);
setProfile(QGLFormat::CoreProfile);
setSampleBuffers(false); ///< no anti-aliasing
// setSamples(1); ///< no anti-aliasing
}
};
public:
GLWidget():QGLWidget(OpenGLFormat()){
std::cout << "OpenGL Context " << this->format().majorVersion() << "." << this->format().minorVersion() << std::endl;
}
void init(){
bool success = vao.create();
if(!success) exit(EXIT_FAILURE);
vao.bind();
}
};
int main(int argc, char* argv[]){
printf("%s starting...\n", argv[0]);
QApplication app(argc, argv);
GLWidget glarea;
glarea.show();
glarea.init();
#ifdef WITH_GLEW
//--- GLEW Initialization (must have a context)
glewExperimental = true;
if (glewInit() != GLEW_NO_ERROR){
fprintf(stderr, "Failed to initialize GLEW\n");
// return EXIT_FAILURE;
}
#endif
/// As in de docs, I get the device after creating the context
int devID = gpuGetMaxGflopsDeviceId();
cudaError status = cudaGLSetGLDevice(devID);
if(status!=cudaSuccess){
std::cout << "Could not get OpenGL compliant device... exiting" << std::endl;
exit(0);
}
///--- These two are paired-up with a bind
struct ResourcePair {
struct cudaGraphicsResource* resouce;
cudaArray* array;
};
///--- OpenGL initialization
int width = 320;
int height = 240;
glViewport(0,0, width, height);
glClearColor(1.0,1.0,1.0,1.0);
glEnable(GL_DEPTH_TEST);
///--- Framebuffer initialization
CustomFrameBuffer fb;
fb.init(width, width);
GLuint texture_id = fb.extra_tex_id();
ResourcePair res;
{
TICTOC_SCOPE(timer, "cudaGraphicsGLRegisterImage");
checkCudaErrors(cudaGraphicsGLRegisterImage(&res.resouce, texture_id, GL_TEXTURE_2D, cudaGraphicsMapFlagsReadOnly));
}
auto draw_map_unmap = [&](bool with_draw){
if(with_draw){
TIMED_SCOPE(timer,"offscreendraw");
fb.bind();
glClear(GL_DEPTH_BUFFER_BIT | GL_COLOR_BUFFER_BIT);
fb.unbind();
glFinish();
}
{
TIMED_SCOPE(timer,"map");
checkCudaErrors(cudaGraphicsMapResources(1, &res.resouce, 0));
checkCudaErrors(cudaGraphicsSubResourceGetMappedArray(&res.array, res.resouce, 0, 0));
}
{
TIMED_SCOPE(timer,"unmap"); //~2 microseconds
checkCudaErrors(cudaGraphicsUnmapResources(1, &res.resouce, 0));
}
};
TICTOC_BLOCK(timer,"1000x (w/ offscreen draw)")
for (int i = 0; i < 1000; ++i)
draw_map_unmap(true);
TICTOC_BLOCK(timer,"1000x (w/o offscreen draw)")
for (int i = 0; i < 1000; ++i)
draw_map_unmap(true);
TICTOC_BLOCK(timer,"cudaGraphicsUnregisterResource")
{
checkCudaErrors(cudaGraphicsUnregisterResource(res.resouce));
}
return 0;
}
================================================
FILE: apps/helloworld_librealsense/CMakeLists.txt
================================================
# https://github.com/IntelRealSense/librealsense/issues/62
cmake_minimum_required(VERSION 2.8)
get_filename_component(PROJECT ${CMAKE_CURRENT_LIST_DIR} NAME)
project(${PROJECT})
add_compile_options(-std=c++11 -fPIC -lusb-1.0 -lpthread )
# libusb-1.0
find_package(Threads REQUIRED)
find_package(PkgConfig)
pkg_check_modules(PC_LIBUSB REQUIRED libusb-1.0)
include_directories( ${LIBUSB_1_INCLUDE_DIRS})
set(CMAKE_MODULE_PATH ${CMAKE_CURRENT_LIST_DIR}/../../cmake)
# include(../../cmake/ConfigureOpenCV.cmake)
include(../../cmake/ConfigureOpenGL.cmake)
# GLUT
#find_package(GLUT REQUIRED)
#include_directories(${GLUT_INCLUDE_DIRS})
#LIST(APPEND LIBRARIES ${GLUT_LIBRARY})
# GLFW
find_package(PkgConfig REQUIRED)
pkg_search_module(GLFW REQUIRED glfw3)
include_directories(${GLFW_INCLUDE_DIRS})
LIST(APPEND LIBRARIES ${GLFW_LIBRARIES})
# librealsense
set(LIBREALSENSE_INCLUDE_DIR "/home/raghu/Desktop/librealsense/include")
set(LIBREALSENSE_LIBRARY "/usr/local/lib/librealsense.so")
include_directories(${LIBREALSENSE_INCLUDE_DIR})
list(APPEND LIBRARIES ${LIBREALSENSE_LIBRARY})
aux_source_directory(. SRC_LIST)
add_executable(${PROJECT_NAME} ${SRC_LIST})
target_link_libraries( ${PROJECT_NAME} ${LIBRARIES} ${CMAKE_THREAD_LIBS_INIT} )
================================================
FILE: apps/helloworld_librealsense/main.cpp
================================================
// License: Apache 2.0. See LICENSE file in root directory.
// Copyright(c) 2015 Intel Corporation. All Rights Reserved.
///////////////////////////////////////////////////////
// librealsense tutorial #3 - Point cloud generation //
///////////////////////////////////////////////////////
// First include the librealsense C++ header file
#include
#include
// Also include GLFW to allow for graphical display
#define GLFW_INCLUDE_GLU
#include
double yaw, pitch, lastX, lastY; int ml;
static void on_mouse_button(GLFWwindow * win, int button, int action, int mods)
{
if(button == GLFW_MOUSE_BUTTON_LEFT) ml = action == GLFW_PRESS;
}
static double clamp(double val, double lo, double hi) { return val < lo ? lo : val > hi ? hi : val; }
static void on_cursor_pos(GLFWwindow * win, double x, double y)
{
if(ml)
{
yaw = clamp(yaw - (x - lastX), -120, 120);
pitch = clamp(pitch + (y - lastY), -80, 80);
}
lastX = x;
lastY = y;
}
int main() try
{
// Turn on logging. We can separately enable logging to console or to file, and use different severity filters for each.
rs::log_to_console(rs::log_severity::warn);
//rs::log_to_file(rs::log_severity::debug, "librealsense.log");
// Create a context object. This object owns the handles to all connected realsense devices.
rs::context ctx;
printf("There are %d connected RealSense devices.\n", ctx.get_device_count());
if(ctx.get_device_count() == 0) return EXIT_FAILURE;
// This tutorial will access only a single device, but it is trivial to extend to multiple devices
rs::device * dev = ctx.get_device(0);
printf("\nUsing device 0, an %s\n", dev->get_name());
printf(" Serial number: %s\n", dev->get_serial());
printf(" Firmware version: %s\n", dev->get_firmware_version());
// Configure depth and color to run with the device's preferred settings
dev->enable_stream(rs::stream::depth, rs::preset::best_quality);
dev->enable_stream(rs::stream::color, rs::preset::best_quality);
dev->start();
// Open a GLFW window to display our output
glfwInit();
GLFWwindow * win = glfwCreateWindow(1280, 960, "librealsense tutorial #3", nullptr, nullptr);
glfwSetCursorPosCallback(win, on_cursor_pos);
glfwSetMouseButtonCallback(win, on_mouse_button);
glfwMakeContextCurrent(win);
while(!glfwWindowShouldClose(win))
{
// Wait for new frame data
glfwPollEvents();
dev->wait_for_frames();
// Retrieve our images
const uint16_t * depth_image = (const uint16_t *)dev->get_frame_data(rs::stream::depth);
const uint8_t * color_image = (const uint8_t *)dev->get_frame_data(rs::stream::color);
// Retrieve camera parameters for mapping between depth and color
rs::intrinsics depth_intrin = dev->get_stream_intrinsics(rs::stream::depth);
rs::extrinsics depth_to_color = dev->get_extrinsics(rs::stream::depth, rs::stream::color);
rs::intrinsics color_intrin = dev->get_stream_intrinsics(rs::stream::color);
float scale = dev->get_depth_scale();
// Set up a perspective transform in a space that we can rotate by clicking and dragging the mouse
glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT);
glMatrixMode(GL_PROJECTION);
glLoadIdentity();
gluPerspective(60, (float)1280/960, 0.01f, 20.0f);
glMatrixMode(GL_MODELVIEW);
glLoadIdentity();
gluLookAt(0,0,0, 0,0,1, 0,-1,0);
glTranslatef(0,0,+0.5f);
glRotated(pitch, 1, 0, 0);
glRotated(yaw, 0, 1, 0);
glTranslatef(0,0,-0.5f);
// We will render our depth data as a set of points in 3D space
glPointSize(2);
glEnable(GL_DEPTH_TEST);
glBegin(GL_POINTS);
for(int dy=0; dy= color_intrin.width || cy >= color_intrin.height)
{
glColor3ub(255, 255, 255);
}
else
{
glColor3ubv(color_image + (cy * color_intrin.width + cx) * 3);
}
// Emit a vertex at the 3D location of this depth pixel
glVertex3f(depth_point.x, depth_point.y, depth_point.z);
}
}
glEnd();
glfwSwapBuffers(win);
}
return EXIT_SUCCESS;
}
catch(const rs::error & e)
{
// Method calls against librealsense objects may throw exceptions of type rs::error
printf("rs::error was thrown when calling %s(%s):\n", e.get_failed_function().c_str(), e.get_failed_args().c_str());
printf(" %s\n", e.what());
return EXIT_FAILURE;
}
================================================
FILE: apps/helloworld_opencv/CMakeLists.txt
================================================
cmake_minimum_required(VERSION 2.8)
get_filename_component(PROJECT ${CMAKE_CURRENT_LIST_DIR} NAME)
project(${PROJECT})
# cmake_policy(SET CMP0046 OLD)
#set(CMAKE_BUILD_TYPE "Release")
#set(CMAKE_BUILD_TYPE "Debug")
set(CMAKE_MODULE_PATH ${CMAKE_CURRENT_LIST_DIR}/../../cmake)
include(../../cmake/ConfigureCompiler.cmake)
include(../../cmake/ConfigureOpenCV.cmake)
add_executable(${PROJECT} main.cpp)
target_link_libraries(${PROJECT} ${LIBRARIES})
file(COPY "input.png" DESTINATION ${PROJECT_BINARY_DIR})
================================================
FILE: apps/helloworld_opencv/main.cpp
================================================
#include
#include
#include "stdlib.h"
#include "opencv2/core/core.hpp"
#include "opencv2/core/types_c.h" ///< CV_RGB2GRAY
#include "opencv2/imgproc/imgproc.hpp" ///< cvtColor
#include "opencv2/highgui/highgui.hpp"
int main(int, char **) {
cv::Mat image = cv::imread("input.png");
std::cout << "image size: " << image.rows << " " << image.cols << std::endl;
assert(image.rows > 0);
assert(image.cols > 0);
cv::cvtColor(image, image, CV_RGB2GRAY);
cv::imshow("input", image);
cv::waitKey(0);
exit(0);
}
================================================
FILE: apps/helloworld_openmp/CMakeLists.txt
================================================
if(UNIX AND NOT APPLE)
return()
endif()
cmake_minimum_required(VERSION 2.8)
get_filename_component(PROJECT ${CMAKE_CURRENT_LIST_DIR} NAME)
project(${PROJECT})
set(CMAKE_MODULE_PATH ${CMAKE_CURRENT_LIST_DIR}/../../cmake)
include(../../cmake/ConfigureCompiler.cmake)
include(../../cmake/ConfigureOpenMP.cmake)
add_executable(${PROJECT} main.cpp)
target_link_libraries(${PROJECT} ${LIBRARIES})
================================================
FILE: apps/helloworld_openmp/main.cpp
================================================
// COMPILE: /usr/local/bin/g++-4.8 -fopenmp openmp.cpp
#include
#include
#include
int main (int argc, char *argv[])
{
int nthreads, tid;
/* Fork a team of threads giving them their own copies of variables */
#pragma omp parallel private(nthreads, tid)
{
/* Obtain thread number */
tid = omp_get_thread_num();
printf("Hello World from thread = %d\n", tid);
/* Only master thread does this */
if (tid == 0)
{
nthreads = omp_get_num_threads();
printf("Number of threads = %d\n", nthreads);
}
} /* All threads join master thread and disband */
}
================================================
FILE: apps/helloworld_openni/CMakeLists.txt
================================================
cmake_minimum_required(VERSION 2.8)
get_filename_component(PROJECT ${CMAKE_CURRENT_LIST_DIR} NAME)
project(${PROJECT})
# cmake_policy(SET CMP0043 OLD)
# cmake_policy(SET CMP0020 OLD)
set(CMAKE_MODULE_PATH ${CMAKE_CURRENT_LIST_DIR}/../../cmake)
include(../../cmake/ConfigureCompiler.cmake)
include(../../cmake/ConfigureOpenNI.cmake)
include(../../cmake/ConfigureOpenCV.cmake)
include(../../cmake/ConfigureQt.cmake)
include(../../cmake/ConfigureEigen.cmake)
if(OPENNI2_FOUND)
set(CMAKE_BUILD_TYPE "Debug")
INCLUDE_DIRECTORIES(../../)
list(APPEND SOURCES ../../tracker/Data/Camera.cpp)
list(APPEND SOURCES ../../tracker/Sensor/Sensor_openni.cpp)
add_executable(${PROJECT} main.cpp ${SOURCES})
target_link_libraries(${PROJECT} ${LIBRARIES})
else()
message(STATUS "Cannot compile this helloworld")
endif()
================================================
FILE: apps/helloworld_openni/main.cpp
================================================
#include
#include "util/tictoc.h"
#include "util/opencv_wrapper.h"
#include "tracker/Sensor/Sensor.h"
#include "tracker/Data/DataFrame.h"
int main(int /*argc*/, char ** /*argv*/){
Camera* camera = new Camera(QVGA, 60 /*FPS*/);
Sensor* sensor = new SensorOpenNI(camera);
///--- start the sensor
sensor->start();
bool success = sensor->spin_wait_for_data(5 /*seconds*/);
assert(success);
DataFrame frame(0);
for(int i=0; i<30 /*seconds*/ *60 /*60FPS*/; i++){
bool success = sensor->fetch_streams(frame);
assert(success);
// cv::normalize(frame.color, frame.color, 0, 255, cv::NORM_MINMAX);
///--- Show color
cvtColor(frame.color, frame.color, CV_BGRA2RGBA);
cv::imshow("color", frame.color);
///--- Show depth
cv::normalize(frame.depth, frame.depth, 0, USHRT_MAX, cv::NORM_MINMAX);
cv::imshow("depth", frame.depth);
///--- Wait a sec
cv::waitKey(15 /*ms -> 60fps*/);
}
std::cout << "finished!" << std::endl;
return 0;
}
================================================
FILE: apps/helloworld_qglviewer/CMakeLists.txt
================================================
cmake_minimum_required(VERSION 2.8)
get_filename_component(PROJECT ${CMAKE_CURRENT_LIST_DIR} NAME)
project(${PROJECT})
#cmake_policy(SET CMP0020 OLD)
#set(CMAKE_BUILD_TYPE "Release")
#set(CMAKE_BUILD_TYPE "Debug")
#--- Where to find the FindPackageName.cmake
set(CMAKE_MODULE_PATH ${CMAKE_CURRENT_LIST_DIR}/../../cmake)
include(../../cmake/ConfigureCompiler.cmake)
include(../../cmake/ConfigureQt.cmake)
include(../../cmake/ConfigureOpenGL.cmake)
include(../../cmake/ConfigureQGLViewer.cmake)
#--- Create exe and link
add_executable(${PROJECT} main.cpp)
target_link_libraries(${PROJECT} ${LIBRARIES})
================================================
FILE: apps/helloworld_qglviewer/main.cpp
================================================
#include
#include
class Viewer : public QGLViewer {
void draw() {
/// @note this would not work in Mac as there is no compatibility profile
/// and this is OpenGL2 stuff.
const float nbSteps = 200.0;
glBegin(GL_QUAD_STRIP);
for (int i=0; i
#include
#include
#include
/// Format class to enable OpenGL4 core profile
class OpenGLFormat : public QGLFormat{
public:
OpenGLFormat(){
setVersion(3,2);
setProfile(QGLFormat::CoreProfile);
setSampleBuffers(false); ///< no anti-aliasing
// setSamples(1); ///< no anti-aliasing
}
};
class GLWidget : public QGLWidget{
QOpenGLVertexArrayObject vao;
public:
GLWidget():QGLWidget(OpenGLFormat()){
std::cout << "OpenGL " << this->format().majorVersion() << "." << this->format().minorVersion() << std::endl;
}
void initializeGL(){
bool success = vao.create();
if(!success) exit(EXIT_FAILURE);
vao.bind();
}
void paintGL() {
glClearColor(0,1,0,1); ///< green
glClear(GL_COLOR_BUFFER_BIT);
}
};
int main(int argc, char* argv[]){
QApplication app(argc, argv);
GLWidget glarea;
glarea.show();
return app.exec();
}
================================================
FILE: apps/helloworld_realsense/CMakeLists.txt
================================================
if(NOT WIN32)
return()
endif()
cmake_minimum_required(VERSION 2.8)
get_filename_component(PROJECT ${CMAKE_CURRENT_LIST_DIR} NAME)
project(${PROJECT})
set(CMAKE_MODULE_PATH ${CMAKE_CURRENT_LIST_DIR}/../../cmake)
include(../../cmake/ConfigureCompiler.cmake)
include(../../cmake/ConfigureOpenNI.cmake)
include(../../cmake/ConfigureOpenCV.cmake)
include(../../cmake/ConfigureQt.cmake)
include(../../cmake/ConfigureEigen.cmake)
include(../../cmake/ConfigureRealSense.cmake)
set(CMAKE_BUILD_TYPE "Debug")
INCLUDE_DIRECTORIES(../../)
list(APPEND EXTRA_SOURCES ../../tracker/Data/Camera.cpp)
list(APPEND EXTRA_SOURCES ../../tracker/Sensor/Sensor_realsense.cpp)
add_executable(${PROJECT} main.cpp ${EXTRA_SOURCES})
target_link_libraries(${PROJECT} ${LIBRARIES})
================================================
FILE: apps/helloworld_realsense/main.cpp
================================================
#include
#include "pxcsensemanager.h"
#include "pxcsession.h"
#include "pxcprojection.h"
#include "util/tictoc.h"
#include "util/opencv_wrapper.h"
#include "tracker/Sensor/Sensor.h"
#include "tracker/Data/DataFrame.h"
int main(int /*argc*/, char ** /*argv*/){
Camera camera(QVGA, 60 /*FPS*/);
SensorRealSense sensor(&camera);
///--- start the sensor
sensor.start();
bool success = sensor.spin_wait_for_data(5 /*seconds*/);
assert(success);
DataFrame frame(0);
for(int i=0; i<30 /*seconds*/ *60 /*60FPS*/; i++){
tic(total);
bool success = sensor.fetch_streams(frame);
assert(success);
// printf("fetch time: %2.2f\n", toc(total)); fflush(stdout);
// cv::normalize(frame.color, frame.color, 0, 255, cv::NORM_MINMAX);
///--- Show color
cvtColor(frame.color, frame.color, CV_BGR2RGB);
cv::imshow("color", frame.color);
///--- Show depth
cv::normalize(frame.depth, frame.depth, 0, USHRT_MAX, cv::NORM_MINMAX);
cv::imshow("depth", frame.depth);
///--- Wait a sec
cv::waitKey(15 /*ms -> 60fps*/);
}
return 0;
}
#if 0
/// @see file:///C:/Developer/RealSense/RSSDK/doc/HTML/index.html
class MyHandler : public PXCSenseManager::Handler {
public:
virtual pxcStatus PXCAPI OnNewSample(pxcUID, PXCCapture::Sample *sample) {
static auto now = std::chrono::system_clock::now();
// Work on sample->color and sample->depth
// ...
// return NO_ERROR to continue, or any error to exit the loop
if (sample->color!=NULL) {
// work on the color sample
}
if (sample->depth!=NULL) {
// work on the depth sample (actual useful data)
auto now2 = std::chrono::system_clock::now();
double elapsed = std::chrono::duration (now2-now).count();
printf("elapsed: %.2f", elapsed); fflush(stdout);
now = now2;
}
return PXC_STATUS_NO_ERROR;
}
};
int main(int /*argc*/, char ** /*argv*/){
// Create a SenseManager instance
PXCSenseManager *sm=PXCSenseManager::CreateInstance();
#define SYNCHRONIZED
#ifdef SYNCHRONIZED
/// C++ Example 26: Capture Aligned Color and Depth Samples using the SenseManager Events
// Select the color and depth streams
PXCVideoModule::DataDesc ddesc={};
ddesc.deviceInfo.streams=PXCCapture::STREAM_TYPE_COLOR|PXCCapture::STREAM_TYPE_DEPTH;
ddesc.streams.color.frameRate = {60.0f, 60.0f};
ddesc.streams.color.sizeMin = {320, 240};
ddesc.streams.color.sizeMax = {320, 240};
ddesc.streams.depth.frameRate = {60.0f, 60.0f};
ddesc.streams.depth.sizeMin = {640, 240};
ddesc.streams.depth.sizeMax = {640, 240};
sm->EnableStreams(&ddesc);
#else
/// C++ Example 25: Capture Unaligned Color and Depth Samples using the SenseManager Events
sm->EnableStream(PXCCapture::STREAM_TYPE_COLOR,320,240,60);
sm->EnableStream(PXCCapture::STREAM_TYPE_DEPTH,640,240,60);
#endif
// Initialize my handler
MyHandler handler;
sm->Init(&handler);
// Stream Data
sm->StreamFrames(true);
// Clean up
sm->Release();
return 0;
}
#endif
#if 0
int main(int /*argc*/, char ** /*argv*/){
PXCSession* session = PXCSession::CreateInstance();
PXCSession::ImplDesc desc={};
desc.group=PXCSession::IMPL_GROUP_SENSOR;
desc.subgroup=PXCSession::IMPL_SUBGROUP_VIDEO_CAPTURE;
for (int i=0;;i++) {
PXCSession::ImplDesc desc1;
if (session->QueryImpl(&desc,i,&desc1)CreateImpl(&desc1,&capture);
for (int i=0;;i++) {
PXCCapture::DeviceInfo dinfo;
if (capture->QueryDeviceInfo(i,&dinfo)CreateDevice(0);
PXCCapture::StreamType streams=PXCCapture::STREAM_TYPE_COLOR|PXCCapture::STREAM_TYPE_DEPTH;
for (int p=0;;p++) {
PXCCapture::Device::StreamProfileSet profiles={};
pxcStatus sts=device->QueryStreamProfileSet(streams, p, &profiles);
if (stsRelease();
capture->Release();
}
return 0;
}
#endif
#if 0
int main(int /*argc*/, char ** /*argv*/){
PXCSenseManager *sm=PXCSenseManager::CreateInstance();
// Select the color and depth streams
sm->EnableStream(PXCCapture::STREAM_TYPE_COLOR,320,240,60);
sm->EnableStream(PXCCapture::STREAM_TYPE_DEPTH,640,240,60);
// Initialize and Stream Samples
sm->Init();
for (int i=0;i<20;i++) {
// This function blocks until both samples are ready
if (sm->AcquireFrame(true)QuerySample();
// work on the samples sample->color and sample->depth
// go fetching the next samples
sm->ReleaseFrame();
}
// Close down
sm->Release();
exit(0);
std::cout << "hello world!" << std::endl;
return 0;
}
#endif
================================================
FILE: apps/helloworld_thrust/CMakeLists.txt
================================================
cmake_minimum_required(VERSION 2.8)
get_filename_component(PROJECT ${CMAKE_CURRENT_LIST_DIR} NAME)
project(${PROJECT})
set(CMAKE_MODULE_PATH ${CMAKE_CURRENT_LIST_DIR}/../../cmake)
include(../../cmake/ConfigureCompiler.cmake)
include(../../cmake/ConfigureCUDA.cmake)
include_directories(../../)
cuda_add_executable(${PROJECT} main.cu)
target_link_libraries(${PROJECT} ${LIBRARIES})
================================================
FILE: apps/helloworld_thrust/main.cu
================================================
#include
#include
#include
#include
#include
#include "util/tictoc.h"
#include "cudax/CudaHelper.h"
int main(void)
{
int major = THRUST_MAJOR_VERSION;
int minor = THRUST_MINOR_VERSION;
std::cout << "Thrust version: " << major << "." << minor << std::endl;
thrust::device_vector d_vec;
thrust::host_vector h_vec(1 << 24);
TICTOC_BLOCK(t_gen,"Generate randoms + h2d transfer")
{
thrust::generate(h_vec.begin(), h_vec.end(), rand);
d_vec = h_vec; ///<
}
TICTOC_BLOCK(t_sort,"GPU sort")
{
thrust::sort(d_vec.begin(), d_vec.end());
cudaDeviceSynchronize(); ///< otherwise time is 0!!
}
TICTOC_BLOCK(t_back,"d2h transfer")
{
thrust::copy(d_vec.begin(), d_vec.end(), h_vec.begin());
}
return 0;
}
================================================
FILE: apps/htrack_atb/AntTweakBarEventFilter.h
================================================
#pragma once
#include
#include
#ifdef WITH_ANTTWEAKBAR
#include "AntTweakBar.h"
#endif
/// QGLWidget support for AntTweakBar (event forwarding)
class AntTweakBarEventFilter : public QObject{
private:
QGLWidget* parent;
public:
AntTweakBarEventFilter(QGLWidget* parent) : QObject(parent){
this->parent = parent;
// all move events detected, not just when clicked
parent->setMouseTracking(true);
}
/// Forward events to AntTweakBar
bool eventFilter(QObject* obj, QEvent* event){
#ifdef WITH_ANTTWEAKBAR
bool event_on_atb = false;
if (obj == parent) {
QMouseEvent* me = dynamic_cast(event);
QKeyEvent* ke = static_cast(event);
TwMouseButtonID mouse_button;
if(me!=NULL){
if(me->button()==Qt::LeftButton) mouse_button = TW_MOUSE_LEFT;
if(me->button()==Qt::RightButton) mouse_button = TW_MOUSE_RIGHT;
if(me->button()==Qt::MiddleButton) mouse_button = TW_MOUSE_MIDDLE;
}
switch(event->type()){
case QEvent::Resize:
event_on_atb = TwWindowSize(parent->width()*2, parent->height()*2);
// qDebug() << "Resize" F<< status;
break;
case QEvent::KeyRelease:
event_on_atb = TwKeyPressed(ke->key(), TW_KMOD_NONE);
// qDebug() << "Key" << status;
break;
case QEvent::MouseMove:
event_on_atb = TwMouseMotion(me->pos().x(), me->pos().y());
// qDebug() << "Move" << status << e->pos();
break;
case QEvent::MouseButtonPress:
event_on_atb = TwMouseButton(TW_MOUSE_PRESSED, mouse_button);
// qDebug() << "Press" << status;
break;
case QEvent::MouseButtonRelease:
event_on_atb = TwMouseButton(TW_MOUSE_RELEASED, mouse_button);
// qDebug() << "Release" << status;
return true;
default:
break;
}
if(event_on_atb == true){
parent->update();
return true;
}
else
return false; // Super::eventFilter(obj, event);
} else {
// pass the event on to the parent class
return false; // Super::eventFilter(obj, event);
}
#else
return false;
#endif
}
};
================================================
FILE: apps/htrack_atb/CMakeLists.txt
================================================
INCLUDE_DIRECTORIES(../../) #< #include "tracker/..."
file(GLOB_RECURSE SRC "*.cpp")
file(GLOB_RECURSE HDR "*.h")
add_executable(htrack_atb ${HDR} ${SRC})
target_link_libraries(htrack_atb htracksdk)
================================================
FILE: apps/htrack_atb/main.cpp
================================================
#include
#include
#include
#include
#include "util/gl_wrapper.h"
#include "util/OpenGL32Format.h"
#include
#include "AntTweakBarEventFilter.h"
#include "tracker/ForwardDeclarations.h"
#include "tracker/HandFinder/HandFinder.h"
#include "tracker/Sensor/Sensor.h"
#include "tracker/Data/Camera.h"
#include "tracker/Calibration/Calibration.h"
#include "tracker/OpenGL/KinectDataRenderer/KinectDataRenderer.h"
#include "tracker/OpenGL/CylindersRenderer/Cylinders_renderer.h"
#include "tracker/Tracker.h"
class GLWidget : public QGLWidget{
public:
Worker*const worker;
DataStream*const datastream;
SolutionStream*const solutions;
Camera*const _camera;
KinectDataRenderer kinect_renderer;
Cylinders_renderer mrenderer;
public:
GLWidget(Worker* worker, DataStream * datastream, SolutionStream * solution):
QGLWidget(OpenGL32Format()),
worker(worker),
datastream(datastream),
solutions(solutions),
_camera(worker->camera),
mrenderer(worker->cylinders)
{
std::cout << "Started OpenGL " << this->format().majorVersion() << "." << this->format().minorVersion() << std::endl;
this->installEventFilter( new AntTweakBarEventFilter(this) ); ///< all actions pass through filter
}
~GLWidget(){
worker->cleanup_graphic_resources();
tw_settings->tw_cleanup();
}
void initializeGL(){
std::cout << "GLWidget::initializeGL()" << std::endl;
initialize_glew();
tw_settings->tw_init(this->width(), this->height()); ///< FIRST!!
glEnable(GL_DEPTH_TEST);
kinect_renderer.init(_camera);
mrenderer.init(Cylinders_renderer::NORMAL);
mrenderer.init_geometry(); // thick model
///--- Initialize other graphic resources
this->makeCurrent();
worker->init_graphic_resources();
///--- Setup with data from worker
kinect_renderer.setup(worker->sensor_color_texture->texid(), worker->sensor_depth_texture->texid());
}
void paintGL() {
glViewport(0,0,this->width(),this->height());
glClearColor(1,1,1,1);
glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT);
///--- Rendering
Eigen::Matrix4f view_projection = _camera->view_projection_matrix();
Eigen::Matrix4f view = _camera->view_matrix();
if(worker->handfinder->wristband_found())
{
kinect_renderer.enable_colormap(true);
kinect_renderer.set_zNear(worker->handfinder->wristband_center()[2] - 150);
kinect_renderer.set_zFar(worker->handfinder->wristband_center()[2] + 150);
}
kinect_renderer.set_uniform("view_projection",view_projection);
kinect_renderer.render();
mrenderer.set_uniform("view",view);
mrenderer.set_uniform("view_projection",view_projection);
mrenderer.render();
tw_settings->tw_draw();
}
void reload_model(){
/// This recomputes segments lengths
worker->cylinders->recomputeLengths();
/// This accepts the new joint translations
worker->skeleton->setInitialTranslations();
/// This generates VBO from segments
mrenderer.init_geometry();
/// After change, show what's happened
this->updateGL();
}
private:
void keyPressEvent(QKeyEvent *event){
GLWidget* qglviewer = this;
switch(event->key()){
case Qt::Key_Escape:
this->close();
break;
case Qt::Key_1:
// make_hand_thinner();
worker->skeleton->scaleWidth(-5);
Calibration::update_radius_helper(worker->cylinders, worker->skeleton);
qglviewer->reload_model();
break;
case Qt::Key_2:
// make_hand_wider();
worker->skeleton->scaleWidth(5);
Calibration::update_radius_helper(worker->cylinders, worker->skeleton);
qglviewer->reload_model();
break;
case Qt::Key_3:
// make_hand_shorter();
worker->skeleton->scaleHeight(-1);
Calibration::update_radius_helper(worker->cylinders, worker->skeleton);
qglviewer->reload_model();
break;
case Qt::Key_4:
// make_hand_longer();
worker->skeleton->scaleHeight(1);
Calibration::update_radius_helper(worker->cylinders, worker->skeleton);
qglviewer->reload_model();
break;
case Qt::Key_5:
// make_hand_smaller();
worker->skeleton->scale(0.99f);
qglviewer->reload_model();
break;
case Qt::Key_6:
// make_hand_bigger();
worker->skeleton->scale(1.01f);
qglviewer->reload_model();
break;
default:
QGLWidget::keyPressEvent(event);
}
}
};
int main(int argc, char* argv[]){
Q_INIT_RESOURCE(shaders); ///< http://qt-project.org/wiki/QtResources
QApplication app(argc, argv);
std::cout << "htrack starting" << std::endl;
std::cout << "--Execution path: " << QDir::currentPath().toStdString() << std::endl;
#if defined(SOFTKIN) && !defined(__APPLE__)
Camera camera(Intel, 60 /*FPS*/);
SensorSoftKin sensor(&camera);
#endif
#if defined(DEPTHSENSEGRABBER) && !defined(__APPLE__)
Camera camera(Intel, 60 /*FPS*/);
SensorDepthSenseGrabber sensor(&camera);
#endif
#if defined(OPENNI)
Camera camera(QVGA, 60 /*FPS*/);
// Camera camera(QVGA, 30 /*FPS*/);
SensorOpenNI sensor(&camera);
#endif
#if defined(REALSENSE)
Camera camera(QVGA, 60 /*FPS*/);
SensorRealSense sensor(&camera);
#endif
#if defined(LIBREALSENSE)
Camera camera(Intel, 60 /*FPS*/);
SensorLibRealSense sensor(&camera);
#endif
DataStream datastream(&camera);
SolutionStream solutions;
Worker worker(&camera);
GLWidget glarea(&worker, &datastream, &solutions);
glarea.resize(640*2,480*2); ///< force resize
worker.bind_glarea(&glarea); ///< TODO: can we avoid this?
///--- Load calibration
Calibration(&worker).autoload();
// glarea->reload_model(); ///< TODO
glarea.show(); ///< calls GLWidget::InitializeGL
Tracker tracker(&worker,camera.FPS());
tracker.sensor = &sensor;
tracker.datastream = &datastream;
tracker.solutions = &solutions;
///--- Starts the tracking
tracker.toggle_tracking(true);
return app.exec();
}
================================================
FILE: apps/htrack_qt/CMakeLists.txt
================================================
#--- This project needs this extra library
include(../../cmake/ConfigureQGLViewer.cmake)
INCLUDE_DIRECTORIES(../../) #< #include "tracker/..."
qt5_wrap_cpp(MOCS_HDRS Main_window.h OpenGL_viewer.h)
file(GLOB_RECURSE SRC "*.cpp")
file(GLOB_RECURSE HDR "*.h")
add_executable(htrack_qt ${HDR} ${SRC} ${MOCS_HDRS})
target_link_libraries(htrack_qt htracksdk ${LIBRARIES})
================================================
FILE: apps/htrack_qt/Main_window.cpp
================================================
#include "Main_window.h"
#include
#include
#include "OpenGL_viewer.h"
#include "tracker/OpenGL/DebugRenderer/DebugRenderer.h"
#include "cudax/Timer.h"
#include "util/opencv_wrapper.h"
#include "util/mylogger.h"
#include "tracker/Worker.h"
#include "tracker/Tracker.h"
#include "tracker/Data/SolutionStream.h"
#include "tracker/Data/DataStream.h"
#include "tracker/Calibration/Calibration.h"
#include "tracker/HandFinder/HandFinder.h"
#include "tracker/DataStructure/SkeletonSerializer.h"
Main_window::Main_window(Worker* worker, DataStream* stream, SolutionStream* solutions, OpenGL_viewer* qglviewer):
worker(worker), datastream(stream), solutions(solutions), qglviewer(qglviewer){
/// Delete class when window closes
this->setAttribute(Qt::WA_DeleteOnClose);
QWidget* widget = new QWidget(this);
QVBoxLayout* v_layout = new QVBoxLayout;
//v_layout->setAlignment(Qt::AlignCenter);
widget->setLayout(v_layout);
this->setCentralWidget(widget);
/// Part 2: opengl
{
// qglviewer->setFixedSize(870, 870);
v_layout->addWidget(qglviewer);
// qglviewer->show();
}
/// Part 3: scrollbar
{
QHBoxLayout* h_layout = new QHBoxLayout;
slider = new QSlider(Qt::Horizontal);
slider->setMaximumHeight(24);
slider_label = new QLabel("0/0");
slider_label->setMaximumHeight(24);
toggle_live_ = new QPushButton("LIVE");
toggle_live_->setMaximumHeight(24);
toggle_live_->setCheckable(true);
toggle_live_->setChecked(false);
h_layout->addWidget(toggle_live_);
toggle_record_ = new QPushButton("REC");
toggle_record_->setMaximumHeight(24);
toggle_record_->setCheckable(true);
toggle_record_->setChecked(false);
h_layout->addWidget(toggle_record_);
h_layout->addWidget(slider);
h_layout->addWidget(slider_label);
v_layout->addLayout(h_layout);
}
///--- Events
connect(slider, SIGNAL(sliderMoved(int)), this, SLOT(display_frame(int)));
/// Menu
{
//--- File menu
QMenu* file = menuBar()->addMenu("File");
{
QAction* save = file->addAction( "Save" );
save->setShortcut( QKeySequence(Qt::CTRL + Qt::Key_S) );
connect(save, SIGNAL(triggered()), this, SLOT(save_slot()));
}
{
QAction* load = file->addAction( "Open" );
load->setShortcut( QKeySequence(Qt::CTRL + Qt::Key_O) );
connect(load, SIGNAL(triggered()), this, SLOT(load_slot()));
}
{
connect(file->addAction("Save frame"), SIGNAL(triggered()), this, SLOT(save_frame_slot()));
}
file->addSeparator();
{
QAction* action = file->addAction( "Save tracking" );
connect(action, SIGNAL(triggered()), this, SLOT(save_tracking_pressed()));
}
{
QAction* action = file->addAction( "Load tracking" );
connect(action, SIGNAL(triggered()), this, SLOT(load_tracking_pressed()));
}
file->addSeparator();
{
QAction* action = file->addAction( "Save results" );
connect(action, SIGNAL(triggered()), this, SLOT(save_results_pressed()));
}
{
QAction* action = file->addAction( "Save results (one frame)" );
connect(action, SIGNAL(triggered()), this, SLOT(save_results_single_pressed()));
}
{
QAction* action = file->addAction( "Save joint positions (seq.)" );
connect(action, SIGNAL(triggered()), this, SLOT(save_joint_position_list()));
}
//--- Track menu
QMenu* track = menuBar()->addMenu("Track");
{
// worker->initialize_offset(frame);
QAction* action = track->addAction( "Offset initialization" );
action->setShortcut( Qt::Key_I );
connect(action, SIGNAL(triggered()), this, SLOT(menu_initialize_offset()));
}
{
QAction* action = track->addAction("Re-Init from previous frame");
action->setShortcut( Qt::Key_F2 );
connect(action, SIGNAL(triggered()), this, SLOT(reinit_from_previous_frame()));
}
{
QAction* action = track->addAction( "Optimize current (1x)" );
#ifdef __unix__
action->setShortcut( Qt::Key_T );
#else
action->setShortcut( Qt::Key_F1 );
#endif
connect(action, SIGNAL(triggered()), this, SLOT(menu_track_pressed()));
}
{
QAction* action = track->addAction( "Optimize current (convergence)" );
// action->setShortcut( Qt::Key_F2 );
connect(action, SIGNAL(triggered()), this, SLOT(menu_track_till_convergence_pressed()));
}
{
A_track_whole = track->addAction( "Re-Optimize whole sequence" );
A_track_whole->setShortcut( Qt::Key_F3 );
A_track_whole->setCheckable(true);
connect(A_track_whole, SIGNAL(toggled(bool)), this, SLOT(track_whole_sequence(bool)));
}
{
QAction* action = track->addAction( "Set Valid (to scrub solution)" );
connect(action, SIGNAL(triggered()), this, SLOT(menu_set_valid()));
}
{
QAction* action = track->addAction( "Set current solution" );
// action->setShortcut( Qt::Key_S );
connect(action, SIGNAL(triggered()), this, SLOT(menu_set_current_solution()));
}
{
A_replay = track->addAction( "Replay sequence" );
A_replay->setShortcut( Qt::Key_Space );
A_replay->setCheckable(true);
connect(A_replay, SIGNAL(toggled(bool)), this, SLOT(replay_sequence(bool)));
}
{
QAction* action = track->addAction( "Next frame" );
action->setShortcut( Qt::Key_Right );
connect(action, SIGNAL(triggered()), this, SLOT(display_next_frame()));
}
{
QAction* action = track->addAction( "Prevous frame" );
action->setShortcut( Qt::Key_Left );
connect(action, SIGNAL(triggered()), this, SLOT(display_previous_frame()));
}
QMenu* extra = menuBar()->addMenu("Extra");
{
connect(extra->addAction("Save Calibration"), SIGNAL(triggered()), this, SLOT(save_calibration_slot()));
connect(extra->addAction("Load Calibration"), SIGNAL(triggered()), this, SLOT(load_calibration_slot()));
extra->addSeparator();
connect(extra->addAction("Reload Model"), SIGNAL(triggered()), qglviewer, SLOT(reload_model()));
}
}
/// I have data on load
if (stream->size()>1) {
qDebug() << "#available frames" << stream->num_frames()-1;
slider->setRange(0,stream->num_frames()-1);
display_frame(0);
}
}
void Main_window::requested_track(int fid)
{
// LOG(INFO) << "Main_window::requested_track";
//solutions->invalidate(fid); ///< we are building it
DataFrame& frame = datastream->get_frame(fid);
worker->track(frame,false,false);
solutions->set(fid, worker->skeleton->getCurrentParameters());
qglviewer->updateGL();
}
void Main_window::reinit_from_previous_frame(){
int fid = slider->value();
if(fid==0) return;
worker->skeleton->set( solutions->get(fid-1) );
}
void Main_window::requested_track_till_convergence(int fid){
// solutions->invalidate(fid); ///< we are building it
DataFrame& frame = datastream->get_frame(fid);
worker->track_till_convergence(frame);
solutions->set(fid, worker->skeleton->getCurrentParameters());
qglviewer->updateGL();
}
void Main_window::track_whole_sequence(bool checked){
///--- Don't restart if disabling
if(checked==false) return;
int start_at = slider->value();
// LOG(INFO) << "!!!Warning only doing first 10";
solutions->invalidate(start_at); ///< we are building it
solutions->resize(datastream->size());
for (int fid = start_at; fid < datastream->num_frames(); fid++){
DataFrame& frame = datastream->get_frame(fid);
display_frame(fid);
///--- Track
worker->track_till_convergence(frame);
///--- Save
solutions->set(fid, worker->skeleton->getCurrentParameters());
qglviewer->updateGL();
QApplication::processEvents();
///--- Allow user to interrupt
if(A_track_whole->isChecked()==false)
break;
}
///--- If we did all this work, we might as well just save it...
solutions->save("tracks/last_track_whole_sequence.track");
solutions->setValid(); ///< we are done building
A_track_whole->setChecked(false);
}
void Main_window::set_current_solution(int fid){
solutions->set(fid, worker->skeleton->getCurrentParameters());
qglviewer->updateGL();
}
void Main_window::replay_sequence(bool checked){
if(checked==false) return;
float interval = 1000.0f / worker->camera->FPS();
cudax::Timer t;
for (int fid = 0; fid < datastream->num_frames(); fid++){
t.restart("");
DataFrame& frame = datastream->get_frame(fid);
display_frame(fid);
QApplication::processEvents();
///--- Allow user to interrupt
if(A_replay->isChecked()==false)
break;
// limit replay fps
float dt = t.elapsed();
float ms = interval- dt - 8.0f; // which 8ms?!
if(ms>0) QThread::usleep(ms*1000);
}
}
void Main_window::display_next_frame(){
int fid = slider->value();
display_frame(++fid);
}
void Main_window::display_previous_frame(){
int fid = slider->value();
display_frame(--fid);
}
void Main_window::display_latest_frame(){
int fid = datastream->size()-1;
display_frame(fid);
}
void Main_window::crop(int from, int to)
{
datastream->crop(from, to);
this->display_latest_frame();
}
void Main_window::save_tracking_pressed()
{
QString filename = QFileDialog::getSaveFileName(QApplication::activeWindow(), tr("Save tracking as..."), QDir::currentPath()+"/tracks");
solutions->save(filename);
}
void Main_window::load_tracking_pressed()
{
QString filename = QFileDialog::getOpenFileName(QApplication::activeWindow(), tr("Load tracking"), QDir::currentPath()+"/tracks");
solutions->load(filename);
}
void Main_window::save_results_pressed()
{
///--- Pick a folder
QDir().mkdir("results"); ///< just returns false if exists
QString fname = QFileDialog::getExistingDirectory(QApplication::activeWindow(),
"Save Image Sequence in folder...",
QDir::currentPath()+"/results"
/*, QFileDialog::ShowDirsOnly*/);
if(fname.isNull())
return;
///--- Save images
qglviewer->transparent_background = true;
for (int fid = 0; fid < datastream->num_frames(); fid++){
worker->skeleton->set( solutions->get(fid) );
display_frame(fid);
qglviewer->updateGL();
QApplication::processEvents();
glFinish();
///--- Time to save
QString filename = fname + QString("/%1.png").arg(fid, /*pad to 10k*/ 6, /*base*/ 10, /*fillchar*/ QLatin1Char('0'));
#define SAVE_RESULTS_EXPORT
#ifdef SAVE_RESULTS_EXPORT
QImage img = qglviewer->grabFrameBuffer(/*withAlpha=*/false);
#else
QImage img = glarea->grabFrameBuffer(/*withAlpha=*/true);
#endif
img.save(filename);
}
qglviewer->transparent_background = false;
}
void Main_window::save_results_single_pressed()
{
QString fname = QFileDialog::getSaveFileName(QApplication::activeWindow(),
"Save Image in file...",
QDir::currentPath()+"/results");
if(fname.isEmpty()) return;
qglviewer->transparent_background = true;
{
int fid = slider->value();
worker->skeleton->set( solutions->get(fid) );
display_frame(fid);
qglviewer->updateGL();
QApplication::processEvents();
glFinish();
///--- Time to save
#define SAVE_RESULTS_SINGLE_EXPORT
#ifdef SAVE_RESULTS_SINGLE_EXPORT
QImage img = qglviewer->grabFrameBuffer(/*withAlpha=*/false);
#else
QImage img = qglviewer->grabFrameBuffer(/*withAlpha=*/true);
#endif
img.save(fname);
}
qglviewer->transparent_background = false;
}
void Main_window::menu_initialize_offset()
{
worker->handfinder->binary_classification(worker->current_frame);
worker->trivial_detector->exec(worker->current_frame, worker->handfinder->sensor_silhouette);
qglviewer->updateGL();
}
void Main_window::menu_set_valid()
{
//allows sequence to be scrubbed
solutions->setValid();
}
void Main_window::display_frame(int frame_id){
if((frame_id<0) || !(frame_idsize())){
mWarning("frame_id out of range: 0<=%d<%d\n",frame_id, datastream->size());
fflush(stdout);
return;
}
DataFrame& frame = datastream->get_frame(frame_id);
update_slider(frame_id);
update_sliderlabel(frame_id);
if(solutions->isValid(frame_id)){
std::vector theta = solutions->get(frame_id);
if(theta.size()>0)
worker->skeleton->set(theta);
}
///--- If it's already done nothing happens anyway...
worker->handfinder->binary_classification(frame);
///--- Update the current dataframe in the worker
worker->current_frame = frame;
///--- Upload the new texture data (if necessary)
worker->sensor_color_texture->load(frame.color.data, frame.id );
worker->sensor_depth_texture->load(frame.depth.data, frame.id );
qglviewer->updateGL();
}
void Main_window::save_slot(){
QString filename = QFileDialog::getSaveFileName(QApplication::activeWindow(), tr("Save as..."), QDir::currentPath()+"/recs");
datastream->save(filename);
}
void Main_window::load_slot(){
QString filename = QFileDialog::getOpenFileName(QApplication::activeWindow(), tr("Load..."), QDir::currentPath()+"/recs");
datastream->load(filename);
///--- Load default calibration
Calibration(worker).autoload();
qglviewer->reload_model();
///--- Load the first frame
if(datastream->size()>0)
display_frame(0);
}
void Main_window::save_frame_slot(){
int fid = slider->value();
DataFrame& frame = datastream->get_frame(fid);
QString filename = QFileDialog::getSaveFileName(this, tr("Save as..."), QDir::currentPath());
if( !filename.isNull() ){
cv::Mat color_bgr;
cv::cvtColor(frame.color, color_bgr, CV_RGB2BGR);
bool s1 = cv::imwrite((filename+"_color.png").toStdString().c_str(), color_bgr);
bool s2 = cv::imwrite((filename+"_depth.png").toStdString().c_str(), frame.depth);
if(!s1 || !s2) LOG(INFO) << "somethign went wrong";
LOG(INFO) << "frame# fid saved to files " << filename.toStdString() << "_{color,depth}.png";
/// TEST (yes, opencv stores BGR instead of RGB)
// QImage im1((uchar*) frame.color.data, stream->width(), stream->height(), QImage::Format_RGB888);
// im1.save(filename+"_color2.png");
}
}
void Main_window::save_calibration_slot(){
QString filename = QFileDialog::getSaveFileName(QApplication::activeWindow(), tr("Save calibration as..."), QDir::currentPath()+"/calib");
Calibration(worker).save(filename.toStdString());
}
void Main_window::load_calibration_slot(){
QString filename = QFileDialog::getOpenFileName(QApplication::activeWindow(), tr("Load calibration..."), QDir::currentPath()+"/calib");
Calibration(worker).load(filename.toStdString());
qglviewer->reload_model();
qglviewer->updateGL();
}
void Main_window::update_slider(int frame){
slider->setRange(0,datastream->size());
slider->setValue(frame);
}
void Main_window::update_sliderlabel(int frame_id){
QString one_frame_idx = QString::number(frame_id);
QString frames_size = QString::number(datastream->size()-1);
slider_label->setText(one_frame_idx+"/"+frames_size);
}
//== hand calibration =============================================//
void Main_window::keyPressEvent(QKeyEvent *event){
/// @todo this is __DUPLICATE CODE__ (TW application needs to do the same)
switch(event->key()){
case Qt::Key_Escape:
this->close();
break;
case Qt::Key_1:
// make_hand_thinner();
worker->skeleton->scaleWidth(-5);
Calibration::update_radius_helper(worker->cylinders, worker->skeleton);
qglviewer->reload_model();
break;
case Qt::Key_2:
// make_hand_wider();
worker->skeleton->scaleWidth(5);
Calibration::update_radius_helper(worker->cylinders, worker->skeleton);
qglviewer->reload_model();
break;
case Qt::Key_3:
// make_hand_shorter();
worker->skeleton->scaleHeight(-1);
Calibration::update_radius_helper(worker->cylinders, worker->skeleton);
qglviewer->reload_model();
break;
case Qt::Key_4:
// make_hand_longer();
worker->skeleton->scaleHeight(1);
Calibration::update_radius_helper(worker->cylinders, worker->skeleton);
qglviewer->reload_model();
break;
case Qt::Key_5:
// make_hand_smaller();
worker->skeleton->scale(0.99f);
qglviewer->reload_model();
break;
case Qt::Key_6:
// make_hand_bigger();
worker->skeleton->scale(1.01f);
qglviewer->reload_model();
break;
default:
QMainWindow::keyPressEvent(event);
}
}
//=================================================================//
//--------------------------------------------------------------------------------------------------
//--------------------------------------------------------------------------------------------------
//--------------------------- EXPERIMENTS -------------------------------------
//--------------------------------------------------------------------------------------------------
//--------------------------------------------------------------------------------------------------
void Main_window::save_joint_position_list(){
std::ofstream out("joint_positions.txt");
for (int fid = 0; fid < datastream->num_frames(); fid++){
///--- apply parameters
worker->skeleton->set( solutions->get(fid) );
///--- save joint positions to file
for(int i=0; iskeleton->getNumberOfJoints(); i++){
Joint * joint = worker->skeleton->getJoint(i);
cout << joint->getName() << std::endl;
Vector3 s = joint->getGlobalTranslation();
out << s.transpose() << " ";
}
out << std::endl;
}
out.close();
}
================================================
FILE: apps/htrack_qt/Main_window.h
================================================
#pragma once
#include
#include
#include
#include
#include
#include
#include
#include
#include
#include "tracker/ForwardDeclarations.h"
class OpenGL_viewer;
class Main_window : public QMainWindow{
Q_OBJECT
private:
Worker*const worker;
OpenGL_viewer*const qglviewer;
DataStream*const datastream;
SolutionStream*const solutions;
QSlider* slider;
QLabel* slider_label;
public:
QPushButton* toggle_record_;
QPushButton* toggle_live_;
public:
~Main_window(){ /*LOG(INFO) << __FUNCTION__;*/ }
Main_window(Worker *worker, DataStream* datastream, SolutionStream* solutions, OpenGL_viewer* qglviewer);
public slots:
void reinit_from_previous_frame();
void requested_track(int);
void requested_track_till_convergence(int);
void track_whole_sequence(bool checked);
void set_current_solution(int);
void replay_sequence(bool checked);
public slots:
void display_frame(int frame_id);
void display_latest_frame();
void display_next_frame();
void display_previous_frame();
void crop(int from, int to);
void save_tracking_pressed();
void load_tracking_pressed();
void save_results_pressed();
void save_results_single_pressed();
/// @{ actions
private:
QAction* A_track_whole = NULL;
QAction* A_replay = NULL;
/// @}
/// @{
private slots:
void menu_track_pressed(){ emit requested_track(slider->value());}
void menu_track_till_convergence_pressed(){ emit requested_track_till_convergence(slider->value()); }
void menu_initialize_offset();
void menu_set_current_solution(){ emit set_current_solution(slider->value()); };
void menu_set_valid();
/// @}
private slots:
void save_slot();
void load_slot();
void save_frame_slot();
void save_calibration_slot();
void load_calibration_slot();
void save_joint_position_list();
private:
void update_gui(int frame_id);
void update_slider(int frame);
void update_sliderlabel(int frame_id);
private:
void keyPressEvent(QKeyEvent *event);
};
================================================
FILE: apps/htrack_qt/OpenGL_viewer.cpp
================================================
#include "OpenGL_viewer.h"
///--- External
#include
#include
#ifdef WITH_QGLVIEWER
#include
#include
#include
#endif
#include "util/OpenGL32Format.h"
#include "util/eigen_opengl_helpers.h"
///--- Internal
#include "tracker/OpenGL/QuadRenderer/QuadRenderer.h"
#include "tracker/OpenGL/CylindersRenderer/Cylinders_renderer.h"
#include "tracker/OpenGL/KinectDataRenderer/KinectDataRenderer.h"
#include "tracker/OpenGL/DebugRenderer/DebugRenderer.h"
#include "tracker/Data/TextureColor8UC3.h"
#include "tracker/Data/TextureDepth16UC1.h"
#include "tracker/Data/Camera.h"
#include "tracker/Worker.h"
#include "util/mylogger.h"
/// IMREAD TEST
#include "opencv2/highgui/highgui.hpp"
#include "tracker/HandFinder/HandFinder.h"
#include "tracker/DataStructure/SkeletonSerializer.h"
// #define RESULTS
OpenGL_viewer::OpenGL_viewer(Worker *_worker) : OpenGL_viewer_Superclass(OpenGL32Format(), NULL), worker(_worker), _camera(_worker->camera){
CHECK_NOTNULL(worker);
CHECK_NOTNULL(worker->cylinders);
CHECK_NOTNULL(worker->skeleton);
CHECK_NOTNULL(worker->camera);
color_ch = std::make_shared(QuadRenderer::Color, _camera);
depth_ch = std::make_shared(QuadRenderer::Depth, _camera);
mrenderer = std::make_shared(worker->cylinders);
srenderer = std::make_shared(worker->cylinders);
kinect_renderer = std::make_shared();
#ifdef BROKEN_CONSTANT_ASPECT_RATIO
/// @see http://stackoverflow.com/questions/16801237/how-to-maintain-specific-height-to-width-ratio-of-widget-in-qt5
/// @see http://doc.qt.digia.com/qq/qq04-height-for-width.html
QSizePolicy policy(QSizePolicy::Preferred, QSizePolicy::Preferred);
policy.setHeightForWidth(true);
setSizePolicy(policy);
#else
setSizePolicy(QSizePolicy::MinimumExpanding, QSizePolicy::MinimumExpanding);
#endif
///--- Create the contextual menu
contextual = new QMenu(this);
auto add_entry = [=](const char* name, bool _default) {
QAction* action = contextual->addAction(name);
action->setCheckable(true);
action->setChecked(_default);
return action;
};
draw_model = add_entry("draw_model", true);
draw_cloud = add_entry("draw_cloud", true);
draw_skeleton = add_entry("draw_skeleton", false);
contextual->addSeparator();
draw_sensor_color = add_entry("draw_sensor_color", true);
draw_sensor_depth = add_entry("draw_sensor_depth", true);
contextual->addSeparator();
disable_depth_test = add_entry("disable_depth_test", false);
use_kinect_camera = add_entry("use_kinect_camera", false);
draw_color_fullscreen = add_entry("draw_color_fullscreen", false);
draw_depth_fullscreen = add_entry("draw_depth_fullscreen", false);
contextual->addSeparator();
draw_debug = add_entry("draw_debug", true);
clear_debug = contextual->addAction("clear_debug");
wristband_colormap = add_entry("wristband_colormap", true);
#ifdef RESULTS
disable_depth_test->setChecked(true);
draw_model->setChecked(false);
draw_skeleton->setChecked(true);
draw_sensor_color->setChecked(false);
draw_sensor_depth->setChecked(false);
use_kinect_camera->setChecked(true);
#endif
///--- Connect single shot events
connect(clear_debug, &QAction::triggered, &(DebugRenderer::instance()), &DebugRenderer::clear);
}
OpenGL_viewer::~OpenGL_viewer(){
worker->cleanup_graphic_resources();
}
void OpenGL_viewer::contextMenuEvent(QContextMenuEvent* event)
{
#ifdef __unix__
// MS: my OS already uses alt+click, but not ctrl+click
if(event->modifiers().testFlag(Qt::ControlModifier))
#else
if(event->modifiers().testFlag(Qt::AltModifier))
#endif
{
contextual->exec(event->globalPos());
updateGL();
}
}
/// @warning QGLViewer pollutes OpenGL status. Resetting it here
void OpenGL_viewer::initializeGL(){
LOG(INFO) << "OpenGL_viewer::initializeGL() OpenGL" << this->format().majorVersion() << "." << this->format().minorVersion();
glClearColor(1.0, 1.0, 1.0, 0.0);
glEnable(GL_DEPTH_TEST);
#ifdef WITH_QGLVIEWER
camera()->frame()->setSpinningSensitivity(100); ///<<< Disable spin
/// Setup default camera
reset_camera();
/// Bindings @see QGLViewer::setDefaultMouseBindings()
/// Extra behavior in this->mouseDoubleClickEvent()
{
/// Disable double click to align scene
setMouseBinding(Qt::NoModifier, Qt::LeftButton, NO_CLICK_ACTION, true); /// ALIGN_CAMERA
setMouseBinding(Qt::ShiftModifier, Qt::RightButton, NO_CLICK_ACTION); /// RAP_FROM_PIXEL
setMouseBinding(Qt::NoModifier, Qt::MiddleButton, NO_CLICK_ACTION, true); /// ZOOM_TO_FIT
}
#endif
#ifdef WITH_GLEW
initialize_glew();
#endif
///--- Compile/initialize shaders
mrenderer->init(Cylinders_renderer::NORMAL);
srenderer->init(Cylinders_renderer::SKINNY);
color_ch->init();
depth_ch->init();
kinect_renderer->init(_camera);
CHECK_ERROR_GL();
///--- Initialize other graphic resources
this->makeCurrent();
worker->init_graphic_resources();
///--- Setup with data from worker
color_ch->setup(worker->sensor_color_texture->texid());
depth_ch->setup(worker->sensor_depth_texture->texid());
kinect_renderer->setup(worker->sensor_color_texture->texid(), worker->sensor_depth_texture->texid());
}
void OpenGL_viewer::mouseDoubleClickEvent(QMouseEvent* e) {
#ifdef WITH_QGLVIEWER
/// MeshLAB like double click action
{
/// Modified version of "RAP_FROM_PIXEL"
if (!camera()->setPivotPointFromPixel(e->pos()))
return; // do nothing
camera()->setSceneCenter( camera()->pivotPoint() );
/// Stolen from "centerScene"
camera()->frame()->projectOnLine(sceneCenter(), camera()->viewDirection());
setVisualHintsMask(1);
update();
}
#endif
}
void OpenGL_viewer::reset_camera() {
#ifdef WITH_QGLVIEWER
/// Default OpenGL camera (right-hand coordinate system)
camera()->setType(qglviewer::Camera::ORTHOGRAPHIC);
//camera()->setType(qglviewer::Camera::PERSPECTIVE);
camera()->setPosition(qglviewer::Vec(0,0,0));
camera()->lookAt(qglviewer::Vec(0,0,1));
camera()->setUpVector(qglviewer::Vec(0,1,0));
/// Setup camera zNear/zFar
camera()->setSceneCenter(qglviewer::Vec(0,0,300/*mm*/));
camera()->setSceneRadius(200 /*mm*/);
camera()->showEntireScene();
#endif
}
void OpenGL_viewer::reload_model(){
/// This recomputes segments lengths
worker->cylinders->recomputeLengths();
/// This resets the "local" transformations
//worker->skeleton->resetPosture(true);
/// This accepts the new joint translations
worker->skeleton->setInitialTranslations();
/// This generates VBO from segments
mrenderer->init_geometry(); // thick model
srenderer->init_geometry(); // skinny model
/// After change, show what's happened
this->updateGL();
}
int OpenGL_viewer::width() {
qreal r = window()->windowHandle()->devicePixelRatio();
return QGLWidget::width()*r;
}
int OpenGL_viewer::height() {
qreal r = window()->windowHandle()->devicePixelRatio();
return QGLWidget::height()*r;
}
void OpenGL_viewer::paintGL() {
/// Mostly for results generation
glEnable(GL_MULTISAMPLE);
glEnable(GL_DEPTH_TEST);
glViewport(0,0,this->width(),this->height());
if(transparent_background)
glClearColor(1,1,1,0); ///< transparent background
else
glClearColor(1,1,1,1);
///--- Clear the screen
glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT);
///--- Setup camera (Model View Projection)
bool use_kinect_camera = this->use_kinect_camera->isChecked();
Eigen::Matrix4f view_projection;
Eigen::Matrix4f view;
#ifndef WITH_QGLVIEWER
use_kinect_camera = true;
#endif
if(!use_kinect_camera){
#ifdef WITH_QGLVIEWER
/// This gives me OpenGL2 style matrices (right-hand system)
/// @see reset_camera()
camera()->getModelViewProjectionMatrix(view_projection.data());
camera()->getModelViewMatrix(view.data());
/// !!! set a left-hand coordinate system (remove x-coord flip of lookAt)
view_projection.col(0) = -view_projection.col(0);
view.col(0) = -view.col(0);
#else
exit(EXIT_FAILURE);
#endif
}
else{
view_projection = _camera->view_projection_matrix();
view = _camera->view_matrix();
}
// std::cout << "MVP\n" << MVP << std::endl;
// std::cout << "MVP" << Camera(QVGA).view_projection_matrix() << std::endl;
if (draw_debug->isChecked()){
DebugRenderer::instance().set_uniform("view_projection",view_projection);
DebugRenderer::instance().render();
CHECK_ERROR_GL();
}
if(use_kinect_camera)
{
if ( draw_color_fullscreen->isChecked() )
{
glViewport(0,0,this->width(),this->height());
color_ch->render();
}
else if( draw_depth_fullscreen->isChecked() )
{
glViewport(0,0,this->width(),this->height());
depth_ch->render();
}
}
///--- draw model
if (draw_model->isChecked()){
mrenderer->set_uniform("view",view);
mrenderer->set_uniform("view_projection",view_projection);
mrenderer->render();
CHECK_ERROR_GL();
}
///--- draw skeleton (when it's shown transparency)
if (draw_skeleton->isChecked() && disable_depth_test->isChecked()){
srenderer->set_uniform("view",view);
srenderer->set_uniform("view_projection",view_projection);
srenderer->render();
CHECK_ERROR_GL();
}
///--- draw kinect point cloud in shader
if(draw_cloud->isChecked())
{
if(wristband_colormap->isChecked() && worker->handfinder->wristband_found())
{
kinect_renderer->enable_colormap(true);
kinect_renderer->set_zNear(worker->handfinder->wristband_center()[2] - 150);
kinect_renderer->set_zFar(worker->handfinder->wristband_center()[2] + 150);
}
kinect_renderer->set_uniform("view_projection",view_projection);
kinect_renderer->render();
CHECK_ERROR_GL();
}
///--- draw skeleton (when it's shown on top)
if (draw_skeleton->isChecked() && !disable_depth_test->isChecked()){
glClear(GL_DEPTH_BUFFER_BIT);
srenderer->set_uniform("view",view);
srenderer->set_uniform("view_projection",view_projection);
srenderer->render();
CHECK_ERROR_GL();
}
///--- channels overlay
{
///--- Settings
const int width = this->width()/5;
const float ratio = 240.0/320.0;
int height = width*ratio;
const int pad = 10;
if(draw_sensor_color->isChecked()){
glViewport(pad,this->height()-height-pad,width,height); ///< Top left
color_ch->render();
CHECK_ERROR_GL();
}
if(draw_sensor_depth->isChecked()){
glViewport(this->width()-width-pad,this->height()-height-pad,width,height); ///< Top right
depth_ch->render();
CHECK_ERROR_GL();
}
}
glDisable(GL_MULTISAMPLE);
CHECK_ERROR_GL();
}
================================================
FILE: apps/htrack_qt/OpenGL_viewer.h
================================================
#pragma once
#include "tracker/ForwardDeclarations.h"
#include "util/gl_wrapper.h"
#include
#include
#ifdef WITH_QGLVIEWER
#include
typedef QGLViewer OpenGL_viewer_Superclass;
#else
#include
typedef QGLWidget OpenGL_viewer_Superclass;
#endif
class OpenGL_viewer : public OpenGL_viewer_Superclass {
Q_OBJECT
private:
Worker*const worker;
Camera*const _camera;
std::shared_ptr color_ch;
std::shared_ptr depth_ch;
std::shared_ptr mrenderer;
std::shared_ptr srenderer;
std::shared_ptr kinect_renderer;
/// @{
private:
friend class Main_window;
bool transparent_background = false;
/// @}
/// @{ contextual menu
protected:
void contextMenuEvent(QContextMenuEvent *event);
protected:
QMenu* contextual;
QAction* draw_cloud;
QAction* draw_skeleton;
QAction* draw_debug;
QAction* use_kinect_camera;
QAction* draw_model;
QAction* draw_sensor_color;
QAction* draw_sensor_depth;
QAction* draw_color_fullscreen;
QAction* draw_depth_fullscreen;
QAction* clear_debug;
QAction* disable_depth_test;
QAction* wristband_colormap;
/// @}
public:
/// default window size
// QSize sizeHint() const { return QSize(640, 480); }
QSize sizeHint() const { return QSize(800, 600); }
OpenGL_viewer(Worker*worker);
~OpenGL_viewer();
public slots:
void reset_camera();
/// Reload for when parameters of hand are modified
void reload_model();
public:
void initializeGL(); /// Inits the whole scene (shaders, buffers, etc)
void paintGL(); /// Draws the whole scene
int width();
int height();
protected:
void mouseDoubleClickEvent(QMouseEvent *e);
};
================================================
FILE: apps/htrack_qt/main.cpp
================================================
#include "util/gl_wrapper.h"
#include
#include
#include
#include
#include
#include "OpenGL_viewer.h"
#include "Main_window.h"
#include "util/mylogger.h"
#include "tracker/ForwardDeclarations.h"
#include "tracker/Sensor/Sensor.h"
#include "tracker/Tracker.h"
#include "tracker/Worker.h"
#include "tracker/Data/DataStream.h"
#include "tracker/Data/SolutionStream.h"
#include "tracker/DataStructure/SkeletonSerializer.h"
#include "tracker/Calibration/Calibration.h"
int main(int argc, char* argv[]) {
Q_INIT_RESOURCE(shaders); ///< http://qt-project.org/wiki/QtResources
LOG(INFO) << "htrack starting";
LOG(INFO) << "--Execution path: " << QDir::currentPath();
QString filename_data = (argc >= 2) ? argv[1] : "";
QString filename_soln = (argc >= 3) ? argv[2] : "";
///--- Setup application
QApplication app(argc, argv);
QThread::currentThread()->setObjectName("Main thread");
QThread::currentThread()->setPriority(QThread::HighestPriority);
#if defined(SOFTKIN) && !defined(__APPLE__)
Camera camera(Intel, 60 /*FPS*/);
SensorSoftKin sensor(&camera);
#endif
#if defined(DEPTHSENSEGRABBER) && !defined(__APPLE__)
Camera camera(Intel, 60 /*FPS*/);
SensorDepthSenseGrabber sensor(&camera);
#endif
#if defined(OPENNI)
Camera camera(QVGA, 60 /*FPS*/);
// Camera camera(QVGA, 30 /*FPS*/);
SensorOpenNI sensor(&camera);
#endif
#if defined(REALSENSE)
Camera camera(QVGA, 60 /*FPS*/);
SensorRealSense sensor(&camera);
#endif
#if defined(LIBREALSENSE)
Camera camera(Intel, 60 /*FPS*/);
SensorLibRealSense sensor(&camera);
#endif
DataStream datastream(&camera);
datastream.load(filename_data);
SolutionStream* solutions = new SolutionStream();
Worker worker(&camera);
OpenGL_viewer* glarea = new OpenGL_viewer(&worker);
worker.bind_glarea(glarea);
Main_window* window = new Main_window(&worker, &datastream, solutions, glarea);
window->raise();
window->show();
Tracker tracker(&worker, camera.FPS());
tracker.sensor = &sensor;
tracker.datastream = &datastream;
tracker.solutions = solutions;
///--- UI connections
QObject::connect(window->toggle_record_, &QPushButton::toggled, &tracker, &Tracker::toggle_recording);
QObject::connect(window->toggle_live_, &QPushButton::toggled, &tracker, &Tracker::toggle_tracking);
///--- Attempt to load data
solutions->resize(datastream.size());
int debug_init_with_frame = 0; ///< decide where to start
if (!filename_soln.isEmpty())
solutions->load(filename_soln);
if (datastream.size() > 0) {
window->display_frame(debug_init_with_frame);
}
///--- Load calibration
Calibration(&worker).autoload();
glarea->reload_model();
///--- Flip the hand model if desired
//#define RIGHT_HAND
#ifdef RIGHT_HAND
/// special case for left-handed calibration...
if (!datastream.get_prefix().startsWith("maschroemelax")) {
// flip mapping and model
worker.skeleton->toRightHand2();
}
else {
// flip mapping only and update
worker.skeleton->setMapping(Mapping::rightArm2());
if (datastream.size() > 0) {
window->display_frame(debug_init_with_frame);
}
}
#endif
///--- Start event loop
return app.exec();
}
================================================
FILE: apps/synthgen/synthgen.cpp
================================================
#if __unix__
#define GL_GLEXT_PROTOTYPES 1
#include
#include
#endif
#include
#include
#include "DataStream.h"
#include "Sensor.h"
#include "Skeleton.h"
#include "Cylinders.h"
#include "Cylinders_renderer.h"
#include "PostureFile.h"
#include "CustomFrameBuffer.h"
#include "OpenGL32Format.h"
#include "mylogger.h"
#include "Types.h"
#include
#include
#include
#include
#include
_INITIALIZE_EASYLOGGINGPP
Settings* settings = NULL;
OpenGL_viewer* glarea = NULL;
int record_sequence(int argc, char* argv[]){
setup_logger();
QApplication app(argc, argv);
string input = "/Users/anastasia/Desktop/Data/Tompson/cpp_new/";
QString output = "/Users/anastasia/Developer/htrack-data/recs/tompson_seq_2.dat";
Settings _settings(QDir::currentPath()+"/settings.ini");
settings = &_settings;
DataStream stream(Tompson);
int num_frames = 2440;
for (int i = 0; i < num_frames; ++i) {
char filename_suffix_char_array[9]; sprintf(filename_suffix_char_array, "1_%07d", i + 1);
string filename_suffix(filename_suffix_char_array);
string depth_image_name = input + "depth_" + filename_suffix + ".png";
cv::Mat depth = cv::imread(depth_image_name, CV_LOAD_IMAGE_UNCHANGED);
cout << i << endl;
string color_image_name = input + "rgb_" + filename_suffix + ".png";
cv::Mat color = cv::imread(color_image_name, CV_LOAD_IMAGE_UNCHANGED);
/*cv::namedWindow( "Display window", cv::WINDOW_AUTOSIZE );
cv::imshow( "Display window", color );
cv::waitKey(0);*/
/*for(int row = 194; row < 200; row++){
for(int col = 194; col < 200; col++){
cout << depth.at(row, col) << " ";
}
cout << "; " << endl;
}
cout << endl;*/
if(!depth.data || !color.data ) {
cout << "Could not open or find the images" << std::endl;
return -1;
}
stream.add_frame(color.data, depth.data);
}
QFile::remove(output);
stream.save(output);
printf("%s finished!\n",argv[0]);
fflush(stdout);
return EXIT_SUCCESS;
}
/// @example this is generated programmatically
/// synthgen SIMPLE_WAVE ../htrack-data/recs/synthwave.dat
/// synthgen SIMPLE_MOVE_X ../htrack-data/recs/synthmovex.dat
/// synthgen SIMPLE_MOVE_Y ../htrack-data/recs/synthmovey.dat
/// synthgen SIMPLE_MOVE_Z ../htrack-data/recs/synthmovez_sphere.dat
/// synthgen SIMPLE_INDEX_SWING ../htrack-data/recs/synthmovez_sphere.dat
///
/// @example this reads postures from file and generate a stream
/// synthgen ./synthwave.mat ../htrack-data/recs/synthwave.dat
/// @example this reads every 100th posture from file and generates a stream
/// synthgen ./synthwave.mat ../htrack-data/recs/synthwave.dat 100
int main(int argc, char* argv[]){
return record_sequence(argc, argv);
setup_logger();
if(argc==1){
LOG(INFO) << "examples";
LOG(INFO) << "./synthgen SIMPLE_INDEX_SWING ../htrack-data/recs/synth_index_swing.dat";
LOG(INFO) << "./synthgen SIMPLE_MOVE_Z ../htrack-data/recs/synthmovez.dat";
LOG(INFO) << "./synthgen SIMPLE_COLLISION ../htrack-data/recs/synth_collision.dat";
LOG(INFO) << "./synthgen ../htrack-data/jangles/genMovements/20101220_152738_Trial02.mat ./recs/synth_genmov02.dat 10";
exit(0);
}
printf("%s starting...\n\n", argv[0]);
QApplication app(argc, argv);
///--- parse input
CHECK(argc >= 3) << "wrong number of arguments";
QString input = argv[1];
QString output = argv[2];
LOG(INFO) << "input: " << argv[1];
/// Settings
Settings _settings(QDir::currentPath()+"/settings.ini");
settings = &_settings;
///--- Read from "input" or generate programmatically
std::vector< vector > thetas;
bool readFromFile = false;
{
if(!input.compare("THUMB_INDEX_COLLISION"))
{
const int num = 3;
VectorN m_theta = VectorN::LinSpaced(num, -49, -50);
float initial[20] = {0.192209, -0.550227, -0.277241, -0.611161, 0.2734, -0.868817, -1.55841, -0.749486, 0.1484,
-0.71486, -1.50187, -0.93126, -0.0890169, -0.887832, -1.659, -1.00195, -0.230305, -1.12951,
-0.577767, -1.82401};
for (int i = 0; i < num; ++i) {
vector t(26, 0.0f);
for (int j = 0; j < 20; ++j) {
t[j + 6] = initial[j];
}
// global translation
t[0] = 0.0f;
t[1] = -70.0f;
t[2] = 400.0f;
// collision route
t[11] = m_theta[i] * M_PI / 180.0;
thetas.push_back(t);
}
}
else if(!input.compare("IMPROBABLE_POSE"))
{
const int num = 5;
float initial[20] = {0.2245, 0.6083, -0.1260, -1.0965, -0.1580, -1.0081, -0.6572, -1.0159, -0.2056, 0.0670, -1.1924,
-0.9529, -0.2882, -1.2361, -0.5992, -0.1336, 0.0659, -0.8790, -1.6130, -1.9549};
for (int i = 0; i < num; ++i) {
vector t(num_thetas, 0.0f);
for (int j = 0; j < 20; ++j) {
t[j + 6] = initial[j];
}
// global translation
t[0] = 0.0f;
t[1] = -70.0f;
t[2] = 400.0f;
thetas.push_back(t);
}
}
else if(!input.compare("SIMPLE_COLLISION"))
{
const int num = 30;
VectorN m_theta = VectorN::LinSpaced(num,0,-15);
VectorN a_theta = VectorN::LinSpaced(num,0,+10);
for (int i = 0; i < num; ++i) {
vector t(num_thetas, 0.0f);
// global translation
t[0] = 0.0f;
t[1] = -10.0f;
t[2] = 400.0f;
// collision route
t[18] = m_theta[i] * M_PI / 180.0;
t[14] = a_theta[i] * M_PI / 180.0;
thetas.push_back(t);
}
}
else if(!input.compare("COLLISION_PROBLEM"))
{
const int num = 5;
VectorN theta_10 = VectorN::LinSpaced(num,8,15);
VectorN theta_11 = VectorN::LinSpaced(num,5,10);
VectorN theta_14 = VectorN::LinSpaced(num,-8,-15);
VectorN theta_15 = VectorN::LinSpaced(num,-5,-10);
for (int i = 0; i < num; ++i) {
vector t(num_thetas, 0.0f);
// global translation
t[0] = 0.0f;
t[1] = -10.0f;
t[2] = 400.0f;
// collision route
t[10] = theta_10[i] * M_PI / 180.0;
t[11] = theta_11[i] * M_PI / 180.0;
t[14] = theta_14[i] * M_PI / 180.0;
t[15] = theta_15[i] * M_PI / 180.0;
thetas.push_back(t);
}
}
else if(!input.compare("SIMPLE_WAVE"))
{
for(float a = 0; a < 45.0f; a += 0.5f)
{
vector t(num_thetas, 0.0f);
// global translation
t[0] = 0.0f;
t[1] = -10.0f;
t[2] = 400.0f;
// global rotation
t[3] = 0.0f;
t[4] = 0.0f;
t[5] = a * M_PI / 180.0f;
thetas.push_back(t);
}
}
else if(!input.compare("SIMPLE_MOVE_Y"))
{
LOG(INFO) << "SIMPLE_MOVE_Y";
for(float a = 0.0; a < 100.0f; a += 2.0f)
{
vector t(num_thetas, 0.0f);
// global translation
t[0] = 0;
t[1] = a;
t[2] = 400.0f;
thetas.push_back(t);
}
}
else if(!input.compare("SIMPLE_MOVE_X"))
{
Vector3 t0 = settings->vector3("skeleton/translation");
for(float a = 0.0; a < 100.0f; a += 2.0f)
{
vector t(num_thetas, 0.0f);
// global translation
t[0] = a+t0[0];
t[1] = t0[1];
t[2] = t0[2];
thetas.push_back(t);
}
}
else if(!input.compare("SIMPLE_MOVE_Z"))
{
for(float a = 200.0f; a > -200.0f; a -= 2.0f)
{
vector t(num_thetas, 0.0f);
// global translation
t[0] = 0.0f;
t[1] = -10.0f;
t[2] = 400.0f + fabs(a);
thetas.push_back(t);
}
}
else if(!input.compare("SIMPLE_INDEX_SWING"))
{
for(float a = -10.0f; a < 25.0f; a += 1.0f)
{
vector t(num_thetas, 0.0f);
// global translation
Vector3 t0 = settings->vector3("skeleton/translation");
t[0] = t0[0];
t[1] = t0[1];
t[2] = t0[2];
// swing index left/right
t[10] = -a * M_PI / 180.0f;
thetas.push_back(t);
}
}
else if(!input.compare("SIMPLE_MOVE_Z_2"))
{
for(float a = 0.0f; a > -200.0f; a -= 2.0f)
{
vector t(num_thetas, 0.0f);
// global translation
t[0] = 0.0f;
t[1] = -10.0f;
t[2] = 400.0f + fabs(a);
thetas.push_back(t);
}
}
else if(!input.compare("SIMPLE_BEND_INDEX"))
{
for(float a = 0.0f; a < 100.0f; a += 1.0f)
{
vector t(num_thetas, 0.0f);
// global translation
t[0] = 0.0f;
t[1] = -10.0f;
t[2] = 400.0f;
// bend index finger
t[11] = -a * M_PI / 180.0f;
thetas.push_back(t);
}
}
else
{
readFromFile = true;
PostureFile p(argv[1]);
if(argc >= 4)
{
int skip = atoi(argv[3]);
for(size_t i = 0; i < p.postures.size(); i+=skip)
{
vector t = p.postures[i];
// global translation
Vector3 t0 = settings->vector3("skeleton/translation");
t[0] = t0[0];
t[1] = t0[1];
t[2] = t0[2];
thetas.push_back(t);
}
}
else
{
thetas = p.postures;
}
}
LOG(INFO) << "rendering" << thetas.size() << "postures";
}
///--- Where data will be saved
DataStream stream;
///--- Initialize offscreen renderering context
Camera camera(QVGA);
OpenGL32Format format;
QGLWidget glarea(format);
glarea.makeCurrent();
CustomFrameBuffer fb;
glViewport(0,0,camera.width(), camera.height());
glClearColor(1.0,1.0,1.0,1.0);
glEnable(GL_DEPTH_TEST);
fb.init(camera.width(), camera.height());
///--- Initialize renderer
Skeleton *skeleton = Skeleton::leftHand();
if(readFromFile){ ///<< ??????????????
// this just looks better with the svn data
skeleton->getJoint("Hand")->rotate(Vec3f(0,0,1), -1.57f);
skeleton->setInitialTransformations();
}
Cylinders *cylinders = new Cylinders(skeleton);
Cylinders_renderer renderer(cylinders);
renderer.init(Cylinders_renderer::FRAMEBUFFER);
renderer.set_uniform("view_projection", camera.view_projection_matrix());
///--- Prinout used matrices
std::cout << "Using view_projection: \n " << camera.view_projection_matrix() << std::endl;
cv::Mat color;
cv::Mat xyz;
for(auto t : thetas){
skeleton->set(t);
///--- Render time
fb.bind();
glClear(GL_DEPTH_BUFFER_BIT | GL_COLOR_BUFFER_BIT);
renderer.render();
fb.unbind();
// #define JUST_SHOW_BUFFERS
#ifdef JUST_SHOW_BUFFERS
fb.display_color_attachment();
fb.display_extra_attachment();
cv::waitKey(0);
break;
#endif
///--- Fetch the textures
fb.fetch_color_attachment(color);
fb.fetch_extra_attachment(xyz);
///--- Flip them to match device
cv::flip(color, color, 0 /*flip rows*/ );
cv::flip(xyz, xyz, 0 /*flip rows*/ );
///--- Convert to depth map
cv::Mat synthdepth = cv::Mat(stream.height(), stream.width(), CV_16UC1, cv::Scalar(1.0));
for(int row = 0; row < synthdepth.rows; row++)
for(int col = 0; col < synthdepth.cols; col++){
cv::Vec4f p = xyz.at(row, col);
synthdepth.at(row, col) = (ushort) p[2];
}
///--- Convert IDs to an indexed color
cv::Mat synthcolor = cv::Mat(stream.height(), stream.width(), CV_8UC4, cv::Scalar(255,255,255,255));
cvtColor(color, synthcolor, CV_GRAY2RGB);
///--- Add synthetic data to stream
stream.add_frame(synthcolor.data, synthdepth.data);
}
QFile::remove(output);
stream.save(output);
printf("%s finished!\n",argv[0]);
fflush(stdout);
return EXIT_SUCCESS;
}
================================================
FILE: cmake/CompileSynthgen.cmake
================================================
set(WITH_SYNTHGEN TRUE)
LIST(APPEND SRC_OPENGL2 "opengl/Cylinders_renderer.cpp" "opengl/Renderer_interface.cpp")
add_executable(synthgen apps/synthgen.cpp ${SRC_MATH} ${SRC_UTIL} ${SRC_GEOMETRY} ${SRC_OPENGL2} ${MATH} ${UTIL} ${GEOMETRY} ${QT_RESOURCES})
target_link_libraries(synthgen ${LIBRARIES})
qt5_use_modules(synthgen OpenGL Xml)
================================================
FILE: cmake/ConfigureAntTweakBar.cmake
================================================
#--- AntTweakBar
find_package(AntTweakBar)
if(ANTTWEAKBAR_FOUND)
include_directories(${ANTTWEAKBAR_INCLUDE_DIR})
list(APPEND LIBRARIES ${ANTTWEAKBAR_LIBRARY})
add_definitions(-DWITH_ANTTWEAKBAR)
message(STATUS "AntTweakBar: ${ANTTWEAKBAR_LIBRARY}")
#--- X11 (required by AntTweakBar)
if(UNIX AND NOT APPLE)
find_package(X11)
if(NOT X11_FOUND)
message(FATAL_ERROR "Cannot found X11 on Linux. Necessary")
endif()
list(APPEND LIBRARIES ${X11_LIBRARIES})
endif()
else()
# message(STATUS ANTTWEAKBAR_INCLUDE_DIR: ${ANTTWEAKBAR_INCLUDE_DIR})
# message(STATUS ANTTWEAKBAR_LIBRARY: ${ANTTWEAKBAR_LIBRARY})
message(STATUS "WARNING: AntTweakbar not found")
endif()
================================================
FILE: cmake/ConfigureCUDA.cmake
================================================
set(WITH_CUDA TRUE)
add_definitions(-DWITH_CUDA)
# Anastasia: what is this for?
if(WIN32)
# set(CUDA_TOOLKIT_ROOT_DIR "C:/Program Files/NVIDIA GPU Computing Toolkit/CUDA/v6.5")
set(CUDA_TOOLKIT_ROOT_DIR "C:/Program Files/NVIDIA GPU Computing Toolkit/CUDA/v7.0")
endif()
#--- Import CUDA/CUBLAS
find_package(CUDA REQUIRED)
include_directories(${CUDA_INCLUDE_DIRS})
list(APPEND LIBRARIES ${CUDA_LIBRARIES})
list(APPEND LIBRARIES ${CUDA_CUBLAS_LIBRARIES})
#--- For matrix operations within Kernels (Eigen not supported)
find_package(GLM REQUIRED)
include_directories(${GLM_INCLUDE_DIRS})
add_definitions(-DGLM_FORCE_CUDA) #< as mentioned in docs
#--- Card needs appropriate version
site_name(HOSTNAME)
message(STATUS "HOSTNAME ${HOSTNAME}")
if(HOSTNAME STREQUAL "lagrange") #--- Andrea/Linux
set(CUDA_NVCC_FLAGS "-gencode arch=compute_50,code=sm_50")# GTX980
set(CUDA_NVCC_FLAGS "${CUDA_NVCC_FLAGS} -w -Xcompiler -fPIC" )
elseif(HOSTNAME STREQUAL "IC-LGG-DPC-06") #--- Andrea,Fridge,Windows
set(CUDA_NVCC_FLAGS "${CUDA_NVCC_FLAGS} -gencode arch=compute_50,code=sm_50") # GTX980
elseif(HOSTNAME STREQUAL "tsf-460-wpa-4-107.epfl.ch") # Euler MAC-PRO Retina
set(CUDA_NVCC_FLAGS "${CUDA_NVCC_FLAGS} -gencode arch=compute_30,code=sm_30") # Geforce 650m
elseif(HOSTNAME STREQUAL "waluigi") #--- Matthias/Linux
set(CUDA_NVCC_FLAGS "-gencode arch=compute_30,code=sm_30")# GTX660 Ti
set(CUDA_NVCC_FLAGS "${CUDA_NVCC_FLAGS} -w -Xcompiler -fPIC" )
elseif(HOSTNAME STREQUAL "nastylinux") #--- Anastasia
set(CUDA_NVCC_FLAGS "-gencode arch=compute_30,code=sm_30")# GTX660 Ti
set(CUDA_NVCC_FLAGS "${CUDA_NVCC_FLAGS} -w -Xcompiler -fPIC -D__CUDACC__" )
elseif(HOSTNAME STREQUAL "thp") #--- THP/Alienware
set(CUDA_NVCC_FLAGS "-gencode arch=compute_30,code=sm_30")# GTX780M
elseif(HOSTNAME STREQUAL "teakwood") #--- THP/Alienware
set(CUDA_NVCC_FLAGS "${CUDA_NVCC_FLAGS} -gencode arch=compute_50,code=sm_50") # GTX980 (Win/Linux Machine)
#--- Generic
else()
#set(CUDA_NVCC_FLAGS "-gencode arch=compute_32,code=sm_32") # invalid device function
set(CUDA_NVCC_FLAGS "${CUDA_NVCC_FLAGS} -gencode arch=compute_30,code=sm_30") # Geforce 650m (MBPro Retina)
set(CUDA_NVCC_FLAGS "${CUDA_NVCC_FLAGS} -gencode arch=compute_32,code=sm_32") # ?
set(CUDA_NVCC_FLAGS "${CUDA_NVCC_FLAGS} -gencode arch=compute_35,code=sm_35") # ?
set(CUDA_NVCC_FLAGS "${CUDA_NVCC_FLAGS} -gencode arch=compute_50,code=sm_50") # GTX980 (Win/Linux Machine)
endif()
#--- Enable debugging flags
#set(CUDA_NVCC_FLAGS "${CUDA_NVCC_FLAGS} -g") # HOST debug mode
#set(CUDA_NVCC_FLAGS "${CUDA_NVCC_FLAGS} -G") # DEV debug mode
#set(CUDA_NVCC_FLAGS "${CUDA_NVCC_FLAGS} -lineinfo")
set(CUDA_NVCC_FLAGS "${CUDA_NVCC_FLAGS} -DNDEBUG") #< disable asserts
if(WIN32)
set(CUDA_PROPAGATE_HOST_FLAGS True)
if (CMAKE_BUILD_TYPE STREQUAL "Release")
set(CUDA_NVCC_FLAGS "${CUDA_NVCC_FLAGS} -O3")
set(CUDA_NVCC_FLAGS "${CUDA_NVCC_FLAGS} -use_fast_math")
endif()
else()
#--- CUDA doesn't like "--compiler-options -std=c++11"
set(CUDA_PROPAGATE_HOST_FLAGS False)
set(CUDA_NVCC_FLAGS "${CUDA_NVCC_FLAGS} -std c++11")
set(CUDA_NVCC_FLAGS "${CUDA_NVCC_FLAGS} -O3")
set(CUDA_NVCC_FLAGS "${CUDA_NVCC_FLAGS} -use_fast_math")
endif()
message(STATUS "CUDA_PROPAGATE_HOST_FLAGS: ${CUDA_PROPAGATE_HOST_FLAGS}")
message(STATUS "CUDA_HOST_COMPILER: ${CUDA_HOST_COMPILER}")
message(STATUS "CUDA_NVCC_FLAGS: ${CUDA_NVCC_FLAGS}")
================================================
FILE: cmake/ConfigureCompiler.cmake
================================================
#--- Build type
# set(CMAKE_BUILD_TYPE "Release") #<<< FORCE SET
if(NOT CMAKE_BUILD_TYPE)
set(CMAKE_BUILD_TYPE "Release")
endif()
message(STATUS "CMAKE_BUILD_TYPE ${CMAKE_BUILD_TYPE}")
if(APPLE)
message(STATUS "Compiler(Apple): clang")
set(CMAKE_CXX_COMPILER "/usr/bin/clang++")
set(CMAKE_CC_COMPILER "/usr/bin/clang")
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wno-deprecated-declarations")
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11")
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -O3")
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -ferror-limit=1") # max number of compiler errors
# set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall") # enable warnings
# set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -fopenmp") # only for clangomp
# set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Ofast -march=native -mtune=native -mno-avx -DNDEBUG")
elseif(UNIX)
message(STATUS "Compiler(Linux): g++-4.8")
set(CMAKE_CXX_COMPILER "/usr/bin/g++-4.8")
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wno-deprecated-declarations")
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11")
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -fopenmp")
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -O3")
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -march=native")
#set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall")
#set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Ofast -march=native -DNDEBUG")
#set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} -flto -fwhole-program")
#The following are needed if you are using librealsense
#add_compile_options(-std=c++11 -fPIC -lusb-1.0 -lpthread )
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -fPIC")
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -lusb-1.0")
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -lpthread")
elseif(WIN32)
message(STATUS "Compiler(Windows): Visual Studio 12 2013 Win64")
if (CMAKE_BUILD_TYPE STREQUAL "Release")
message(STATUS "--> NOTE: enabled windows performance flags")
add_definitions(-DNDEBUG)
# set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} /Ox /Ot /fp:fast /GS- /GL")
# set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} /LTCG")
endif()
endif()
================================================
FILE: cmake/ConfigureCudaOctree.cmake
================================================
#if(FALSE)
# message(STATUS "CudaOctree internal build")
# include_directories(${CMAKE_SOURCE_DIR}/cuda_octree)
# file(GLOB_RECURSE CPP_SOURCES "${CMAKE_SOURCE_DIR}/cuda_octree/*.cpp")
# file(GLOB_RECURSE HPP_SOURCES "${CMAKE_SOURCE_DIR}/cuda_octree/*.hpp")
# file(GLOB_RECURSE CUDA_SOURCES "${CMAKE_SOURCE_DIR}/cuda_octree/*.cu")
# file(GLOB_RECURSE CPP_HEADERS "${CMAKE_SOURCE_DIR}/cuda_octree/*.h")
# cuda_add_library(CudaOctree STATIC ${CUDA_SOURCES} ${CPP_SOURCES} ${HPP_SOURCES} ${CPP_HEADERS})
# list(APPEND LIBRARIES CudaOctree)
#else()
# list(APPEND LIBRARIES /usr/local/lib/libCudaOctree.a)
#endif()
================================================
FILE: cmake/ConfigureEigen.cmake
================================================
find_package(Eigen3 REQUIRED)
include_directories(${EIGEN3_INCLUDE_DIRS})
add_definitions(-DWITH_EIGEN)
================================================
FILE: cmake/ConfigureGLEW.cmake
================================================
#--- STATICALLY LINKED!!!
find_package(GLEW REQUIRED)
include_directories(${GLEW_INCLUDE_DIRS})
link_directories(${GLEW_LIBRARY_DIRS})
add_definitions(-DGLEW_STATIC)
add_definitions(-DWITH_GLEW)
LIST(APPEND LIBRARIES ${GLEW_LIBRARIES})
message(STATUS "GLEW_LIBRARIES: ${GLEW_LIBRARIES}")
================================================
FILE: cmake/ConfigureGLFW.cmake
================================================
#--- CMake extension to load GLFW
find_package(GLFW REQUIRED)
include_directories(${GLFW_INCLUDE_DIRS})
add_definitions(${GLFW_DEFINITIONS})
if(NOT GLFW_FOUND)
message(ERROR " GLFW not found!")
endif()
LIST(APPEND LIBRARIES ${GLFW_LIBRARIES})
================================================
FILE: cmake/ConfigureLibRealSense.cmake
================================================
add_compile_options(-std=c++11 -fPIC -lusb-1.0 -lpthread )
# libusb-1.0
find_package(Threads REQUIRED)
find_package(PkgConfig)
pkg_check_modules(PC_LIBUSB REQUIRED libusb-1.0)
include_directories( ${LIBUSB_1_INCLUDE_DIRS})
## GLFW
#find_package(PkgConfig REQUIRED)
#pkg_search_module(GLFW REQUIRED glfw3)
#include_directories(${GLFW_INCLUDE_DIRS})
#LIST(APPEND LIBRARIES ${GLFW_LIBRARIES})
# librealsense
set(LIBREALSENSE_INCLUDE_DIR "/home/raghu/Desktop/librealsense/include")
set(LIBREALSENSE_LIBRARY "/usr/local/lib/librealsense.so")
include_directories(${LIBREALSENSE_INCLUDE_DIR})
list(APPEND LIBRARIES ${LIBREALSENSE_LIBRARY})
#--- Mark as available
add_definitions(-DHAS_LIBREALSENSE)
================================================
FILE: cmake/ConfigureOpenCV.cmake
================================================
find_package(OpenCV2 REQUIRED)
if(OpenCV2_FOUND)
include_directories(${OpenCV2_INCLUDE_DIRS})
LIST(APPEND LIBRARIES ${OpenCV2_LIBRARIES})
add_definitions(-DWITH_OPENCV)
else()
message(FATAL_ERROR "OpenCV required")
endif()
#message(STATUS "OpenCV2_LIBRARIES: ${OpenCV2_LIBRARIES}")
#message(STATUS "OpenCV2_INCLUDE_DIRS: ${OpenCV2_INCLUDE_DIRS}")
#--- (OBSOLETE) find it with PkgConfig
#find_package(PkgConfig REQUIRED)
#pkg_check_modules(OPENCV REQUIRED opencv)
#list(APPEND LIBRARIES ${OPENCV_LDFLAGS})
#include_directories(${OPENCV_INCLUDE_DIRS})
================================================
FILE: cmake/ConfigureOpenGL.cmake
================================================
#--- OpenGL
find_package(OpenGL REQUIRED)
if(NOT OPENGL_FOUND)
message(ERROR " OPENGL not found!")
endif(NOT OPENGL_FOUND)
include_directories(${OpenGL_INCLUDE_DIRS})
link_directories(${OpenGL_LIBRARY_DIRS})
add_definitions(${OpenGL_DEFINITIONS})
LIST(APPEND LIBRARIES ${OPENGL_LIBRARIES})
if(UNIX)
LIST(APPEND LIBRARIES ${OPENGL_glu_LIBRARY})
endif()
================================================
FILE: cmake/ConfigureOpenGP.cmake
================================================
#--- OPENGP
find_package(OpenGP REQUIRED)
include_directories(${OpenGP_INCLUDE_DIRS})
add_definitions(-DHEADERONLY)
add_definitions(-DUSE_EIGEN)
if(NOT OPENGP_FOUND)
message(ERROR " OPENGP not found!")
endif()
================================================
FILE: cmake/ConfigureOpenMP.cmake
================================================
if(UNIX)
# only for g++ or for the Clang+OpenMP compiler
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -fopenmp")
elseif(WIN32)
message(STATUS "OpenMP not tested on windows!")
endif()
add_definitions(-DWITH_OPENMP)
================================================
FILE: cmake/ConfigureOpenNI.cmake
================================================
#--- OpenNI2
find_package(OpenNI2)
if(OPENNI2_FOUND)
include_directories(${OPENNI2_INCLUDE_DIR})
list(APPEND LIBRARIES ${OPENNI2_LIBRARY})
add_definitions(-DWITH_OPENNI)
else()
message(STATUS "WARNING: OpenNI2 not found!")
endif()
#message(STATUS "OpenNI2: ${OPENNI2_LIBRARY}")
#message(STATUS "OpenNI2: ${OPENNI2_INCLUDE_DIR}")
================================================
FILE: cmake/ConfigureQGLViewer.cmake
================================================
find_package(QGLViewer) #<<< Optional
if(QGLVIEWER_FOUND)
include_directories(${QGLVIEWER_INCLUDE_DIR})
add_definitions(-DQGLVIEWER)
LIST(APPEND LIBRARIES ${QGLVIEWER_LIBRARIES})
add_definitions(-DWITH_QGLVIEWER)
#message(STATUS "INCLUDE DIR" ${QGLVIEWER_INCLUDE_DIR})
endif()
================================================
FILE: cmake/ConfigureQt.cmake
================================================
# @see http://doc.qt.io/qt-5/cmake-manual.html
#--- Tell cmake where to find Qt5. (Unfortunately cmake3 does not support Qt5 yet)
#--- Debug
#message(STATUS QT5_CMAKE_DIR $ENV{QT5_CMAKE_DIR})
#message(STATUS CMAKE_PREFIX_PATH $ENV{CMAKE_PREFIX_PATH})
if(DEFINED ENV{CMAKE_PREFIX_PATH})
# If user has specified it, just use it...
set(CMAKE_PREFIX_PATH $ENV{CMAKE_PREFIX_PATH})
message(STATUS "Qt5: Using environment CMAKE_PREFIX_PATH: ${CMAKE_PREFIX_PATH}")
elseif(DEFINED ENV{QT5_CMAKE_DIR})
# User could have also specified QT5_CMAKE_DIR
set(CMAKE_PREFIX_PATH $ENV{QT5_CMAKE_DIR})
message(STATUS "Qt5: Using environment variable QT5_CMAKE_DIR: ${CMAKE_PREFIX_PATH}")
else()
# Otherwise just resort to some built-in stuff
if(WIN32)
set(CMAKE_PREFIX_PATH "C:/Developer/Qt/5.4/msvc2013_64_opengl/lib/cmake")
elseif(APPLE)
set(CMAKE_PREFIX_PATH "/usr/local/Cellar/qt5/5.4.1/lib/cmake")
elseif(UNIX)
set(CMAKE_PREFIX_PATH "/usr/local/qt/5.3/gcc_64/lib/cmake")
endif()
message(STATUS "!!!WARNING Qt5: resorting to default Qt5 paths (might fail): ${CMAKE_PREFIX_PATH}")
endif()
#--- Needed for GUI
find_package(Qt5Widgets REQUIRED)
include_directories(${Qt5Widgets_INCLUDE_DIRS})
list(APPEND LIBRARIES Qt5::Widgets)
#--- Needed for OpenGL
find_package(Qt5OpenGL REQUIRED)
include_directories(${Qt5OpenGL_INCLUDE_DIRS})
list(APPEND LIBRARIES Qt5::OpenGL)
#--- Needed for the QGLViewer library
find_package(Qt5Xml REQUIRED)
include_directories(${Qt5Xml_INCLUDE_DIRS})
list(APPEND LIBRARIES Qt5::Xml)
================================================
FILE: cmake/ConfigureRealSense.cmake
================================================
# TODO: use the find_file macro
if(WIN32)
set(REALSENSE_INCLUDE_DIR "C:/Developer/RealSense/RSSDK/include")
set(REALSENSE_UTILITY_DIR "C:/Developer/RealSense/RSSDK/sample/common/include")
if(${CMAKE_BUILD_TYPE} STREQUAL "Debug")
set(REALSENSE_LIBRARY "C:/Developer/RealSense/RSSDK/lib/x64/libpxcmd_d.lib")
set(REALSENSE_UTILITY_LIBRARY "C:/Developer/RealSense/RSSDK/sample/common/lib/x64/v120/libpxcutilsmd_d.lib")
endif()
if(${CMAKE_BUILD_TYPE} STREQUAL "Release")
set(REALSENSE_LIBRARY "C:/Developer/RealSense/RSSDK/lib/x64/libpxcmd.lib")
set(REALSENSE_UTILITY_LIBRARY "C:/Developer/RealSense/RSSDK/sample/common/lib/x64/v120/libpxcutilsmd.lib")
endif()
include_directories(${REALSENSE_INCLUDE_DIR} ${REALSENSE_UTILITY_DIR})
list(APPEND LIBRARIES ${REALSENSE_LIBRARY})
list(APPEND LIBRARIES ${REALSENSE_UTILITY_LIBRARY})
#--- DEBUG
# message(STATUS "REALSENSE_LIBRARY ${REALSENSE_LIBRARY}")
# message(STATUS "REALSENSE_UTILITY_LIBRARY ${REALSENSE_UTILITY_LIBRARY}")
#--- Mark as available
add_definitions(-DHAS_REALSENSE)
endif()
================================================
FILE: cmake/ConfigureSensor.cmake
================================================
#--- Choose a sensor
#SET(SENSOR_DEPTHSENSEGRABBER 0 CACHE BOOL "Use SoftKinetic with DepthSenseGrabber")
#SET(SENSOR_SOFTKIN 0 CACHE BOOL "Use SoftKinetic with SoftKin")
#SET(SENSOR_REALSENSE 0 CACHE BOOL "Use Intel RealSense")
#SET(SENSOR_LIBREALSENSE 0 CACHE BOOL "Use Intel LibRealSense")
#SET(SENSOR_OPENNI 0 CACHE BOOL "Use PrimeSense Carmine or ASUS Xtion with OpenNI")
SET(SENSOR "librealsense" CACHE STRING "Define your own sensor while configuring CMAKE")
SET(SENSOR_LIST depthsensegrabber librealsense openni realsense softkin)
SET_PROPERTY(CACHE SENSOR PROPERTY STRINGS ${SENSOR_LIST})
if (";${SENSOR_LIST};" MATCHES ";${SENSOR};")
message(STATUS "Sensor is in Sensor List")
else (";${SENSOR_LIST};" MATCHES ";${SENSOR};")
message(STATUS "${SENSOR} is not a valid option (${SENSOR_LIST}). Setting the SENSOR value to librealsense")
SET(SENSOR librealsense)
endif (";${SENSOR_LIST};" MATCHES ";${SENSOR};")
message(STATUS "SENSOR ${SENSOR}")
SET(SENSOR_COUNT 0)
#macro(SENSOR_RESET SENSOR_1 SENSOR_2)
# UNSET(SENSOR_DEPTHSENSEGRABBER CACHE)
# UNSET(SENSOR_SOFTKIN CACHE)
# UNSET(SENSOR_REALSENSE CACHE)
# UNSET(SENSOR_LIBREALSENSE CACHE)
# UNSET(SENSOR_OPENNI CACHE)
# message(FATAL_ERROR "Sensor conflict: both ${SENSOR_1} and ${SENSOR_2} are set to enabled. Resetting cache, please run cmake and choose a sensor again.")
#endmacro(SENSOR_RESET)
if (SENSOR STREQUAL "depthsensegrabber")
set (SENSOR_TEST DEPTHSENSEGRABBER)
if (SENSOR_COUNT EQUAL 0)
set(SENSOR_COUNT 1)
set(SENSOR_TYPE ${SENSOR_TEST})
message(STATUS "Enabling ${SENSOR_TEST}")
else (SENSOR_COUNT EQUAL 0)
SENSOR_RESET(${SENSOR_TYPE} ${SENSOR_TEST})
endif (SENSOR_COUNT EQUAL 0)
endif (SENSOR STREQUAL "depthsensegrabber")
if (SENSOR STREQUAL "softkin")
set (SENSOR_TEST SOFTKIN)
if (SENSOR_COUNT EQUAL 0)
set(SENSOR_COUNT 1)
set(SENSOR_TYPE ${SENSOR_TEST})
message(STATUS "Enabling ${SENSOR_TEST}")
else (SENSOR_COUNT EQUAL 0)
SENSOR_RESET(${SENSOR_TYPE} ${SENSOR_TEST})
endif (SENSOR_COUNT EQUAL 0)
endif (SENSOR STREQUAL "softkin")
if (SENSOR STREQUAL "realsense")
set (SENSOR_TEST REALSENSE)
if (SENSOR_COUNT EQUAL 0)
set(SENSOR_COUNT 1)
set(SENSOR_TYPE ${SENSOR_TEST})
message(STATUS "Enabling ${SENSOR_TEST}")
else (SENSOR_COUNT EQUAL 0)
SENSOR_RESET(${SENSOR_TYPE} ${SENSOR_TEST})
endif (SENSOR_COUNT EQUAL 0)
endif (SENSOR STREQUAL "realsense")
if (SENSOR STREQUAL "librealsense")
set (SENSOR_TEST LIBREALSENSE)
if (SENSOR_COUNT EQUAL 0)
set(SENSOR_COUNT 1)
set(SENSOR_TYPE ${SENSOR_TEST})
message(STATUS "Enabling ${SENSOR_TEST}")
else (SENSOR_COUNT EQUAL 0)
SENSOR_RESET(${SENSOR_TYPE} ${SENSOR_TEST})
endif (SENSOR_COUNT EQUAL 0)
endif (SENSOR STREQUAL "librealsense")
if (SENSOR STREQUAL "openni")
set (SENSOR_TEST OPENNI)
if (SENSOR_COUNT EQUAL 0)
set(SENSOR_COUNT 1)
set(SENSOR_TYPE ${SENSOR_TEST})
message(STATUS "Enabling ${SENSOR_TEST}")
else (SENSOR_COUNT EQUAL 0)
SENSOR_RESET(${SENSOR_TYPE} ${SENSOR_TEST})
endif (SENSOR_COUNT EQUAL 0)
endif (SENSOR STREQUAL "openni")
if (NOT SENSOR_COUNT)
message(FATAL_ERROR "Please choose a sensor, example: cmake -DSENSOR=librealsense (valid options: ${SENSOR_LIST}), or use cmake-gui. realsense works on Windows with RealSense SDK while librealsense works on Linux with librealsense SDK")
endif (NOT SENSOR_COUNT)
set(DEFINITION_SENSOR "-D${SENSOR_TYPE}")
================================================
FILE: cmake/ConfigureSoftKinetic.cmake
================================================
#--- OpenNI2
find_package(SoftKinetic) #NOT REQUIRED (mac doesn't have it)
if(SOFTKINETIC_FOUND)
include_directories(${SOFTKINETIC_INCLUDE_DIR})
list(APPEND LIBRARIES ${SOFTKINETIC_LIBRARIES})
add_definitions(-DHAS_SOFTKINETIC)
endif()
================================================
FILE: cmake/FindAntTweakBar.cmake
================================================
#
# Try to find AntTweakBar library and include path.
# Once done this will define
#
# ANTTWEAKBAR_FOUND
# ANTTWEAKBAR_INCLUDE_DIR
# ANTTWEAKBAR_LIBRARY
#
FIND_PATH(ANTTWEAKBAR_INCLUDE_DIR AntTweakBar.h PATHS
$ENV{ANTTWEAKBAR_ROOT}/include
#--- External folder
${CMAKE_CURRENT_LIST_DIR}/../external/AntTweakBar/include/
#--- Windows
C:/Developer/include/AntTweakBar
#--- Mac
/usr/local/include
/usr/X11/include
/usr/include
NO_DEFAULT_PATH
DOC "The directory where AntTweakBar.h resides")
if(WIN32)
set(BITS "64")
endif()
FIND_LIBRARY( ANTTWEAKBAR_LIBRARY AntTweakBar${BITS} PATHS
$ENV{ANTTWEAKBAR_ROOT}/lib
#--- Windows
C:/Developer/lib
#---
/usr/local/lib
/usr/local
/usr/X11
/usr
PATH_SUFFIXES a lib64 lib dylib NO_DEFAULT_PATH
DOC "The AntTweakBar library")
if(ANTTWEAKBAR_INCLUDE_DIR AND ANTTWEAKBAR_LIBRARY)
message(STATUS "Found ANTTWEAKBAR: ${ANTTWEAKBAR_LIBRARY}")
set(ANTTWEAKBAR_FOUND TRUE)
endif()
#--- DEBUG
#message(STATUS "ANTTWEAKBAR_INCLUDE_DIR: ${ANTTWEAKBAR_INCLUDE_DIR}")
#message(STATUS "ANTTWEAKBAR_LIBRARY: ${ANTTWEAKBAR_LIBRARY}")
================================================
FILE: cmake/FindEigen3.cmake
================================================
if(WIN32)
set(EIGEN3_INCLUDE_DIRS "C:/Developer/include")
else()
FIND_PATH( EIGEN3_INCLUDE_DIRS Eigen/Geometry
$ENV{EIGEN3DIR}/include
/usr/local/include/eigen3
/usr/local/include
/usr/local/X11R6/include
/usr/X11R6/include
/usr/X11/include
/usr/include/X11
/usr/include/eigen3/
/usr/include
/opt/X11/include
/opt/include
${CMAKE_SOURCE_DIR}/external/eigen/include)
endif()
SET(EIGEN3_FOUND "NO")
IF(EIGEN3_INCLUDE_DIRS)
SET(EIGEN3_FOUND "YES")
ENDIF()
================================================
FILE: cmake/FindGLEW.cmake
================================================
FIND_PATH( GLEW_INCLUDE_DIRS GL/glew.h
$ENV{GLEWDIR}/include
/usr/local/include
/usr/local/X11R6/include
/usr/X11R6/include
/usr/X11/include
/usr/include/X11
/usr/include
/opt/X11/include
/opt/include
# FOR WINDOWS
C:/Developer/include
${CMAKE_SOURCE_DIR}/external/glew/include)
if(WIN32)
SET(GLEWLIBNAME glew32s) # static
# SET(GLEWLIBNAME glew32) # dyn
else()
# IMPORTANT: uppercase otherwise problem on linux
SET(GLEWLIBNAME GLEW)
endif()
FIND_LIBRARY( GLEW_LIBRARIES NAMES ${GLEWLIBNAME} PATHS
$ENV{GLEWDIR}/lib
/usr/local/lib
/usr/local/X11R6/lib
/usr/X11R6/lib
/usr/X11/lib
/usr/lib/X11
/usr/lib
/opt/X11/lib
/opt/lib
# FOR UBUNTU 12.04 LTS
/usr/lib/x86_64-linux-gnu
# FOR WINDOWS
C:/Developer/lib
${CMAKE_SOURCE_DIR}/external/glew/lib)
SET(GLEW_FOUND "NO")
IF(GLEW_LIBRARIES AND GLEW_INCLUDE_DIRS)
SET(GLEW_FOUND "YES")
ENDIF()
#message(STATUS "GLEW_LIBRARIES: ${GLEW_LIBRARIES}")
#message(STATUS "GLEW_INCLUDE_DIRS: ${GLEW_INCLUDE_DIRS}")
================================================
FILE: cmake/FindGLFW.cmake
================================================
# Locate the GLFW library (version 2.0)
# This module defines the following variables:
# GLFW_LIBRARIES, the name of the library;
# GLFW_INCLUDE_DIRS, where to find GLFW include files.
# GLFW_FOUND, true if library path was resolved
#
# Usage example to compile an "executable" target to the glfw library:
#
# FIND_PACKAGE (GLFW REQUIRED)
# INCLUDE_DIRECTORIES (${GLFW_INCLUDE_DIRS})
# ADD_EXECUTABLE (executable ${YOUR_EXECUTABLE_SRCS})
# TARGET_LINK_LIBRARIES (executable ${GLFW_LIBRARIES})
#
# TODO:
# Lookup for windows
# Allow the user to select to link to a shared library or to a static library.
#
# SEE:
# - https://raw.github.com/progschj/OpenGL-Examples/master/cmake_modules/FindGLFW.cmake
#
FIND_PATH( GLFW_INCLUDE_DIRS GL/glfw.h
$ENV{GLFWDIR}/include
/usr/local/include
/usr/local/X11R6/include
/usr/X11R6/include
/usr/X11/include
/usr/include/X11
/usr/include
/opt/X11/include
/opt/include
#--- FOR WINDOWS
C:/Developer/include
#--- Deployed
${CMAKE_SOURCE_DIR}/external/glfw/include)
message(STATUS "GLFW_INCLUDE_DIRS: ${GLFW_INCLUDE_DIRS}")
FIND_LIBRARY( GLFW_LIBRARIES NAMES glfw PATHS
$ENV{GLFWDIR}/lib
/usr/local/lib
/usr/local/X11R6/lib
/usr/X11R6/lib
/usr/X11/lib
/usr/lib/X11
/usr/lib
/opt/X11/lib
/opt/lib
#--- FOR WINDOWS
C:/Developer/lib
#--- Deployed
${CMAKE_SOURCE_DIR}/external/glfw/lib)
SET(GLFW_FOUND "NO")
IF(GLFW_LIBRARIES AND GLFW_INCLUDE_DIRS)
SET(GLFW_FOUND "YES")
ENDIF(GLFW_LIBRARIES AND GLFW_INCLUDE_DIRS)
================================================
FILE: cmake/FindGLM.cmake
================================================
# FIND_PACKAGE (GLM REQUIRED)
# INCLUDE_DIRECTORIES (${GLM_INCLUDE_DIRS})
# ADD_EXECUTABLE (executable ${YOUR_EXECUTABLE_SRCS})
if(WIN32)
set(GLM_INCLUDE_DIRS "C:/Developer/include")
else()
FIND_PATH( GLM_INCLUDE_DIRS glm/glm.hpp
$ENV{GLM_DIR}
/usr/local/include
/usr/include
/opt/include
${CMAKE_SOURCE_DIR}/external)
endif()
SET(GLM_FOUND "NO")
IF(GLM_INCLUDE_DIRS)
SET(GLM_FOUND "YES")
ENDIF()
================================================
FILE: cmake/FindOpenCV2.cmake
================================================
# To find OpenCV 2 library visit http://opencv.willowgarage.com/wiki/
#
# The follwoing variables are optionally searched for defaults
# OpenCV2_ROOT_DIR: Base directory of OpenCV 2 tree to use.
#
# The following are set after configuration is done:
# OpenCV2_FOUND
# OpenCV2_INCLUDE_DIRS
# OpenCV2_LIBRARIES
#
# $Id: $
#
# Balazs [2011-01-18]:
# - Created from scratch for the reorganized OpenCV 2 structure introduced at version 2.2
# Jbohren [2011-06-10]:
# - Added OpenCV_ROOT_DIR for UNIX platforms & additional opencv include dir
# jmorrison [2013-11-14]:
# - Added flag to disable GPU requirement (NO_OPENCV_GPU)
#
# This file should be removed when CMake will provide an equivalent
#--- Select exactly ONE OpenCV 2 base directory to avoid mixing different version headers and libs
find_path(OpenCV2_ROOT_INC_DIR NAMES opencv2/opencv.hpp
PATHS
#--- WINDOWS
C:/Developer/include # Windows
"$ENV{OpenCV_ROOT_DIR}/include" # *NIX: custom install
/usr/local/include # Linux: default dir by CMake
/usr/include # Linux
/opt/local/include # OS X: default MacPorts location
NO_DEFAULT_PATH)
#--- DEBUG
#message(STATUS "OpenCV2_ROOT_INC_DIR: ${OpenCV2_ROOT_INC_DIR}")
#--- OBSOLETE
# Get parent of OpenCV2_ROOT_INC_DIR. We do this as it is more
# reliable than finding include/opencv2/opencv.hpp directly.
#GET_FILENAME_COMPONENT(OpenCV2_ROOT_DIR ${OpenCV2_ROOT_INC_DIR} PATH)
#message(STATUS "OpenCV2_ROOT_DIR: ${OpenCV2_ROOT_DIR}")
find_path(OpenCV2_CORE_INCLUDE_DIR NAMES core.hpp PATHS "${OpenCV2_ROOT_INC_DIR}/opencv2/core")
find_path(OpenCV2_IMGPROC_INCLUDE_DIR NAMES imgproc.hpp PATHS "${OpenCV2_ROOT_INC_DIR}/opencv2/imgproc")
find_path(OpenCV2_CONTRIB_INCLUDE_DIR NAMES contrib.hpp PATHS "${OpenCV2_ROOT_INC_DIR}/opencv2/contrib")
find_path(OpenCV2_HIGHGUI_INCLUDE_DIR NAMES highgui.hpp PATHS "${OpenCV2_ROOT_INC_DIR}/opencv2/highgui")
find_path(OpenCV2_FLANN_INCLUDE_DIR NAMES flann.hpp PATHS "${OpenCV2_ROOT_INC_DIR}/opencv2/flann")
set(OpenCV2_INCLUDE_DIRS
${OpenCV2_ROOT_INC_DIR}
${OpenCV2_ROOT_INC_DIR}/opencv2
${OpenCV2_CORE_INCLUDE_DIR}
${OpenCV2_IMGPROC_INCLUDE_DIR}
${OpenCV2_CONTRIB_INCLUDE_DIR}
${OpenCV2_HIGHGUI_INCLUDE_DIR}
${OpenCV2_FLANN_INCLUDE_DIR})
# absolute path to all libraries
# set(OPENCV2_LIBRARY_SEARCH_PATHS "${OpenCV2_ROOT_DIR}/lib")
#--- Specify where DLL is searched for
#message(STATUS "OPENCV2_LIBRARY_SEARCH_PATHS ${OPENCV2_LIBRARY_SEARCH_PATHS}")
list(APPEND OPENCV2_LIBRARY_SEARCH_PATHS $ENV{OpenCV_ROOT_DIR})
list(APPEND OPENCV2_LIBRARY_SEARCH_PATHS "C:/Developer/lib")
list(APPEND OPENCV2_LIBRARY_SEARCH_PATHS "/usr/local/lib")
list(APPEND OPENCV2_LIBRARY_SEARCH_PATHS "/opt/local/lib")
list(APPEND OPENCV2_LIBRARY_SEARCH_PATHS "/usr/lib")
#--- FIND RELEASE LIBRARIES
find_library(OpenCV2_CORE_LIBRARY_REL NAMES opencv_core opencv_core230 opencv_core220 opencv_core2410 PATHS ${OPENCV2_LIBRARY_SEARCH_PATHS})
find_library(OpenCV2_IMGPROC_LIBRARY_REL NAMES opencv_imgproc opencv_imgproc230 opencv_imgproc220 opencv_imgproc2410 PATHS ${OPENCV2_LIBRARY_SEARCH_PATHS})
find_library(OpenCV2_CONTRIB_LIBRARY_REL NAMES opencv_contrib opencv_contrib230 opencv_contrib220 opencv_contrib2410 PATHS ${OPENCV2_LIBRARY_SEARCH_PATHS})
find_library(OpenCV2_HIGHGUI_LIBRARY_REL NAMES opencv_highgui opencv_highgui230 opencv_highgui220 opencv_highgui2410 PATHS ${OPENCV2_LIBRARY_SEARCH_PATHS})
list(APPEND OpenCV2_LIBRARIES_REL ${OpenCV2_CORE_LIBRARY_REL})
list(APPEND OpenCV2_LIBRARIES_REL ${OpenCV2_IMGPROC_LIBRARY_REL})
list(APPEND OpenCV2_LIBRARIES_REL ${OpenCV2_CONTRIB_LIBRARY_REL})
list(APPEND OpenCV2_LIBRARIES_REL ${OpenCV2_HIGHGUI_LIBRARY_REL})
#--- FIND DEBUG LIBRARIES
if(WIN32)
find_library(OpenCV2_CORE_LIBRARY_DEB NAMES opencv_cored opencv_core230d opencv_core220d opencv_core2410d PATHS ${OPENCV2_LIBRARY_SEARCH_PATHS})
find_library(OpenCV2_IMGPROC_LIBRARY_DEB NAMES opencv_imgprocd opencv_imgproc230d opencv_imgproc220d opencv_imgproc2410d PATHS ${OPENCV2_LIBRARY_SEARCH_PATHS})
find_library(OpenCV2_CONTRIB_LIBRARY_DEB NAMES opencv_contribd opencv_contrib230d opencv_contrib220d opencv_contrib2410d PATHS ${OPENCV2_LIBRARY_SEARCH_PATHS})
find_library(OpenCV2_HIGHGUI_LIBRARY_DEB NAMES opencv_highguid opencv_highgui230d opencv_highgui220d opencv_highgui2410d PATHS ${OPENCV2_LIBRARY_SEARCH_PATHS})
list(APPEND OpenCV2_LIBRARIES_DEB ${OpenCV2_CORE_LIBRARY_DEB})
list(APPEND OpenCV2_LIBRARIES_DEB ${OpenCV2_IMGPROC_LIBRARY_DEB})
list(APPEND OpenCV2_LIBRARIES_DEB ${OpenCV2_CONTRIB_LIBRARY_DEB})
list(APPEND OpenCV2_LIBRARIES_DEB ${OpenCV2_HIGHGUI_LIBRARY_DEB})
endif()
#--- Setup cross-config libraries
set(OpenCV2_LIBRARIES "")
if(WIN32)
list(APPEND OpenCV2_LIBRARIES optimized ${OpenCV2_CORE_LIBRARY_REL} debug ${OpenCV2_CORE_LIBRARY_DEB})
list(APPEND OpenCV2_LIBRARIES optimized ${OpenCV2_IMGPROC_LIBRARY_REL} debug ${OpenCV2_IMGPROC_LIBRARY_DEB})
list(APPEND OpenCV2_LIBRARIES optimized ${OpenCV2_CONTRIB_LIBRARY_REL} debug ${OpenCV2_CONTRIB_LIBRARY_DEB})
list(APPEND OpenCV2_LIBRARIES optimized ${OpenCV2_HIGHGUI_LIBRARY_REL} debug ${OpenCV2_HIGHGUI_LIBRARY_DEB})
else()
list(APPEND OpenCV2_LIBRARIES ${OpenCV2_CORE_LIBRARY_REL} )
list(APPEND OpenCV2_LIBRARIES ${OpenCV2_IMGPROC_LIBRARY_REL})
list(APPEND OpenCV2_LIBRARIES ${OpenCV2_CONTRIB_LIBRARY_REL})
list(APPEND OpenCV2_LIBRARIES ${OpenCV2_HIGHGUI_LIBRARY_REL})
endif()
#--- Verifies everything (include) was found
set(OpenCV2_FOUND ON)
FOREACH(NAME ${OpenCV2_INCLUDE_DIRS})
IF(NOT EXISTS ${NAME})
message(WARNING "Could not find: ${NAME}")
set(OpenCV2_FOUND OFF)
endif(NOT EXISTS ${NAME})
ENDFOREACH(NAME)
#--- Verifies everything (release lib) was found
FOREACH(NAME ${OpenCV2_LIBRARIES_REL})
IF(NOT EXISTS ${NAME})
message(WARNING "Could not find: ${NAME}")
set(OpenCV2_FOUND OFF)
endif(NOT EXISTS ${NAME})
ENDFOREACH()
#--- Verifies everything (debug lib) was found
FOREACH(NAME ${OpenCV2_LIBRARIES_DEB})
IF(NOT EXISTS ${NAME})
message(WARNING "Could not find: ${NAME}")
set(OpenCV2_FOUND OFF)
endif(NOT EXISTS ${NAME})
ENDFOREACH()
#--- Display help message
IF(NOT OpenCV2_FOUND)
IF(OpenCV2_FIND_REQUIRED)
MESSAGE(FATAL_ERROR "OpenCV 2 not found.")
else()
MESSAGE(STATUS "OpenCV 2 not found.")
endif()
endif()
================================================
FILE: cmake/FindOpenGP.cmake
================================================
# Locate the OpenGP library (version 1.0)
# This module defines the following variables:
# OpenGP_INCLUDE_DIRS, where to find OpenGP include files.
# OpenGP_FOUND and OPENGP_FOUND true if library path was resolved
#
# Usage example to compile an "executable" target:
#
# FIND_PACKAGE (OpenGP REQUIRED)
# INCLUDE_DIRECTORIES (${OpenGP_INCLUDE_DIRS})
# ADD_EXECUTABLE (executable ${YOUR_EXECUTABLE_SRCS})
#
# DEBUG: outputs given environment variable
# message(STATUS OpenGPDIR $ENV{OpenGP_DIR})
FIND_PATH( OpenGP_INCLUDE_DIRS OpenGP/Surface_mesh.h
$ENV{OpenGP_DIR}
/usr/local/include
/usr/local/X11R6/include
/usr/X11R6/include
/usr/X11/include
/usr/include/X11
/usr/include
/opt/X11/include
/opt/include
/Users/andrea/Developer/OpenGP/src # local build
${CMAKE_SOURCE_DIR}/external/opengp/include)
SET(OPENGP_FOUND "NO")
SET(OpenGP_FOUND "NO")
IF(OpenGP_INCLUDE_DIRS)
SET(OPENGP_FOUND "YES")
SET(OpenGP_FOUND "YES")
ENDIF()
================================================
FILE: cmake/FindOpenNI2.cmake
================================================
# OPENNI2_INCLUDE_DIR
# OPENNI2_LIBRARY
# OPENNI2_FOUND
find_path(OPENNI2_INCLUDE_DIR "OpenNI.h"
PATHS
#--- MAC
/usr/include/ni2
/usr/local/include/ni2
#--- WINDOWS
C:/Developer/include/openni
#--- LINUX (self deployed)
${CMAKE_SOURCE_DIR}/openni/include
${CMAKE_SOURCE_DIR}/../openni/include
DOC "OpenNI c++ interface header")
find_library(OPENNI2_LIBRARY "OpenNI2"
PATHS
#--- MAC
/usr/lib/ni2
/usr/local/lib/ni2
#--- LINUX (self deployed)
/usr/lib
#--- WINDOWS
C:/Developer/lib
C:/Program Files/OpenNI2/Lib
${CMAKE_SOURCE_DIR}/openni/lib
${CMAKE_SOURCE_DIR}/../openni/lib
DOC "OpenNI2 library")
#message(STATUS "OPENNI2_LIBRARY: ${OPENNI2_LIBRARY}")
#message(STATUS "OPENNI2_INCLUDE_DIR: ${OPENNI2_INCLUDE_DIR}")
if(OPENNI2_INCLUDE_DIR AND OPENNI2_LIBRARY)
set(OPENNI2_FOUND TRUE)
endif()
#--- Notifications
if(OPENNI2_FOUND AND NOT OpenNI2__FIND_QUIETLY)
message(STATUS "Found OpenNI: ${OPENNI2_LIBRARY}")
else()
if(OpenNI2_FIND_REQUIRED)
message(STATUS OPENNI2_INCLUDE_DIR: ${OPENNI2_INCLUDE_DIR})
message(STATUS OPENNI2_LIBRARY: ${OPENNI2_LIBRARY})
message(FATAL_ERROR "Could not find OpenNI2")
endif()
endif()
================================================
FILE: cmake/FindQGLViewer.cmake
================================================
# - Try to find QGLViewer
# Once done this will define
#
# QGLVIEWER_FOUND - system has QGLViewer
# QGLVIEWER_INCLUDE_DIR - the QGLViewer include directory
# QGLVIEWER_LIBRARIES - Link these to use QGLViewer
# QGLVIEWER_DEFINITIONS - Compiler switches required for using QGLViewer
#
find_path(QGLVIEWER_INCLUDE_DIR
NAMES QGLViewer/qglviewer.h
PATHS
#--- Windows
C:/Developer/include
#--- Mac
/Library/Frameworks
#--- Linux
/usr/include
/usr/local/include
#--- Environment
ENV QGLVIEWERROOT
PATH_SUFFIXES Headers)
find_library(QGLVIEWER_LIBRARY_RELEASE
NAMES QGLViewer QGLViewer2 QGLViewer2
HINTS
#--- Windows
C:/Developer/lib
#--- Linux
/usr/lib
/usr/local/lib
#--- Mac
/Library/Frameworks
#--- Environment
ENV QGLVIEWERROOT
ENV LD_LIBRARY_PATH
ENV LIBRARY_PATH
PATH_SUFFIXES
QGLViewer
QGLViewer/release)
find_library(QGLVIEWER_LIBRARY_DEBUG
NAMES
dqglviewer
dQGLViewer
dQGLViewer2
QGLViewerd2
PATHS
#--- Windows
C:/Developer/lib
#--- Linux
/usr/lib
/usr/local/lib
#--- Mac
/Library/Frameworks
#--- Environment
ENV QGLVIEWERROOT
ENV LD_LIBRARY_PATH
ENV LIBRARY_PATH
PATH_SUFFIXES
QGLViewer
QGLViewer/debug)
if(QGLVIEWER_LIBRARY_RELEASE)
if(QGLVIEWER_LIBRARY_DEBUG)
set(QGLVIEWER_LIBRARIES_ optimized ${QGLVIEWER_LIBRARY_RELEASE} debug ${QGLVIEWER_LIBRARY_DEBUG})
else()
set(QGLVIEWER_LIBRARIES_ ${QGLVIEWER_LIBRARY_RELEASE})
endif()
set(QGLVIEWER_LIBRARIES ${QGLVIEWER_LIBRARIES_} CACHE FILEPATH "The QGLViewer library")
endif()
#message(STATUS "QGLVIEWER_INCLUDE_DIR: ${QGLVIEWER_INCLUDE_DIR}")
#message(STATUS "QGLVIEWER_LIBRARIES: ${QGLVIEWER_LIBRARIES}")
IF(QGLVIEWER_INCLUDE_DIR AND QGLVIEWER_LIBRARIES)
SET(QGLVIEWER_FOUND TRUE)
ENDIF()
IF(QGLVIEWER_FOUND)
IF(NOT CMAKE_FIND_QUIETLY)
MESSAGE(STATUS "Found QGLViewer: ${QGLVIEWER_LIBRARIES}")
ENDIF()
ELSE()
IF(QGLViewer_FIND_REQUIRED)
MESSAGE(FATAL_ERROR "Could not find QGLViewer")
ENDIF()
ENDIF()
================================================
FILE: cmake/FindSoftKinetic.cmake
================================================
FIND_PATH( SOFTKINETIC_INCLUDE_DIR DepthSenseTypes.h
$ENV{SOFTKINETIC_DIR}
/opt/softkinetic/DepthSenseSDK/include
${CMAKE_SOURCE_DIR}/external/softkinetic/DepthSenseSDK/include)
find_library(TURBOJPEG_LIB
NAMES turbojpeg
PATHS /opt/softkinetic/DepthSenseSDK/lib)
find_library(DEPTHSENSE_LIB
NAMES DepthSense
PATHS /opt/softkinetic/DepthSenseSDK/lib)
find_library(DEPTHSENSEPLUGINS_LIB
NAMES DepthSensePlugins
PATHS /opt/softkinetic/DepthSenseSDK/lib)
#message(STATUS "INCLUDES ${SOFTKINETIC_INCLUDE_DIRS}")
#message(STATUS "LIBS ${DEPTHSENSE_LIB}, ${TURBOJPEG_LIB}, ${DEPTHSENSEPLUGINS_LIB}")
if(TURBOJPEG_LIB AND DEPTHSENSE_LIB AND DEPTHSENSEPLUGINS_LIB)
LIST(APPEND SOFTKINETIC_LIBRARIES ${TURBOJPEG_LIB})
LIST(APPEND SOFTKINETIC_LIBRARIES ${DEPTHSENSE_LIB})
LIST(APPEND SOFTKINETIC_LIBRARIES ${DEPTHSENSEPLUGINS_LIB})
endif()
IF(SOFTKINETIC_INCLUDE_DIR AND SOFTKINETIC_LIBRARIES)
SET(SOFTKINETIC_FOUND TRUE)
else()
SET(SOFTKINETIC_FOUND FALSE)
ENDIF()
IF(SOFTKINETIC_FOUND)
IF(NOT CMAKE_FIND_QUIETLY)
MESSAGE(STATUS "Found SoftKinetic: ${SOFTKINETIC_INCLUDE_DIR}")
ENDIF()
ELSE()
IF(SOFTKINETIC_FOUND_REQUIRED)
MESSAGE(FATAL_ERROR "Could not find SoftKinetic")
ENDIF()
ENDIF()
================================================
FILE: cudax/CMakeLists.txt
================================================
if(NOT WITH_CUDA)
return()
endif()
#--- Dummy rule to show whole cudax folder in explorer
file(GLOB CUDA_FILES "*")
add_custom_target(cudax_files SOURCES ${CUDA_FILES})
#--- C++ sources (non-kernel) that need cuda are appended
file(GLOB_RECURSE CUDAX_CPP "${CMAKE_CURRENT_LIST_DIR}/*.cpp")
file(GLOB_RECURSE CUDAX_CU "${CMAKE_CURRENT_LIST_DIR}/*.cu")
file(GLOB_RECURSE CUDAX_H "${CMAKE_CURRENT_LIST_DIR}/*.h")
#--- Create the cudax static library & add it
INCLUDE_DIRECTORIES(.)
INCLUDE_DIRECTORIES(../) #so we can say #include "cudax/..."
cuda_add_library(cudax STATIC ${CUDAX_CPP} ${CUDAX_CU} ${CUDAX_H})
================================================
FILE: cudax/CublasHelper.h
================================================
#pragma once
#include
#include
#include
#include
#include
#include "thrust/device_vector.h"
#include
#include "util/singleton.h"
#include "externs.h"
//== NAMESPACE ================================================================
namespace cudax {
//=============================================================================
class CublasHelper{
SINGLETON(CublasHelper)
public:
cublasHandle_t _handle;
public:
static cublasHandle_t handle(){ return instance()._handle; }
static void init(){
std::cout << "Starting up CUBLAS" << std::endl;
cublasStatus_t status = cublasCreate(&(instance()._handle));
if (status != CUBLAS_STATUS_SUCCESS){
fprintf(stderr, "!!!! CUBLAS initialization error\n");
exit(EXIT_FAILURE);
}
}
static void cleanup(){
std::cout << "Shutting down CUBLAS" << std::endl;
cublasStatus_t status = cublasDestroy(instance()._handle);
if (status != CUBLAS_STATUS_SUCCESS) {
fprintf(stderr, "!!!! CUBLAS shutdown error\n");
exit(EXIT_FAILURE);
}
}
//-----------------------------------------------------------------------------
public:
static void outer_product_J(const Jacobian& J, ///< input
thrust::device_vector& JtJ, ///< output
int num_constr, ///< #rows of J
int num_pars) ///< #cols of J
{
assert(J.size()==(num_constr)); ///< check jacobian rows
assert(JtJ.size()==(num_pars*num_pars));
outer_product((float*)thrust::raw_pointer_cast(J.data()),
thrust::raw_pointer_cast(&JtJ[0]),
num_constr,
num_pars);
}
public:
static void vector_product_J(const Jacobian& J, ///< input
const thrust::device_vector& e, ///< input
thrust::device_vector& Jte, ///< output
int num_constr, ///< #rows of J and e
int num_pars) ///< #cols of J
{
assert(J.size()==(num_constr)); ///< check jacobian rows
assert(e.size()==(num_constr));
assert(Jte.size()==(num_pars));
vector_product((float*)thrust::raw_pointer_cast(J.data()),
thrust::raw_pointer_cast(&e[0]),
thrust::raw_pointer_cast(&Jte[0]),
num_constr,
num_pars);
}
public:
static void dot_product_e(const thrust::device_vector& e, ///< input
float& ete, ///< output
int num_constr) ///< # elements of vector e
{
assert(e.size()==(num_constr));
dot_product(thrust::raw_pointer_cast(&e[0]),
thrust::raw_pointer_cast(&e[0]),
&ete, num_constr);
}
//-----------------------------------------------------------------------------
public:
static void outer_product(const thrust::device_vector& J, ///< input
thrust::device_vector& JtJ, ///< output
int num_constr, ///< #rows of J
int num_pars) ///< #cols of J
{
assert(J.size()==(num_constr*num_pars));
assert(JtJ.size()==(num_pars*num_pars));
outer_product((float*)thrust::raw_pointer_cast(J.data()),
(float*)thrust::raw_pointer_cast(&JtJ[0]),
num_constr,
num_pars);
}
public:
static void vector_product(const thrust::device_vector& J, ///< input
const thrust::device_vector& e, ///< input
thrust::device_vector& Jte, ///< output
int num_constr, ///< #rows of J and e
int num_pars) ///< #cols of J
{
assert(J.size()==(num_constr*num_pars));
assert(e.size()==(num_constr));
assert(Jte.size()==(num_pars));
vector_product((float*)thrust::raw_pointer_cast(J.data()),
(float*)thrust::raw_pointer_cast(&e[0]),
(float*)thrust::raw_pointer_cast(&Jte[0]),
num_constr,
num_pars);
}
//-----------------------------------------------------------------------------
private:
/// Computes J^t*J and stores in pre-allocated matrix JtJ
static void outer_product(const float* J, float* JtJ, int num_constr, int num_pars /*num_thetas*/){
// C = \beta C + \alpha op(A) op(B);
//
// "ld" refers to the leading dimension of the matrix, which in the case of column-major
// storage is the number of rows of the allocated matrix (even if only a submatrix of
// it is being used).
//
const float alpha = 1.0;
const float beta = 0.0;
#define ROW_MAJOR_INPUT
#ifdef ROW_MAJOR_INPUT
// Cublas expects column major matrices, but our input is row major.
// Therefore we let cublas treat our row major input as column major
// and compute: J_colmajor * J_colmajor^T == J_rowmajor^T * J_rowmajor
cublasStatus_t status = cublasSgemm(CublasHelper::handle(),
CUBLAS_OP_N, // J_rowmajor^T == J_colmajor
CUBLAS_OP_T, // J_rowmajor == J_colmajor^T
num_pars, num_pars, num_constr,
&alpha,
J, // A
num_pars, // ld_A
J, // B,
num_pars, // ld_B
&beta,
JtJ, // C
num_pars // ld_C
);
#else
// column major input matrix
cublasStatus_t status = cublasSgemm(CublasHelper::handle(),
CUBLAS_OP_T, //J^t
CUBLAS_OP_N, //J
num_pars, num_pars, num_constr,
&alpha,
J, // A
num_constr, // ld_A
J, // B,
num_constr, // ld_B
&beta,
JtJ, // C
num_pars // ld_C
);
#endif
if(status != CUBLAS_STATUS_SUCCESS){
fprintf(stderr, "!!!! CUBLAS matrix multiplication (constr: %d pars: %d) failure!\n", num_constr, num_pars);
// fprintf(stderr, "!!!! CUBLAS matrix multiplication failure!\n");
exit(EXIT_FAILURE);
}
}
private:
/// Computes J^t*e and stores in pre-allocated matrix Jte
static void vector_product(
const float* J,
const float* e,
float* Jte,
int num_constr,
int num_pars /*num_thetas*/)
{
// y = \alpha op(A) x + \beta y
const float alpha = 1.0;
const float beta = 0.0;
const int inc1 = 1;
// Cublas expects column major matrices, but our input is row major.
// Therefore we let cublas treat our row major input as column major
// and compute: J_colmajor * e == J_rowmajor^T * e
#if 1
cublasStatus_t status = cublasSgemv(CublasHelper::handle(),
CUBLAS_OP_N, // J_rowmajor^T == J_colmajor
num_pars, num_constr,
&alpha, // 1
J, // A
num_pars, // ld_A
e, // x
inc1, // stride of x
&beta, // 0
Jte, // y
inc1 // stride of y
);
#else
cublasStatus_t status = cublasSgemm(CublasHelper::handle(),
CUBLAS_OP_N, // J_rowmajor^T == J_colmajor
CUBLAS_OP_T, // e_rowmajor == e_colmajor^T
num_pars, 1, num_constr,
&alpha,
J, // A
num_pars, // ld_A
e, // B,
inc1, // ld_B
&beta,
Jte, // C
inc1 // ld_C
);
#endif
if(status != CUBLAS_STATUS_SUCCESS){
fprintf(stderr, "!!!! CUBLAS matrix-vector multiplication (constr: %d pars: %d) failure!\n", num_constr, num_pars);
exit(EXIT_FAILURE);
}
}
private:
/// Computes u^t*v and stores in referenced variable utv
static void dot_product(
const float* u,
const float* v,
float* utv,
int dim)
{
/*
cublasStatus_t cublasSdot (cublasHandle_t handle, int n,
const float *x, int incx,
const float *y, int incy,
float *result)
*/
cublasStatus_t status = cublasSdot(CublasHelper::handle(),
dim,
u, 1,
v, 1,
utv);
if(status != CUBLAS_STATUS_SUCCESS){
fprintf(stderr, "!!!! CUBLAS vector-vector multiplication (d: %d) failure!\n", dim);
exit(EXIT_FAILURE);
}
}
};
//=============================================================================
} // namespace cudax
//=============================================================================
================================================
FILE: cudax/CudaHelper.h
================================================
/// @warning this cannot contain any c++11!!
#pragma once
#include
#include "util/gl_wrapper.h"
#include
#include "util/singleton.h"
#include "cudax/helper_cuda.h"
//== NAMESPACE ================================================================
namespace cudax {
//=============================================================================
class CudaHelper{
SINGLETON(CudaHelper)
public:
/// @note to be done ***after*** OpenGL for optimal OpenGL/CUDA performance
static void init(){
int devID = gpuGetMaxGflopsDeviceId();
cudaError status = cudaGLSetGLDevice(devID);
if(status!=cudaSuccess){
std::cout << "Could not get OpenGL compliant device... exiting" << std::endl;
exit(0);
}
}
static void cleanup(){
std::cout << "Shutting down CUDA device" << std::endl;
cudaDeviceReset();
}
public:
/// To debug calls to: cudaBindTextureToArray
static void check_array(cudaArray* array){
struct cudaChannelFormatDesc desc;
checkCudaErrors(cudaGetChannelDesc(&desc, array));
printf("CUDA Array channel descriptor, bits per component:\n");
printf("X %d Y %d Z %d W %d, kind %d\n",
desc.x,desc.y,desc.z,desc.w,desc.f);
printf("Possible values for channel format kind: i %d, u%d, f%d:\n",
cudaChannelFormatKindSigned, cudaChannelFormatKindUnsigned,
cudaChannelFormatKindFloat);
}
};
//=============================================================================
} // namespace cudax
//=============================================================================
================================================
FILE: cudax/CudaTimer.h
================================================
#pragma once
#include
#include
#include
//== NAMESPACE ================================================================
namespace cudax {
//=============================================================================
// http://devblogs.nvidia.com/parallelforall/how-implement-performance-metrics-cuda-cc/
struct CudaTimer{
cudaEvent_t _start, _stop;
std::string message;
std::string prefix;
bool event_on_destroy;
/// Same as create + restart
CudaTimer(const std::string& message){
cudaEventCreate(&_start);
cudaEventCreate(&_stop);
this->message = message;
cudaEventRecord(_start);
event_on_destroy = true;
std::cout << std::setprecision(3);
prefix = "Executed ";
}
CudaTimer(){
prefix = "Executed ";
event_on_destroy = false;
cudaEventCreate(&_start);
cudaEventCreate(&_stop);
}
~CudaTimer(){
if(event_on_destroy)
display();
cudaEventDestroy(_start);
cudaEventDestroy(_stop);
}
void set_prefix(const std::string& prefix){
this->prefix = prefix;
}
void restart(const std::string& message){
this->message = message;
cudaEventRecord(_start);
}
void display(){
static std::ofstream out("cuda.log");
cudaEventRecord(_stop);
cudaEventSynchronize(_stop);
float milliseconds = 0;
cudaEventElapsedTime(&milliseconds, _start, _stop);
std::cout << prefix << "["<< message <<"] in [" << milliseconds << "ms]" << std::endl;
}
float elapsed(){
cudaEventRecord(_stop);
cudaEventSynchronize(_stop);
float milliseconds = 0;
cudaEventElapsedTime(&milliseconds, _start, _stop);
return milliseconds;
}
};
//=============================================================================
} // namespace cudax
//=============================================================================
#define CUDA_TIMED_BLOCK(obj, blockName) for ( struct { int i; cudax::CudaTimer timer; } obj = { 0, cudax::CudaTimer(blockName) }; obj.i < 1; ++obj.i)
================================================
FILE: cudax/KinectCamera.h
================================================
#pragma once
#include
#include "cuda_runtime.h"
#include "cuda_glm.h"
//== NAMESPACE ================================================================
namespace cudax {
//=============================================================================
struct KinectCamera{
thrust::device_vector inv_proj_matrix; ///< only containts one
glm::mat3x3* D_mat_ptr; ///< device pointer to its content
KinectCamera(const float* H_inv_proj_matrix){
inv_proj_matrix.resize(1);
thrust::device_ptr mat = &inv_proj_matrix[0];
D_mat_ptr = thrust::raw_pointer_cast(mat);
cudaMemcpy((void*) D_mat_ptr, H_inv_proj_matrix, 9*sizeof(float), cudaMemcpyHostToDevice);
}
const glm::mat3x3& D_inv_proj_matrix(){
return (*D_mat_ptr);
}
};
//=============================================================================
} // namespace cudax
//=============================================================================
================================================
FILE: cudax/Kinematic.h
================================================
#pragma once
#include
#include "tracker/DataStructure/CustomJointInfo.h"
//== NAMESPACE ================================================================
namespace cudax {
//=============================================================================
struct Kinematic{
/// These hold memory
thrust::device_vector D_jointinfos;
thrust::device_vector D_chains;
/// These are used to access data in the kernel
CustomJointInfo* jointinfos; ///< @note device raw pointer
ChainElement* chains; ///< @note device raw pointer
};
//=============================================================================
} // namespace cudax
//=============================================================================
================================================
FILE: cudax/MeshGrid.h
================================================
#pragma once
#include
#include "thrust/device_vector.h"
//== NAMESPACE ================================================================
namespace cudax {
//=============================================================================
/// Device array containing MATLAB meshgrid like data
/// int4:
/// x) i: row
/// y) j: col
/// z) off: linear array iterator (i*width+j)
/// w) id: recycled for computation later (constraint id)
struct MeshGrid{
typedef int4 Elem;
typedef thrust::device_vector Offsets;
int width;
int height;
Offsets offsets;
MeshGrid(int width, int height){
this->width = width;
this->height = height;
offsets.resize(width*height);
thrust::counting_iterator fst_index(0);
thrust::counting_iterator lst_index(width*height);
thrust::transform(fst_index, lst_index, offsets.begin(), index_to_offset(width,height) );
}
Offsets::iterator begin(){ return offsets.begin(); }
Offsets::iterator end(){ return offsets.end(); }
/// a functor hashing indices to image-space coordinates
struct index_to_offset {
int n_rows, n_cols;
__host__ __device__
index_to_offset(int n_rows, int n_cols){
this->n_rows = n_rows;
this->n_cols = n_cols;
}
__host__ __device__
int4 operator()(int index) {
int4 offset;
offset.y = index/n_rows; // j
offset.x = index-(n_rows*offset.y); // i
offset.z = index;
offset.w = -1; ///< invalid index
return offset;
}
};
struct GetPixelIndex : public thrust::unary_function{
__device__
int operator()(MeshGrid::Elem& off){ return off.w; }
};
};
//=============================================================================
} // namespace cudax
//=============================================================================
/// Ability to output Elem values to std::cout
inline std::ostream& operator<< (std::ostream& d, cudax::MeshGrid::Elem val) {
return d << val.x << " " << val.y << " " << val.z << " " << val.w;
}
================================================
FILE: cudax/OpenCVOutputBuffer.h
================================================
#pragma once
#include
//== NAMESPACE ================================================================
namespace cudax {
//=============================================================================
///--- Deals with debug memory copy&mapping
class OpenCVOutputBuffer{
typedef unsigned char uchar;
uchar* host_mem;
thrust::device_vector dev_mem;
int _width, _height;
public:
OpenCVOutputBuffer(uchar* host_mem, int width, int height) :
host_mem(host_mem),
dev_mem(host_mem, host_mem+(width*height)),
_width(width), _height(height){}
~OpenCVOutputBuffer(){
thrust::copy(dev_mem.begin(), dev_mem.end(), host_mem);
}
uchar* get(){ return dev_mem.data().get(); }
int width(){ return _width; }
int height(){ return _height; }
};
//=============================================================================
} // namespace cudax
//=============================================================================
================================================
FILE: cudax/PixelIndexer.h
================================================
#pragma once
#include "kernel.h"
#include
#include "cudax/functors/IsMatchingDepth.h"
#include "cudax/functors/IsSilhouetteBoundary.h"
#include "cudax/functors/IsSilhouette.h"
#include "cudax/MeshGrid.h"
//== NAMESPACE ================================================================
namespace cudax {
//=============================================================================
struct PixelIndexer : public thrust::unary_function{
const int INVALID;
thrust::device_vector counters_memory;
thrust::device_vector render_indexes_memory; ///< row index of a pixel in the render cloud
thrust::device_vector sensor_indexes_memory; ///< row index of a pixel in the sensor cloud
int* counters; ///< raw devive pointer!!
int* render_indexes; ///< raw devive pointer!!
int* sensor_indexes; ///< raw devive pointer!!
int2* cnstr_indexes; ///< raw devive pointer!!
public:
/// @see https://github.com/thrust/thrust/blob/master/examples/arbitrary_transformation.cu
PixelIndexer(thrust::device_vector& indexes)
: INVALID(-1),
counters_memory(PixelType::SIZE, 0 /*init*/),
render_indexes_memory(H_width*H_height, PixelIndexer::INVALID),
sensor_indexes_memory(H_width*H_height, PixelIndexer::INVALID)
{
this->counters = thrust::raw_pointer_cast(&counters_memory[0]);
this->render_indexes = thrust::raw_pointer_cast(&render_indexes_memory[0]);
this->sensor_indexes = thrust::raw_pointer_cast(&sensor_indexes_memory[0]);
this->cnstr_indexes = thrust::raw_pointer_cast(&indexes[0]);
}
void clear(){
thrust::fill(counters_memory.begin(), counters_memory.end(), 0);
/// @todo these could be done during operator() for efficiency
thrust::fill(render_indexes_memory.begin(), render_indexes_memory.end(), PixelIndexer::INVALID);
thrust::fill(sensor_indexes_memory.begin(), sensor_indexes_memory.end(), PixelIndexer::INVALID);
}
int num_silho_constraints(){ return counters_memory[PixelType::CONSTRAINT_SILHO]; }
int num_depth_constraints(){ return counters_memory[PixelType::CONSTRAINT_DEPTH]; }
int num_extra_pull_constraints(){ return 3*counters_memory[PixelType::CONSTRAINT_EXTRA_PULL]; }
int num_extra_push_constraints(){ return 2*counters_memory[PixelType::CONSTRAINT_EXTRA_PUSH]; }
int num_silho_sensor(){ return counters_memory[PixelType::SENSOR_SILHOUETTE]; }
int num_silho_render(){ return counters_memory[PixelType::RENDER_SILHOUETTE]; }
int num_silho_overlap(){ return counters_memory[PixelType::OVERLAP_SILHOUETTE]; }
int num_silho_union(){ return counters_memory[PixelType::UNION_SILHOUETTE]; }
void print_constraints(){
// printf(" #silho: %d\n", num_silho_constraints());
// printf(" #depth: %d\n", num_depth_constraints());
printf(" #extra_pull: %d\n", num_extra_pull_constraints());
// printf(" #extra_push: %d\n", num_extra_push_constraints());
// printf(" #rendered: %d\n", num_silho_render());
}
__device__ int type(const MeshGrid::Elem& off){ return cnstr_indexes[off.z].x; }
__device__ int constraint_index(const MeshGrid::Elem& off){ return cnstr_indexes[off.z].y; }
__device__ int render_cloud_index(const MeshGrid::Elem& off){ return render_indexes[off.z]; }
__device__ int sensor_cloud_index(const MeshGrid::Elem& off){ return sensor_indexes[off.z]; }
void exec(){
clear();
Functor functor(counters, render_indexes, sensor_indexes, cnstr_indexes);
thrust::for_each(meshgrid->begin(), meshgrid->end(), functor);
}
struct IsExtraPullConstraint{
IsSensorSilhouette is_sensor_silhouette;
IsExtraPullConstraint() : is_sensor_silhouette(*silhouette_sensor){}
__device__
bool operator()(const int4& off){
#ifndef DISCARD_BAD_SENSOR
return is_sensor_silhouette(off);
#else
if(!is_sensor_silhouette(off)) return false;
return true;
float4 sensor_normal = SENSOR_NORMALS(off);
// printf("sensor_normal %f %f %f\n", sensor_normal.x, sensor_normal.y, sensor_normal.z);
return (-sensor_normal.z > .05); ///< minus: normal point toward camera
#endif
}
};
struct IsExtraPushConstraint{
IsRenderedSilhouette is_r_silho;
IsSensorSilhouette is_s_silho;
IsExtraPushConstraint() : is_s_silho(*silhouette_sensor){}
__device__
bool operator()(const int4& off){
return is_r_silho(off) && !is_s_silho(off);
}
};
///--- @note unfortunately functors cannot contain device_vector members, so we need to move
/// operator() in a nested functor class
struct Functor{
// typedef IsSensorSilhouette IsExtraPullConstraint; ///< TEMP
// typedef IsRenderedSilhouette IsExtraPushConstraint; ///< TEMP
IsDepthConstraint is_depth_constraint;
IsSilhouetteBoundary is_silhouette_boundary;
IsRenderedSilhouette is_rendered_silhouette;
IsSensorSilhouette is_sensor_silhouette;
IsExtraPullConstraint is_extra_pull_constraint;
IsExtraPushConstraint is_extra_push_constraint;
int* counters; ///< global memory holding pixels in
int* render_indexes; ///< row associated to pixel in the render cloud
int* sensor_indexes; ///< row associated to pixel in the sensor cloud
int2* cnstr_indexes;
bool silho_enabled;
bool depth_enabled;
bool extra_pull_enabled;
bool extra_push_enabled;
int extra_skip_every;
Functor(int* counters, int* render_indexes, int* sensor_indexes, int2* cnstr_indexes) :
is_depth_constraint(*silhouette_sensor),
is_sensor_silhouette(*silhouette_sensor)
{
this->counters = counters;
this->render_indexes = render_indexes;
this->sensor_indexes = sensor_indexes;
this->cnstr_indexes = cnstr_indexes;
silho_enabled = settings->silho_enable;
depth_enabled = settings->depth_enable;
extra_push_enabled = settings->fit2D_enable;
extra_pull_enabled = settings->fit3D_enable;
extra_skip_every = settings->fit3D_stepsize;
}
__device__
void operator()(MeshGrid::Elem& off){
///--- Invalidate constraints
cnstr_indexes[off.z] = make_int2( PixelType::INVALID, PixelType::INVALID );
///--- Update counters for tracking failure detection
{
bool is_rendered = is_rendered_silhouette(off);
bool is_sensor = is_sensor_silhouette(off);
if( is_rendered) atomicAdd(&counters[PixelType::RENDER_SILHOUETTE],1);
if( is_sensor) atomicAdd(&counters[PixelType::SENSOR_SILHOUETTE],1);
if( is_rendered && is_sensor ) atomicAdd(&counters[PixelType::OVERLAP_SILHOUETTE],1);
if( is_rendered || is_sensor ) atomicAdd(&counters[PixelType::UNION_SILHOUETTE],1);
}
///--- Mark constraints
if( silho_enabled && is_silhouette_boundary(off) ){
cnstr_indexes[off.z] = make_int2(PixelType::CONSTRAINT_SILHO, atomicAdd(&counters[PixelType::CONSTRAINT_SILHO],1));
return;
}
if( depth_enabled && is_depth_constraint(off) && /*for safety only*/ !is_silhouette_boundary(off) ){
cnstr_indexes[off.z] = make_int2(PixelType::CONSTRAINT_DEPTH, atomicAdd(&counters[PixelType::CONSTRAINT_DEPTH],1));
return;
}
///--- Anything not taken care by depth and silhouette arrives here
if( extra_pull_enabled && is_extra_pull_constraint(off) ){
cnstr_indexes[off.z] = make_int2(PixelType::CONSTRAINT_EXTRA_PULL, atomicAdd(&counters[PixelType::CONSTRAINT_EXTRA_PULL],1));
return;
}
if( extra_push_enabled && is_extra_push_constraint(off) ){
cnstr_indexes[off.z] = make_int2(PixelType::CONSTRAINT_EXTRA_PUSH, atomicAdd(&counters[PixelType::CONSTRAINT_EXTRA_PUSH],1));
return;
}
}
};
};
//=============================================================================
} // namespace cudax
//=============================================================================
================================================
FILE: cudax/Timer.h
================================================
/// @note this measures wall clock times, not GPU times!!
/// You'd need to sync the GPU (at the cost of a stall) to get
/// the real times
#pragma once
#include
#include
#include
#include
//== NAMESPACE ================================================================
namespace cudax {
//=============================================================================
struct Timer {
clock_t start;
clock_t end;
static const size_t buffer_length=256;
char buffer[buffer_length];
Timer(void) {
restart("");
//std::cout << "!!! WARNING: obsolete, why are you using it?" << std::endl;
}
void restart(const char* format, ...) {
va_list args;
va_start (args, format);
/// @note http://www.tin.org/bin/man.cgi?section=3&topic=vsnprintf
vsnprintf (buffer, buffer_length, format, args);
va_end (args);
start = clock();
}
double elapsed(void) {
end = clock();
return static_cast(end - start) / static_cast(CLOCKS_PER_SEC);
}
double epsilon(void) {
return 1.0 / static_cast(CLOCKS_PER_SEC);
}
void display() {
#ifndef DISABLE_TIMER_PRINTF
printf("[%s]: %.2fms\n",buffer,1e3 * elapsed());
fflush(stdout);
#endif
}
};
//=============================================================================
} // namespace cudax
//=============================================================================
================================================
FILE: cudax/cuda_glm.h
================================================
#pragma once
//#define GLM_COMPILER 0
#define CUDA_VERSION 7000
#if __unix__
// GLM wants to redefine these functions, which causes
// compilation errors in Linux. Undef'ing them WorksForMe...
#undef isnan
#undef isinf
#endif
#include "glm/glm.hpp"
/// To access raw pointer: glm::value_ptr(glm_mat4_variable)
// #include
================================================
FILE: cudax/externs.h
================================================
#pragma once
#include
#include
#include
#include "cudax/cuda_glm.h"
#include
namespace energy{namespace fitting{struct Settings;}}
struct CustomJointInfo;
struct ChainElement;
typedef unsigned char uchar;
//== NAMESPACE ================================================================
namespace cudax {
//=============================================================================
///--- Jacobian type
#define NUM_THETAS 29 ///< hand parameter size (size of jacobian row)
struct J_row{ float data[NUM_THETAS]; }; ///< Row of Jacobian
typedef thrust::device_vector Jacobian; ///< ROW major!!!
///--- Externally defined resources
extern cudaArray* render_color;
extern cudaArray* render_points;
extern cudaArray* render_normals;
extern cudaArray* sensor_depth;
extern cudaArray* sensor_normals;
//=============================================================================
} // namespace cudax
//=============================================================================
extern "C"
void kernel_init(energy::fitting::Settings* settings,
int _width,
int _height,
int thetas_size,
float H_focal_length_x,
float H_focal_length_y,
const float *H_inv_proj_matrix);
extern "C" void kernel_upload_kinematic(const std::vector& jointinfos, const std::vector& H_kinchains);
extern "C" void kernel_upload_cylinders(const float* H_cylinders);
extern "C" void kernel_upload_sensor_data(uchar* H_silhouette_sensor);
extern "C" void kernel_upload_dtform_idxs(int* H_dtform_idxs);
extern "C" void kernel_bind();
extern "C" void kernel(float* eigen_JtJ, float* eigen_Jte, float & push_error, float & pull_error, bool eval_metric, bool reweight);
extern "C" void kernel_unbind();
extern "C"
void kernel_copy_extra_corresp(thrust::host_vector& H_queries,
thrust::host_vector& H_target,
thrust::host_vector& H_idxs);
extern "C"
void kernel_store_closedform_corresp(int num);
extern "C"
void kernel_copy_closedform_corresp(thrust::host_vector &H_closedform_corrs);
extern "C"
void kernel_cleanup();
extern "C"
void kernel_memory_tests();
extern "C"
void kernel_constraint_type_image(uchar *, int, int);
extern "C"
void kernel_simplify_jacobian();
================================================
FILE: cudax/functors/ClosestPoint.h
================================================
#include "cudax/kernel.h"
#include "cudax/cuda_glm.h"
//== NAMESPACE ================================================================
namespace cudax {
//=============================================================================
struct ClosestPoint {
float *_data_cylinders; ///< raw
bool do_backface_check;
public:
ClosestPoint(){
_data_cylinders = thrust::raw_pointer_cast(cylinder_segments->data());
do_backface_check = settings->fit3D_backface_check;
}
//-------------------------------------------------------------//
__device__
float SAFE_DOT(glm::vec3 u, glm::vec3 v){
return u.x*v.x + u.y*v.y + u.z*v.z;
}
__device__
float SAFE_LENGTH(glm::vec3 u){
assert(u.x==u.x);
return sqrt(u.x*u.x + u.y*u.y + u.z*u.z);
}
__device__
glm::vec3 SAFE_NORMALIZE(glm::vec3 v, glm::vec3 fallback){
glm::vec3 ret = fallback;
if(SAFE_DOT(v, v) > FLT_MIN)
ret = glm::normalize(v);
return ret;
}
//-------------------------------------------------------------//
__device__
void line_segment_distance(glm::vec3 point,
const glm::vec3 &start, const glm::vec3 &end,
glm::vec3 &p, float &d)
{
glm::vec3 d1 = point - start;
glm::vec3 d2 = end - start;
glm::vec3 min_v = start;
float t = SAFE_DOT(d2, d2);
if(t > FLT_MIN){
t = SAFE_DOT(d1, d2) / t;
if (t > 1.0f) d1 = point - (min_v = end);
else if (t > 0.0f) d1 = point - (min_v = start + d2*t);
}
p = min_v;
assert(d1.x==d1.x);
d = SAFE_LENGTH(d1);
}
//-------------------------------------------------------------//
__device__
void backface_check(glm::vec3 point, glm::vec3 &p,
const glm::vec3 &n, const glm::vec3 &v,
const glm::vec3 &start, const glm::vec3 &end,
float r1, float r2, float r1y, float r2y, float l)
{
// check angle between normal and view direction
float nv = SAFE_DOT(n, v);
if(nv > 0) return; // point is front-facing
// compute intersection planes
// normal vectors n*, support vectors s*
glm::vec3 n1, n2, n3, s1, s2, s3, c, h;
{
// start sphere plane
n1 = n;
s1 = start;
// end sphere plane
n2 = n;
s2 = end;
// cone segment plane
c = SAFE_NORMALIZE(end - start, v);
h = SAFE_NORMALIZE(glm::cross(v, c), v);
n3 = SAFE_NORMALIZE(glm::cross(h, c), n1);
s3 = start;
}
// project point to intersection planes
glm::vec3 p1, p2, p3, o1, o2, o3;
{
p1 = point - SAFE_DOT(point - s1, n1) * n1;
p2 = point - SAFE_DOT(point - s2, n2) * n2;
p3 = point - SAFE_DOT(point - s3, n3) * n3;
glm::vec3 x(1,0,0), y(0,1,0);
if(fabs(SAFE_DOT(y, n1)) != 1.0f){
o1 = SAFE_NORMALIZE(y - SAFE_DOT(y, n1) * n1, y);
}else{
o1 = SAFE_NORMALIZE(x - SAFE_DOT(x, n1) * n1, y);
}
if(fabs(SAFE_DOT(y, n2)) != 1.0f){
o2 = SAFE_NORMALIZE(y - SAFE_DOT(y, n2) * n2, y);
}else{
o2 = SAFE_NORMALIZE(x - SAFE_DOT(x, n2) * n2, y);
}
if(fabs(SAFE_DOT(y, n3)) != 1.0f){
o3 = SAFE_NORMALIZE(y - SAFE_DOT(y, n3) * n3, y);
}else{
o3 = SAFE_NORMALIZE(x - SAFE_DOT(x, n3) * n3, y);
}
}
// project onto intersection curves
glm::vec3 u1, v1, u2, v2, u3, v3;
{
// start sphere
u1 = p1 - s1;
v1 = SAFE_NORMALIZE(u1, o1) * r1;
p1 -= u1 - v1;
// end sphere
u2 = p2 - s2;
v2 = SAFE_NORMALIZE(u2, o2) * r2;
p2 -= u2 - v2;
// cone segment
glm::vec3 s_; float d;
line_segment_distance(p3, start, end, s_, d);
glm::vec3 tmp = end-start; assert(tmp.x==tmp.x);
float le = SAFE_LENGTH(end - start);
glm::vec3 tmp2 = s_-start; assert(tmp2.x==tmp2.x);
float lp = SAFE_LENGTH(s_ - start);
float t = lp / le;
float r_ = t * r2 + (1 - t) * r1;
float ry = t * r2y + (1 - t) * r1y;
float ratio = ry/r_;
u3 = p3 - s_;
v3 = SAFE_NORMALIZE(u3, o3) * r_ * ratio;
p3 -= u3 - v3;
}
// select closest point to query
{
glm::vec3 tmp3 = p1-point; assert(tmp3.x==tmp3.x);
float d1 = SAFE_LENGTH(p1 - point);
glm::vec3 tmp4 = p2-point; assert(tmp4.x==tmp4.x);
float d2 = SAFE_LENGTH(p2 - point);
glm::vec3 tmp5 = p3-point; assert(tmp5.x==tmp5.x);
float d3 = SAFE_LENGTH(p3 - point);
p = (d1 < d2) ? ((d1 < d3) ? p1 : p3) : (d2 < d3) ? p2 : p3;
}
}
//-------------------------------------------------------------//
__device__
void cylinder_distance(glm::vec3 point,
const glm::vec3 &start, const glm::vec3 &end,
float r1, float r2, float r1y, float r2y, float l,
const glm::mat4 &T, const glm::mat4 &Ti,
glm::vec3 &p, glm::vec3 &n, float &d)
{
// compute projection on center line segment
line_segment_distance(point, start, end, p, d);
// interpolate start/end radius
glm::vec3 tmp1 = end-start; assert(tmp1.x==tmp1.x);
float le = SAFE_LENGTH(end - start);
glm::vec3 tmp2 = p-start; assert(tmp2.x==tmp2.x);
float lp = SAFE_LENGTH(p - start);
float t = lp / le;
float r = t * r2 + (1 - t) * r1;
float ry = t * r2y + (1 - t) * r1y;
float ratio = ry/r;
// scale from elliptical to circular
glm::vec3 p0 = point;
glm::vec3 pt = glm::vec3(Ti * glm::vec4(point, 1));
pt.x *= ratio;
point = glm::vec3(T * glm::vec4(pt, 1));
// project onto cylindroid surface
glm::vec3 view(0,0,-1);
n = SAFE_NORMALIZE(point - p, -view);
p += n * r * ratio;
#define ENABLE_BACKFACE_CHECK
#ifdef ENABLE_BACKFACE_CHECK
// only allow front-facing points
if(do_backface_check)
backface_check(point, p, n, view, start, end, r1, r2, r1y, r2y, l);
#endif
// unscale from circular to elliptical
pt = glm::vec3(Ti * glm::vec4(p, 1));
pt.x /= ratio;
p = glm::vec3(T * glm::vec4(pt, 1));
// compute correct normal at this point
pt = glm::vec3(Ti * glm::vec4(n, 0));
pt.x *= ratio;
n = SAFE_NORMALIZE(glm::vec3(T * glm::vec4(pt, 0)), -view);
// compute distance
glm::vec3 tmp3 = p-p0; assert(tmp3.x==tmp3.x);
if(ratio!=1.0f) d = SAFE_LENGTH(p - p0);
}
//-------------------------------------------------------------//
__device__
void closest_point(const float4 &p_sensor, float4 &p_model, float4 &n_model, int &joint_id){
p_model = p_sensor;
joint_id = -1;
float min_dist = FLT_MAX;
for(int i = 0; i < SEGMENT_JOINTS; ++i){
int id, k = 0;
glm::vec3 start, end;
float r1, r2, r1y, r2y, l;
glm::mat4 T, Ti;
// joint id
id = (int)_data_cylinders[i*SEGMENT_VALUES + k++];
if(id == -1) continue;
// start position
start.x = _data_cylinders[i*SEGMENT_VALUES + k++];
start.y = _data_cylinders[i*SEGMENT_VALUES + k++];
start.z = _data_cylinders[i*SEGMENT_VALUES + k++];
// end position
end.x = _data_cylinders[i*SEGMENT_VALUES + k++];
end.y = _data_cylinders[i*SEGMENT_VALUES + k++];
end.z = _data_cylinders[i*SEGMENT_VALUES + k++];
// segment parameters
r1 = _data_cylinders[i*SEGMENT_VALUES + k++];
r2 = _data_cylinders[i*SEGMENT_VALUES + k++];
r1y = _data_cylinders[i*SEGMENT_VALUES + k++];
r2y = _data_cylinders[i*SEGMENT_VALUES + k++];
l = _data_cylinders[i*SEGMENT_VALUES + k++];
// joint transform matrices
for(int j = 0; j < 16; ++j){
int r = j % 4;
int c = j / 4;
T[c][r] = _data_cylinders[i*SEGMENT_VALUES + k];
Ti[c][r] = _data_cylinders[i*SEGMENT_VALUES + k + 16];
++k;
}
float d;
glm::vec3 p, n;
glm::vec3 point(p_sensor.x, p_sensor.y, p_sensor.z);
cylinder_distance(point, start, end, r1, r2, r1y, r2y, l, T, Ti, p, n, d);
if(d < min_dist){
min_dist = d;
joint_id = id;
p_model.x = p.x;
p_model.y = p.y;
p_model.z = p.z;
p_model.w = 0;
n_model.x = n.x;
n_model.y = n.y;
n_model.z = n.z;
n_model.w = 0;
}
}
}
//-------------------------------------------------------------//
__device__
void relocate_target(float4 &p_sensor, float4 &p_model, float4 &n_model){
glm::vec3 ps(p_sensor.x, p_sensor.y, p_sensor.z);
glm::vec3 pm(p_model.x, p_model.y, p_model.z);
glm::vec3 nm(n_model.x, n_model.y, n_model.z);
glm::vec3 p = pm + SAFE_DOT(ps - pm, nm) * nm;
p_sensor.x = p.x;
p_sensor.y = p.y;
p_sensor.z = p.z;
}
//-------------------------------------------------------------//
__device__
bool is_nan(float4 n){
return n.x != n.x
|| n.y != n.y
|| n.z != n.z;
}
//-------------------------------------------------------------//
__device__
bool is_valid(float4 &p_sensor, float4 &p_model, float4 &n_model, int joint_id){
return joint_id != -1 && !is_nan(p_sensor) && !is_nan(p_model) && !is_nan(n_model);
}
//-------------------------------------------------------------//
};
//=============================================================================
} // namespace cudax
//=============================================================================
================================================
FILE: cudax/functors/ComputeJacobianRow.h
================================================
#pragma once
#include "cudax/kernel.h"
#include "cudax/MeshGrid.h"
//== NAMESPACE ================================================================
namespace cudax {
//=============================================================================
class ComputeJacobianRow : public thrust::unary_function{
protected:
J_row* J_raw; ///< array of rows
float* e_raw; ///< right hand side (constraints)
int2* cnstr_indexes; ///< raw
CustomJointInfo* jointinfos; ///< raw
ChainElement* chains; ///< raw
public:
ComputeJacobianRow(J_row* J_raw, float* e_raw){
assert(J_raw!=NULL);
assert(e_raw!=NULL);
this->J_raw = J_raw;
this->e_raw = e_raw;
this->cnstr_indexes = ::pixel_indexer->cnstr_indexes;
this->jointinfos = ::kinematic->jointinfos;
this->chains = ::kinematic->chains;
}
protected:
inline __device__ int type(const MeshGrid::Elem& off){ return cnstr_indexes[off.z].x; }
inline __device__ int constraint_index(const MeshGrid::Elem& off){ return cnstr_indexes[off.z].y; }
__device__
glm::mat3x2 projection_jacobian(const glm::vec3& pos){
// printf("focal length: %f", focal_length);
glm::mat3x2 M(0); ///< remember column major!
M[0][0] = focal_length_x / pos[2];
M[1][1] = focal_length_y / pos[2];
M[2][0] = -pos[0] * focal_length_x / ( pos[2]*pos[2] );
M[2][1] = -pos[1] * focal_length_y / ( pos[2]*pos[2] );
return M;
}
};
//=============================================================================
} // namespace cudax
//=============================================================================
================================================
FILE: cudax/functors/ComputeJacobianRowDepth.h
================================================
#include "cudax/kernel.h"
#include "cudax/functors/ImageGradientDepth.h"
#include "cudax/functors/IsMatchingDepth.h"
//== NAMESPACE ================================================================
namespace cudax {
//=============================================================================
/// Computes the content of a row of the jacobian
struct ComputeJacobianRowDepth : public thrust::unary_function{
ImageGradientDepth gradient;
CustomJointInfo* jointinfos; ///< device
ChainElement* chains; ///< device
int2* cnstr_indexes; ///< raw
uchar* silhouette_sensor; ///< raw
J_row* J_raw; ///< array of rows
float* e_raw; ///< right hand side (constraints)
float weight;
ComputeJacobianRowDepth(J_row* J_raw, float* e_raw) :
J_raw(J_raw), e_raw(e_raw)
{
this->jointinfos = kinematic->jointinfos;
this->chains = kinematic->chains;
this->cnstr_indexes = pixel_indexer->cnstr_indexes;
this->silhouette_sensor = thrust::raw_pointer_cast(cudax::silhouette_sensor->data());
weight = settings->depth_weight;
}
__device__
glm::mat3x2 projection_jacobian(const glm::vec3& pos){
// printf("focal length: %f", focal_length);
glm::mat3x2 M(0); ///< remember column major!
M[0][0] = focal_length_x / pos[2];
M[1][1] = focal_length_y / pos[2];
M[2][0] = -pos[0] * focal_length_x / ( pos[2]*pos[2] );;
M[2][1] = -pos[1] * focal_length_y / ( pos[2]*pos[2] );;
return M;
}
__device__ int type(const MeshGrid::Elem& off){ return cnstr_indexes[off.z].x; }
__device__ int constraint_index(const MeshGrid::Elem& off){ return cnstr_indexes[off.z].y; }
__device__
void operator()(MeshGrid::Elem& off){
if( type(off) != PixelType::CONSTRAINT_DEPTH) return;
int row_index = constraint_index(off);
J_row* J_sub = J_raw + row_index;
float* e_sub = e_raw + row_index;
int joint_id = (int) tex2D(color_tex, off.x, off.y);
///--- Joint axis
glm::vec3 pos;
pos[0] = tex2D(extra_tex, off.x, off.y).x;
pos[1] = tex2D(extra_tex, off.x, off.y).y;
pos[2] = tex2D(extra_tex, off.x, off.y).z;
/// Gradient of the depth image
glm::vec2 grad = gradient(off);
/// Jacobian of the projection matrix
glm::mat3x2 J_proj = projection_jacobian(pos);
glm::vec3 projector = grad * J_proj;
///--- Two depth values
float d_real = (float) SENSOR_DEPTH(off);
float d_rend = (float) tex2D(extra_tex, off.x, off.y).z;
// #define DEPTH_RE_WEIGHTING
#ifdef DEPTH_RE_WEIGHTING
float weight = std::sqrt( 1 / ( std::abs(d_real-d_rend) + 1e-5 ) );
#endif
for(int i_column=0; i_columndata[jinfo.index] = weight * ( glm::dot(projector, col) + col.z );
break;
}
case 0: // ROT
{
glm::vec3 t(jointinfos[jointinfo_id].mat[3][0],jointinfos[jointinfo_id].mat[3][1],jointinfos[jointinfo_id].mat[3][2]);
glm::vec3 a = glm::normalize(glm::vec3(jointinfos[jointinfo_id].mat * glm::vec4( axis, 1 )) - t);
glm::vec3 col = glm::cross(a, pos - t);
J_sub->data[jinfo.index] = weight * ( glm::dot(projector, col) + col.z );
break;
}
}
}
///--- Compute right hand side
*e_sub = weight * ( d_real-d_rend );
}
};
//=============================================================================
} // namespace cudax
//=============================================================================
================================================
FILE: cudax/functors/ComputeJacobianRowExtraClosedForm.h
================================================
#include "cudax/kernel.h"
#include "cudax/MeshGrid.h"
#include "cudax/PixelIndexer.h"
#include "ClosestPoint.h"
//== NAMESPACE ================================================================
namespace cudax {
//=============================================================================
/// Computes the content of a row of the jacobian
struct ComputeJacobianRowExtraClosedForm : public ComputeJacobianRow{
const glm::mat3x3& iproj; ///< to compute cloud from depth
ClosestPoint matcher;
bool debug_store;
float *debug_correspondences_raw;
float weight;
bool point_to_plane;
bool reweight;
public:
ComputeJacobianRowExtraClosedForm(J_row* J_raw, float* e_raw, bool reweight) :
ComputeJacobianRow(J_raw, e_raw),
iproj( cudax::camera_matrix->D_inv_proj_matrix() )
{
point_to_plane = settings->fit3D_point2plane;
weight = settings->fit3D_weight;
this->reweight = reweight;
debug_store = false;
debug_correspondences_raw = NULL;
}
void store_data(float *debug_correspondences)
{
if(debug_correspondences != NULL){
debug_store = true;
debug_correspondences_raw = debug_correspondences;
} else {
debug_store = false;
debug_correspondences_raw = NULL;
}
}
///--- Computes 3D point
inline __device__ float4 sensor_point_at(const MeshGrid::Elem off){
float depth = (float) SENSOR_DEPTH(off);
glm::vec3 wrld = iproj * glm::vec3( off.x*depth, off.y*depth, depth);
return make_float4(wrld[0], wrld[1], wrld[2], 0 /*unused*/);
}
// dot product
inline __device__ float dot(float2 a, float2 b)
{
return a.x * b.x + a.y * b.y;
}
inline __device__ float2 difference(float2 a, float2 b)
{
return make_float2(a.x - b.x, a.y - b.y);
}
inline __device__ float4 difference(float4 a, float4 b)
{
return make_float4(a.x - b.x, a.y - b.y, a.z - b.z, 0);
}
inline __device__ float norm(float4 a)
{
return sqrt(a.x*a.x + a.y*a.y + a.z*a.z);
}
__device__
float SAFE_DOT(glm::vec3 u, glm::vec3 v){
return u.x*v.x + u.y*v.y + u.z*v.z;
}
/// Last argument accesses THREE rows!
__device__
void skeleton_jacobian(const int joint_id, const glm::vec3& pos, J_row* sub_J, glm::vec3 nrm=glm::vec3(0), bool project=false){
for(int i_column=0; i_column jointinfo_id: %d %d\n", i_column, jointinfo_id);
int jointinfo_id = chains[joint_id].data[i_column];
if(jointinfo_id==-1) break;
const CustomJointInfo& jinfo = jointinfos[jointinfo_id];
glm::vec3& axis = jointinfos[jointinfo_id].axis;
glm::vec3 col;
switch(jinfo.type){
case 1 /*TRA*/:
{
col = glm::vec3( jointinfos[jointinfo_id].mat * glm::vec4( axis, 1 ) );
break;
}
case 0 /*ROT*/:
{
glm::vec3 t(jointinfos[jointinfo_id].mat[3][0],jointinfos[jointinfo_id].mat[3][1],jointinfos[jointinfo_id].mat[3][2]);
glm::vec3 a = glm::normalize(glm::vec3(jointinfos[jointinfo_id].mat * glm::vec4( axis, 1 )) - t);
col = glm::cross(a, pos - t);
break;
}
}
if(point_to_plane || project){
sub_J->data[jinfo.index] = weight * SAFE_DOT( col, nrm );
} else {
(sub_J+0)->data[jinfo.index] = weight * col[0];
(sub_J+1)->data[jinfo.index] = weight * col[1];
(sub_J+2)->data[jinfo.index] = weight * col[2];
}
}
}
__device__
void operator()(MeshGrid::Elem& off){
if( type(off) != PixelType::CONSTRAINT_EXTRA_PULL) return;
// printf("processing pixel[%d %d - %d] \n ", off.x, off.y, off.z);
///--- Access to a 3xN block of Jacobian
// printf(" constraint_index(off): %d\n", constraint_index(off));
J_row* J_sub = J_raw + 3*constraint_index(off);
float* e_sub = e_raw + 3*constraint_index(off);
float4 p_sensor = sensor_point_at(off);
float4 p_model, n_model;
int joint_id;
matcher.closest_point(p_sensor, p_model, n_model, joint_id);
if(!matcher.is_valid(p_sensor, p_model, n_model, joint_id)) return;
// Project sensor point onto the line along the model point's normal.
// This relocates the target point such that the corresponding source
// point is its orthogonal projection onto the model, which stabilizes
// the solution at the expense of slightly wrong target positions.
// (Note: this is only relevant for palm segment constraints!)
matcher.relocate_target(p_sensor, p_model, n_model);
if(debug_store){
#if 0
debug_correspondences_raw[6 * constraint_index(off) + 0] = p_model.x + 10*n_model.x;
debug_correspondences_raw[6 * constraint_index(off) + 1] = p_model.y + 10*n_model.y;
debug_correspondences_raw[6 * constraint_index(off) + 2] = p_model.z + 10*n_model.z;
#else
debug_correspondences_raw[6 * constraint_index(off) + 0] = p_sensor.x;
debug_correspondences_raw[6 * constraint_index(off) + 1] = p_sensor.y;
debug_correspondences_raw[6 * constraint_index(off) + 2] = p_sensor.z;
#endif
debug_correspondences_raw[6 * constraint_index(off) + 3] = p_model.x;
debug_correspondences_raw[6 * constraint_index(off) + 4] = p_model.y;
debug_correspondences_raw[6 * constraint_index(off) + 5] = p_model.z;
}
//printf(" p_model: %f %f %f %f\n", p_model.x, p_model.y, p_model.z, p_model.w);
//printf(" joint_id: %d\n", joint_id);
if(reweight){
float d = norm(difference(p_sensor, p_model));
//float w = sqrt(1.0f / (d + 1e-3));
float w = rsqrt(d + 1e-3);
if(d > 1e-3) weight *= w * 3.5f;
// factor 3.5 compensates for residual magnitude change
}
if(point_to_plane){
///--- Fills LHS
float4 n = n_model;
//float4 n = SENSOR_NORMALS(off);
//if( isnan(n.x) || isnan(n.y) || isnan(n.z) ) printf("ERROR: %f %f %f %f\n",n.x, n.y, n.z, n.w);
glm::vec3 normal(n.x, n.y, n.z);
skeleton_jacobian(joint_id, glm::vec3(p_model.x, p_model.y, p_model.z), J_sub, normal);
///--- Fills RHS
glm::vec3 residual(p_sensor.x-p_model.x, p_sensor.y-p_model.y, p_sensor.z-p_model.z);
*e_sub = weight * SAFE_DOT( residual, normal );
} else {
skeleton_jacobian(joint_id, glm::vec3(p_model.x, p_model.y, p_model.z), J_sub);
e_sub[0] = weight * ( p_sensor.x - p_model.x );
e_sub[1] = weight * ( p_sensor.y - p_model.y );
e_sub[2] = weight * ( p_sensor.z - p_model.z );
}
}
};
//=============================================================================
} // namespace cudax
//=============================================================================
================================================
FILE: cudax/functors/ComputeJacobianRowPush.h
================================================
#pragma once
#include "ComputeJacobianRow.h"
//== NAMESPACE ================================================================
namespace cudax {
//=============================================================================
class ComputeJacobianRowPush : public ComputeJacobianRow{
private:
///--- These are for the extra_push
int* sensor_dtform_idxs;
float weight;
public:
ComputeJacobianRowPush(J_row* J_raw, float* e_raw) : ComputeJacobianRow(J_raw, e_raw){
this->sensor_dtform_idxs = thrust::raw_pointer_cast(::sensor_dtform_idxs->data());
weight = settings->fit2D_weight;
assert(cudax::render_color!=NULL);
assert(render_points!=NULL);
}
public:
__device__
void operator()(MeshGrid::Elem& off){
if( type(off) != PixelType::CONSTRAINT_EXTRA_PUSH) return;
int row_index = constraint_index(off);
J_row* J_sub = J_raw + row_index;
float* e_sub = e_raw + row_index;
int joint_id = (int) tex2D(color_tex, off.x, off.y);
///--- Fetch closest point on sensor data
int closest_idx = sensor_dtform_idxs[off.z];
int row = closest_idx / width;
int col = closest_idx - width*row;
glm::vec2 p_rend(off.x, off.y);
glm::vec2 p_sens(col, row);
glm::vec2 p_diff = p_sens-p_rend;
//#define PAD_DISTANCE_TRANSFORM
#ifdef PAD_DISTANCE_TRANSFORM
float threshold = 3.0f;
float l_orig = glm::length(p_diff);
if(l_orig < threshold)
p_diff = glm::vec2(0);
else
p_diff *= (l_orig - threshold) / l_orig;
#endif
/// Fills LHS
glm::vec3 p_rend_3D;
p_rend_3D[0] = tex2D(extra_tex, off.x, off.y).x;
p_rend_3D[1] = tex2D(extra_tex, off.x, off.y).y;
p_rend_3D[2] = tex2D(extra_tex, off.x, off.y).z;
glm::mat3x2 J_proj = projection_jacobian(p_rend_3D);
// skeleton_jacobian(joint_id, p_rend_3D, J_sub, projector, true);
// #define BIAS_PALM_SILHO
#ifdef BIAS_PALM_SILHO
int weight = this->weight;
if(joint_id==3)
weight = this->weight/**10*/;
else
weight = 0; //this->weight;
#endif
///--- Compute LHS
for(int i_column=0; i_columndata[jinfo.index] = weight * jcol.x;
(J_sub+1)->data[jinfo.index] = weight * jcol.y;
break;
}
case 0: // ROT
{
glm::vec3 t(jointinfos[jointinfo_id].mat[3][0],jointinfos[jointinfo_id].mat[3][1],jointinfos[jointinfo_id].mat[3][2]);
glm::vec3 a = glm::normalize(glm::vec3(jointinfos[jointinfo_id].mat * glm::vec4( axis, 1 )) - t);
glm::vec3 col = glm::cross(a, p_rend_3D - t);
glm::vec2 jcol = J_proj * col;
(J_sub+0)->data[jinfo.index] = weight * jcol.x;
(J_sub+1)->data[jinfo.index] = weight * jcol.y;
break;
}
}
}
/// Fills RHS
*(e_sub+0) = weight * p_diff.x;
*(e_sub+1) = weight * p_diff.y;
}
};
//=============================================================================
} // namespace cudax
//=============================================================================
================================================
FILE: cudax/functors/ComputeJacobianRowSilho.h
================================================
#include "cudax/kernel.h"
#include "cudax/functors/ImageGradient.h"
#include "cudax/Kinematic.h"
//== NAMESPACE ================================================================
namespace cudax {
//=============================================================================
/// Computes the content of a row of the jacobian
struct ComputeJacobianRowSilho : public thrust::unary_function{
ImageGradient gradient;
CustomJointInfo* jointinfos; ///< device
ChainElement* chains; ///< device
int2* cnstr_indexes; ///< raw
uchar* silhouette_sensor; ///< raw
J_row* J_raw; ///< array of rows
float* e_raw; ///< right hand side (constraints)
float weight;
ComputeJacobianRowSilho(J_row* J_raw, float* e_raw) :
J_raw(J_raw), e_raw(e_raw)
{
this->jointinfos = kinematic->jointinfos;
this->chains = kinematic->chains;
this->cnstr_indexes = pixel_indexer->cnstr_indexes;
this->silhouette_sensor = thrust::raw_pointer_cast(cudax::silhouette_sensor->data());
weight = settings->silho_weight;
}
__device__
glm::mat3x2 projection_jacobian(const glm::vec3& pos){
// printf("focal length: %f", focal_length);
glm::mat3x2 M(0); ///< remember column major!
M[0][0] = focal_length_x / pos[2];
M[1][1] = focal_length_y / pos[2];
M[2][0] = -pos[0] * focal_length_x / ( pos[2]*pos[2] );
M[2][1] = -pos[1] * focal_length_y / ( pos[2]*pos[2] );
return M;
}
__device__ int type(const MeshGrid::Elem& off){ return cnstr_indexes[off.z].x; }
__device__ int constraint_index(const MeshGrid::Elem& off){ return cnstr_indexes[off.z].y; }
__device__
void operator()(MeshGrid::Elem& off){
if( type(off) != PixelType::CONSTRAINT_SILHO) return;
int row_index = constraint_index(off);
J_row* J_sub = J_raw + row_index;
float* e_sub = e_raw + row_index;
int joint_id = (int) tex2D(color_tex, off.x, off.y);
///--- Joint axis
glm::vec3 pos;
pos[0] = tex2D(extra_tex, off.x, off.y).x;
pos[1] = tex2D(extra_tex, off.x, off.y).y;
pos[2] = tex2D(extra_tex, off.x, off.y).z;
/// Gradient of the silhouette image
glm::vec2 grad = gradient(off);
/// Jacobian of the projection matrix
glm::mat3x2 J_proj = projection_jacobian(pos);
glm::vec3 projector = grad * J_proj;
int Ss = (silhouette_sensor[off.z]>125);
int Sr = (joint_id<255); ///< white is BG
#define SKIP_INSIDE_CONSTRAINTS
#ifdef SKIP_INSIDE_CONSTRAINTS
if(Ss==true)
return;
#endif
///--- Compute RHS
*e_sub = weight*(Ss-Sr);
///--- Compute LHS
for(int i_column=0; i_columndata[jinfo.index] = weight * glm::dot(projector, col);
break;
}
case 0: // ROT
{
glm::vec3 t(jointinfos[jointinfo_id].mat[3][0],jointinfos[jointinfo_id].mat[3][1],jointinfos[jointinfo_id].mat[3][2]);
glm::vec3 a = glm::normalize(glm::vec3(jointinfos[jointinfo_id].mat * glm::vec4( axis, 1 )) - t);
glm::vec3 col = glm::cross(a, pos - t);
J_sub->data[jinfo.index] = weight * glm::dot(projector, col);
break;
}
}
}
}
};
//=============================================================================
} // namespace cudax
//=============================================================================
================================================
FILE: cudax/functors/CopyOver.h
================================================
// #include "cudax/kernel.h"
#include "cudax/OpenCVOutputBuffer.h"
#include "cudax/MeshGrid.h"
//== NAMESPACE ================================================================
namespace cudax {
//=============================================================================
/// http://docs.thrust.googlecode.com/hg/structthrust_1_1unary__function.html
struct CopyOver : public thrust::unary_function{
enum MODE{_color, _idxs} mode;
uchar* out;
float width, height;
CopyOver(uchar* out, int width, int height):out(out),width(width),height(height){}
__device__
void operator()(int4 off){
switch(mode){
case _color: out[off.z] = tex2D(color_tex, off.x, off.y); break; ///< Simply copies in to out
case _idxs: out[off.z] = off.w*255/counter; break; ///< see correct indexes
}
// out[off.z] = tex2D(extra_tex, off.x, off.y).x; ///< test
// out[off.z] = tex2D(depth_tex, off.x, off.y).x; ///< test
// out[off.z] = (off.x/width)*255; ///< print x coords
// out[off.z] = (off.y/height)*255; ///< print y coords
}
static void copyover(MeshGrid* meshgrid, uchar* output, CopyOver::MODE mode){
OpenCVOutputBuffer _output(output, meshgrid->width, meshgrid->height);
CopyOver functor(_output.get(), meshgrid->width, meshgrid->height);
functor.mode = mode;
thrust::for_each(meshgrid->begin(), meshgrid->end(), functor);
}
static void color(MeshGrid* meshgrid, uchar* output){copyover(meshgrid, output, _idxs);}
static void idxs(MeshGrid* meshgrid, uchar* output){copyover(meshgrid, output, _color);}
};
//=============================================================================
} // namespace cudax
//=============================================================================
================================================
FILE: cudax/functors/ImageGradient.h
================================================
#include "cudax/kernel.h"
#include "cudax/functors/IsSilhouette.h"
#include "cudax/cuda_glm.h"
//== NAMESPACE ================================================================
namespace cudax {
//=============================================================================
///--- anonymous so it's not exposed outside
namespace { __constant__ float gradient_kernel[3][3]; }
struct ImageGradient{
IsRenderedSilhouette is_silhouette; ///< @todo this might be changed with other functors if needed
ImageGradient(){
///--- Initialization of constant memory
float sobel[3][3] = {{-1, 0, 1}, {-2, 0, 2}, {-1, 0, 1}};
cudaMemcpyToSymbol(gradient_kernel, sobel, 9*sizeof(float));
}
__device__
glm::vec2 operator()(const MeshGrid::Elem& off){
glm::vec2 ret;
// printf("kernel gradient: \n");
#pragma unroll
for(int i = -1; i <= 1; ++i){
#pragma unroll
for(int j = -1; j <= 1; ++j){
int x = off.x+i;
int y = off.y+j;
float value = (float) is_silhouette(x,y);
ret[0] += gradient_kernel[i+1][j+1] * value;
ret[1] += gradient_kernel[j+1][i+1] * value;
// printf("%d ", is_silhouette(x,y));
}
// printf("\n");
}
if(glm::dot(ret,ret) < 0.1f){
return glm::vec2(0,0);
} else {
ret = glm::normalize(ret);
}
#define ENABLE_MATCH_CPU_GRADIENT
#ifdef ENABLE_MATCH_CPU_GRADIENT
float tmp = -ret[0];
ret[0] = -ret[1];
ret[1] = tmp;
#endif
return ret;
}
};
//=============================================================================
} // namespace cudax
//=============================================================================
================================================
FILE: cudax/functors/ImageGradientDepth.h
================================================
#pragma once
#include "cudax/kernel.h"
#include "cudax/cuda_glm.h"
//== NAMESPACE ================================================================
namespace cudax {
//=============================================================================
///--- anonymous so it's not exposed outside
namespace { __constant__ float gradient_kernel_depth[3][3]; }
struct ImageGradientDepth{
ImageGradientDepth(){
///--- Initialization of constant memory
float sobel[3][3] = {{-1, 0, 1}, {-2, 0, 2}, {-1, 0, 1}};
cudaMemcpyToSymbol(gradient_kernel_depth, sobel, 9*sizeof(float));
}
__device__
glm::vec2 operator()(const MeshGrid::Elem& off){
glm::vec2 ret;
// printf("kernel gradient: \n");
#pragma unroll
for(int i = -1; i <= 1; ++i){
#pragma unroll
for(int j = -1; j <= 1; ++j){
int x = off.x+i;
int y = off.y+j;
float value = (float)tex2D(extra_tex, x, y).z;
ret[0] += gradient_kernel_depth[i+1][j+1] * value;
ret[1] += gradient_kernel_depth[j+1][i+1] * value;
// printf("%d ", is_silhouette(x,y));
}
// printf("\n");
}
//ret = glm::normalize(ret);
#define ENABLE_MATCH_CPU_GRADIENT
#ifdef ENABLE_MATCH_CPU_GRADIENT
float tmp = -ret[0];
ret[0] = -ret[1]/8.0f;
ret[1] = tmp/8.0f;
#endif
return ret;
}
};
//=============================================================================
} // namespace cudax
//=============================================================================
================================================
FILE: cudax/functors/ImageHighlighter.h
================================================
#pragma once
#include "cudax/kernel.h"
#include "cudax/functors/IsSilhouetteBoundary.h"
#include "cudax/functors/IsSilhouette.h"
#include "cudax/OpenCVOutputBuffer.h"
//== NAMESPACE ================================================================
namespace cudax {
//=============================================================================
template
struct ImageHighlighter{
MeshGridElemBoolFunctor condition;
uchar* out;
ImageHighlighter(OpenCVOutputBuffer& opencv){
out = opencv.get();
}
__device__
void operator()(MeshGrid::Elem& off){
if(condition(off))
out[off.z] = 255;
else
out[off.z] = 0;
}
};
/// Specializations
typedef ImageHighlighter SilhouetteBoundaryHighlighter;
typedef ImageHighlighter SilhouetteHighlighter;
//=============================================================================
} // namespace cudax
//=============================================================================
================================================
FILE: cudax/functors/IsMatchingDepth.h
================================================
#pragma once
#include "cudax/kernel.h"
#include "IsSilhouette.h"
//== NAMESPACE ================================================================
namespace cudax {
//=============================================================================
//== NAMESPACE ================================================================
namespace hidden {
//=============================================================================
struct IsMatchingDepth{
float z_th;
IsMatchingDepth(){
z_th = settings->depth_z_th;
}
__device__
bool operator()(const int4& off){
float d_real = (float)SENSOR_DEPTH(off);
float d_rend = (float)RENDER_DEPTH(off);
float diff = fabs(d_real - d_rend);
/// This is the one used by chen_cvpr14
//#define ENABLE_OCCLUSION_ENERGY
#ifdef ENABLE_OCCLUSION_ENERGY
if(d_rend& silhouette_sensor) :
test_1(silhouette_sensor){}
__device__
bool operator()(const int4& off){
return test_1(off) && test_2(off);
}
};
//=============================================================================
} // namespace cudax
//=============================================================================
================================================
FILE: cudax/functors/IsSilhouette.h
================================================
#pragma once
#include "cudax/kernel.h"
//== NAMESPACE ================================================================
namespace cudax {
//=============================================================================
struct IsRenderedSilhouette{
__device__
bool operator()(const int4& off){
return (tex2D(color_tex, off.x, off.y)<255);
}
__device__
bool operator()(int x, int y){
return (tex2D(color_tex, x, y)<255);
}
};
struct IsSensorSilhouette{
uchar* silhouette_sensor;
IsSensorSilhouette(thrust::device_vector& silhouette_sensor){
this->silhouette_sensor = thrust::raw_pointer_cast(&silhouette_sensor[0]);
}
__device__
bool operator()(const int4& off){
return (silhouette_sensor[off.z] > 125);
}
};
//=============================================================================
} // namespace cudax
//=============================================================================
================================================
FILE: cudax/functors/IsSilhouetteBoundary.h
================================================
#pragma once
#include "cudax/kernel.h"
//== NAMESPACE ================================================================
namespace cudax {
//=============================================================================
struct IsSilhouetteBoundary{
__device__
bool operator()(const int4 off){
uchar p0 = tex2D(color_tex, off.x, off.y);
/// Don't bother processing outside pixels
if(p0==255) {
return false;
}
/// Inside pixels, keep only the ones that see outside
for(int i= -1; i<=1; i++){
for(int j=-1; j<=1; j++){
if( tex2D(color_tex,off.x+i,off.y+j)==255 )
return true;
}
}
/// This one didn't see any outside
return false;
}
};
//=============================================================================
} // namespace cudax
//=============================================================================
================================================
FILE: cudax/functors/IsTopLeft3x3Block.h
================================================
#pragma once
#include "cudax/kernel.h"
//== NAMESPACE ================================================================
namespace cudax {
//=============================================================================
struct IsTopLeft3x3Block : public thrust::unary_function{
__device__
bool operator()(MeshGrid::Elem off){
return ((off.x<3) && (off.y<3));
}
};
//=============================================================================
} // namespace cudax
//=============================================================================
================================================
FILE: cudax/functors/SkeletonJacobian.h
================================================
#pragma once
#include
#include "cudax/cuda_glm.h"
#include "cudax/kernel.h"
#include "CustomJointInfo.h"
//== NAMESPACE ================================================================
namespace cudax {
//=============================================================================
struct SkeletonJacobian{
CustomJointInfo* jointinfos; ///< device
ChainElement* chains; ///< device
public:
SkeletonJacobian(CustomJointInfo* jointinfos, ChainElement* chains){
assert(jointinfos!=NULL);
assert(chains!=NULL);
this->jointinfos = jointinfos;
this->chains = chains;
}
/// Last argument accesses THREE rows!
__device__
void operator()(const int joint_id, const glm::vec3& pos, J_row* sub_J){
J_row& J0 = *(sub_J+0);
J_row& J1 = *(sub_J+1);
J_row& J2 = *(sub_J+2);
// printf("joint_id: %d\n", joint_id);
for(int i_column=0; i_column