#include <node_handle.hpp>
Public Member Functions | |
| template<class M > | |
| Publisher | advertise (const std::string &topic, uint32_t queue_size, bool latch=false) |
| Advertise a topic, simple version, compatible with ros. | |
| 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()) |
| Subscribe to a topic, version for bare function, compatible with ros. | |
| ~NodeHandle () | |
Private Attributes | |
| ros::NodeHandle | ros_nh_ |
Definition at line 32 of file node_handle.hpp.
| micros_rtt::NodeHandle::NodeHandle | ( | const std::string & | ns = std::string(), |
| const ros::M_string & | remappings = ros::M_string() |
||
| ) | [inline] |
Definition at line 35 of file node_handle.hpp.
| micros_rtt::NodeHandle::~NodeHandle | ( | ) | [inline] |
Definition at line 42 of file node_handle.hpp.
| Publisher micros_rtt::NodeHandle::advertise | ( | const std::string & | topic, |
| uint32_t | queue_size, | ||
| bool | latch = false |
||
| ) | [inline] |
Advertise a topic, simple version, compatible with ros.
The detail of this method will coming soon.
| topic | Topic to advertise on |
| queue_size | Maximum number of outgoing messages to be queued for delivery to subscribers |
| latch | (optional) If true, the last message published on this topic will be saved and sent to new subscribers when they connect |
| InvalidNameException | If the topic name begins with a tilde, or is an otherwise invalid graph resource name, or is an otherwise invalid graph resource name |
Definition at line 80 of file node_handle.hpp.
Definition at line 29 of file node_handle.cpp.
| const std::string & micros_rtt::NodeHandle::getNamespace | ( | ) | const |
Definition at line 34 of file node_handle.cpp.
| const std::string & micros_rtt::NodeHandle::getUnresolvedNamespace | ( | ) |
Definition at line 39 of file node_handle.cpp.
| std::string micros_rtt::NodeHandle::resolveName | ( | const std::string & | name, |
| bool | remap = true |
||
| ) | const |
Definition at line 44 of file node_handle.cpp.
| void micros_rtt::NodeHandle::setCallbackQueue | ( | ros::CallbackQueueInterface * | queue | ) |
Definition at line 24 of file node_handle.cpp.
| Subscriber micros_rtt::NodeHandle::subscribe | ( | const std::string & | topic, |
| uint32_t | queue_size, | ||
| void(*)(M) | fp, | ||
| const ros::TransportHints & | transport_hints = ros::TransportHints() |
||
| ) | [inline] |
Subscribe to a topic, version for bare function, compatible with ros.
The detail of this method will coming soon.
This version of subscribe is a convenience function for using bare functions, and can be used like so:
void callback(const std_msgs::Empty::ConstPtr& message)
{
}
ros::Subscriber sub = handle.subscribe("my_topic", 1, callback);
| M | [template] M here is the callback parameter type (e.g. const boost::shared_ptr<M const>& or const M&), not the message type, and should almost always be deduced |
| topic | Topic to subscribe to |
| queue_size | Number of incoming messages to queue up for processing (messages in excess of this queue capacity will be discarded). |
| fp | Function pointer to call when a message has arrived |
| transport_hints | a TransportHints structure which defines various transport-related options |
if (handle)
{
...
}
| InvalidNameException | If the topic name begins with a tilde, or is an otherwise invalid graph resource name |
| ConflictingSubscriptionException | If this node is already subscribed to the same topic with a different datatype |
Definition at line 154 of file node_handle.hpp.
Definition at line 193 of file node_handle.hpp.