#include <node_handle.h>
Public Member Functions | |
template<class M > | |
Publisher | advertise (const std::string &topic, uint32_t queue_size, bool latch=false) |
ros::CallbackQueueInterface * | getCallbackQueue () const |
const std::string & | getNamespace () const |
const std::string & | getUnresolvedNamespace () |
NodeHandle (const std::string &ns=std::string(), const ros::M_string &remappings=ros::M_string()) | |
std::string | resolveName (const std::string &name, bool remap=true) const |
void | setCallbackQueue (ros::CallbackQueueInterface *queue) |
template<class M > | |
Subscriber | subscribe (const std::string &topic, uint32_t queue_size, void(*fp)(M), const ros::TransportHints &transport_hints=ros::TransportHints()) |
~NodeHandle () | |
Private Attributes | |
ros::NodeHandle | ros_nh |
Definition at line 11 of file node_handle.h.
hpcl_rtt::NodeHandle::NodeHandle | ( | const std::string & | ns = std::string() , |
const ros::M_string & | remappings = ros::M_string() |
||
) |
Definition at line 6 of file node_handle.cpp.
Definition at line 26 of file node_handle.cpp.
Publisher hpcl_rtt::NodeHandle::advertise | ( | const std::string & | topic, |
uint32_t | queue_size, | ||
bool | latch = false |
||
) | [inline] |
Definition at line 49 of file node_handle.h.
ros::CallbackQueueInterface* hpcl_rtt::NodeHandle::getCallbackQueue | ( | ) | const [inline] |
Definition at line 27 of file node_handle.h.
const std::string& hpcl_rtt::NodeHandle::getNamespace | ( | ) | const [inline] |
Definition at line 32 of file node_handle.h.
const std::string& hpcl_rtt::NodeHandle::getUnresolvedNamespace | ( | ) | [inline] |
Definition at line 37 of file node_handle.h.
std::string hpcl_rtt::NodeHandle::resolveName | ( | const std::string & | name, |
bool | remap = true |
||
) | const [inline] |
Definition at line 42 of file node_handle.h.
void hpcl_rtt::NodeHandle::setCallbackQueue | ( | ros::CallbackQueueInterface * | queue | ) | [inline] |
Definition at line 22 of file node_handle.h.
Subscriber hpcl_rtt::NodeHandle::subscribe | ( | const std::string & | topic, |
uint32_t | queue_size, | ||
void(*)(M) | fp, | ||
const ros::TransportHints & | transport_hints = ros::TransportHints() |
||
) | [inline] |
Definition at line 69 of file node_handle.h.
ros::NodeHandle hpcl_rtt::NodeHandle::ros_nh [private] |
Definition at line 91 of file node_handle.h.