#include <ros/ros.h>#include <ros/package.h>#include <std_msgs/UInt8.h>#include <tf/transform_broadcaster.h>#include <XnOpenNI.h>#include <XnCppWrapper.h>#include <XnHash.h>#include <XnLog.h>#include <XnVNite.h>#include <XnVPointControl.h>
Go to the source code of this file.
Classes | |
| class | XnVPointPublisher |
Defines | |
| #define | CHECK_RC(nRetVal, what) |
Enumerations | |
| enum | SessionState { IN_SESSION, NOT_IN_SESSION, QUICK_REFOCUS } |
Functions | |
| void XN_CALLBACK_TYPE | FocusProgress (const XnChar *strFocus, const XnPoint3D &ptPosition, XnFloat fProgress, void *UserCxt) |
| int | main (int argc, char **argv) |
| void XN_CALLBACK_TYPE | NoHands (void *UserCxt) |
| void XN_CALLBACK_TYPE | SessionEnding (void *UserCxt) |
| void XN_CALLBACK_TYPE | SessionStarting (const XnPoint3D &ptPosition, void *UserCxt) |
Variables | |
| xn::Context | g_Context |
| xn::DepthGenerator | g_DepthGenerator |
| xn::HandsGenerator | g_HandsGenerator |
| XnVFlowRouter * | g_pFlowRouter |
| XnVPointPublisher * | g_pPublisher |
| XnVSessionManager * | g_pSessionManager |
| SessionState | g_SessionState = NOT_IN_SESSION |
| ros::Publisher | hand_point_pub_ |
| ros::Publisher | hand_point_status_pub_ |
| #define CHECK_RC | ( | nRetVal, | |
| what | |||
| ) |
if (nRetVal != XN_STATUS_OK){ \ printf ("%s failed: %s\n", what, xnGetStatusString (nRetVal)); \ return nRetVal; \ }
Definition at line 35 of file openni_pointer.cpp.
| enum SessionState |
Definition at line 28 of file openni_pointer.cpp.
| void XN_CALLBACK_TYPE FocusProgress | ( | const XnChar * | strFocus, |
| const XnPoint3D & | ptPosition, | ||
| XnFloat | fProgress, | ||
| void * | UserCxt | ||
| ) |
Definition at line 44 of file openni_pointer.cpp.
| int main | ( | int | argc, |
| char ** | argv | ||
| ) |
Definition at line 183 of file openni_pointer.cpp.
| void XN_CALLBACK_TYPE NoHands | ( | void * | UserCxt | ) |
Definition at line 64 of file openni_pointer.cpp.
| void XN_CALLBACK_TYPE SessionEnding | ( | void * | UserCxt | ) |
Definition at line 58 of file openni_pointer.cpp.
| void XN_CALLBACK_TYPE SessionStarting | ( | const XnPoint3D & | ptPosition, |
| void * | UserCxt | ||
| ) |
Definition at line 51 of file openni_pointer.cpp.
| xn::Context g_Context |
Definition at line 16 of file openni_pointer.cpp.
| xn::DepthGenerator g_DepthGenerator |
Definition at line 17 of file openni_pointer.cpp.
| xn::HandsGenerator g_HandsGenerator |
Definition at line 18 of file openni_pointer.cpp.
| XnVFlowRouter* g_pFlowRouter |
Definition at line 22 of file openni_pointer.cpp.
Definition at line 181 of file openni_pointer.cpp.
| XnVSessionManager* g_pSessionManager |
Definition at line 21 of file openni_pointer.cpp.
Definition at line 41 of file openni_pointer.cpp.
Definition at line 25 of file openni_pointer.cpp.
Definition at line 26 of file openni_pointer.cpp.