mrs_lib
Various reusable classes, functions and utilities for use in MRS projects
subscribe_handler/simple_example.cpp

This example may be run after building mrs_lib by executing rosrun mrs_lib subscribe_handler_simple_example.

// clang: MatousFormat
// Include the SubscribeHandler header
#include <std_msgs/String.h>
int main(int argc, char **argv)
{
/* Set up ROS. */
const std::string node_name = "subscribe_handler_simple_example";
ros::init(argc, argv, node_name);
ros::NodeHandle nh;
/* Basic configuration of the SubscribeHandler. */
shopts.node_name = node_name; //< used for the ROS logging from inside the SubscribeHandler (ROS_INFO, ROS_WARN etc.)
shopts.no_message_timeout = ros::Duration(3.0); //< SubscribeHandler warns if no messages arrive for this duration
/* name of the topic to be handled */
const std::string topic_name = "test_topic";
/* This is how a new SubscribeHandler object is initialized. */
shopts,
topic_name
);
/* Now let's just spin to process calbacks until the user decides to stop the program. */
ros::Duration d(0.1);
while (ros::ok())
{
ROS_INFO_STREAM_THROTTLE(1.0, "[" << node_name << "]: Spinning");
ros::spinOnce();
/* Print out any new messages */
if (handler.newMsg())
ROS_INFO_STREAM("[" << node_name << "]: Got a new message: " << handler.getMsg()->data);
d.sleep();
}
}
mrs_lib::SubscribeHandlerOptions
A helper class to simplify setup of SubscribeHandler construction. This class is passed to the Subscr...
Definition: subscribe_handler.h:31
subscribe_handler.h
Defines SubscribeHandler and related convenience classes for subscribing to ROS topics.
mrs_lib::SubscribeHandler::getMsg
virtual MessageType::ConstPtr getMsg()
Returns the last received message on the topic, handled by this SubscribeHandler. Use hasMsg() first ...
Definition: subscribe_handler.h:108
mrs_lib::SubscribeHandler
The main class for ROS topic subscription, message timeout handling etc.
Definition: subscribe_handler.h:82
mrs_lib::SubscribeHandlerOptions::no_message_timeout
ros::Duration no_message_timeout
If no new message is received for this duration, the timeout_callback function will be called....
Definition: subscribe_handler.h:44
mrs_lib::SubscribeHandlerOptions::node_name
std::string node_name
Name of the ROS node, using this handle (used for messages printed to console).
Definition: subscribe_handler.h:38
mrs_lib::SubscribeHandler::newMsg
virtual bool newMsg() const
Used to check whether at least one message has been received on the handled topic since the last call...
Definition: subscribe_handler.h:129