Classes | Public Member Functions | Private Attributes
HandDetector Class Reference

HandDetector is the main ROS communication class, and its function is just to tye things together. More...

List of all members.

Classes

struct  calibrationBundle

Public Member Functions

void armCalculationTurtlePub (float &l, float &r, float &h)
void armCalibration (calibrationBundle &c, std::pair< pcl::PointXYZ, pcl::PointXYZ > hands, std::pair< pcl::PointXYZ, pcl::PointXYZ > shoulders)
void armCalibrationDataProcessing ()
float calcDist (float a, float b)
float calcPercVal (float a, float b)
void cloudcb (const sensor_msgs::PointCloud2ConstPtr &scan)
void cloudcb (const sensor_msgs::PointCloud2ConstPtr &scan)
void cls ()
void distancDataProcessing (pcl::PointXYZ *p)
void getInfoStateMachine (body_msgs::Skeleton &skel, body_msgs::Hands &handsmsg, pcl::PointXYZ *skelpos, bool *isJoint)
 HandDetector ()
 HandDetector ()
void makeHand (pcl::PointCloud< pcl::PointXYZ > &cloud, Eigen::Vector4f &_arm, body_msgs::Hand &handmsg)
void messageSync ()
void printRecog (int state, int LR)
void processData (body_msgs::Skeletons skels, sensor_msgs::PointCloud2 cloud, calibrationBundle &c)
void skelcb (const body_msgs::SkeletonsConstPtr &skels)
void tRecognition (pcl::PointXYZ *p, bool *a)

Private Attributes

double a_scale_
double angular_
calibrationBundle calib
vector< calibrationBundlecalibData
int calibNum
ros::Publisher cloudpub_ [2]
ros::Subscriber cloudsub_
std::string fixedframe
ros::Publisher handspub_
float height_pub
bool isJoint [SKEL_POINTS]
double l_scale_
int lastcloudseq
int lastskelseq
float left_pub
double linear_
ros::NodeHandle n_
ros::NodeHandle nh_
sensor_msgs::PointCloud2 pcloudmsg
pair< pcl::PointXYZ,
pcl::PointXYZ > 
ramena
float right_pub
pair< pcl::PointXYZ,
pcl::PointXYZ > 
ruke
body_msgs::Skeletons skelmsg
pcl::PointXYZ skelpos [SKEL_POINTS]
ros::Subscriber skelsub_
ros::Subscriber sub_
turtlesim::Velocity vel
ros::Publisher vel_pub_

Detailed Description

HandDetector is the main ROS communication class, and its function is just to tye things together.

Author:
Garratt Gallagher

Definition at line 328 of file detect_hands.cpp.


Constructor & Destructor Documentation

Definition at line 339 of file detect_hands.cpp.

Definition at line 650 of file detect_hands_wskel.cpp.


Member Function Documentation

void HandDetector::armCalculationTurtlePub ( float &  l,
float &  r,
float &  h 
) [inline]

Definition at line 697 of file detect_hands_wskel.cpp.

void HandDetector::armCalibration ( calibrationBundle c,
std::pair< pcl::PointXYZ, pcl::PointXYZ >  hands,
std::pair< pcl::PointXYZ, pcl::PointXYZ >  shoulders 
) [inline]

Definition at line 686 of file detect_hands_wskel.cpp.

Definition at line 1195 of file detect_hands_wskel.cpp.

float HandDetector::calcDist ( float  a,
float  b 
) [inline]

Definition at line 675 of file detect_hands_wskel.cpp.

float HandDetector::calcPercVal ( float  a,
float  b 
) [inline]

Definition at line 679 of file detect_hands_wskel.cpp.

void HandDetector::cloudcb ( const sensor_msgs::PointCloud2ConstPtr &  scan) [inline]

Definition at line 367 of file detect_hands.cpp.

void HandDetector::cloudcb ( const sensor_msgs::PointCloud2ConstPtr &  scan) [inline]

Definition at line 1338 of file detect_hands_wskel.cpp.

void HandDetector::cls ( ) [inline]

Definition at line 1175 of file detect_hands_wskel.cpp.

