#include <mrs_lib/impl/subscribe_handler.hpp>
#include <std_msgs/String.h>
void timeout_callback(const std::string& topic_name, const ros::Time& last_msg)
{
ROS_ERROR_STREAM("Have not received a message on topic '" << topic_name << "' for " << (ros::Time::now() - last_msg).toSec() << " seconds");
}
void message_callback(const std_msgs::String::ConstPtr msg)
{
ROS_INFO_STREAM("Received: '" << msg->data << "'.");
}
{
public:
void callback_method(const std_msgs::String::ConstPtr msg)
{
ROS_INFO_STREAM("Object received: '" << msg->data << "'.");
}
void timeout_method(const std::string& topic_name, const ros::Time& last_msg)
{
ROS_ERROR_STREAM("Object has not received a message on topic '" << topic_name << "' for " << (ros::Time::now()-last_msg).toSec() << " seconds");
}
} sub_obj;
int main(int argc, char **argv)
{
const std::string node_name("subscribe_handler_example");
ros::init(argc, argv, node_name);
ros::NodeHandle nh;
const std::string topic_name = "test_topic";
const ros::Duration no_message_timeout = ros::Duration(1.0);
ROS_INFO("[%s]: Creating SubscribeHandlers.", node_name.c_str());
shopts.node_name = node_name;
shopts.no_message_timeout = no_message_timeout;
shopts,
topic_name,
timeout_callback,
message_callback
);
handler,
shopts,
topic_name,
no_message_timeout,
&SubObject::timeout_method, &sub_obj,
&SubObject::callback_method, &sub_obj
);
ros::Publisher pub = nh.advertise<
message_type>(topic_name, 5);
ros::Duration d(3.0);
while (ros::ok())
{
msg.data = "asdf";
pub.publish(msg);
ROS_INFO_THROTTLE(1.0, "[%s]: Spinning", ros::this_node::getName().c_str());
ros::spinOnce();
d.sleep();
}
}