Classes | Defines | Functions | Variables
detect_hands_wskel.cpp File Reference
#include <boost/thread/thread.hpp>
#include <boost/thread/mutex.hpp>
#include <boost/thread/condition.hpp>
#include <ros/ros.h>
#include <tf/transform_listener.h>
#include <sensor_msgs/PointCloud.h>
#include <mapping_msgs/PolygonalMap.h>
#include <body_msgs/Hands.h>
#include <sensor_msgs/point_cloud_conversion.h>
#include <pcl_tools/pcl_utils.h>
#include <nnn/nnn.hpp>
#include <pcl_tools/segfast.hpp>
#include "pcl/io/pcd_io.h"
#include "pcl/point_types.h"
#include <pcl/ModelCoefficients.h>
#include <pcl/features/normal_3d.h>
#include <pcl/filters/extract_indices.h>
#include <pcl/filters/passthrough.h>
#include <pcl/sample_consensus/method_types.h>
#include <pcl/sample_consensus/model_types.h>
#include <pcl/segmentation/sac_segmentation.h>
#include <body_msgs/Skeletons.h>
#include <turtlesim/Velocity.h>
Include dependency graph for detect_hands_wskel.cpp:

Go to the source code of this file.

Classes

struct  HandDetector::calibrationBundle
class  HandDetector
 HandDetector is the main ROS communication class, and its function is just to tye things together. More...
struct  stateMachine
 TimeEvaluator is a nifty function to make benchmarking programs much simpler More...
class  TimeEvaluator

Defines

#define ABS(A)   (((A) < 0) ? (-(A)) : (A))
#define HANDSTOGETHER   100
#define HEADPOS   0
#define LEFT_ELBOWPOS   (RIGHT_ELBOWPOS+1)
#define LEFT_FOOTPOS   (RIGHT_KNEEPOS+1)
#define LEFT_HIPPOS   (TORSOPOS+1)
#define LEFT_KNEEPOS   (RIGHT_HIPPOS+1)
#define LEFT_SHOULDERPOS   (RIGHT_SHOULDERPOS+1)
#define LHANDPOS   (HEADPOS+1)
#define MAX(A, B)   ((A) > (B) ? (A) : (B))
#define MIN(A, B)   ((A) < (B) ? (A) : (B))
#define NECKPOS   (RHANDPOS+1)
#define RHANDPOS   (LHANDPOS+1)
#define RIGHT_ELBOWPOS   (LEFT_SHOULDERPOS+1)
#define RIGHT_FOOTPOS   (LEFT_FOOTPOS+1)
#define RIGHT_HIPPOS   (LEFT_HIPPOS+1)
#define RIGHT_KNEEPOS   (LEFT_KNEEPOS+1)
#define RIGHT_SHOULDERPOS   (NECKPOS+1)
#define SKEL_POINTS   (RIGHT_FOOTPOS+1)
#define TORSOPOS   (LEFT_ELBOWPOS+1)
#define UNDEFINED   99

Functions

pcl::PointXYZ addVector (const Eigen::Vector4f &_C, geometry_msgs::Point A, geometry_msgs::Vector3 B, double scale)
void cleanState (stateMachine &state)
geometry_msgs::Point eigenToMsgPoint (const Eigen::Vector4f &v)
geometry_msgs::Point32 eigenToMsgPoint32 (const Eigen::Vector4f &v)
pcl::PointXYZ eigenToPclPoint (const Eigen::Vector4f &v)
void eventState (stateMachine &state, uint a)
void flipvec (const Eigen::Vector4f &palm, const Eigen::Vector4f &fcentroid, Eigen::Vector4f &dir)
float gdist (pcl::PointXYZ pt, const Eigen::Vector4f &v)
void getEigens (body_msgs::Hand &h)
void getHandCloud (body_msgs::Hand &hand, sensor_msgs::PointCloud2 &fullcloud)
 grabs the correct portion of the point cloud to get the hand cloud
void getHandPos (body_msgs::Hand &hand, pcl::PointXYZ &hand1, char a)
void getHandPos (body_msgs::Hand &hand, pcl::PointXYZ &hand1)
void getHands (body_msgs::Skeleton &skel, sensor_msgs::PointCloud2 &cloud, body_msgs::Hands &handsmsg)
 converts a skeleton + cloud into a hands message, by calling getHandCloud