void HandDetector::distancDataProcessing ( pcl::PointXYZ *  p) [inline]

Definition at line 1179 of file detect_hands_wskel.cpp.

void HandDetector::getInfoStateMachine ( body_msgs::Skeleton &  skel,
body_msgs::Hands &  handsmsg,
pcl::PointXYZ *  skelpos,
bool *  isJoint 
) [inline]

Definition at line 722 of file detect_hands_wskel.cpp.

void HandDetector::makeHand ( pcl::PointCloud< pcl::PointXYZ > &  cloud,
Eigen::Vector4f &  _arm,
body_msgs::Hand &  handmsg 
) [inline]

Definition at line 351 of file detect_hands.cpp.

void HandDetector::messageSync ( ) [inline]

Definition at line 1219 of file detect_hands_wskel.cpp.

void HandDetector::printRecog ( int  state,
int  LR 
) [inline]

Definition at line 887 of file detect_hands_wskel.cpp.

void HandDetector::processData ( body_msgs::Skeletons  skels,
sensor_msgs::PointCloud2  cloud,
calibrationBundle c 
) [inline]

Definition at line 1247 of file detect_hands_wskel.cpp.

void HandDetector::skelcb ( const body_msgs::SkeletonsConstPtr &  skels) [inline]

Definition at line 1343 of file detect_hands_wskel.cpp.

void HandDetector::tRecognition ( pcl::PointXYZ *  p,
bool *  a 
) [inline]

Definition at line 1009 of file detect_hands_wskel.cpp.


Member Data Documentation

double HandDetector::a_scale_ [private]

Definition at line 626 of file detect_hands_wskel.cpp.

double HandDetector::angular_ [private]

Definition at line 626 of file detect_hands_wskel.cpp.

Definition at line 637 of file detect_hands_wskel.cpp.

Definition at line 636 of file detect_hands_wskel.cpp.

int HandDetector::calibNum [private]

Definition at line 635 of file detect_hands_wskel.cpp.

Definition at line 333 of file detect_hands.cpp.

Definition at line 620 of file detect_hands_wskel.cpp.

std::string HandDetector::fixedframe [private]

Definition at line 335 of file detect_hands.cpp.

Definition at line 333 of file detect_hands.cpp.

float HandDetector::height_pub [private]

Definition at line 629 of file detect_hands_wskel.cpp.

Definition at line 639 of file detect_hands_wskel.cpp.

double HandDetector::l_scale_ [private]

Definition at line 626 of file detect_hands_wskel.cpp.

Definition at line 634 of file detect_hands_wskel.cpp.

Definition at line 634 of file detect_hands_wskel.cpp.

float HandDetector::left_pub [private]

Definition at line 629 of file detect_hands_wskel.cpp.

double HandDetector::linear_ [private]

Definition at line 626 of file detect_hands_wskel.cpp.

Definition at line 332 of file detect_hands.cpp.

Definition at line 625 of file detect_hands_wskel.cpp.

sensor_msgs::PointCloud2 HandDetector::pcloudmsg [private]

Definition at line 633 of file detect_hands_wskel.cpp.

pair<pcl::PointXYZ,pcl::PointXYZ> HandDetector::ramena [private]

Definition at line 645 of file detect_hands_wskel.cpp.

float HandDetector::right_pub [private]

Definition at line 629 of file detect_hands_wskel.cpp.

pair<pcl::PointXYZ,pcl::PointXYZ> HandDetector::ruke [private]

Definition at line 645 of file detect_hands_wskel.cpp.

body_msgs::Skeletons HandDetector::skelmsg [private]

Definition at line 632 of file detect_hands_wskel.cpp.

pcl::PointXYZ HandDetector::skelpos[SKEL_POINTS] [private]

Definition at line 638 of file detect_hands_wskel.cpp.

Definition at line 620 of file detect_hands_wskel.cpp.

Definition at line 334 of file detect_hands.cpp.

turtlesim::Velocity HandDetector::vel [private]

Definition at line 628 of file detect_hands_wskel.cpp.

Definition at line 627 of file detect_hands_wskel.cpp.


The documentation for this class was generated from the following files:


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