Showing preview only (2,730K chars total). Download the full file or copy to clipboard to get everything.
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. <http://fsf.org/>
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 <iostream>
#include <opencv2/opencv.hpp>
#include <opencv2/core/core.hpp>
#include <opencv2/highgui/highgui.hpp>
#include <opencv2/imgproc/imgproc.hpp>
#include <opencv2/imgproc/types_c.h>
#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<vector<cv::Point> > contours;
vector<cv::Vec4i> 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<Vec3b>(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 <iostream>
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 <iostream>
#include <QDebug>
#include <QApplication>
#include <QGLWidget>
#include <QOpenGLVertexArrayObject>
#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 <iostream>
#include <QDebug>
#include <QApplication>
#include <QGLWidget>
#include <QOpenGLWidget>
#include <QOpenGLVertexArrayObject>
#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 <iostream>
#include <string>
#include <vector>
#include <fstream>
#include <sstream> // for std::ostringstream
#include <stdexcept>
#include <cstdio>
#include <cstdlib> // for getenv()
#include <list> // for std::list
#if defined(WIN32) || defined(_WIN32) || defined(__WIN32__) || defined(__TOS_WIN__)
//defined for 32 and 64-bit environments
#include <io.h> // 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 <unistd.h> // 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<std::string> 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<double> &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<double> &x,
const std::vector<double> &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<double> &x,
const std::vector<double> &y,
const std::vector<double> &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<<cmdstr;
return *this;
}
//----------------------------------------------------------------------------------
///\brief Clears the title of a gnuplot session
/// The title is not set by default.
///
/// \param ---
///
/// \return <-- reference to the gnuplot object
// ---------------------------------------------------------------------------------
inline Gnuplot& unset_title()
{
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<typename X>
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<typename X, typename Y>
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<typename X, typename Y, typename E>
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<typename X, typename Y, typename Z>
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<double> &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<double> &x,
const std::vector<double> &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<double> &x,
const std::vector<double> &y,
const std::vector<double> &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<typename X>
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<typename X, typename Y>
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<typename X, typename Y, typename E>
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<typename X, typename Y, typename Z>
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] <<std::endl;
tmp.flush();
tmp.close();
plotfile_xyz(name, 1, 2, 3, title);
return *this;
}
//------------------------------------------------------------------------------
//
// define static member function: set Gnuplot path manual
// for windows: path with slash '/' not backslash '\'
//
bool Gnuplot::set_GNUPlotPath(const std::string &path)
{
std::string tmp = path + "/" + 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 = path;
return true;
}
else
{
Gnuplot::m_sGNUPlotPath.clear();
return false;
}
}
//------------------------------------------------------------------------------
//
// define static member function: set standart terminal, used by showonscreen
// defaults: Windows - win, Linux - x11, Mac - aqua
//
void Gnuplot::set_terminal_std(const std::string &type)
{
#if defined(unix) || defined(__unix) || defined(__unix__) || defined(__APPLE__)
if (type.find("x11") != std::string::npos && getenv("DISPLAY") == NULL)
{
throw GnuplotException("Can't find DISPLAY variable");
}
#endif
Gnuplot::terminal_std = type;
return;
}
//------------------------------------------------------------------------------
//
// A string tokenizer taken from http://www.sunsite.ualberta.ca/Documentation/
// /Gnu/libstdc++-2.90.8/html/21_strings/stringtok_std_h.txt
//
template <typename Container>
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<float>(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<std::string> 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<std::string>::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<int>(tmpfile_list.size());
}
}
#endif
================================================
FILE: apps/helloworld_cublas/main_performance.cpp
================================================
#include <cassert>
#include <Eigen/Dense>
#include <QApplication>
#include "util/gl_wrapper.h"
#include "util/OpenGL32Format.h"
#include <QGLWidget>
#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<Scalar, Eigen::Dynamic, Eigen::Dynamic> 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<Scalar,
Eigen::Dynamic,
Eigen::Dynamic,
Eigen::RowMajor> 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<float> data_x0(MAX_NUM_CONSTRAINTS); // Matrix dimension
vector<float> data_y1(MAX_NUM_CONSTRAINTS); // GPU JTJ runtime
vector<float> data_y2(MAX_NUM_CONSTRAINTS); // CPU JTJ runtime
vector<float> data_y3(MAX_NUM_CONSTRAINTS); // GPU JTe runtime
vector<float> 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 <cassert>
#include "util/gl_wrapper.h"
#include "util/OpenGL32Format.h"
#include <QApplication>
#include <QGLWidget>
#include <Eigen/Dense>
#include "cudax/CublasHelper.h"
#include "cudax/CudaHelper.h"
#include "cudax/CublasHelper.h"
using namespace std;
using namespace cudax;
typedef float Scalar;
typedef Eigen::Matrix<Scalar, Eigen::Dynamic, Eigen::Dynamic> 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 <iostream>
#include "util/gl_wrapper.h"
#include "util/tictoc.h"
#include "cudax/CudaHelper.h"
#include <QApplication>
#include <QGLWidget>
#include <QOpenGLVertexArrayObject>
#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 <librealsense/rs.hpp>
#include <cstdio>
// Also include GLFW to allow for graphical display
#define GLFW_INCLUDE_GLU
#include <GLFW/glfw3.h>
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<depth_intrin.height; ++dy)
{
for(int dx=0; dx<depth_intrin.width; ++dx)
{
// Retrieve the 16-bit depth value and map it into a depth in meters
uint16_t depth_value = depth_image[dy * depth_intrin.width + dx];
float depth_in_meters = depth_value * scale;
// Skip over pixels with a depth value of zero, which is used to indicate no data
if(depth_value == 0) continue;
// Map from pixel coordinates in the depth image to pixel coordinates in the color image
rs::float2 depth_pixel = {(float)dx, (float)dy};
rs::float3 depth_point = depth_intrin.deproject(depth_pixel, depth_in_meters);
rs::float3 color_point = depth_to_color.transform(depth_point);
rs::float2 color_pixel = color_intrin.project(color_point);
// Use the color from the nearest color pixel, or pure white if this point falls outside the color image
const int cx = (int)std::round(color_pixel.x), cy = (int)std::round(color_pixel.y);
if(cx < 0 || cy < 0 || cx >= 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 <iostream>
#include <fstream>
#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 <omp.h>
#include <stdio.h>
#include <stdlib.h>
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 <iostream>
#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 <QApplication>
#include <QGLViewer/qglviewer.h>
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<nbSteps; ++i) {
const float ratio = i/nbSteps;
const float angle = 21.0*ratio;
const float c = cos(angle);
const float s = sin(angle);
const float r1 = 1.0 - 0.8f*ratio;
const float r2 = 0.8f - 0.8f*ratio;
const float alt = ratio - 0.5f;
const float nor = 0.5f;
const float up = sqrt(1.0-nor*nor);
glColor3f(1.0-ratio, 0.2f , ratio);
glNormal3f(nor*c, up, nor*s);
glVertex3f(r1*c, alt, r1*s);
glVertex3f(r2*c, alt+0.05f, r2*s);
}
glEnd();
}
void init() {
restoreStateFromFile();
}
};
int main(int argc, char* argv[]){
QApplication app(argc, argv);
Viewer viewer;
viewer.setWindowTitle("helloworld_qglviewer");
viewer.show();;
return app.exec();
}
================================================
FILE: apps/helloworld_qtopengl/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)
add_executable(${PROJECT} main.cpp)
target_link_libraries(${PROJECT} ${LIBRARIES})
================================================
FILE: apps/helloworld_qtopengl/main.cpp
================================================
#include <iostream>
#include <QApplication>
#include <QGLWidget>
#include <QOpenGLVertexArrayObject>
/// 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 <iostream>
#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 <double, milli> (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)<PXC_STATUS_NO_ERROR) break;
///--- Create capture device
PXCCapture *capture;
session->CreateImpl<PXCCapture>(&desc1,&capture);
for (int i=0;;i++) {
PXCCapture::DeviceInfo dinfo;
if (capture->QueryDeviceInfo(i,&dinfo)<PXC_STATUS_NO_ERROR) break;
wprintf_s(L"device[%d]: %s\n", i, dinfo.name);
}
PXCCapture::Device* device = capture->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 (sts<PXC_STATUS_NO_ERROR) break;
if(profiles.depth.imageInfo.width < 641 )
printf("[%d] color: %dx%d@[%d %d] depth: %dx%d@[%d %d]\n", p,
profiles.color.imageInfo.width,
profiles.color.imageInfo.height,
profiles.color.frameRate.min, profiles.color.frameRate.max,
profiles.depth.imageInfo.width,
profiles.depth.imageInfo.height,
profiles.depth.frameRate.min, profiles.color.frameRate.max);
}
device->Release();
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)<PXC_STATUS_NO_ERROR){
std::cout << "AcquireFrame Error" << std::endl;
break;
}
std::cout << "RUNNING: " << i << std::endl;
// retrieve the color and depth samples aligned
PXCCapture::Sample *sample=sm->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 <thrust/version.h>
#include <thrust/host_vector.h>
#include <thrust/device_vector.h>
#include <thrust/sort.h>
#include <iostream>
#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<int> d_vec;
thrust::host_vector<int> 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 <QMouseEvent>
#include <QGLWidget>
#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<QMouseEvent*>(event);
QKeyEvent* ke = static_cast<QKeyEvent*>(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 <iostream>
#include <QDebug>
#include <QApplication>
#include <QDir>
#include "util/gl_wrapper.h"
#include "util/OpenGL32Format.h"
#include <QGLWidget>
#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 <QFileDialog>
#include <QThread>
#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_id<datastream->size())){
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<Scalar> 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; i<worker->skeleton->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 <QMainWindow>
#include <QLayout>
#include <QLabel>
#include <QSlider>
#include <QPushButton>
#include <QMenuBar>
#include <QKeyEvent>
#include <QTimer>
#include <QApplication>
#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 <QContextMenuEvent>
#include <QWindow>
#ifdef WITH_QGLVIEWER
#include <QGLViewer/qglviewer.h>
#include <QGLViewer/camera.h>
#include <QGLViewer/manipulatedCameraFrame.h>
#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>(QuadRenderer::Color, _camera);
depth_ch = std::make_shared<QuadRenderer>(QuadRenderer::Depth, _camera);
mrenderer = std::make_shared<Cylinders_renderer>(worker->cylinders);
srenderer = std::make_shared<Cylinders_renderer>(worker->cylinders);
kinect_renderer = std::make_shared<KinectDataRenderer>();
#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 <memory>
#include <QMenu>
#ifdef WITH_QGLVIEWER
#include <QGLViewer/qglviewer.h>
typedef QGLViewer OpenGL_viewer_Superclass;
#else
#include <QGLWidget>
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<QuadRenderer> color_ch;
std::shared_ptr<QuadRenderer> depth_ch;
std::shared_ptr<Cylinders_renderer> mrenderer;
std::shared_ptr<Cylinders_renderer> srenderer;
std::shared_ptr<KinectDataRenderer> 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 <QApplication>
#include <QString>
#include <QDebug>
#include <QDir>
#include <QThread>
#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 <GL/gl.h>
#include <GL/glext.h>
#endif
#include <QApplication>
#include <QSettings>
#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 <opencv2/core/core.hpp>
#include <opencv2/highgui/highgui.hpp>
#include <opencv2/highgui/highgui_c.h>
#include <iostream>
#include <iomanip>
_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<unsigned short>(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<float> > 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<float> 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<float> 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<float> 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<float> 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<float> 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<float> 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<float> 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<float> 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<float> 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<float> 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<float> 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<float> 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<cv::Vec4f>(row, col);
synthdepth.at<ushort>(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:/Develope
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
SYMBOL INDEX (723 symbols across 160 files)
FILE: apps/colorpick/colorpick.cpp
function filter (line 25) | void filter()
function onMouse (line 71) | static void onMouse(int event, int x, int y, int f, void *)
function main (line 171) | int main(int argc, char **argv)
FILE: apps/helloworld/main.cpp
function main (line 2) | int main(int /*argc*/, char ** /*argv*/)
FILE: apps/helloworld_atb/main.cpp
class OpenGLFormat (line 18) | class OpenGLFormat : public QGLFormat{
method OpenGLFormat (line 20) | OpenGLFormat(){
class GLWidget (line 28) | class GLWidget : public QGLWidget{
method GLWidget (line 31) | GLWidget():QGLWidget(OpenGLFormat()){
method initializeGL (line 38) | void initializeGL(){
method paintGL (line 48) | void paintGL() {
function main (line 57) | int main(int argc, char* argv[]){
FILE: apps/helloworld_atb/main_new.cpp
class GLWidget (line 16) | class GLWidget : public QOpenGLWidget{
method GLWidget (line 19) | GLWidget():QOpenGLWidget(){
method initializeGL (line 26) | void initializeGL(){
method paintGL (line 39) | void paintGL() {
function main (line 47) | int main(int argc, char* argv[]){
FILE: apps/helloworld_cublas/gnuplot_i.h
function class (line 60) | class GnuplotException : public std::runtime_error
function class (line 68) | class Gnuplot
function set_GNUPlotPath (line 943) | bool Gnuplot::set_GNUPlotPath(const std::string &path)
function set_terminal_std (line 971) | void Gnuplot::set_terminal_std(const std::string &type)
function file_available (line 1946) | bool Gnuplot::file_available(const std::string &filename)
function remove_tmpfiles (line 2040) | void Gnuplot::remove_tmpfiles()
FILE: apps/helloworld_cublas/main_performance.cpp
function wait_for_key (line 36) | void wait_for_key (){
function main (line 44) | int main(int argc, char *argv[]){
FILE: apps/helloworld_cublas/main_simple.cpp
function main (line 22) | int main(int argc, char *argv[]){
FILE: apps/helloworld_cudagl/main.cpp
class GLWidget (line 29) | class GLWidget : public QGLWidget{
class OpenGLFormat (line 31) | class OpenGLFormat : public QGLFormat{
method OpenGLFormat (line 33) | OpenGLFormat(){
method GLWidget (line 41) | GLWidget():QGLWidget(OpenGLFormat()){
method init (line 44) | void init(){
function main (line 51) | int main(int argc, char* argv[]){
FILE: apps/helloworld_librealsense/main.cpp
function on_mouse_button (line 17) | static void on_mouse_button(GLFWwindow * win, int button, int action, in...
function clamp (line 21) | static double clamp(double val, double lo, double hi) { return val < lo ...
function on_cursor_pos (line 22) | static void on_cursor_pos(GLFWwindow * win, double x, double y)
function main (line 33) | int main() try
FILE: apps/helloworld_opencv/main.cpp
function main (line 9) | int main(int, char **) {
FILE: apps/helloworld_openmp/main.cpp
function main (line 6) | int main (int argc, char *argv[])
FILE: apps/helloworld_openni/main.cpp
function main (line 7) | int main(int /*argc*/, char ** /*argv*/){
FILE: apps/helloworld_qglviewer/main.cpp
class Viewer (line 4) | class Viewer : public QGLViewer {
method draw (line 5) | void draw() {
method init (line 27) | void init() {
function main (line 32) | int main(int argc, char* argv[]){
FILE: apps/helloworld_qtopengl/main.cpp
class OpenGLFormat (line 7) | class OpenGLFormat : public QGLFormat{
method OpenGLFormat (line 9) | OpenGLFormat(){
class GLWidget (line 17) | class GLWidget : public QGLWidget{
method GLWidget (line 20) | GLWidget():QGLWidget(OpenGLFormat()){
method initializeGL (line 23) | void initializeGL(){
method paintGL (line 29) | void paintGL() {
function main (line 36) | int main(int argc, char* argv[]){
FILE: apps/helloworld_realsense/main.cpp
function main (line 11) | int main(int /*argc*/, char ** /*argv*/){
class MyHandler (line 43) | class MyHandler : public PXCSenseManager::Handler {
method pxcStatus (line 45) | virtual pxcStatus PXCAPI OnNewSample(pxcUID, PXCCapture::Sample *sampl...
function main (line 66) | int main(int /*argc*/, char ** /*argv*/){
function main (line 103) | int main(int /*argc*/, char ** /*argv*/){
function main (line 147) | int main(int /*argc*/, char ** /*argv*/){
FILE: apps/htrack_atb/AntTweakBarEventFilter.h
function class (line 9) | class AntTweakBarEventFilter : public QObject{
FILE: apps/htrack_atb/main.cpp
class GLWidget (line 20) | class GLWidget : public QGLWidget{
method GLWidget (line 31) | GLWidget(Worker* worker, DataStream * datastream, SolutionStream * sol...
method initializeGL (line 48) | void initializeGL(){
method paintGL (line 67) | void paintGL() {
method reload_model (line 92) | void reload_model(){
method keyPressEvent (line 104) | void keyPressEvent(QKeyEvent *event){
function main (line 150) | int main(int argc, char* argv[]){
FILE: apps/htrack_qt/Main_window.cpp
function connect (line 61) | connect(slider, SIGNAL(sliderMoved(int)), this, SLOT(display_frame(int)));
FILE: apps/htrack_qt/Main_window.h
function class (line 15) | class Main_window : public QMainWindow{
FILE: apps/htrack_qt/OpenGL_viewer.h
type QGLViewer (line 10) | typedef QGLViewer OpenGL_viewer_Superclass;
type QGLWidget (line 13) | typedef QGLWidget OpenGL_viewer_Superclass;
function class (line 16) | class OpenGL_viewer : public OpenGL_viewer_Superclass {
FILE: apps/htrack_qt/main.cpp
function main (line 23) | int main(int argc, char* argv[]) {
FILE: apps/synthgen/synthgen.cpp
function record_sequence (line 34) | int record_sequence(int argc, char* argv[]){
function main (line 101) | int main(int argc, char* argv[]){
FILE: cudax/CublasHelper.h
function namespace (line 13) | namespace cudax {
FILE: cudax/CudaHelper.h
function namespace (line 10) | namespace cudax {
FILE: cudax/CudaTimer.h
function namespace (line 7) | namespace cudax {
FILE: cudax/KinectCamera.h
function namespace (line 7) | namespace cudax {
FILE: cudax/Kinematic.h
function namespace (line 6) | namespace cudax {
FILE: cudax/MeshGrid.h
function namespace (line 6) | namespace cudax {
type GetPixelIndex (line 53) | struct GetPixelIndex
FILE: cudax/OpenCVOutputBuffer.h
function namespace (line 5) | namespace cudax {
FILE: cudax/PixelIndexer.h
function namespace (line 10) | namespace cudax {
FILE: cudax/Timer.h
function namespace (line 12) | namespace cudax {
FILE: cudax/externs.h
function namespace (line 8) | namespace energy{namespace fitting{struct Settings;}}
type CustomJointInfo (line 9) | struct CustomJointInfo
type ChainElement (line 10) | struct ChainElement
type uchar (line 11) | typedef unsigned char uchar;
function namespace (line 14) | namespace cudax {
FILE: cudax/functors/ClosestPoint.h
function namespace (line 5) | namespace cudax {
FILE: cudax/functors/ComputeJacobianRow.h
function namespace (line 6) | namespace cudax {
function __device__ (line 29) | inline __device__ int constraint_index(const MeshGrid::Elem& off){ retur...
function __device__ (line 31) | __device__
FILE: cudax/functors/ComputeJacobianRowDepth.h
function namespace (line 6) | namespace cudax {
FILE: cudax/functors/ComputeJacobianRowExtraClosedForm.h
function namespace (line 7) | namespace cudax {
FILE: cudax/functors/ComputeJacobianRowPush.h
function namespace (line 5) | namespace cudax {
FILE: cudax/functors/ComputeJacobianRowSilho.h
function namespace (line 6) | namespace cudax {
FILE: cudax/functors/CopyOver.h
function namespace (line 6) | namespace cudax {
FILE: cudax/functors/ImageGradient.h
function namespace (line 6) | namespace cudax {
FILE: cudax/functors/ImageGradientDepth.h
function namespace (line 6) | namespace cudax {
FILE: cudax/functors/ImageHighlighter.h
function namespace (line 8) | namespace cudax {
FILE: cudax/functors/IsMatchingDepth.h
function namespace (line 6) | namespace cudax {
FILE: cudax/functors/IsSilhouette.h
function namespace (line 5) | namespace cudax {
type IsSensorSilhouette (line 19) | struct IsSensorSilhouette{
FILE: cudax/functors/IsSilhouetteBoundary.h
function namespace (line 5) | namespace cudax {
FILE: cudax/functors/IsTopLeft3x3Block.h
function namespace (line 5) | namespace cudax {
FILE: cudax/functors/SkeletonJacobian.h
function namespace (line 8) | namespace cudax {
FILE: cudax/helper_cuda.h
function __getLastCudaError (line 763) | inline void __getLastCudaError(const char *errorMessage, const char *fil...
function _ConvertSMVer2Cores (line 782) | inline int _ConvertSMVer2Cores(int major, int minor)
function gpuDeviceInit (line 826) | inline int gpuDeviceInit(int devID)
function gpuGetMaxGflopsDeviceId (line 873) | inline int gpuGetMaxGflopsDeviceId()
function findCudaDevice (line 957) | inline int findCudaDevice(int argc, const char **argv)
function checkCudaCapabilities (line 997) | inline bool checkCudaCapabilities(int major_version, int minor_version)
FILE: cudax/kernel.h
function namespace (line 17) | namespace cudax {
FILE: cudax/kernel_debug.h
type ConstraintTypeFunctor (line 10) | struct ConstraintTypeFunctor{
function type (line 21) | int type(const MeshGrid::Elem& off){ return cnstr_indexes[off.z].x; }
function __device__ (line 22) | __device__ int constraint_index(const MeshGrid::Elem& off){ return cnstr...
function __device__ (line 24) | __device__
function kernel_constraint_type_image (line 51) | void kernel_constraint_type_image(uchar *opencv_image, int w, int h){
type SetZeroFunctor (line 61) | struct SetZeroFunctor{
function kernel_simplify_jacobian (line 74) | void kernel_simplify_jacobian(int n_total){
function kernel_store_closedform_corresp (line 81) | void kernel_store_closedform_corresp(int num)
function kernel_copy_closedform_corresp (line 98) | void kernel_copy_closedform_corresp(thrust::host_vector<float> &H_closed...
FILE: cudax/kernel_init.h
function kernel_init (line 10) | void kernel_init(energy::fitting::Settings* _settings, int H_width, int ...
function kernel_cleanup (line 62) | void kernel_cleanup(){
function kernel_memory_tests (line 80) | void kernel_memory_tests(){
FILE: cudax/kernel_upload.h
function kernel_upload_dtform_idxs (line 7) | void kernel_upload_dtform_idxs(int* H_dtform_idxs){
function kernel_upload_sensor_data (line 11) | void kernel_upload_sensor_data(uchar* H_silhouette_sensor)
function kernel_upload_kinematic (line 16) | void kernel_upload_kinematic(const JointTransformations& H_jointinfos, c...
function kernel_upload_cylinders (line 31) | void kernel_upload_cylinders(const float* H_cylinders)
FILE: openni/include/Driver/OniDriverAPI.h
function namespace (line 30) | namespace oni { namespace driver {
function ONI_C_API_EXPORT (line 185) | ONI_C_API_EXPORT void oniDriverCreate(OniDriverServices* driverServices)...
function ONI_C_API_EXPORT (line 188) | ONI_C_API_EXPORT void oniDriverDestroy() \
function ONI_C_API_EXPORT (line 193) | ONI_C_API_EXPORT OniStatus oniDriverInitialize(oni::driver::DeviceConnec...
function ONI_C_API_EXPORT (line 201) | ONI_C_API_EXPORT OniStatus oniDriverTryDevice(const char* uri) ...
function ONI_C_API_EXPORT (line 207) | ONI_C_API_EXPORT oni::driver::DeviceBase* oniDriverDeviceOpen(const char...
function ONI_C_API_EXPORT (line 211) | ONI_C_API_EXPORT void oniDriverDeviceClose(oni::driver::DeviceBase* pDev...
function ONI_C_API_EXPORT (line 216) | ONI_C_API_EXPORT OniStatus oniDriverDeviceGetSensorInfoList(oni::driver:...
function ONI_C_API_EXPORT (line 222) | ONI_C_API_EXPORT oni::driver::StreamBase* oniDriverDeviceCreateStream(on...
function ONI_C_API_EXPORT (line 228) | ONI_C_API_EXPORT void oniDriverDeviceDestroyStream(oni::driver::DeviceBa...
function ONI_C_API_EXPORT (line 233) | ONI_C_API_EXPORT OniStatus oniDriverDeviceSetProperty(oni::driver::Devic...
function ONI_C_API_EXPORT (line 238) | ONI_C_API_EXPORT OniStatus oniDriverDeviceGetProperty(oni::driver::Devic...
function ONI_C_API_EXPORT (line 243) | ONI_C_API_EXPORT OniBool oniDriverDeviceIsPropertySupported(oni::driver:...
function ONI_C_API_EXPORT (line 247) | ONI_C_API_EXPORT void oniDriverDeviceSetPropertyChangedCallback(oni::dri...
function ONI_C_API_EXPORT (line 252) | ONI_C_API_EXPORT void oniDriverDeviceNotifyAllProperties(oni::driver::De...
function ONI_C_API_EXPORT (line 256) | ONI_C_API_EXPORT OniStatus oniDriverDeviceInvoke(oni::driver::DeviceBase...
function ONI_C_API_EXPORT (line 261) | ONI_C_API_EXPORT OniBool oniDriverDeviceIsCommandSupported(oni::driver::...
function ONI_C_API_EXPORT (line 265) | ONI_C_API_EXPORT OniStatus oniDriverDeviceTryManualTrigger(oni::driver::...
function ONI_C_API_EXPORT (line 269) | ONI_C_API_EXPORT OniBool oniDriverDeviceIsImageRegistrationModeSupported...
function ONI_C_API_EXPORT (line 276) | ONI_C_API_EXPORT OniStatus oniDriverStreamSetProperty(oni::driver::Strea...
function ONI_C_API_EXPORT (line 281) | ONI_C_API_EXPORT OniStatus oniDriverStreamGetProperty(oni::driver::Strea...
function ONI_C_API_EXPORT (line 286) | ONI_C_API_EXPORT OniBool oniDriverStreamIsPropertySupported(oni::driver:...
function ONI_C_API_EXPORT (line 290) | ONI_C_API_EXPORT void oniDriverStreamSetPropertyChangedCallback(oni::dri...
function ONI_C_API_EXPORT (line 295) | ONI_C_API_EXPORT void oniDriverStreamNotifyAllProperties(oni::driver::St...
function ONI_C_API_EXPORT (line 299) | ONI_C_API_EXPORT OniStatus oniDriverStreamInvoke(oni::driver::StreamBase...
function ONI_C_API_EXPORT (line 304) | ONI_C_API_EXPORT OniBool oniDriverStreamIsCommandSupported(oni::driver::...
function ONI_C_API_EXPORT (line 309) | ONI_C_API_EXPORT OniStatus oniDriverStreamStart(oni::driver::StreamBase*...
function ONI_C_API_EXPORT (line 313) | ONI_C_API_EXPORT void oniDriverStreamStop(oni::driver::StreamBase* pStre...
function ONI_C_API_EXPORT (line 318) | ONI_C_API_EXPORT void oniDriverStreamSetNewFrameCallback(oni::driver::St...
function ONI_C_API_EXPORT (line 324) | ONI_C_API_EXPORT void oniDriverStreamAddRefToFrame(oni::driver::StreamBa...
function ONI_C_API_EXPORT (line 329) | ONI_C_API_EXPORT void oniDriverStreamReleaseFrame(oni::driver::StreamBas...
function ONI_C_API_EXPORT (line 334) | ONI_C_API_EXPORT OniStatus oniDriverStreamConvertDepthToColorCoordinates...
function ONI_C_API_EXPORT (line 340) | ONI_C_API_EXPORT void* oniDriverEnableFrameSync(oni::driver::StreamBase*...
function ONI_C_API_EXPORT (line 345) | ONI_C_API_EXPORT void oniDriverDisableFrameSync(void* frameSyncGroup) ...
FILE: openni/include/Driver/OniDriverTypes.h
type OniGeneralBuffer (line 29) | typedef struct
type OniDriverFrame (line 35) | typedef struct
type OniDriverServices (line 43) | struct OniDriverServices
FILE: openni/include/NiTE.h
function namespace (line 16) | namespace nite {
function set (line 38) | void set(float x, float y, float z)
function operator (line 51) | bool operator==(const Point3f& other) const
function operator (line 55) | bool operator!=(const Point3f& other) const
function class (line 61) | class Plane : public NitePlane
function class (line 75) | class Quaternion : public NiteQuaternion
function class (line 91) | class BoundingBox : public NiteBoundingBox
function setData (line 122) | void setData(int size, T* data) {m_data = data; m_size = size;}
function T (line 126) | const T& operator[](int index) const {return m_data[index];}
type UserId (line 150) | typedef short int UserId;
function class (line 155) | class PoseData : protected NitePoseData
function class (line 182) | class UserMap : private NiteUserMap
function class (line 208) | class SkeletonJoint : private NiteSkeletonJoint
function class (line 235) | class Skeleton : private NiteSkeleton
function class (line 250) | class UserData : private NiteUserData
function PoseData (line 287) | const PoseData& getPose(PoseType type) const {return (const PoseData&)po...
function class (line 291) | class UserTrackerFrameRef
function setReference (line 375) | void setReference(NiteUserTrackerHandle userTrackerHandle, NiteUserTrack...
function class (line 394) | class UserTracker
function destroy (line 452) | void destroy()
function Status (line 462) | Status readFrame(UserTrackerFrameRef* pFrame)
function Status (line 477) | Status setSkeletonSmoothingFactor(float factor)
function getSkeletonSmoothingFactor (line 481) | float getSkeletonSmoothingFactor() const
function Status (line 493) | Status startSkeletonTracking(UserId id)
function stopSkeletonTracking (line 498) | void stopSkeletonTracking(UserId id)
function Status (line 504) | Status startPoseDetection(UserId user, PoseType type)
function stopPoseDetection (line 510) | void stopPoseDetection(UserId user, PoseType type)
function addNewFrameListener (line 515) | void addNewFrameListener(NewFrameListener* pListener)
function removeNewFrameListener (line 520) | void removeNewFrameListener(NewFrameListener* pListener)
function Status (line 531) | Status convertJointCoordinatesToDepth(float x, float y, float z, float* ...
function Status (line 540) | Status convertDepthCoordinatesToJoint(int x, int y, int z, float* pOutX,...
type HandId (line 551) | typedef short int HandId;
function class (line 553) | class GestureData : protected NiteGestureData
function class (line 563) | class HandData : protected NiteHandData
function class (line 576) | class HandTrackerFrameRef
function class (line 649) | class HandTracker
function destroy (line 703) | void destroy()
function Status (line 713) | Status readFrame(HandTrackerFrameRef* pFrame)
function Status (line 728) | Status setSmoothingFactor(float factor)
function getSmoothingFactor (line 732) | float getSmoothingFactor() const
function Status (line 747) | Status startHandTracking(const Point3f& position, HandId* pNewHandId)
function stopHandTracking (line 752) | void stopHandTracking(HandId id)
function addNewFrameListener (line 757) | void addNewFrameListener(NewFrameListener* pListener)
function removeNewFrameListener (line 762) | void removeNewFrameListener(NewFrameListener* pListener)
function Status (line 769) | Status startGestureDetection(GestureType type)
function stopGestureDetection (line 774) | void stopGestureDetection(GestureType type)
function Status (line 784) | Status convertHandCoordinatesToDepth(float x, float y, float z, float* p...
function Status (line 793) | Status convertDepthCoordinatesToHand(int x, int y, int z, float* pOutX, ...
function class (line 806) | class NiTE
FILE: openni/include/NiteCEnums.h
type NiteJointType (line 12) | typedef enum
type NiteSkeletonState (line 35) | typedef enum
type NiteUserState (line 54) | typedef enum
type NiteStatus (line 65) | typedef enum
type NitePoseType (line 73) | typedef enum
type NitePoseState (line 79) | typedef enum
type NiteGestureType (line 89) | typedef enum
type NiteGestureState (line 97) | typedef enum
type NiteHandState (line 105) | typedef enum
FILE: openni/include/NiteCTypes.h
type NiteUserId (line 14) | typedef short int NiteUserId;
type NiteUserTracker (line 16) | struct NiteUserTracker
type NitePoint3f (line 22) | typedef struct
type NiteQuaternion (line 28) | typedef struct
type NiteSkeletonJoint (line 34) | typedef struct
type NiteBoundingBox (line 49) | typedef struct
type NitePoseData (line 55) | typedef struct
type NiteSkeleton (line 62) | typedef struct
type NiteUserData (line 69) | typedef struct
type NiteUserMap (line 83) | typedef struct
type NitePlane (line 94) | typedef struct
type NiteUserTrackerFrame (line 101) | typedef struct
type NiteUserTrackerCallbacks (line 122) | typedef struct
type NiteHandId (line 128) | typedef short int NiteHandId;
type NiteHandData (line 131) | typedef struct
type NiteGestureData (line 139) | typedef struct
type NiteHandTrackerFrame (line 147) | typedef struct
type NiteHandTrackerCallbacks (line 167) | typedef struct
type NiteHandTracker (line 192) | struct NiteHandTracker
FILE: openni/include/NiteEnums.h
type JointType (line 12) | typedef enum
type SkeletonState (line 35) | typedef enum
type Status (line 54) | typedef enum
type PoseType (line 62) | typedef enum
type GestureType (line 69) | typedef enum
FILE: openni/include/OniCEnums.h
type OniStatus (line 25) | typedef enum
type OniSensorType (line 38) | typedef enum
type OniPixelFormat (line 47) | typedef enum
type OniDeviceState (line 63) | typedef enum
type OniImageRegistrationMode (line 71) | typedef enum
FILE: openni/include/OniCTypes.h
type OniBool (line 28) | typedef int OniBool;
type OniCallbackHandleImpl (line 40) | struct OniCallbackHandleImpl
type OniCallbackHandleImpl (line 41) | struct OniCallbackHandleImpl
type OniHardwareVersion (line 59) | typedef int OniHardwareVersion;
type OniVideoMode (line 62) | typedef struct
type OniSensorInfo (line 71) | typedef struct
type OniDeviceInfo (line 79) | typedef struct
type _OniDevice (line 88) | struct _OniDevice
type _OniDevice (line 89) | typedef _OniDevice* OniDeviceHandle;
type _OniStream (line 91) | struct _OniStream
type _OniStream (line 92) | typedef _OniStream* OniStreamHandle;
type _OniRecorder (line 94) | struct _OniRecorder
type _OniRecorder (line 95) | typedef _OniRecorder* OniRecorderHandle;
type OniFrame (line 98) | typedef struct
type OniDeviceCallbacks (line 123) | typedef struct
type OniCropping (line 130) | typedef struct
type OniDepthPixel (line 143) | typedef uint16_t OniDepthPixel;
type OniGrayscale16Pixel (line 148) | typedef uint16_t OniGrayscale16Pixel;
function _ONI_DECLARE_YUV422_PIXEL (line 164) | _ONI_DECLARE_RGB888_PIXEL(OniRGB888Pixel)
function pack (line 184) | _ONI_DECLARE_YUV422_PIXEL(OniYUV422DoublePixel)
FILE: openni/include/OniEnums.h
function namespace (line 24) | namespace kinect
FILE: openni/include/OniProperties.h
function namespace (line 24) | namespace kinect
FILE: openni/include/OpenNI.h
function namespace (line 34) | namespace kinect
function clear (line 128) | void clear()
function class (line 156) | class VideoMode : private OniVideoMode
function setPixelFormat (line 222) | void setPixelFormat(PixelFormat format) { this->pixelFormat = (OniPixelF...
function setResolution (line 231) | void setResolution(int resolutionX, int resolutionY)
function setFps (line 243) | void setFps(int fps) { this->fps = fps; }
function class (line 267) | class SensorInfo
function class (line 325) | class DeviceInfo : private OniDeviceInfo
function class (line 359) | class VideoFrameRef
function class (line 603) | class VideoStream
function getMinPixelValue (line 886) | int getMinPixelValue() const
function getCropping (line 914) | bool getCropping(int* pOriginX, int* pOriginY, int* pWidth, int* pHeight...
function Status (line 942) | Status setCropping(int originX, int originY, int width, int height)
function Status (line 957) | Status resetCropping()
function getMirroringEnabled (line 968) | bool getMirroringEnabled() const
function Status (line 984) | Status setMirroringEnabled(bool isEnabled)
function getHorizontalFieldOfView (line 993) | float getHorizontalFieldOfView() const
function isPropertySupported (line 1047) | bool isPropertySupported(int propertyId) const
function Status (line 1066) | Status invoke(int commandId, void* data, int dataSize)
function isCommandSupported (line 1096) | bool isCommandSupported(int commandId) const
function _setHandle (line 1109) | void _setHandle(OniStreamHandle stream)
function class (line 1147) | class Device
function Status (line 1382) | Status setImageRegistrationMode(ImageRegistrationMode mode)
function Status (line 1415) | Status setDepthColorSyncEnabled(bool isEnabled)
function isPropertySupported (line 1468) | bool isPropertySupported(int propertyId) const
function Status (line 1482) | Status invoke(int commandId, const void* data, int dataSize)
function isCommandSupported (line 1507) | bool isCommandSupported(int commandId) const
function clearSensors (line 1516) | void clearSensors()
function Status (line 1524) | Status _setHandle(OniDeviceHandle deviceHandle)
function class (line 1561) | class PlaybackControl
function class (line 1740) | class CameraSettings
function class (line 1807) | class OpenNI
function class (line 2165) | class CoordinateConverter
function class (line 2264) | class Recorder
function Status (line 2342) | Status start()
function stop (line 2354) | void stop()
function destroy (line 2365) | void destroy()
function Status (line 2390) | Status VideoStream::create(const Device& device, SensorType sensorType)
function destroy (line 2409) | void VideoStream::destroy()
function Status (line 2429) | Status Device::open(const char* uri)
function close (line 2448) | void Device::close()
FILE: openni/include/PS1080.h
type XnFWVer (line 128) | typedef enum
type XnSensorVer (line 147) | typedef enum {
type XnHWVer (line 155) | typedef enum {
type XnChipVer (line 166) | typedef enum {
type XnCMOSType (line 173) | typedef enum
type XnIOImageFormats (line 181) | typedef enum
type XnIODepthFormats (line 193) | typedef enum
type XnParamResetType (line 202) | typedef enum
type XnSensorUsbInterface (line 209) | typedef enum XnSensorUsbInterface
type XnProcessingType (line 216) | typedef enum XnProcessingType
type XnCroppingMode (line 223) | typedef enum XnCroppingMode
type XnSDKVersion (line 239) | typedef struct XnSDKVersion
type XnVersions (line 247) | typedef struct {
type XnInnerParamData (line 263) | typedef struct
type XnDepthAGCBin (line 269) | typedef struct XnDepthAGCBin
type XnControlProcessingData (line 276) | typedef struct XnControlProcessingData
type XnAHBData (line 282) | typedef struct XnAHBData
type XnPixelRegistration (line 289) | typedef struct XnPixelRegistration
type XnLedState (line 300) | typedef struct XnLedState
FILE: tracker/Calibration/Calibration.cpp
function file_exists (line 10) | inline bool file_exists(const std::string& name){
FILE: tracker/Calibration/Calibration.h
function class (line 8) | class Calibration{
FILE: tracker/Calibration/Skeleton_IO.h
function class (line 5) | class Skeleton_IO{
FILE: tracker/Data/Camera.cpp
function Vector3 (line 82) | Vector3 Camera::depth_to_world(Real i, Real j, Real depth){
function Vector3 (line 91) | Vector3 Camera::unproject(int i, int j, Scalar depth){
function Vector3 (line 95) | Vector3 Camera::pixel_to_image_plane(int i, int j){
function Vector2 (line 101) | Vector2 Camera::world_to_image(const Vector3& wrld){
function Matrix_2x3 (line 131) | Matrix_2x3 Camera::projection_jacobian(const Vector3 &p){
FILE: tracker/Data/Camera.h
type CAMERAMODE (line 6) | enum CAMERAMODE{ INVALID=-1, QVGA, VGA, Tompson, Chen, Tang, Intel}
function class (line 8) | class Camera{
FILE: tracker/Data/DataFrame.h
type DepthPixel (line 6) | typedef unsigned short DepthPixel;
type cv (line 7) | typedef cv::Vec3b ColorPixel;
function point_at_pixel (line 9) | struct DataFrame{
function Real (line 24) | Real depth_at_pixel(const Vector2i& pixel /*row,col*/){
function Real (line 28) | Real depth_at_pixel(int x, int y){
FILE: tracker/Data/DataStream.cpp
function DataFrame (line 42) | DataFrame&DataStream::get_frame(int id){
function QString (line 71) | QString DataStream::get_prefix()
function QString (line 76) | QString DataStream::get_basename()
function foreach (line 100) | foreach(const DataFrame* frame, frames){
FILE: tracker/Data/DataStream.h
function class (line 10) | class DataStream{
function is_synthetic (line 39) | bool is_synthetic(){ return get_prefix().startsWith("synth", Qt::CaseIns...
function is_tompson (line 40) | bool is_tompson(){ return get_prefix().startsWith("tompson", Qt::CaseIns...
function is_tang (line 41) | bool is_tang(){ return get_prefix().startsWith("tang", Qt::CaseInsensiti...
function is_chen (line 42) | bool is_chen(){ return get_prefix().startsWith("chen", Qt::CaseInsensiti...
function is_colorglove (line 43) | bool is_colorglove(){ return get_prefix().startsWith("colorglove", Qt::C...
function is_legacy_maschroe (line 44) | bool is_legacy_maschroe(){ return get_basename().startsWith("maschroe_se...
function is_melax (line 45) | bool is_melax(){ return _filename.endsWith(".bin"); }
function is_sridhar (line 46) | bool is_sridhar(){ return get_prefix().startsWith("sridhar", Qt::CaseIns...
FILE: tracker/Data/SolutionStream.h
function class (line 10) | class SolutionStream{
function setValid (line 18) | void setValid(){
function invalidate (line 21) | void invalidate(int fid){
function reserve (line 25) | void reserve(int size){
function resize (line 29) | void resize(int num_frames){
function set (line 35) | void set(int frame_id, const std::vector<Scalar>& theta ){
function save (line 49) | void save(QString filename){
function load (line 75) | void load(QString filename){
FILE: tracker/Data/TextureColor8UC3.h
function class (line 5) | class ColorTexture8UC3{
FILE: tracker/Data/TextureDepth16UC1.h
function class (line 6) | class DepthTexture16UC1 {
function load (line 34) | void load(GLvoid* pixels, int fid){
function check_loaded (line 43) | bool check_loaded(int fid){ return this->fid == fid; }
FILE: tracker/DataStructure/CustomJointInfo.h
type CustomJointInfo (line 12) | struct CustomJointInfo{
type std (line 24) | typedef std::vector<CustomJointInfo> JointTransformations;
type ChainElement (line 53) | struct ChainElement{ int data[CHAIN_MAX_LENGTH]; }
type std (line 54) | typedef std::vector<ChainElement> KinematicChain;
function clear_kinematic (line 56) | inline void clear_kinematic(KinematicChain& chain){
FILE: tracker/DataStructure/SkeletonSerializer.cpp
function Matrix_3xN (line 70) | Matrix_3xN SkeletonSerializer::jacobian(int joint_id_, const Vector3 &po...
function Vector3 (line 153) | inline Vector3 toVec3(float a[3]){ return Vector3(a[0], a[1], a[2]); }
FILE: tracker/DataStructure/SkeletonSerializer.h
function class (line 10) | class SkeletonSerializer : public Skeleton{
FILE: tracker/Detection/DetectionStream.h
function size_t_comparator (line 16) | inline bool size_t_comparator(std::pair<size_t, size_t> a, std::pair<siz...
function PalmIndices (line 23) | struct PalmIndices {
type FingerIndices (line 30) | struct FingerIndices {
function initialize_permutations_vector (line 134) | void initialize_permutations_vector() {
function initialize_directions_vector (line 160) | void initialize_directions_vector() {
function get_num_permutations (line 192) | size_t get_num_permutations(){
function VectorN (line 195) | VectorN get_permutation(size_t i){
function get_num_directions (line 198) | size_t get_num_directions(){
function VectorN (line 203) | VectorN get_direction(size_t i){
function get_num_point_targets (line 206) | size_t get_num_point_targets(){
function get_num_line_targets (line 209) | size_t get_num_line_targets(){
function get_num_plane_targets (line 212) | size_t get_num_plane_targets(){
function get_num_direction_targets (line 215) | size_t get_num_direction_targets(){
function Vector3 (line 227) | Vector3 get_point_target(size_t i){
function Vector3 (line 230) | Vector3 get_line_target_start(size_t i){
function Vector3 (line 233) | Vector3 get_line_target_end(size_t i){
function Vector3 (line 236) | Vector3 get_plane_target_origin(){
function Vector3 (line 239) | Vector3 get_direction_target(size_t direction_number, size_t index, size...
function Vector3 (line 248) | Vector3 get_line_target_normal(size_t i){
function Vector3 (line 255) | Vector3 get_plane_target_normal(){
function Vector3 (line 262) | Vector3 get_point_source(size_t id){
function Vector3 (line 269) | Vector3 get_line_source(size_t id){
function Vector3 (line 274) | Vector3 get_plane_source(size_t j){
function get_plane_id (line 301) | size_t get_plane_id(){
function get_num_targets (line 330) | size_t get_num_targets(){
function Vector3 (line 333) | Vector3 get_palm_center(){
function set_point_targets (line 344) | void set_point_targets(const Matrix_MxN & point_targets) {
function set_line_targets (line 348) | void set_line_targets(const Matrix_MxN & line_targets) {
function set_plane_targets (line 352) | void set_plane_targets(const VectorN & plane_targets) {
function set_direction_targets (line 356) | void set_direction_targets(const Matrix_MxN & direction_targets) {
function set_point_targets_indices (line 360) | void set_point_targets_indices(const std::vector<size_t> & point_targets...
function set_line_targets_indices (line 364) | void set_line_targets_indices(const std::vector<size_t> & line_targets_i...
function set_direction_targets_indices (line 368) | void set_direction_targets_indices(const std::vector<size_t> & direction...
function set_num_targets (line 372) | void set_num_targets(size_t num_targets){
function set_num_directions (line 376) | void set_num_directions(size_t num_directions){
function set_radial_order (line 380) | void set_radial_order(const std::vector<size_t> & radial_order) {
function set_linear_order (line 384) | void set_linear_order(const std::vector<size_t> & linear_order) {
function set_thumb_index (line 388) | void set_thumb_index(int thumb_index){
function get_thumb_index (line 391) | int get_thumb_index(){
function set_hand_side (line 394) | void set_hand_side(int hand_side){
function update_permutations_vector (line 398) | void update_permutations_vector() {
function display_current_constraints (line 452) | void display_current_constraints(){
FILE: tracker/Detection/FindFingers.cpp
function float_comparator (line 28) | inline bool float_comparator(std::pair<Scalar, size_t> a, std::pair<Scal...
function Matrix_MxN (line 48) | Matrix_MxN FindFingers::crop_image(const Matrix_MxN &depth) {
function Matrix_MxN (line 128) | Matrix_MxN FindFingers::downsample_image(const Matrix_MxN &depth) {
function Scalar (line 736) | Scalar FindFingers::get_median_depth(const Matrix_MxN &depth, Vector2 uv) {
function Matrix_MxN (line 872) | Matrix_MxN FindFingers::process_input() {
FILE: tracker/Detection/FindFingers.h
type Eigen (line 9) | typedef Eigen::Matrix<size_t, 2, 1> Vector2s;
type Eigen (line 10) | typedef Eigen::Matrix<size_t, Eigen::Dynamic, 1> VectorNs;
type Eigen (line 11) | typedef Eigen::Matrix<bool, Eigen::Dynamic, Eigen::Dynamic> Matrix_MxN_b;
function class (line 14) | class FindFingers {
FILE: tracker/Detection/QianDetection.cpp
function Scalar (line 301) | Scalar QianDetection::compute_detection_energy(size_t permutation, size_...
FILE: tracker/Detection/QianDetection.h
function class (line 5) | class QianDetection {
FILE: tracker/Detection/TrivialDetector.h
function class (line 6) | class TrivialDetector{
FILE: tracker/Detection/matlab_helpers.h
function namespace (line 4) | namespace matlab{
FILE: tracker/Energy/Collision.cpp
type geometry (line 14) | namespace geometry{
function segment_to_segment_distance (line 23) | std::pair<Vector3, Vector3> segment_to_segment_distance( std::pair<Ve...
function ray_triangle_intersection (line 117) | bool ray_triangle_intersection(Vector3 O, Vector3 D, Vector3 P1, Vecto...
function Vector3 (line 187) | Vector3 transform_point_position(Vector3 point, Mat4f transformation){
function get_axis_endpoints (line 196) | std::pair<Vector3, Vector3> get_axis_endpoints(Segment segment){
function debug_display_phalange (line 207) | void debug_display_phalange(std::vector<Segment> segments) {
function debug_display_constraints (line 253) | void debug_display_constraints(std::pair<Vector3, Vector3> shortest_path...
function Matrix_MxN (line 270) | Matrix_MxN create_adjacency_matrix(Skeleton* skeleton, std::vector<Segm...
function create_distance_matrix (line 295) | std::vector<std::vector<std::pair<Vector3, Vector3>>> create_distance_ma...
type energy (line 327) | namespace energy{
function Matrix_3xN (line 329) | Matrix_3xN jacobian_block(Collision::Point point, SkeletonSerializer* ...
function Scalar (line 389) | Scalar Collision::create_collision_constraints(){
FILE: tracker/Energy/Collision.h
function namespace (line 7) | namespace energy{
FILE: tracker/Energy/Damping.cpp
type energy (line 5) | namespace energy{
FILE: tracker/Energy/Damping.h
function namespace (line 7) | namespace energy{
FILE: tracker/Energy/Energy.cpp
type energy (line 3) | namespace energy{
function VectorN (line 52) | VectorN Energy::solve(LinearSystem &system){
FILE: tracker/Energy/Energy.h
type TrackingError (line 4) | struct TrackingError{
function namespace (line 10) | namespace energy{
FILE: tracker/Energy/Fitting.cpp
type MappedResource (line 21) | struct MappedResource {
type cudaGraphicsResource (line 22) | struct cudaGraphicsResource
method init (line 26) | void init(GLuint texid){
method cleanup (line 30) | void cleanup(){
method cudaArray (line 34) | cudaArray* bind() {
method unbind (line 39) | void unbind() {
FILE: tracker/Energy/Fitting.h
type MappedResource (line 5) | struct MappedResource
function namespace (line 7) | namespace energy{
FILE: tracker/Energy/Fitting/Settings.h
function namespace (line 6) | namespace energy{
FILE: tracker/Energy/Fitting/TrackingMonitor.h
function class (line 6) | class TrackingMonitor{
FILE: tracker/Energy/JointLimits.h
function namespace (line 7) | namespace energy{
FILE: tracker/Energy/PoseSpace.cpp
type Eigen (line 14) | namespace Eigen{
function write_binary (line 16) | void write_binary(std::string filename, const Matrix& matrix){
function read_binary (line 25) | void read_binary(std::string filename, Matrix& matrix){
function read_binary_vector (line 36) | void read_binary_vector(std::string filename, Vector& vector){
type energy (line 46) | namespace energy{
FILE: tracker/Energy/PoseSpace.h
function namespace (line 7) | namespace energy{
FILE: tracker/Energy/Temporal.cpp
class SolutionQueue (line 7) | class SolutionQueue{
method valid (line 13) | bool valid(int id){
method set (line 18) | void set(int id, const Solution &s){
method update (line 21) | void update(int id, const Solution &s){
type energy (line 34) | namespace energy{
function extract_positions (line 61) | void extract_positions(
FILE: tracker/Energy/Temporal.h
function namespace (line 8) | namespace energy{
FILE: tracker/Energy/Wristband.cpp
function draw_dot (line 11) | void draw_dot( cv::Mat& bw, const Vector2& c, Derived color ){ cv::circl...
function draw_circle (line 12) | void draw_circle( cv::Mat& bw, const Vector2& c, Derived color ){ cv::ci...
function draw_line (line 13) | inline void draw_line( cv::Mat& bw, const Vector2& p1, const Vector2& p2...
FILE: tracker/Energy/Wristband.h
function namespace (line 7) | namespace energy{
FILE: tracker/ForwardDeclarations.h
type DataFrame (line 7) | struct DataFrame
function namespace (line 46) | namespace cv{ class Mat; }
function namespace (line 47) | namespace cudax{class CudaHelper;}
FILE: tracker/HandFinder/HandFinder.h
function class (line 7) | class HandFinder{
FILE: tracker/HandFinder/connectedComponents.cpp
type cv (line 47) | namespace cv{
type connectedcomponents (line 48) | namespace connectedcomponents{
type NoOp (line 50) | struct NoOp{
method NoOp (line 51) | NoOp(){
method init (line 53) | void init(int /*labels*/){
method finish (line 61) | void finish(){}
type Point2ui64 (line 63) | struct Point2ui64{
method Point2ui64 (line 65) | Point2ui64(uint64 _x, uint64 _y):x(_x), y(_y){}
type CCStatsOp (line 68) | struct CCStatsOp{
method CCStatsOp (line 75) | CCStatsOp(OutputArray _statsv, OutputArray _centroidsv): _mstatsv(...
method init (line 77) | inline
method finish (line 105) | void finish(){
function LabelT (line 122) | inline static
function setRoot (line 133) | inline static
function LabelT (line 145) | inline static
function LabelT (line 154) | inline static
function LabelT (line 170) | inline static
type LabelingImpl (line 192) | struct LabelingImpl{
method LabelT (line 193) | LabelT operator()(const cv::Mat &I, cv::Mat &L, int connectivity, ...
function connectedComponents_sub1 (line 340) | static
FILE: tracker/HandFinder/connectedComponents.h
function namespace (line 10) | namespace cv{
FILE: tracker/Legacy/LegacyTracker.h
function class (line 13) | class LegacyTracker{
FILE: tracker/Legacy/algorithm/Detector.h
function class (line 9) | class Detector
FILE: tracker/Legacy/algorithm/ICP.cpp
function Mat4f (line 181) | Mat4f ICP::registration(
function icp_invalid (line 437) | bool icp_invalid(const Vec3f &s, const Vec3f &t, const Vec3f &n, const V...
FILE: tracker/Legacy/algorithm/ICP.h
function class (line 7) | class ICP
FILE: tracker/Legacy/geometry/Cylinders.cpp
function dist_point_linesegment (line 8) | float dist_point_linesegment(const Vec3f& _p,
type JointDistance (line 143) | struct JointDistance
method JointDistance (line 150) | JointDistance()
method JointDistance (line 155) | JointDistance(float distance, const Vec3f &point, const Vec3f &normal,...
function compareSuffix (line 193) | bool compareSuffix(const std::string &fullString, const std::string &end...
FILE: tracker/Legacy/geometry/Cylinders.h
type Segment (line 10) | struct Segment
function class (line 24) | class Cylinders
FILE: tracker/Legacy/geometry/Effector.cpp
function Joint (line 34) | Joint *Effector::getJoint()
function Vec3f (line 39) | Vec3f Effector::getPosition()
function Vec3f (line 44) | Vec3f Effector::getTarget()
function Vec3f (line 49) | Vec3f Effector::getOffset()
function Vec3f (line 54) | Vec3f Effector::getPositionNormal()
function Vec3f (line 59) | Vec3f Effector::getTargetNormal()
FILE: tracker/Legacy/geometry/Effector.h
function class (line 4) | class Effector
FILE: tracker/Legacy/geometry/Joint.cpp
function Vec3f (line 133) | Vec3f Joint::getTranslation()
function Vec3f (line 138) | Vec3f Joint::getGlobalTranslation()
function Mat3f (line 143) | Mat3f Joint::getRotation()
function Mat3f (line 148) | Mat3f Joint::getGlobalRotation()
function Mat4f (line 153) | Mat4f &Joint::getLocalTransformation()
function Mat4f (line 158) | Mat4f &Joint::getGlobalTransformation()
function Joint (line 163) | Joint *Joint::getParent()
function Vec3f (line 173) | Vec3f Joint::getEndPosition(bool force_y)
FILE: tracker/Legacy/geometry/Joint.h
function class (line 7) | class Joint
FILE: tracker/Legacy/geometry/Mapping.cpp
function Vec3f (line 256) | Vec3f Mapping::getRotationAxis(int i)
function Vector3i (line 270) | Vector3i Mapping::getRotationAxes()
function Vec3f (line 277) | Vec3f Mapping::toEulerAngles(const Mat3f &m)
function Vec3f (line 284) | Vec3f Mapping::toEulerAngles(const Mat4f &m)
function Mat3f (line 291) | Mat3f Mapping::fromEulerAngles(const Vec3f &v)
function Mat3f (line 298) | Mat3f Mapping::fromEulerAngles(float a, float b, float c)
function resetMap (line 417) | void resetMap(map<int, float> &m, size_t f, size_t n, float val)
function MatXf (line 531) | MatXf Mapping::getPCs(size_t dof)
function PCA (line 550) | PCA &Mapping::getPCA() { return *pca; }
function JointInfo (line 564) | JointInfo Mapping::getJointInfo(int index)
FILE: tracker/Legacy/geometry/Mapping.h
type AxisType (line 16) | enum AxisType
type AxisInfo (line 24) | struct AxisInfo
function hasLimits (line 121) | bool hasLimits(int index)
function hasLimitsPC (line 134) | bool hasLimitsPC(int index)
function setMin (line 141) | void setMin(int index, float val) { mins[index] = val; }
function setMax (line 142) | void setMax(int index, float val) { maxs[index] = val; }
function setMinPC (line 144) | void setMinPC(int index, float val) { minsPC[index] = val; }
function setMaxPC (line 145) | void setMaxPC(int index, float val) { maxsPC[index] = val; }
function getDimension (line 184) | int getDimension()
function Mapping (line 201) | static Mapping leftArm()
function Mapping (line 208) | static Mapping leftArm2()
function Mapping (line 215) | static Mapping rightHand()
function Mapping (line 222) | static Mapping rightArm()
function Mapping (line 229) | static Mapping rightArm2()
FILE: tracker/Legacy/geometry/Skeleton.cpp
function Mat4f (line 491) | Mat4f Skeleton::getInitialTransformation(const string &jointName)
function Joint (line 648) | Joint *Skeleton::getRoot()
function Joint (line 653) | Joint *Skeleton::getPoseJoint()
function Joint (line 678) | Joint *Skeleton::getScaleJoint()
function Vec3f (line 698) | Vec3f Skeleton::getEulerAngles()
function VectorN (line 724) | VectorN Skeleton::get() {
function Mapping (line 791) | Mapping &Skeleton::getMapping()
function Joint (line 847) | Joint *Skeleton::getJoint(const std::string &joint)
FILE: tracker/Legacy/geometry/Skeleton.h
function class (line 12) | class Skeleton{
FILE: tracker/Legacy/math/Inverse_kinematics.cpp
function MatXf (line 252) | MatXf Inverse_kinematics::dampingMatrix(Skeleton &skeleton)
function MatXf (line 465) | MatXf Inverse_kinematics::constructJacobian(
FILE: tracker/Legacy/math/Inverse_kinematics.h
function class (line 6) | class Inverse_kinematics
FILE: tracker/Legacy/math/MathUtils.cpp
function Vec3f (line 10) | Vec3f toEuler(const Mat3f &m, int e1, int e2, int e3)
function Vec3f (line 17) | Vec3f toEuler(const Mat4f &m, int e1, int e2, int e3)
function Mat3f (line 25) | Mat3f fromEuler(const Vec3f &v, int e1, int e2, int e3)
function Mat3f (line 35) | Mat3f fromEuler(float a, float b, float c, int e1, int e2, int e3)
function MatXf (line 42) | MatXf pinv(const MatXf &sym)
function MatXf (line 49) | MatXf transp(const MatXf &m)
function MatXf (line 67) | MatXf addpar(const MatXf &a, const MatXf &b)
function MatXf (line 87) | MatXf maxvol(const MatXf &A)
function MatXf (line 95) | MatXf maxvol(const MatXf &A, std::vector<int> &indices)
FILE: tracker/Legacy/math/MathUtils.h
type Eigen (line 9) | typedef Eigen::Vector3f Vec3f;
type Eigen (line 10) | typedef Eigen::Vector3d Vec3d;
type Eigen (line 13) | typedef Eigen::Vector4f Vec4f;
type Eigen (line 14) | typedef Eigen::Vector4d Vec4d;
type Eigen (line 17) | typedef Eigen::VectorXf VecXf;
type Eigen (line 18) | typedef Eigen::VectorXd VecXd;
type Eigen (line 21) | typedef Eigen::Matrix<float, 3, 3, Eigen::ColMajor> Mat3f;
type Eigen (line 22) | typedef Eigen::Matrix<double, 3, 3, Eigen::ColMajor> Mat3d;
type Eigen (line 25) | typedef Eigen::Matrix<float, 4, 4, Eigen::ColMajor> Mat4f;
type Eigen (line 26) | typedef Eigen::Matrix<double, 4, 4, Eigen::ColMajor> Mat4d;
type Eigen (line 29) | typedef Eigen::Matrix<float, Eigen::Dynamic, Eigen::Dynamic, Eigen::ColM...
type Eigen (line 30) | typedef Eigen::Matrix<double, Eigen::Dynamic, Eigen::Dynamic, Eigen::Col...
type Eigen (line 33) | typedef Eigen::Transform<float, 3, Eigen::Affine, Eigen::ColMajor> Trans...
type Eigen (line 34) | typedef Eigen::Transform<double, 3, Eigen::Affine, Eigen::ColMajor> Tran...
type std (line 39) | typedef std::vector<T, Eigen::aligned_allocator<T> > type;
type std (line 45) | typedef std::map<K, V, std::less<K>,
FILE: tracker/Legacy/math/PCA.cpp
function MatXf (line 155) | MatXf PCA::getPCs(size_t dof)
function VecXf (line 168) | VecXf PCA::adapt(
FILE: tracker/Legacy/math/PCA.h
function class (line 15) | class PCA
FILE: tracker/Legacy/util/PostureFile.h
function class (line 9) | class PostureFile
FILE: tracker/Legacy/util/Util.cpp
function cat (line 15) | std::string cat(const std::vector<std::string> &v)
function contains_string (line 24) | bool contains_string(const std::string &a, const std::string &b)
function ColorHSV (line 32) | ColorHSV rgb2hsv(const ColorRGB &in)
function ColorRGB (line 83) | ColorRGB hsv2rgb(const ColorHSV &in)
function cvc (line 157) | cv::Scalar cvc(const ColorRGB &c, bool bgr)
function cvc (line 167) | cv::Scalar cvc(const ColorHSV &c)
function ColorRGB (line 174) | ColorRGB cvc(const cv::Scalar &c, bool bgr)
function ColorHSV (line 184) | ColorHSV cvc(const cv::Scalar &c)
FILE: tracker/Legacy/util/openmp_helpers.h
function namespace (line 6) | namespace openmp{
FILE: tracker/OffscreenRender/CustomFrameBuffer.h
function class (line 14) | class CustomFrameBuffer {
function GLuint (line 35) | GLuint extra_tex_id() { return extra_tex; }
function GLuint (line 36) | GLuint norms_tex_id() { return norms_tex; }
function bind (line 43) | void bind() {
function unbind (line 48) | void unbind() {
function init (line 52) | void init(int image_width, int image_height) {
function cleanup (line 64) | void cleanup() {
function fetch_color_attachment (line 109) | void fetch_color_attachment(cv::Mat& image){
function display_color_attachment (line 116) | void display_color_attachment() {
function GLuint (line 125) | GLuint create_depth_attachment(int image_width, int image_height) {
function GLuint (line 135) | GLuint create_extra_attachment(int image_width, int image_height) {
function GLuint (line 148) | GLuint create_normals_attachment(int image_width, int image_height) {
function fetch_extra_attachment (line 169) | void fetch_extra_attachment(cv::Mat& image){
function display_extra_attachment (line 178) | void display_extra_attachment() {
FILE: tracker/OffscreenRender/OffscreenRenderer.h
function class (line 5) | class OffscreenRenderer{
FILE: tracker/OpenGL/CylindersRenderer/Cylinders_renderer.cpp
class Cylindroid (line 10) | class Cylindroid{
method Cylindroid (line 16) | Cylindroid(QGLShaderProgram& program,
method render (line 95) | void render(QGLShaderProgram& program, const Matrix4 &m, size_t id, Ve...
function Vector3 (line 188) | Vector3 rgb_color_for(std::string& name)
FILE: tracker/OpenGL/CylindersRenderer/Cylinders_renderer.h
function class (line 8) | class Cylinders_renderer : public ObjectRenderer{
FILE: tracker/OpenGL/CylindersRenderer/icopill.h
function namespace (line 2) | namespace icopill{
FILE: tracker/OpenGL/KinectDataRenderer/KinectDataRenderer.cpp
type Grid (line 5) | struct Grid{
method Grid (line 9) | Grid(int grid_width, int grid_height){
FILE: tracker/OpenGL/KinectDataRenderer/KinectDataRenderer.h
function class (line 6) | class KinectDataRenderer : public ObjectRenderer{
FILE: tracker/OpenGL/ObjectRenderer.h
function class (line 10) | class ObjectRenderer{
FILE: tracker/OpenGL/QuadRenderer/QuadRenderer.cpp
type quad (line 7) | namespace quad{
FILE: tracker/OpenGL/QuadRenderer/QuadRenderer.h
function class (line 4) | class QuadRenderer : public ObjectRenderer{
FILE: tracker/Sensor/Sensor.h
type DataFrame (line 4) | struct DataFrame
function class (line 7) | class Sensor{
function class (line 23) | class SensorOpenNI : public Sensor{
function class (line 35) | class SensorSoftKin : public Sensor{
function class (line 47) | class SensorDepthSenseGrabber : public Sensor{
function class (line 59) | class SensorRealSense : public Sensor {
function class (line 71) | class SensorLibRealSense : public Sensor {
FILE: tracker/Sensor/Sensor_depthsensegrabber.cpp
function initFilterWeights (line 100) | void initFilterWeights(float* A, float* d1, float* d2, int n, int s, int...
function filterNew (line 112) | uint16_t filterNew(uint16_t sample, float* w0, float* w1, float* w2, int...
function configureDepthNode (line 166) | void configureDepthNode() {
function configureColorNode (line 202) | void configureColorNode() {
function configureNode (line 243) | void configureNode(Node node) {
function onNodeConnected (line 258) | void onNodeConnected(Device device, Device::NodeAddedData data) {
function onNodeDisconnected (line 263) | void onNodeDisconnected(Device device, Device::NodeRemovedData data) {
function onDeviceConnected (line 272) | void onDeviceConnected(Context context, Context::DeviceAddedData data) {
function onDeviceDisconnected (line 281) | void onDeviceDisconnected(Context context, Context::DeviceRemovedData da...
function getFirstAvailableNode (line 287) | static void getFirstAvailableNode (Context context) {
function run (line 320) | void run(){
function onNewColorSample (line 324) | void onNewColorSample(ColorNode, ColorNode::NewSampleReceivedData data) {
function onNewDepthSample (line 342) | void onNewDepthSample(DepthNode node, DepthNode::NewSampleReceivedData d...
FILE: tracker/Sensor/Sensor_openni.cpp
function openni_hard_quit (line 10) | void openni_hard_quit(){ std::cout << "!!!ERROR: Cannot use SensorOpenNI...
function force_reinit (line 296) | void force_reinit(){
function auto_exposure (line 312) | void auto_exposure(bool flag){
FILE: tracker/Sensor/Sensor_softkin.cpp
function configureDepthNode (line 86) | void configureDepthNode() {
function configureColorNode (line 119) | void configureColorNode() {
function configureNode (line 160) | void configureNode(Node node) {
function onNodeConnected (line 175) | void onNodeConnected(Device device, Device::NodeAddedData data) {
function onNodeDisconnected (line 180) | void onNodeDisconnected(Device device, Device::NodeRemovedData data) {
function onDeviceConnected (line 189) | void onDeviceConnected(Context context, Context::DeviceAddedData data) {
function onDeviceDisconnected (line 198) | void onDeviceDisconnected(Context context, Context::DeviceRemovedData da...
function getFirstAvailableNode (line 204) | static void getFirstAvailableNode (Context context) {
function run (line 237) | void run(){
function onNewColorSample (line 241) | void onNewColorSample(ColorNode, ColorNode::NewSampleReceivedData data) {
function onNewDepthSample (line 259) | void onNewDepthSample(DepthNode node, DepthNode::NewSampleReceivedData d...
FILE: tracker/Tracker.h
function class (line 17) | class Tracker : public QTimer{
FILE: tracker/TwSettings.h
type TwBar (line 2) | typedef struct CTwBar TwBar;
function class (line 4) | class TwSettings{
FILE: tracker/Types.h
type Scalar (line 9) | typedef float Scalar;
type Scalar (line 10) | typedef Scalar Real;
type std (line 11) | typedef std::string String;
type uint (line 12) | typedef unsigned int uint;
type Integer (line 13) | typedef int Integer;
type Eigen (line 14) | typedef Eigen::Matrix4f Matrix4;
type Eigen (line 15) | typedef Eigen::Matrix3f Matrix3;
type Eigen (line 16) | typedef Eigen::Vector2f Vector2;
type Eigen (line 17) | typedef Eigen::Vector3f Vector3;
type Eigen (line 18) | typedef Eigen::Vector4f Vector4;
type Eigen (line 19) | typedef Eigen::VectorXf VectorN;
type Eigen (line 33) | typedef Eigen::Matrix<Scalar, num_thetas, 1> Thetas;
type Eigen (line 36) | typedef Eigen::Matrix<Scalar, 2, 3> Matrix_2x3;
type Eigen (line 37) | typedef Eigen::Matrix<Scalar, 1, Eigen::Dynamic> Matrix_1xN;
type Eigen (line 38) | typedef Eigen::Matrix<Scalar, 2, Eigen::Dynamic> Matrix_2xN;
type Eigen (line 39) | typedef Eigen::Matrix<Scalar, 3, Eigen::Dynamic> Matrix_3xN;
type Eigen (line 40) | typedef Eigen::Matrix<Scalar, Eigen::Dynamic, 2> Matrix_Nx2;
type Eigen (line 41) | typedef Eigen::Matrix<Scalar, Eigen::Dynamic, Eigen::Dynamic> Matrix_MxN;
type Eigen (line 43) | typedef Eigen::Hyperplane<Scalar,3> Plane3;
type Eigen (line 44) | typedef Eigen::ParametrizedLine<Scalar,3> Ray3;
type Eigen (line 45) | typedef Eigen::AlignedBox3f BBox3;
type Eigen (line 46) | typedef Eigen::Vector2i Vector2i;
type Eigen (line 47) | typedef Eigen::AlignedBox2i BBox2i;
type Eigen (line 48) | typedef Eigen::Quaternion<Real> Quaternion;
function Real (line 51) | inline Real nan(){ return std::numeric_limits<Real>::quiet_NaN(); }
function Real (line 52) | inline Real inf(){ return std::numeric_limits<Real>::max(); }
function LinearSystem (line 55) | struct LinearSystem {
FILE: tracker/Worker.cpp
function TrackingError (line 86) | TrackingError Worker::track(DataFrame& frame, bool rigid_only, bool eval...
FILE: tracker/Worker.h
function class (line 17) | class Worker{
FILE: util/MLogger.h
function class (line 6) | class MLogger{
function MLogger (line 44) | inline MLogger& operator()(){
function MLogger (line 49) | inline MLogger& operator()(const char* fmt, ...){
function MLogger (line 64) | static MLogger make_mLogger(){ MLogger out(std::cout); return out; }
function MLogger (line 65) | static MLogger make_mDebug(){ MLogger out(std::cout); return out; }
function MLogger (line 66) | static MLogger make_mFatal(){ MLogger out(std::cout); out._with_fatal=tr...
function MLogger (line 67) | static MLogger make_mWarning(){ MLogger out(std::cout); out<<"!!!WARNING...
FILE: util/MLogger_Eigen.h
function namespace (line 5) | namespace Eigen{
FILE: util/OpenGL32Format.h
function class (line 3) | class OpenGL32Format : public QGLFormat {
FILE: util/Sleeper.h
function class (line 3) | class Sleeper : public QThread{
function msleep (line 6) | static void msleep(unsigned long msecs){QThread::msleep(msecs);}
function sleep (line 7) | static void sleep(unsigned long secs){QThread::sleep(secs);}
FILE: util/check_error_gl.h
function sdkCheckErrorGL (line 17) | inline bool
FILE: util/eigen_opengl_helpers.h
function namespace (line 3) | namespace Eigen{
FILE: util/gl_wrapper.h
function initialize_glew (line 14) | inline void initialize_glew(){
FILE: util/opencv_wrapper.h
function namespace (line 14) | namespace cv{
FILE: util/opengl_helper.h
function namespace (line 2) | namespace opengl{
FILE: util/qt2eigen.h
function namespace (line 2) | namespace Convert{
FILE: util/rand.h
function namespace (line 5) | namespace my {
FILE: util/tictoc.h
function class (line 10) | class TicTocTimerObject{
Condensed preview — 273 files, each showing path, character count, and a content snippet. Download the .json file or copy for the full structured content (2,766K chars).
[
{
"path": ".gitignore",
"chars": 367,
"preview": "*.txt.user\n\n*-build\n\n#################\n## openFrameworks\n#################\n\n[Bb]in/*\n![Bb]in/data/\n[Bb]uild/\n[Oo]bj/\n*.o"
},
{
"path": "CMakeLists.txt",
"chars": 1590,
"preview": "cmake_minimum_required(VERSION 2.8)\nproject(htrack)\n\n#--- Gets rid of annoying CMake 3 warnings\nif(NOT (CMAKE_MAJOR_VERS"
},
{
"path": "COPYING.txt",
"chars": 7651,
"preview": " GNU LESSER GENERAL PUBLIC LICENSE\n Version 3, 29 June 2007\n\n Copyright (C) 2007"
},
{
"path": "README.md",
"chars": 1561,
"preview": "# Robust Articulated-ICP for Real-Time Hand Tracking\n\n- **YouTube Video**: https://youtu.be/rm3YnClSmIQ\n- **Paper PDF**:"
},
{
"path": "apps/CMakeLists.txt",
"chars": 783,
"preview": "cmake_minimum_required(VERSION 2.8)\nproject(htrack-helloworlds)\n\n#--- Gets rid of annoying CMake 3 warnings\nif(NOT (CMAK"
},
{
"path": "apps/colorpick/CMakeLists.txt",
"chars": 301,
"preview": "#--- This project needs this extra library\n#include(../../cmake/ConfigureQGLViewer.cmake)\n\nINCLUDE_DIRECTORIES(../../) #"
},
{
"path": "apps/colorpick/colorpick.cpp",
"chars": 5231,
"preview": "// based on http://pastebin.com/EHz2a0YP\n\n#include <iostream>\n#include <opencv2/opencv.hpp>\n#include <opencv2/core/core."
},
{
"path": "apps/helloworld/CMakeLists.txt",
"chars": 344,
"preview": "cmake_minimum_required(VERSION 2.8)\nget_filename_component(FOLDERNAME ${CMAKE_CURRENT_LIST_DIR} NAME)\nproject(${FOLDERNA"
},
{
"path": "apps/helloworld/main.cpp",
"chars": 125,
"preview": "#include <iostream>\nint main(int /*argc*/, char ** /*argv*/)\n{\n std::cout << \"hello world!\" << std::endl;\n return "
},
{
"path": "apps/helloworld_atb/CMakeLists.txt",
"chars": 642,
"preview": "cmake_minimum_required(VERSION 2.8)\nget_filename_component(PROJECT ${CMAKE_CURRENT_LIST_DIR} NAME)\nproject(${PROJECT})\n\n"
},
{
"path": "apps/helloworld_atb/main.cpp",
"chars": 1680,
"preview": "#include <iostream>\n#include <QDebug>\n#include <QApplication>\n#include <QGLWidget>\n#include <QOpenGLVertexArrayObject>\n\n"
},
{
"path": "apps/helloworld_atb/main_new.cpp",
"chars": 1745,
"preview": "#include <iostream>\n#include <QDebug>\n#include <QApplication>\n#include <QGLWidget>\n#include <QOpenGLWidget>\n#include <QO"
},
{
"path": "apps/helloworld_cublas/CMakeLists.txt",
"chars": 840,
"preview": "cmake_minimum_required(VERSION 2.8)\nget_filename_component(PROJECT ${CMAKE_CURRENT_LIST_DIR} NAME)\nproject(${PROJECT})\n\n"
},
{
"path": "apps/helloworld_cublas/gnuplot_i.h",
"chars": 60402,
"preview": "////////////////////////////////////////////////////////////////////////////////\n///\n/// \\brief A C++ interface to gnup"
},
{
"path": "apps/helloworld_cublas/main_performance.cpp",
"chars": 6913,
"preview": "#include <cassert>\n#include <Eigen/Dense>\n#include <QApplication>\n#include \"util/gl_wrapper.h\"\n#include \"util/OpenGL32Fo"
},
{
"path": "apps/helloworld_cublas/main_simple.cpp",
"chars": 1289,
"preview": "///--- Computes matrix products on GPU\n/// this example is broken, but if it runs it's \"okay\"\n/// TODO: matthias, it run"
},
{
"path": "apps/helloworld_cudagl/CMakeLists.txt",
"chars": 758,
"preview": "cmake_minimum_required(VERSION 2.8)\nget_filename_component(PROJECTNAME ${CMAKE_CURRENT_LIST_DIR} NAME)\nproject(${PROJECT"
},
{
"path": "apps/helloworld_cudagl/main.cpp",
"chars": 4185,
"preview": "// Test the CUDA OpenGL interoperability\n//\n// Performance on GeForce 650M (OSX):\n// [cudaGraphicsGLRegisterImage] 21."
},
{
"path": "apps/helloworld_librealsense/CMakeLists.txt",
"chars": 1241,
"preview": "# https://github.com/IntelRealSense/librealsense/issues/62\n\ncmake_minimum_required(VERSION 2.8)\nget_filename_component(P"
},
{
"path": "apps/helloworld_librealsense/main.cpp",
"chars": 5853,
"preview": "// License: Apache 2.0. See LICENSE file in root directory.\n// Copyright(c) 2015 Intel Corporation. All Rights Reserved."
},
{
"path": "apps/helloworld_opencv/CMakeLists.txt",
"chars": 507,
"preview": "cmake_minimum_required(VERSION 2.8)\nget_filename_component(PROJECT ${CMAKE_CURRENT_LIST_DIR} NAME)\nproject(${PROJECT})\n#"
},
{
"path": "apps/helloworld_opencv/main.cpp",
"chars": 555,
"preview": "#include <iostream>\n#include <fstream>\n#include \"stdlib.h\"\n#include \"opencv2/core/core.hpp\"\n#include \"opencv2/core/types"
},
{
"path": "apps/helloworld_openmp/CMakeLists.txt",
"chars": 398,
"preview": "if(UNIX AND NOT APPLE)\n return()\nendif()\n\ncmake_minimum_required(VERSION 2.8)\nget_filename_component(PROJECT ${CMAKE_"
},
{
"path": "apps/helloworld_openmp/main.cpp",
"chars": 675,
"preview": "// COMPILE: /usr/local/bin/g++-4.8 -fopenmp openmp.cpp\n#include <omp.h>\n#include <stdio.h>\n#include <stdlib.h>\n\nint main"
},
{
"path": "apps/helloworld_openni/CMakeLists.txt",
"chars": 832,
"preview": "cmake_minimum_required(VERSION 2.8)\nget_filename_component(PROJECT ${CMAKE_CURRENT_LIST_DIR} NAME)\nproject(${PROJECT})\n\n"
},
{
"path": "apps/helloworld_openni/main.cpp",
"chars": 1107,
"preview": "#include <iostream>\n#include \"util/tictoc.h\"\n#include \"util/opencv_wrapper.h\"\n#include \"tracker/Sensor/Sensor.h\"\n#includ"
},
{
"path": "apps/helloworld_qglviewer/CMakeLists.txt",
"chars": 604,
"preview": "cmake_minimum_required(VERSION 2.8)\nget_filename_component(PROJECT ${CMAKE_CURRENT_LIST_DIR} NAME)\nproject(${PROJECT})\n#"
},
{
"path": "apps/helloworld_qglviewer/main.cpp",
"chars": 1184,
"preview": "#include <QApplication>\n#include <QGLViewer/qglviewer.h>\n\nclass Viewer : public QGLViewer {\n void draw() {\n //"
},
{
"path": "apps/helloworld_qtopengl/CMakeLists.txt",
"chars": 392,
"preview": "cmake_minimum_required(VERSION 2.8)\nget_filename_component(PROJECT ${CMAKE_CURRENT_LIST_DIR} NAME)\nproject(${PROJECT})\n\n"
},
{
"path": "apps/helloworld_qtopengl/main.cpp",
"chars": 1018,
"preview": "#include <iostream>\n#include <QApplication>\n#include <QGLWidget>\n#include <QOpenGLVertexArrayObject>\n\n/// Format class t"
},
{
"path": "apps/helloworld_realsense/CMakeLists.txt",
"chars": 761,
"preview": "if(NOT WIN32)\n return()\nendif()\n\ncmake_minimum_required(VERSION 2.8)\nget_filename_component(PROJECT ${CMAKE_CURRENT_L"
},
{
"path": "apps/helloworld_realsense/main.cpp",
"chars": 5865,
"preview": "#include <iostream>\n#include \"pxcsensemanager.h\"\n#include \"pxcsession.h\"\n#include \"pxcprojection.h\"\n\n#include \"util/tict"
},
{
"path": "apps/helloworld_thrust/CMakeLists.txt",
"chars": 383,
"preview": "cmake_minimum_required(VERSION 2.8)\nget_filename_component(PROJECT ${CMAKE_CURRENT_LIST_DIR} NAME)\nproject(${PROJECT})\n\n"
},
{
"path": "apps/helloworld_thrust/main.cu",
"chars": 926,
"preview": "#include <thrust/version.h>\n#include <thrust/host_vector.h>\n#include <thrust/device_vector.h> \n#include <thrust/sort.h>\n"
},
{
"path": "apps/htrack_atb/AntTweakBarEventFilter.h",
"chars": 2533,
"preview": "#pragma once\n#include <QMouseEvent>\n#include <QGLWidget>\n#ifdef WITH_ANTTWEAKBAR\n #include \"AntTweakBar.h\"\n#endif\n\n//"
},
{
"path": "apps/htrack_atb/CMakeLists.txt",
"chars": 200,
"preview": "INCLUDE_DIRECTORIES(../../) #< #include \"tracker/...\"\nfile(GLOB_RECURSE SRC \"*.cpp\")\nfile(GLOB_RECURSE HDR \"*.h\")\nadd_ex"
},
{
"path": "apps/htrack_atb/main.cpp",
"chars": 6681,
"preview": "#include <iostream>\n#include <QDebug>\n#include <QApplication>\n#include <QDir>\n\n#include \"util/gl_wrapper.h\"\n#include \"ut"
},
{
"path": "apps/htrack_qt/CMakeLists.txt",
"chars": 367,
"preview": "#--- This project needs this extra library\ninclude(../../cmake/ConfigureQGLViewer.cmake)\n\nINCLUDE_DIRECTORIES(../../) #<"
},
{
"path": "apps/htrack_qt/Main_window.cpp",
"chars": 19243,
"preview": "#include \"Main_window.h\"\n\n#include <QFileDialog>\n#include <QThread>\n#include \"OpenGL_viewer.h\"\n#include \"tracker/OpenGL/"
},
{
"path": "apps/htrack_qt/Main_window.h",
"chars": 2145,
"preview": "#pragma once\n#include <QMainWindow>\n#include <QLayout>\n#include <QLabel>\n#include <QSlider>\n#include <QPushButton>\n#incl"
},
{
"path": "apps/htrack_qt/OpenGL_viewer.cpp",
"chars": 11409,
"preview": "#include \"OpenGL_viewer.h\"\n\n///--- External\n#include <QContextMenuEvent>\n#include <QWindow>\n\n#ifdef WITH_QGLVIEWER\n#incl"
},
{
"path": "apps/htrack_qt/OpenGL_viewer.h",
"chars": 1850,
"preview": "#pragma once\n#include \"tracker/ForwardDeclarations.h\"\n\n#include \"util/gl_wrapper.h\"\n#include <memory>\n#include <QMenu>\n\n"
},
{
"path": "apps/htrack_qt/main.cpp",
"chars": 3371,
"preview": "#include \"util/gl_wrapper.h\"\n\n#include <QApplication>\n#include <QString>\n#include <QDebug>\n#include <QDir>\n#include <QTh"
},
{
"path": "apps/synthgen/synthgen.cpp",
"chars": 13781,
"preview": "#if __unix__\n#define GL_GLEXT_PROTOTYPES 1\n#include <GL/gl.h>\n#include <GL/glext.h>\n#endif\n\n#include <QApplication>\n#inc"
},
{
"path": "cmake/CompileSynthgen.cmake",
"chars": 337,
"preview": "set(WITH_SYNTHGEN TRUE)\nLIST(APPEND SRC_OPENGL2 \"opengl/Cylinders_renderer.cpp\" \"opengl/Renderer_interface.cpp\")\nadd_exe"
},
{
"path": "cmake/ConfigureAntTweakBar.cmake",
"chars": 741,
"preview": "#--- AntTweakBar\nfind_package(AntTweakBar)\nif(ANTTWEAKBAR_FOUND)\n include_directories(${ANTTWEAKBAR_INCLUDE_DIR})\n "
},
{
"path": "cmake/ConfigureCUDA.cmake",
"chars": 3459,
"preview": "set(WITH_CUDA TRUE)\nadd_definitions(-DWITH_CUDA)\n\n# Anastasia: what is this for?\nif(WIN32)\n # set(CUDA_TOOLKIT_ROOT_DI"
},
{
"path": "cmake/ConfigureCompiler.cmake",
"chars": 2168,
"preview": "#--- Build type\n# set(CMAKE_BUILD_TYPE \"Release\") #<<< FORCE SET\nif(NOT CMAKE_BUILD_TYPE)\n set(CMAKE_BUILD_TYPE \"Rele"
},
{
"path": "cmake/ConfigureCudaOctree.cmake",
"chars": 639,
"preview": "#if(FALSE)\n# message(STATUS \"CudaOctree internal build\")\n# include_directories(${CMAKE_SOURCE_DIR}/cuda_octree)\n# "
},
{
"path": "cmake/ConfigureEigen.cmake",
"chars": 104,
"preview": "find_package(Eigen3 REQUIRED)\ninclude_directories(${EIGEN3_INCLUDE_DIRS})\nadd_definitions(-DWITH_EIGEN)\n"
},
{
"path": "cmake/ConfigureGLEW.cmake",
"chars": 288,
"preview": "#--- STATICALLY LINKED!!!\nfind_package(GLEW REQUIRED)\ninclude_directories(${GLEW_INCLUDE_DIRS})\nlink_directories(${GLEW_"
},
{
"path": "cmake/ConfigureGLFW.cmake",
"chars": 247,
"preview": "#--- CMake extension to load GLFW\nfind_package(GLFW REQUIRED)\ninclude_directories(${GLFW_INCLUDE_DIRS})\nadd_definitions("
},
{
"path": "cmake/ConfigureLibRealSense.cmake",
"chars": 698,
"preview": "add_compile_options(-std=c++11 -fPIC -lusb-1.0 -lpthread )\n\n# libusb-1.0\nfind_package(Threads REQUIRED)\nfind_package(Pkg"
},
{
"path": "cmake/ConfigureOpenCV.cmake",
"chars": 570,
"preview": "find_package(OpenCV2 REQUIRED)\n\nif(OpenCV2_FOUND)\n include_directories(${OpenCV2_INCLUDE_DIRS})\n LIST(APPEND LIBRA"
},
{
"path": "cmake/ConfigureOpenGL.cmake",
"chars": 362,
"preview": "#--- OpenGL\nfind_package(OpenGL REQUIRED)\nif(NOT OPENGL_FOUND)\n message(ERROR \" OPENGL not found!\")\nendif(NOT OPENGL_"
},
{
"path": "cmake/ConfigureOpenGP.cmake",
"chars": 213,
"preview": "#--- OPENGP\nfind_package(OpenGP REQUIRED)\ninclude_directories(${OpenGP_INCLUDE_DIRS})\nadd_definitions(-DHEADERONLY)\nadd_"
},
{
"path": "cmake/ConfigureOpenMP.cmake",
"chars": 223,
"preview": "if(UNIX)\n # only for g++ or for the Clang+OpenMP compiler\n set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -fopenmp\")\nels"
},
{
"path": "cmake/ConfigureOpenNI.cmake",
"chars": 346,
"preview": "#--- OpenNI2\nfind_package(OpenNI2)\nif(OPENNI2_FOUND)\n include_directories(${OPENNI2_INCLUDE_DIR})\n list(APPEND LIB"
},
{
"path": "cmake/ConfigureQGLViewer.cmake",
"chars": 297,
"preview": "find_package(QGLViewer) #<<< Optional\nif(QGLVIEWER_FOUND)\n include_directories(${QGLVIEWER_INCLUDE_DIR})\n add_defi"
},
{
"path": "cmake/ConfigureQt.cmake",
"chars": 1572,
"preview": "# @see http://doc.qt.io/qt-5/cmake-manual.html\n#--- Tell cmake where to find Qt5. (Unfortunately cmake3 does not support"
},
{
"path": "cmake/ConfigureRealSense.cmake",
"chars": 1136,
"preview": "# TODO: use the find_file macro\n\nif(WIN32)\n set(REALSENSE_INCLUDE_DIR \"C:/Developer/RealSense/RSSDK/include\")\n set"
},
{
"path": "cmake/ConfigureSensor.cmake",
"chars": 3578,
"preview": "#--- Choose a sensor\n\n#SET(SENSOR_DEPTHSENSEGRABBER 0 CACHE BOOL \"Use SoftKinetic with DepthSenseGrabber\")\n#SET(SENSOR_S"
},
{
"path": "cmake/ConfigureSoftKinetic.cmake",
"chars": 249,
"preview": "#--- OpenNI2\nfind_package(SoftKinetic) #NOT REQUIRED (mac doesn't have it)\nif(SOFTKINETIC_FOUND)\n include_directorie"
},
{
"path": "cmake/FindAntTweakBar.cmake",
"chars": 1156,
"preview": "#\n# Try to find AntTweakBar library and include path.\n# Once done this will define\n#\n# ANTTWEAKBAR_FOUND\n# ANTTWEAKBAR_I"
},
{
"path": "cmake/FindEigen3.cmake",
"chars": 507,
"preview": "if(WIN32)\nset(EIGEN3_INCLUDE_DIRS \"C:/Developer/include\")\nelse()\nFIND_PATH( EIGEN3_INCLUDE_DIRS Eigen/Geometry\n $ENV{"
},
{
"path": "cmake/FindGLEW.cmake",
"chars": 1082,
"preview": "FIND_PATH( GLEW_INCLUDE_DIRS GL/glew.h\n $ENV{GLEWDIR}/include\n /usr/local/include\n /usr/local/X11R6/include\n "
},
{
"path": "cmake/FindGLFW.cmake",
"chars": 1547,
"preview": "# Locate the GLFW library (version 2.0)\n# This module defines the following variables:\n# GLFW_LIBRARIES, the name of the"
},
{
"path": "cmake/FindGLM.cmake",
"chars": 427,
"preview": "# FIND_PACKAGE (GLM REQUIRED)\n# INCLUDE_DIRECTORIES (${GLM_INCLUDE_DIRS})\n# ADD_EXECUTABLE (executable ${YOUR_EXECUTABLE"
},
{
"path": "cmake/FindOpenCV2.cmake",
"chars": 6677,
"preview": "# To find OpenCV 2 library visit http://opencv.willowgarage.com/wiki/\n#\n# The follwoing variables are optionally searche"
},
{
"path": "cmake/FindOpenGP.cmake",
"chars": 979,
"preview": "# Locate the OpenGP library (version 1.0)\n# This module defines the following variables:\n# OpenGP_INCLUDE_DIRS, where to"
},
{
"path": "cmake/FindOpenNI2.cmake",
"chars": 1325,
"preview": "# OPENNI2_INCLUDE_DIR\n# OPENNI2_LIBRARY\n# OPENNI2_FOUND\n\nfind_path(OPENNI2_INCLUDE_DIR \"OpenNI.h\"\n PATHS\n #---"
},
{
"path": "cmake/FindQGLViewer.cmake",
"chars": 2283,
"preview": "# - Try to find QGLViewer\n# Once done this will define\n#\n# QGLVIEWER_FOUND - system has QGLViewer\n# QGLVIEWER_INCLUDE_"
},
{
"path": "cmake/FindSoftKinetic.cmake",
"chars": 1326,
"preview": "FIND_PATH( SOFTKINETIC_INCLUDE_DIR DepthSenseTypes.h\n $ENV{SOFTKINETIC_DIR}\n /opt/softkinetic/DepthSenseSDK/includ"
},
{
"path": "cudax/CMakeLists.txt",
"chars": 618,
"preview": "if(NOT WITH_CUDA)\n return()\nendif()\n\n#--- Dummy rule to show whole cudax folder in explorer\nfile(GLOB CUDA_FILES \"*\")"
},
{
"path": "cudax/CublasHelper.h",
"chars": 10907,
"preview": "#pragma once\n#include <stdio.h>\n#include <stdlib.h>\n#include <string.h>\n#include <cuda_runtime.h>\n#include <cublas_v2.h>"
},
{
"path": "cudax/CudaHelper.h",
"chars": 1706,
"preview": "/// @warning this cannot contain any c++11!!\n#pragma once\n#include <cuda_runtime.h>\n#include \"util/gl_wrapper.h\"\n#includ"
},
{
"path": "cudax/CudaTimer.h",
"chars": 2202,
"preview": "#pragma once\n#include <iostream>\n#include <iomanip>\n#include <fstream>\n\n//== NAMESPACE ================================="
},
{
"path": "cudax/KinectCamera.h",
"chars": 1016,
"preview": "#pragma once\n#include <thrust/device_vector.h>\n#include \"cuda_runtime.h\"\n#include \"cuda_glm.h\"\n\n//== NAMESPACE ========="
},
{
"path": "cudax/Kinematic.h",
"chars": 791,
"preview": "#pragma once\n#include <thrust/device_vector.h>\n#include \"tracker/DataStructure/CustomJointInfo.h\"\n\n//== NAMESPACE ======"
},
{
"path": "cudax/MeshGrid.h",
"chars": 2217,
"preview": "#pragma once\n#include <cuda_runtime.h>\n#include \"thrust/device_vector.h\"\n\n//== NAMESPACE ==============================="
},
{
"path": "cudax/OpenCVOutputBuffer.h",
"chars": 1032,
"preview": "#pragma once\n#include <thrust/device_vector.h>\n\n//== NAMESPACE ========================================================="
},
{
"path": "cudax/PixelIndexer.h",
"chars": 8639,
"preview": "#pragma once\n#include \"kernel.h\"\n#include <thrust/device_vector.h>\n#include \"cudax/functors/IsMatchingDepth.h\"\n#include "
},
{
"path": "cudax/Timer.h",
"chars": 1530,
"preview": "/// @note this measures wall clock times, not GPU times!!\n/// You'd need to sync the GPU (at the cost of a stall) to get"
},
{
"path": "cudax/cuda_glm.h",
"chars": 349,
"preview": "#pragma once\n//#define GLM_COMPILER 0\n#define CUDA_VERSION 7000\n\n#if __unix__\n// GLM wants to redefine these functions, "
},
{
"path": "cudax/externs.h",
"chars": 2452,
"preview": "#pragma once\n#include <cuda_runtime.h>\n#include <thrust/device_vector.h>\n#include <thrust/host_vector.h>\n#include \"cudax"
},
{
"path": "cudax/functors/ClosestPoint.h",
"chars": 10444,
"preview": "#include \"cudax/kernel.h\"\n#include \"cudax/cuda_glm.h\"\n\n//== NAMESPACE =================================================="
},
{
"path": "cudax/functors/ComputeJacobianRow.h",
"chars": 1709,
"preview": "#pragma once\n#include \"cudax/kernel.h\"\n#include \"cudax/MeshGrid.h\"\n\n//== NAMESPACE ====================================="
},
{
"path": "cudax/functors/ComputeJacobianRowDepth.h",
"chars": 4307,
"preview": "#include \"cudax/kernel.h\"\n#include \"cudax/functors/ImageGradientDepth.h\"\n#include \"cudax/functors/IsMatchingDepth.h\"\n\n//"
},
{
"path": "cudax/functors/ComputeJacobianRowExtraClosedForm.h",
"chars": 7336,
"preview": "#include \"cudax/kernel.h\"\n#include \"cudax/MeshGrid.h\"\n#include \"cudax/PixelIndexer.h\"\n#include \"ClosestPoint.h\"\n\n//== NA"
},
{
"path": "cudax/functors/ComputeJacobianRowPush.h",
"chars": 4231,
"preview": "#pragma once\n#include \"ComputeJacobianRow.h\"\n\n//== NAMESPACE ==========================================================="
},
{
"path": "cudax/functors/ComputeJacobianRowSilho.h",
"chars": 4182,
"preview": "#include \"cudax/kernel.h\"\n#include \"cudax/functors/ImageGradient.h\"\n#include \"cudax/Kinematic.h\"\n\n//== NAMESPACE ======="
},
{
"path": "cudax/functors/CopyOver.h",
"chars": 1859,
"preview": "// #include \"cudax/kernel.h\"\n#include \"cudax/OpenCVOutputBuffer.h\"\n#include \"cudax/MeshGrid.h\"\n\n//== NAMESPACE ========="
},
{
"path": "cudax/functors/ImageGradient.h",
"chars": 1880,
"preview": "#include \"cudax/kernel.h\"\n#include \"cudax/functors/IsSilhouette.h\"\n#include \"cudax/cuda_glm.h\"\n\n//== NAMESPACE ========="
},
{
"path": "cudax/functors/ImageGradientDepth.h",
"chars": 1691,
"preview": "#pragma once\n#include \"cudax/kernel.h\"\n#include \"cudax/cuda_glm.h\"\n\n//== NAMESPACE ====================================="
},
{
"path": "cudax/functors/ImageHighlighter.h",
"chars": 1080,
"preview": "#pragma once\n#include \"cudax/kernel.h\"\n#include \"cudax/functors/IsSilhouetteBoundary.h\"\n#include \"cudax/functors/IsSilho"
},
{
"path": "cudax/functors/IsMatchingDepth.h",
"chars": 1688,
"preview": "#pragma once\n#include \"cudax/kernel.h\"\n#include \"IsSilhouette.h\"\n\n//== NAMESPACE ======================================="
},
{
"path": "cudax/functors/IsSilhouette.h",
"chars": 978,
"preview": "#pragma once\n#include \"cudax/kernel.h\"\n\n//== NAMESPACE ================================================================\n"
},
{
"path": "cudax/functors/IsSilhouetteBoundary.h",
"chars": 997,
"preview": "#pragma once\n#include \"cudax/kernel.h\"\n\n//== NAMESPACE ================================================================\n"
},
{
"path": "cudax/functors/IsTopLeft3x3Block.h",
"chars": 591,
"preview": "#pragma once\n#include \"cudax/kernel.h\"\n\n//== NAMESPACE ================================================================\n"
},
{
"path": "cudax/functors/SkeletonJacobian.h",
"chars": 2441,
"preview": "#pragma once\n#include <thrust/device_vector.h>\n#include \"cudax/cuda_glm.h\"\n#include \"cudax/kernel.h\"\n#include \"CustomJoi"
},
{
"path": "cudax/helper_cuda.h",
"chars": 30863,
"preview": "/**\r\n * Copyright 1993-2014 NVIDIA Corporation. All rights reserved.\r\n *\r\n * Please refer to the NVIDIA end user licens"
},
{
"path": "cudax/kernel.cu",
"chars": 6495,
"preview": "#include \"util/gl_wrapper.h\" ///< for cuda_gl_interop\n#include <cuda_gl_interop.h>\n#include <thrust/host_vector.h>\n#incl"
},
{
"path": "cudax/kernel.h",
"chars": 4409,
"preview": "/// @warning NEVER include this on the C++ side, only externals\n#pragma once\n\n#ifndef __CUDACC__\n #error you cannot c"
},
{
"path": "cudax/kernel_debug.h",
"chars": 3505,
"preview": "#pragma once\n#include \"kernel.h\"\n#include <thrust/device_vector.h>\n#include <thrust/copy.h>\n\nusing namespace cudax;\n\n//-"
},
{
"path": "cudax/kernel_init.h",
"chars": 3598,
"preview": "#pragma once\n#include \"kernel.h\"\n#include \"cudax/MeshGrid.h\"\n#include \"cudax/Kinematic.h\"\n#include \"cudax/PixelIndexer.h"
},
{
"path": "cudax/kernel_upload.h",
"chars": 1369,
"preview": "#pragma once\n#include \"kernel.h\"\n#include \"Kinematic.h\"\n\nusing namespace cudax;\n\nvoid kernel_upload_dtform_idxs(int* H_d"
},
{
"path": "cudax/outer_product.cu",
"chars": 2063,
"preview": "#include \"thrust/device_vector.h\"\n#include \"thrust/host_vector.h\"\n#include \"thrust/copy.h\"\n#include \"cudax/Timer.h\"\n#inc"
},
{
"path": "matlab/ik_alignment/FKObject.m",
"chars": 3119,
"preview": "%==========================================================================\n% "
},
{
"path": "matlab/ik_alignment/PiecewiseRigidAlignment2D.m",
"chars": 7963,
"preview": "%==========================================================================\n% Dynamic 2D/3D Regist"
},
{
"path": "matlab/is_tracking_lost/andrew_ng_logistic_regression.m",
"chars": 652,
"preview": "function [f, theta] = andrew_ng_logistic_regression(x, y)\n\n[m, n] = size(x);\n\n%% Add intercept term to x\nx = [ones(m, 1)"
},
{
"path": "matlab/is_tracking_lost/data.txt",
"chars": 93571,
"preview": "0.352393 9.64347\n0.494556 8.07644\n0.542435 7.55977\n0.508226 7.59468\n0.532876 7.32193\n0.578142 7.00238\n0.56232 7.60578\n0."
},
{
"path": "matlab/is_tracking_lost/main.m",
"chars": 1664,
"preview": "clear; close all; clc;\r\nnum_frames = 5500;\r\n\r\n%% Create labels\r\nsuccess_and_failure_switch = [1, 8, 2240, 2321, 2423, 25"
},
{
"path": "matlab/is_tracking_lost/readme.txt",
"chars": 800,
"preview": "Each line of the file data.txt contains two numbers those are the metrics computed at a given frame. The first metric i"
},
{
"path": "openni/include/Driver/OniDriverAPI.h",
"chars": 17763,
"preview": "/*****************************************************************************\n* "
},
{
"path": "openni/include/Driver/OniDriverTypes.h",
"chars": 2315,
"preview": "/*****************************************************************************\n* "
},
{
"path": "openni/include/Linux-x86/OniPlatformLinux-x86.h",
"chars": 4576,
"preview": "/*****************************************************************************\n* "
},
{
"path": "openni/include/NiTE.h",
"chars": 21528,
"preview": "/*******************************************************************************\n* "
},
{
"path": "openni/include/NiteCAPI.h",
"chars": 4102,
"preview": "/*******************************************************************************\n* "
},
{
"path": "openni/include/NiteCEnums.h",
"chars": 3041,
"preview": "/*******************************************************************************\n* "
},
{
"path": "openni/include/NiteCTypes.h",
"chars": 4257,
"preview": "/*******************************************************************************\n* "
},
{
"path": "openni/include/NiteEnums.h",
"chars": 1685,
"preview": "/*******************************************************************************\n* "
},
{
"path": "openni/include/NiteVersion.h",
"chars": 1268,
"preview": "/*******************************************************************************\n* "
},
{
"path": "openni/include/OniCAPI.h",
"chars": 10663,
"preview": "/*****************************************************************************\n* "
},
{
"path": "openni/include/OniCEnums.h",
"chars": 2842,
"preview": "/*****************************************************************************\n* "
},
{
"path": "openni/include/OniCProperties.h",
"chars": 2881,
"preview": "/*****************************************************************************\n* "
},
{
"path": "openni/include/OniCTypes.h",
"chars": 6153,
"preview": "/*****************************************************************************\n* "
},
{
"path": "openni/include/OniEnums.h",
"chars": 2749,
"preview": "/*****************************************************************************\n* "
},
{
"path": "openni/include/OniPlatform.h",
"chars": 3324,
"preview": "/*****************************************************************************\n* "
},
{
"path": "openni/include/OniProperties.h",
"chars": 2832,
"preview": "/*****************************************************************************\n* "
},
{
"path": "openni/include/OniVersion.h",
"chars": 2601,
"preview": "/*****************************************************************************\n* "
},
{
"path": "openni/include/OpenNI.h",
"chars": 86815,
"preview": "/*****************************************************************************\n* "
},
{
"path": "openni/include/PS1080.h",
"chars": 9443,
"preview": "/*****************************************************************************\n* "
},
{
"path": "tracker/CMakeLists.txt",
"chars": 1626,
"preview": "#--- TODO: fully decouple library in subdirectory\n# http://stackoverflow.com/questions/7819647/cmake-build-library-and-l"
},
{
"path": "tracker/Calibration/Calibration.cpp",
"chars": 4074,
"preview": "#include \"Calibration.h\"\n\n#include \"util/qfile_helper.h\"\n#include \"tracker/Legacy/geometry/Cylinders.h\"\n#include \"tracke"
},
{
"path": "tracker/Calibration/Calibration.h",
"chars": 593,
"preview": "#pragma once\n#include <string>\n\nclass Cylinders;\nclass SkeletonSerializer;\nclass Worker;\n\nclass Calibration{\nprivate:\n "
},
{
"path": "tracker/Calibration/Skeleton_IO.cpp",
"chars": 1987,
"preview": "#include \"Skeleton_IO.h\"\n\n#include <fstream>\n#include <iostream>\n#include \"tracker/Legacy/geometry/Skeleton.h\"\nusing nam"
},
{
"path": "tracker/Calibration/Skeleton_IO.h",
"chars": 364,
"preview": "#pragma once\nclass Skeleton;\n#include <string>\n\nclass Skeleton_IO{\n Skeleton *_skeleton;\npublic:\n Skeleton_IO(Skel"
},
{
"path": "tracker/Calibration/default.calib",
"chars": 2742,
"preview": "root root 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1\npose root 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1\nscale pose 0.811646 0 0 0 0 0.811646"
},
{
"path": "tracker/Data/Camera.cpp",
"chars": 4171,
"preview": "#include \"Camera.h\"\n\n// Vector2i Camera::COL2DEPTHOFFSET;\n\n//Camera::Matrix44f Camera::view_matrix(){\n// // static Ma"
},
{
"path": "tracker/Data/Camera.h",
"chars": 1703,
"preview": "#pragma once\n#include \"tracker/Types.h\"\n#include <QSize>\n\n/// The running modes for cameras\nenum CAMERAMODE{ INVALID=-1,"
},
{
"path": "tracker/Data/DataFrame.h",
"chars": 908,
"preview": "#pragma once\n#include \"opencv2/core/core.hpp\" /// cv::Mat\n#include \"tracker/Types.h\"\n#include \"Camera.h\"\n\ntypedef unsign"
},
{
"path": "tracker/Data/DataStream.cpp",
"chars": 5986,
"preview": "#include \"DataStream.h\"\n#include <QFileDialog>\n#include <QByteArray>\n#include <QFile>\n\n#include \"util/qt2eigen.h\"\n#inclu"
},
{
"path": "tracker/Data/DataStream.h",
"chars": 1800,
"preview": "#pragma once\n#include <QList>\n\n#include \"tracker/ForwardDeclarations.h\"\n#include \"tracker/Types.h\"\n#include \"Camera.h\"\n#"
},
{
"path": "tracker/Data/SolutionStream.h",
"chars": 3669,
"preview": "#pragma once\n#include \"tracker/Types.h\"\n#include <vector>\n#include <QString>\n#include <fstream>\n#include <stdio.h>\n#incl"
},
{
"path": "tracker/Data/TextureColor8UC3.h",
"chars": 1614,
"preview": "#pragma once\n#include \"util/gl_wrapper.h\"\n#include \"util/mylogger.h\"\n\nclass ColorTexture8UC3{\nprivate:\n GLuint textur"
},
{
"path": "tracker/Data/TextureDepth16UC1.h",
"chars": 2184,
"preview": "#pragma once\n#include \"util/gl_wrapper.h\"\n#include \"util/mylogger.h\"\n#include \"stdint.h\" ///< uint16_t\n\nclass DepthTextu"
},
{
"path": "tracker/DataStructure/CustomJointInfo.h",
"chars": 2257,
"preview": "#pragma once\n#include <vector>\n#include <iostream>\n\n#ifdef __CUDACC__\n #include \"cudax/cuda_glm.h\"\n#else \n #includ"
},
{
"path": "tracker/DataStructure/SkeletonSerializer.cpp",
"chars": 6186,
"preview": "#include \"SkeletonSerializer.h\"\n\nSkeletonSerializer::SkeletonSerializer(Joint *root, const Mapping &mapping) : Skeleton("
},
{
"path": "tracker/DataStructure/SkeletonSerializer.h",
"chars": 1079,
"preview": "#pragma once\n#include \"tracker/Types.h\"\n#include \"util/mylogger.h\"\n#include \"tracker/Legacy/geometry/Mapping.h\"\n#include"
},
{
"path": "tracker/Detection/DetectionStream.h",
"chars": 18232,
"preview": "#pragma once\n#include <vector>\n#include <QString>\n#include <fstream>\n#include <stdio.h>\n#include <bitset>\n#include \"trac"
},
{
"path": "tracker/Detection/FindFingers.cpp",
"chars": 42127,
"preview": "#include \"FindFingers.h\"\n\n#include <iostream>\n#include <Eigen/Dense>\n#include <vector>\n#include <bitset>\n\n#include <open"
},
{
"path": "tracker/Detection/FindFingers.h",
"chars": 3867,
"preview": "#pragma once\n#include \"tracker/Types.h\"\n#include <vector>\n#include <set>\n#include \"tracker/ForwardDeclarations.h\"\nclass "
},
{
"path": "tracker/Detection/QianDetection.cpp",
"chars": 20999,
"preview": "#include <fstream>\n#include <math.h>\n#include \"util/gl_wrapper.h\"\n#include \"util/opencv_wrapper.h\"\n\n#include \"tracker/Wo"
},
{
"path": "tracker/Detection/QianDetection.h",
"chars": 1788,
"preview": "#pragma once\n#include \"tracker/ForwardDeclarations.h\"\n#include \"tracker/Types.h\"\n\nclass QianDetection {\nprivate:\n\tWorker"
},
{
"path": "tracker/Detection/TrivialDetector.cpp",
"chars": 3364,
"preview": "#include \"TrivialDetector.h\"\n\n#include \"util/mylogger.h\"\n#include \"util/opencv_wrapper.h\"\n#include \"tracker/Data/DataFra"
},
{
"path": "tracker/Detection/TrivialDetector.h",
"chars": 806,
"preview": "#pragma once\n#include \"tracker/Types.h\"\n#include \"tracker/ForwardDeclarations.h\"\n#include \"util/opencv_wrapper.h\"\n\nclass"
},
{
"path": "tracker/Detection/matlab_helpers.h",
"chars": 3245,
"preview": "#pragma once\n#include \"tracker/Types.h\"\n\nnamespace matlab{\n\n/// see matlab randn\nstatic inline Real randn( const double "
},
{
"path": "tracker/Energy/Collision.cpp",
"chars": 17946,
"preview": "#include \"Collision.h\"\n\n#include \"DebugRenderer.h\"\n#include \"util/mylogger.h\"\n\n#include \"tracker/Legacy/geometry/Cylinde"
},
{
"path": "tracker/Energy/Collision.h",
"chars": 1031,
"preview": "#pragma once\n#include \"tracker/ForwardDeclarations.h\"\n#include \"Energy.h\"\n#include \"tracker/Types.h\"\n#include <vector>\n\n"
},
{
"path": "tracker/Energy/Damping.cpp",
"chars": 1303,
"preview": "#include \"Damping.h\"\n#include \"tracker/DataStructure/SkeletonSerializer.h\"\n#include \"tracker/TwSettings.h\"\n\nnamespace en"
},
{
"path": "tracker/Energy/Damping.h",
"chars": 480,
"preview": "#pragma once\n#include \"tracker/ForwardDeclarations.h\"\n#include \"Energy.h\"\n#include \"tracker/Types.h\"\n#include <vector>\n\n"
},
{
"path": "tracker/Energy/Energy.cpp",
"chars": 2931,
"preview": "#include \"Energy.h\"\n#include \"util/mylogger.h\"\nnamespace energy{\n\nstatic bool debug_print_delta_theta = false;\n\nbool Ene"
},
{
"path": "tracker/Energy/Energy.h",
"chars": 388,
"preview": "#pragma once\n#include \"tracker/Types.h\"\n\nstruct TrackingError{\n float _3D;\n float _2D;\n static TrackingError in"
},
{
"path": "tracker/Energy/Fitting/DistanceTransform.h",
"chars": 5532,
"preview": "#pragma once\n#ifdef WITH_OPENCV\n #include \"opencv2/core/core.hpp\" \n#endif\n\nclass DistanceTransform{\nprivate:\n i"
},
{
"path": "tracker/Energy/Fitting/Settings.h",
"chars": 1047,
"preview": "#pragma once\n\n/// @note this needs to be placed outside of Fitting.h as these settings\n/// are parsed by the CUDA "
},
{
"path": "tracker/Energy/Fitting/TrackingMonitor.h",
"chars": 1771,
"preview": "#pragma once\n#include <queue>\n#include <fstream>\n#include \"tracker/Types.h\"\n\nclass TrackingMonitor{\nprivate:\n std::qu"
},
{
"path": "tracker/Energy/Fitting.cpp",
"chars": 7053,
"preview": "#include \"Fitting.h\"\n\n#include \"util/mylogger.h\"\n#include \"util/tictoc.h\"\n\n#include \"tracker/Worker.h\"\n#include \"tracker"
},
{
"path": "tracker/Energy/Fitting.h",
"chars": 934,
"preview": "#pragma once\n#include \"tracker/ForwardDeclarations.h\"\n#include \"tracker/Types.h\"\n#include \"tracker/Energy/Fitting/Settin"
},
{
"path": "tracker/Energy/JointLimits.cpp",
"chars": 1806,
"preview": "#include \"JointLimits.h\"\n#include \"tracker/DataStructure/SkeletonSerializer.h\"\n\nvoid energy::JointLimits::init(SkeletonS"
},
{
"path": "tracker/Energy/JointLimits.h",
"chars": 470,
"preview": "#pragma once\n#include \"tracker/ForwardDeclarations.h\"\n#include \"Energy.h\"\n#include \"tracker/Types.h\"\n#include <vector>\n\n"
},
{
"path": "tracker/Energy/PoseSpace.cpp",
"chars": 13884,
"preview": "#include \"PoseSpace.h\"\n#include \"util/opencv_wrapper.h\"\n#include \"util/mylogger.h\"\n#include \"util/qfile_helper.h\"\n#inclu"
},
{
"path": "tracker/Energy/PoseSpace.h",
"chars": 2842,
"preview": "#pragma once\n#include \"tracker/ForwardDeclarations.h\"\n#include \"tracker/Energy/Energy.h\"\n#include \"tracker/Types.h\"\n#inc"
},
{
"path": "tracker/Energy/Temporal.cpp",
"chars": 5179,
"preview": "#include \"Temporal.h\"\n#include \"tracker/Data/DataFrame.h\"\n#include \"tracker/DataStructure/SkeletonSerializer.h\"\n#include"
},
{
"path": "tracker/Energy/Temporal.h",
"chars": 1011,
"preview": "#pragma once\n#include <vector>\n#include \"tracker/ForwardDeclarations.h\"\n#include \"tracker/Types.h\"\n#include \"tracker/Ene"
},
{
"path": "tracker/Energy/Wristband.cpp",
"chars": 3584,
"preview": "#include \"Wristband.h\"\n\n#include \"util/gl_wrapper.h\"\n#include \"util/opencv_wrapper.h\"\n\n#include \"tracker/Data/Camera.h\"\n"
},
{
"path": "tracker/Energy/Wristband.h",
"chars": 575,
"preview": "#pragma once\n#include \"tracker/ForwardDeclarations.h\"\n#include \"Energy.h\"\n#include \"tracker/Types.h\"\n#include <vector>\n\n"
},
{
"path": "tracker/ForwardDeclarations.h",
"chars": 909,
"preview": "///--- Global Forward Declaration of classes\n\n/// @note keep this super-lightweight (no includes here)\n#pragma once\n\n///"
},
{
"path": "tracker/HandFinder/HandFinder.cpp",
"chars": 10612,
"preview": "#include \"HandFinder.h\"\n\n#include <numeric> ///< std::iota\n#include <fstream> ///< ifstream\n#include \"util/mylogger.h\"\n#"
},
{
"path": "tracker/HandFinder/HandFinder.h",
"chars": 1349,
"preview": "#pragma once\n#include \"tracker/ForwardDeclarations.h\"\n#include \"tracker/Types.h\"\n#include \"util/opencv_wrapper.h\"\n#inclu"
},
{
"path": "tracker/HandFinder/connectedComponents.cpp",
"chars": 15828,
"preview": "/*M///////////////////////////////////////////////////////////////////////////////////////\n//\n// IMPORTANT: READ BEFORE"
},
{
"path": "tracker/HandFinder/connectedComponents.h",
"chars": 1270,
"preview": "//Snipped of opencv3 imgproc.hpp containing these functions\n\n#include \"opencv2/core/core.hpp\"\n\n/// andrea: also on linux"
},
{
"path": "tracker/HandFinder/wristband.txt",
"chars": 39,
"preview": "hsv_min: 94 111 37\nhsv_max: 120 255 255"
},
{
"path": "tracker/Legacy/LegacyTracker.cpp",
"chars": 3409,
"preview": "#include \"LegacyTracker.h\"\n#include \"tracker/Data/DataStream.h\"\n#include \"algorithm/ICP.h\"\n#include \"geometry/Cylinders."
},
{
"path": "tracker/Legacy/LegacyTracker.h",
"chars": 1051,
"preview": "#pragma once\n#include \"tracker/ForwardDeclarations.h\"\n#include \"tracker/Types.h\"\n\n#if 0\n /// TODO: re-wire legacy tra"
},
{
"path": "tracker/Legacy/algorithm/Detector.h",
"chars": 3979,
"preview": "#pragma once\n\n#include <vector>\n#include \"DataStream.h\"\n#include \"MathUtils.h\"\n#include \"Util.h\"\n#include \"util/opencv_w"
},
{
"path": "tracker/Legacy/algorithm/ICP.cpp",
"chars": 11832,
"preview": "#include \"ICP.h\"\n\n#include <cassert>\n#include <iostream>\n\n//============================================================"
},
{
"path": "tracker/Legacy/algorithm/ICP.h",
"chars": 1507,
"preview": "#pragma once\n\n#include \"../math/Inverse_kinematics.h\"\n#include \"../math/MathUtils.h\"\n#include \"../geometry/Cylinders.h\"\n"
},
{
"path": "tracker/Legacy/fingerfist.mat",
"chars": 1511032,
"preview": "-5.57381 -4.8743 18.1969 0.0991416 -0.102195 1.71925 0.0321766 -0.137997 0.219164 -0.00622965 0.0695568 0.0145279 -0.103"
},
{
"path": "tracker/Legacy/geometry/Cylinders.cpp",
"chars": 9894,
"preview": "#include \"Cylinders.h\"\n#include <vector>\n\nusing namespace std;\n\n//======================================================"
},
{
"path": "tracker/Legacy/geometry/Cylinders.h",
"chars": 2322,
"preview": "#pragma once\n\n#include <map>\n#include <string>\n#include \"Joint.h\"\n#include \"Skeleton.h\"\n\n//============================="
},
{
"path": "tracker/Legacy/geometry/Effector.cpp",
"chars": 1343,
"preview": "#include \"Effector.h\"\n\nEffector::Effector(\n\t\tJoint *joint,\n\t\tconst Vec3f &position,\n\t\tconst Vec3f &target,\n\t\tconst Vec3f"
},
{
"path": "tracker/Legacy/geometry/Effector.h",
"chars": 1067,
"preview": "#pragma once\n#include \"Joint.h\"\n\nclass Effector\n{\n public:\n\n Effector(\n Joint *joint,\n "
},
{
"path": "tracker/Legacy/geometry/Joint.cpp",
"chars": 4649,
"preview": "#include \"Joint.h\"\n\n#include <Eigen/Geometry>\n\n#include \"../util/Util.h\"\n\nusing namespace Eigen;\n\nJoint::Joint(\n\tconst s"
},
{
"path": "tracker/Legacy/geometry/Joint.h",
"chars": 1439,
"preview": "#pragma once\n#include <string>\n#include <vector>\n\n#include \"../math/MathUtils.h\"\n\nclass Joint\n{\n public:\n\n Joi"
},
{
"path": "tracker/Legacy/geometry/Mapping.cpp",
"chars": 19748,
"preview": "#include \"Mapping.h\"\n\n#include <iostream>\n#include <iomanip>\n#include \"../math/PCA.h\"\n\nusing namespace std;\nusing namesp"
},
{
"path": "tracker/Legacy/geometry/Mapping.h",
"chars": 6012,
"preview": "#pragma once\n\n\n#include <string>\n#include <vector>\n#include <map>\n#include <unordered_map>\n#include <limits>\n\n#include \""
},
{
"path": "tracker/Legacy/geometry/Skeleton.cpp",
"chars": 28093,
"preview": "#include \"Skeleton.h\"\n\n#include <Eigen/Geometry>\n\n#include <iostream>\n#include \"../util/Util.h\"\n\nusing namespace std;\nus"
},
{
"path": "tracker/Legacy/geometry/Skeleton.h",
"chars": 19025,
"preview": "#pragma once\n\n#include <map>\n#include <vector>\n\n#include \"../math/MathUtils.h\"\n#include \"Joint.h\"\n#include \"Effector.h\"\n"
},
{
"path": "tracker/Legacy/math/Gauss_newton.h",
"chars": 0,
"preview": ""
},
{
"path": "tracker/Legacy/math/Inverse_kinematics.cpp",
"chars": 15643,
"preview": "#include \"Inverse_kinematics.h\"\n\n#include \"../util/Util.h\"\n#include \"MathUtils.h\"\n#include <iostream>\n#include \"../util/"
}
]
// ... and 73 more files (download for full content)
About this extraction
This page contains the full source code of the OpenGP/htrack GitHub repository, extracted and formatted as plain text for AI agents and large language models (LLMs). The extraction includes 273 files (2.6 MB), approximately 683.2k tokens, and a symbol index with 723 extracted functions, classes, methods, constants, and types. Use this with OpenClaw, Claude, ChatGPT, Cursor, Windsurf, or any other AI tool that accepts text input. You can copy the full output to your clipboard or download it as a .txt file.
Extracted by GitExtract — free GitHub repo to text converter for AI. Built by Nikandr Surkov.