#include <topic_service_client.h>
Public Member Functions | |
bool | call (MReq &request, MRes &response) |
bool | exists () |
std::string | getService () |
void | initialize (ros::NodeHandle &nh, const std::string &service, const std::string &client_name="") |
bool | logCalls () const |
void | setLogCalls (bool enable) |
TopicServiceClientRaw () | |
Private Types | |
typedef boost::mutex | request_lock_ |
Private Member Functions | |
void | response_callback (const boost::shared_ptr< MRes > &message) |
Private Attributes | |
std::string | name_ |
ros::Publisher | request_pub_ |
boost::shared_ptr< MRes > | response_ |
ros::Subscriber | response_sub_ |
int | sequence_ |
std::string | service_name_ |
ros::Duration | timeout_ |
Definition at line 42 of file topic_service_client.h.
typedef boost::mutex swri::TopicServiceClientRaw< MReq, MRes >::request_lock_ [private] |
Definition at line 46 of file topic_service_client.h.
swri::TopicServiceClientRaw< MReq, MRes >::TopicServiceClientRaw | ( | ) | [inline] |
Definition at line 58 of file topic_service_client.h.
bool swri::TopicServiceClientRaw< MReq, MRes >::call | ( | MReq & | request, |
MRes & | response | ||
) | [inline] |
Definition at line 75 of file topic_service_client.h.
bool swri::TopicServiceClientRaw< MReq, MRes >::exists | ( | ) | [inline] |
Definition at line 119 of file topic_service_client.h.
std::string swri::TopicServiceClientRaw< MReq, MRes >::getService | ( | ) | [inline] |
Definition at line 114 of file topic_service_client.h.
void swri::TopicServiceClientRaw< MReq, MRes >::initialize | ( | ros::NodeHandle & | nh, |
const std::string & | service, | ||
const std::string & | client_name = "" |
||
) | [inline] |
Definition at line 63 of file topic_service_client.h.
bool swri::TopicServiceClientRaw< MReq, MRes >::logCalls | ( | ) | const |
void swri::TopicServiceClientRaw< MReq, MRes >::response_callback | ( | const boost::shared_ptr< MRes > & | message | ) | [inline, private] |
Definition at line 130 of file topic_service_client.h.
void swri::TopicServiceClientRaw< MReq, MRes >::setLogCalls | ( | bool | enable | ) |
std::string swri::TopicServiceClientRaw< MReq, MRes >::name_ [private] |
Definition at line 52 of file topic_service_client.h.
ros::Publisher swri::TopicServiceClientRaw< MReq, MRes >::request_pub_ [private] |
Definition at line 48 of file topic_service_client.h.
boost::shared_ptr<MRes> swri::TopicServiceClientRaw< MReq, MRes >::response_ [private] |
Definition at line 49 of file topic_service_client.h.
ros::Subscriber swri::TopicServiceClientRaw< MReq, MRes >::response_sub_ [private] |
Definition at line 47 of file topic_service_client.h.
int swri::TopicServiceClientRaw< MReq, MRes >::sequence_ [private] |
Definition at line 55 of file topic_service_client.h.
std::string swri::TopicServiceClientRaw< MReq, MRes >::service_name_ [private] |
Definition at line 53 of file topic_service_client.h.
ros::Duration swri::TopicServiceClientRaw< MReq, MRes >::timeout_ [private] |
Definition at line 51 of file topic_service_client.h.