void getHands (body_msgs::Skeleton &skel, sensor_msgs::PointCloud2 &cloud, body_msgs::Hands &handsmsg, std::pair< pcl::PointXYZ, pcl::PointXYZ > &var, std::pair< pcl::PointXYZ, pcl::PointXYZ > &shoulders)
bool isJointGood (body_msgs::SkeletonJoint &joint)
int main (int argc, char **argv)
bool pointComparison (pcl::PointXYZ a, pcl::PointXYZ b)
bool pointComparisonHands (pcl::PointXYZ a, pcl::PointXYZ b)
bool pointComparisonHead (pcl::PointXYZ a, pcl::PointXYZ b)
template<typename Point1 , typename Point2 >
void PointConversion (Point1 pt1, Point2 &pt2)
pcl::PointXYZ pointToPclPoint (geometry_msgs::Point p)
geometry_msgs::Transform pointToTransform (geometry_msgs::Point p)

Variables

int CALIB_FLAG = 0
int DIST_FLAG = 0
int distCounter = 0
stateMachine leftState
int LHAND_FLAG = 0
int RECOG_FLAG = 1
stateMachine rightState
int STATE_BEFORE = -1
int tRecogCounter = 0
int turtlePubCounter = 0

Define Documentation

#define ABS (   A)    (((A) < 0) ? (-(A)) : (A))

Definition at line 79 of file detect_hands_wskel.cpp.

#define HANDSTOGETHER   100

Definition at line 112 of file detect_hands_wskel.cpp.

#define HEADPOS   0

Definition at line 90 of file detect_hands_wskel.cpp.

#define LEFT_ELBOWPOS   (RIGHT_ELBOWPOS+1)

Definition at line 97 of file detect_hands_wskel.cpp.

#define LEFT_FOOTPOS   (RIGHT_KNEEPOS+1)

Definition at line 103 of file detect_hands_wskel.cpp.

#define LEFT_HIPPOS   (TORSOPOS+1)

Definition at line 99 of file detect_hands_wskel.cpp.

#define LEFT_KNEEPOS   (RIGHT_HIPPOS+1)

Definition at line 101 of file detect_hands_wskel.cpp.

Definition at line 95 of file detect_hands_wskel.cpp.

#define LHANDPOS   (HEADPOS+1)

Definition at line 91 of file detect_hands_wskel.cpp.

#define MAX (   A,
 
)    ((A) > (B) ? (A) : (B))

Definition at line 77 of file detect_hands_wskel.cpp.

#define MIN (   A,
 
)    ((A) < (B) ? (A) : (B))

Definition at line 78 of file detect_hands_wskel.cpp.

#define NECKPOS   (RHANDPOS+1)

Definition at line 93 of file detect_hands_wskel.cpp.

#define RHANDPOS   (LHANDPOS+1)

Definition at line 92 of file detect_hands_wskel.cpp.

#define RIGHT_ELBOWPOS   (LEFT_SHOULDERPOS+1)

Definition at line 96 of file detect_hands_wskel.cpp.

#define RIGHT_FOOTPOS   (LEFT_FOOTPOS+1)

Definition at line 104 of file detect_hands_wskel.cpp.

#define RIGHT_HIPPOS   (LEFT_HIPPOS+1)

Definition at line 100 of file detect_hands_wskel.cpp.

#define RIGHT_KNEEPOS   (LEFT_KNEEPOS+1)

Definition at line 102 of file detect_hands_wskel.cpp.

#define RIGHT_SHOULDERPOS   (NECKPOS+1)

Definition at line 94 of file detect_hands_wskel.cpp.

#define SKEL_POINTS   (RIGHT_FOOTPOS+1)

Definition at line 108 of file detect_hands_wskel.cpp.

#define TORSOPOS   (LEFT_ELBOWPOS+1)

Definition at line 98 of file detect_hands_wskel.cpp.

#define UNDEFINED   99

Definition at line 109 of file detect_hands_wskel.cpp.


Function Documentation

pcl::PointXYZ addVector ( const Eigen::Vector4f &  _C,
geometry_msgs::Point  A,
geometry_msgs::Vector3  B,
double  scale 
)

Definition at line 258 of file detect_hands_wskel.cpp.

void cleanState ( stateMachine state)

Definition at line 546 of file detect_hands_wskel.cpp.

geometry_msgs::Point eigenToMsgPoint ( const Eigen::Vector4f &  v)

Definition at line 228 of file detect_hands_wskel.cpp.

geometry_msgs::Point32 eigenToMsgPoint32 ( const Eigen::Vector4f &  v)

Definition at line 223 of file detect_hands_wskel.cpp.

