$search

CopClient Class Reference

#include <cop_client.h>

List of all members.

Public Member Functions

long CallCop (std::string object_class, std::vector< unsigned long > position_ids, int num_of_objects, unsigned long alterantive_id, unsigned long action_type)
long CallCop (std::string object_class, unsigned long position_id, int num_objects=1, unsigned long alterantive_id=0, unsigned long action_type=0)
 CopClient (ros::NodeHandle &nh, std::string stTopicName="/tracking/cop_handler", std::string stCopName="cop")
void CopFeedBack (long primitive, double evaluation, unsigned long error_id)
std::vector
< vision_msgs::cop_answer > 
GetResult (long perception_primitive)
size_t HasResult (long perception_primitive)
double LODistanceQuery (unsigned long child, unsigned long parent)
unsigned long LOFrameQuery (unsigned long child, unsigned long parent)
void LOFreeID (unsigned long id)
unsigned long LONameQuery (std::string name)
unsigned long LOOffset (unsigned long id, unsigned long parent, float x, float y, float z)
void LOPointQuery (unsigned long child, float *vector)
tf::Stamped< tf::PoseLOPoseQuery (unsigned long child)

Private Member Functions

void callback (const boost::shared_ptr< const vision_msgs::cop_answer > &msg)

Private Attributes

std::string m_answerTopic
ros::ServiceClient m_client
ros::ServiceClient m_jlo_client
std::map< unsigned long,
std::vector
< vision_msgs::cop_answer > > 
m_msg_cluster
ros::Publisher m_pubFeedBack
ros::Subscriber m_readAnswer

Detailed Description

Definition at line 11 of file cop_client.h.


Constructor & Destructor Documentation

CopClient::CopClient ( ros::NodeHandle nh,
std::string  stTopicName = "/tracking/cop_handler",
std::string  stCopName = "cop" 
)

subscribe to the topic cop should publish the results

Publish

Definition at line 42 of file cop_client.cpp.


Member Function Documentation

void CopClient::callback ( const boost::shared_ptr< const vision_msgs::cop_answer > &  msg  )  [private]
long CopClient::CallCop ( std::string  object_class,
std::vector< unsigned long >  position_ids,
int  num_of_objects,
unsigned long  alterantive_id,
unsigned long  action_type 
)

Definition at line 232 of file cop_client.cpp.

long CopClient::CallCop ( std::string  object_class,
unsigned long  position_id,
int  num_objects = 1,
unsigned long  alterantive_id = 0,
unsigned long  action_type = 0 
)

Definition at line 199 of file cop_client.cpp.

void CopClient::CopFeedBack ( long  primitive,
double  evaluation,
unsigned long  error_id 
)

Definition at line 268 of file cop_client.cpp.

std::vector<vision_msgs::cop_answer> CopClient::GetResult ( long  perception_primitive  )  [inline]

Definition at line 33 of file cop_client.h.

size_t CopClient::HasResult ( long  perception_primitive  )  [inline]

Definition at line 26 of file cop_client.h.

double CopClient::LODistanceQuery ( unsigned long  child,
unsigned long  parent 
)

Definition at line 82 of file cop_client.cpp.

unsigned long CopClient::LOFrameQuery ( unsigned long  child,
unsigned long  parent 
)

Definition at line 63 of file cop_client.cpp.

void CopClient::LOFreeID ( unsigned long  id  ) 

Definition at line 74 of file cop_client.cpp.

unsigned long CopClient::LONameQuery ( std::string  name  ) 

Definition at line 160 of file cop_client.cpp.

unsigned long CopClient::LOOffset ( unsigned long  id,
unsigned long  parent,
float  x,
float  y,
float  z 
)

Definition at line 138 of file cop_client.cpp.

void CopClient::LOPointQuery ( unsigned long  child,
float *  vector 
)

Definition at line 96 of file cop_client.cpp.

tf::Stamped< tf::Pose > CopClient::LOPoseQuery ( unsigned long  child  ) 

Definition at line 113 of file cop_client.cpp.


Member Data Documentation

std::string CopClient::m_answerTopic [private]

Definition at line 49 of file cop_client.h.

Definition at line 47 of file cop_client.h.

Definition at line 48 of file cop_client.h.

std::map<unsigned long, std::vector<vision_msgs::cop_answer> > CopClient::m_msg_cluster [private]

Definition at line 50 of file cop_client.h.

Definition at line 46 of file cop_client.h.

Definition at line 45 of file cop_client.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


cop_client_cpp
Author(s): Ulrich F Klank
autogenerated on Tue Dec 4 07:34:24 2012