Classes | Defines | Typedefs | Functions | Variables
kinect_teleop.cpp File Reference
#include <math.h>
#include <vector>
#include <ros/ros.h>
#include <ros/package.h>
#include <pr2_controllers_msgs/JointTrajectoryAction.h>
#include <actionlib/client/simple_action_client.h>
#include <tf/transform_broadcaster.h>
#include <kdl/frames.hpp>
#include <std_msgs/String.h>
#include <geometry_msgs/Twist.h>
#include <Eigen/Core>
#include <XnOpenNI.h>
#include <XnCodecIDs.h>
#include <XnCppWrapper.h>
Include dependency graph for kinect_teleop.cpp:

Go to the source code of this file.

Classes

struct  pr2_joint
class  TeleopPR2Ni

Defines

#define CHECK_RC(nRetVal, what)
#define my_pi   3.141592653589793

Typedefs

typedef
actionlib::SimpleActionClient
< pr2_controllers_msgs::JointTrajectoryAction
TrajClient
typedef std::vector< std::pair
< Eigen::VectorXd,
Eigen::VectorXd > > 
Trajectory

Functions

void checkPose (TeleopPR2Ni &obj)
float getAngleBetweenLimbs (XnUserID const &user, XnSkeletonJoint const &eJoint1, XnSkeletonJoint const &eJoint2, XnSkeletonJoint const &eJoint3, XnSkeletonJoint const &eJoint4)
XnPoint3D getBodyLoc (XnUserID const &user, XnSkeletonJoint const &eJoint1)
float getLimbAngle (XnUserID const &user, XnSkeletonJoint const &eJoint1, XnSkeletonJoint const &eJoint2, XnSkeletonJoint const &eJoint3)
float getTorsoRotation (XnUserID const &user, XnSkeletonJoint const &eJoint1, XnSkeletonJoint const &eJoint2)
int main (int argc, char **argv)
void XN_CALLBACK_TYPE User_LostUser (xn::UserGenerator &generator, XnUserID nId, void *pCookie)
void XN_CALLBACK_TYPE User_NewUser (xn::UserGenerator &generator, XnUserID nId, void *pCookie)
void XN_CALLBACK_TYPE UserCalibration_CalibrationEnd (xn::SkeletonCapability &capability, XnUserID nId, XnBool bSuccess, void *pCookie)
void XN_CALLBACK_TYPE UserCalibration_CalibrationStart (xn::SkeletonCapability &capability, XnUserID nId, void *pCookie)
void XN_CALLBACK_TYPE UserPose_PoseDetected (xn::PoseDetectionCapability &capability, XnChar const *strPose, XnUserID nId, void *pCookie)

Variables

TrajClientarm_client_l
TrajClientarm_client_r
XnBool g_bNeedPose = FALSE
xn::Context g_Context
xn::DepthGenerator g_DepthGenerator
XnChar g_strPose [20] = ""
xn::UserGenerator g_UserGenerator
XnPoint3D init_usr_loc
XnPoint3D init_usr_LS
XnPoint3D init_usr_RS

Define Documentation

#define CHECK_RC (   nRetVal,
  what 
)
Value:
if (nRetVal != XN_STATUS_OK)                                          \
    {                                                                   \
      printf("%s failed: %s\n", what, xnGetStatusString(nRetVal));      \
      return nRetVal;                                                   \
    }

Definition at line 53 of file kinect_teleop.cpp.

#define my_pi   3.141592653589793

Author Jan Wuelfing and Tobias Springenberg

Please note that parts of the angle calculation were taken from the veltrobot teleop implementation which can be found at http://www.ros.org/wiki/veltrobot_teleop

Definition at line 31 of file kinect_teleop.cpp.


Typedef Documentation

Definition at line 35 of file kinect_teleop.cpp.

typedef std::vector<std::pair<Eigen::VectorXd, Eigen::VectorXd> > Trajectory

Definition at line 36 of file kinect_teleop.cpp.


Function Documentation

void checkPose ( TeleopPR2Ni obj)

Definition at line 552 of file kinect_teleop.cpp.

float getAngleBetweenLimbs ( XnUserID const user,
XnSkeletonJoint const eJoint1,
XnSkeletonJoint const eJoint2,
XnSkeletonJoint const eJoint3,
XnSkeletonJoint const eJoint4 
)

Definition at line 332 of file kinect_teleop.cpp.

XnPoint3D getBodyLoc ( XnUserID const user,
XnSkeletonJoint const eJoint1 
)

Definition at line 298 of file kinect_teleop.cpp.

float getLimbAngle ( XnUserID const user,
XnSkeletonJoint const eJoint1,
XnSkeletonJoint const eJoint2,
XnSkeletonJoint const eJoint3 
)

Definition at line 412 of file kinect_teleop.cpp.

float getTorsoRotation ( XnUserID const user,
XnSkeletonJoint const eJoint1,
XnSkeletonJoint const eJoint2 
)

Definition at line 486 of file kinect_teleop.cpp.

int main ( int  argc,
char **  argv 
)

Definition at line 673 of file kinect_teleop.cpp.

void XN_CALLBACK_TYPE User_LostUser ( xn::UserGenerator &  generator,
XnUserID  nId,
void *  pCookie 
)

Definition at line 263 of file kinect_teleop.cpp.

void XN_CALLBACK_TYPE User_NewUser ( xn::UserGenerator &  generator,
XnUserID  nId,
void *  pCookie 
)

Definition at line 254 of file kinect_teleop.cpp.

void XN_CALLBACK_TYPE UserCalibration_CalibrationEnd ( xn::SkeletonCapability &  capability,
XnUserID  nId,
XnBool  bSuccess,
void *  pCookie 
)

Definition at line 273 of file kinect_teleop.cpp.

void XN_CALLBACK_TYPE UserCalibration_CalibrationStart ( xn::SkeletonCapability &  capability,
XnUserID  nId,
void *  pCookie 
)

Definition at line 268 of file kinect_teleop.cpp.

void XN_CALLBACK_TYPE UserPose_PoseDetected ( xn::PoseDetectionCapability &  capability,
XnChar const strPose,
XnUserID  nId,
void *  pCookie 
)

Definition at line 290 of file kinect_teleop.cpp.


Variable Documentation

Definition at line 38 of file kinect_teleop.cpp.

Definition at line 37 of file kinect_teleop.cpp.

XnBool g_bNeedPose = FALSE

Definition at line 49 of file kinect_teleop.cpp.

xn::Context g_Context

Definition at line 41 of file kinect_teleop.cpp.

xn::DepthGenerator g_DepthGenerator

Definition at line 42 of file kinect_teleop.cpp.

XnChar g_strPose[20] = ""

Definition at line 50 of file kinect_teleop.cpp.

xn::UserGenerator g_UserGenerator

Definition at line 43 of file kinect_teleop.cpp.

XnPoint3D init_usr_loc

Definition at line 45 of file kinect_teleop.cpp.

XnPoint3D init_usr_LS

Definition at line 47 of file kinect_teleop.cpp.

XnPoint3D init_usr_RS

Definition at line 46 of file kinect_teleop.cpp.

 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines


kinect_teleop
Author(s): Jan Wülfing
autogenerated on Wed Dec 26 2012 16:45:13