pcl::PointXYZ eigenToPclPoint ( const Eigen::Vector4f &  v)

Definition at line 234 of file detect_hands_wskel.cpp.

void eventState ( stateMachine state,
uint  a 
)

Definition at line 563 of file detect_hands_wskel.cpp.

void flipvec ( const Eigen::Vector4f &  palm,
const Eigen::Vector4f &  fcentroid,
Eigen::Vector4f &  dir 
)

Definition at line 209 of file detect_hands_wskel.cpp.

float gdist ( pcl::PointXYZ  pt,
const Eigen::Vector4f &  v 
)

Definition at line 205 of file detect_hands_wskel.cpp.

void getEigens ( body_msgs::Hand &  h)

Definition at line 274 of file detect_hands_wskel.cpp.

void getHandCloud ( body_msgs::Hand &  hand,
sensor_msgs::PointCloud2 &  fullcloud 
)

grabs the correct portion of the point cloud to get the hand cloud

Parameters:
theresultant Hand message with the location of the hand and arm already added. This message is filled out further in this function
fullcloudthe full point cloud from the kinect

Definition at line 312 of file detect_hands_wskel.cpp.

void getHandPos ( body_msgs::Hand &  hand,
pcl::PointXYZ &  hand1,
char  a 
)

Definition at line 361 of file detect_hands_wskel.cpp.

void getHandPos ( body_msgs::Hand &  hand,
pcl::PointXYZ &  hand1 
)

Definition at line 381 of file detect_hands_wskel.cpp.

void getHands ( body_msgs::Skeleton &  skel,
sensor_msgs::PointCloud2 &  cloud,
body_msgs::Hands &  handsmsg 
)

converts a skeleton + cloud into a hands message, by calling getHandCloud

Parameters:
skelthe skeleton who's hands we need to find
cloudthe full point cloud from the kinect
handsmsgthe resultant Hands message

Definition at line 404 of file detect_hands_wskel.cpp.

void getHands ( body_msgs::Skeleton &  skel,
sensor_msgs::PointCloud2 &  cloud,
body_msgs::Hands &  handsmsg,
std::pair< pcl::PointXYZ, pcl::PointXYZ > &  var,
std::pair< pcl::PointXYZ, pcl::PointXYZ > &  shoulders 
)

Definition at line 449 of file detect_hands_wskel.cpp.

bool isJointGood ( body_msgs::SkeletonJoint &  joint)

Definition at line 267 of file detect_hands_wskel.cpp.

int main ( int  argc,
char **  argv 
)

Definition at line 1354 of file detect_hands_wskel.cpp.

bool pointComparison ( pcl::PointXYZ  a,
pcl::PointXYZ  b 
)

Definition at line 532 of file detect_hands_wskel.cpp.

bool pointComparisonHands ( pcl::PointXYZ  a,
pcl::PointXYZ  b 
)

Definition at line 495 of file detect_hands_wskel.cpp.

bool pointComparisonHead ( pcl::PointXYZ  a,
pcl::PointXYZ  b 
)

Definition at line 517 of file detect_hands_wskel.cpp.

template<typename Point1 , typename Point2 >
void PointConversion ( Point1  pt1,
Point2 &  pt2 
)

Definition at line 216 of file detect_hands_wskel.cpp.

pcl::PointXYZ pointToPclPoint ( geometry_msgs::Point  p)

Definition at line 250 of file detect_hands_wskel.cpp.

geometry_msgs::Transform pointToTransform ( geometry_msgs::Point  p)

Definition at line 241 of file detect_hands_wskel.cpp.


Variable Documentation

int CALIB_FLAG = 0

Definition at line 140 of file detect_hands_wskel.cpp.

int DIST_FLAG = 0

Definition at line 146 of file detect_hands_wskel.cpp.

int distCounter = 0

Definition at line 147 of file detect_hands_wskel.cpp.

Definition at line 138 of file detect_hands_wskel.cpp.

int LHAND_FLAG = 0

Definition at line 141 of file detect_hands_wskel.cpp.

int RECOG_FLAG = 1

Definition at line 142 of file detect_hands_wskel.cpp.

Definition at line 138 of file detect_hands_wskel.cpp.

int STATE_BEFORE = -1

Definition at line 144 of file detect_hands_wskel.cpp.

int tRecogCounter = 0

Definition at line 143 of file detect_hands_wskel.cpp.

Definition at line 145 of file detect_hands_wskel.cpp.



labust_kinect
Author(s): LABUST
autogenerated on Fri Feb 7 2014 11:37:27