#include <mrs_lib/impl/subscriber_handler.hpp>
#include <std_msgs/msg/string.hpp>
#include <functional>  
 
void timeout_callback(rclcpp::Node::SharedPtr node, const std::string& topic_name, const rclcpp::Time& last_msg)
{
  RCLCPP_ERROR_STREAM(rclcpp::get_logger("timeout_callback"), "Have not received a message on topic '" << topic_name << "' for " << (node->now() - last_msg).seconds() << " seconds");
}
 
void message_callback(const std_msgs::msg::String::ConstSharedPtr msg)
{
  RCLCPP_INFO_STREAM(rclcpp::get_logger("message_callback"), "Received: '" << msg->data << "'.");
}
 
{
  public:
    void callback_method(const std_msgs::msg::String::ConstSharedPtr msg)
    {
      RCLCPP_INFO_STREAM(rclcpp::get_logger("callback method"), "Object received: '" << msg->data << "'.");
    }
 
    void timeout_method(rclcpp::Node::SharedPtr node, const std::string& topic_name, const rclcpp::Time& last_msg)
    {
      RCLCPP_ERROR_STREAM(rclcpp::get_logger("timer method"), "Object has not received a message on topic '" << topic_name << "' for " << (node->now() - last_msg).seconds() << " seconds");
    }
} sub_obj;
 
int main(int argc, char **argv)
{
  
  const std::string node_name("subscribe_handler_example");
  rclcpp::init(argc, argv);
  auto node = std::make_shared<rclcpp::Node>(node_name);
 
  
  const std::string topic_name = "test_topic";
  
  const rclcpp::Duration no_message_timeout = rclcpp::Duration(1.0, 0);
 
  RCLCPP_INFO(node->get_logger(), "[%s]: Creating SubscriberHandlers.", node_name.c_str());
 
  shopts.node_name = node_name;
  shopts.no_message_timeout = no_message_timeout;
 
   
            shopts,
            topic_name,
            std::bind(timeout_callback, node, std::placeholders::_1, std::placeholders::_2),
            message_callback
            );
 
   
            handler,
            shopts,
            topic_name,
            no_message_timeout,
            std::bind(&SubObject::timeout_method, &sub_obj, node, std::placeholders::_1, std::placeholders::_2),
            std::bind(&SubObject::callback_method, &sub_obj, std::placeholders::_1)
            );
 
   
  rclcpp::Publisher<message_type>::SharedPtr publisher_ = node->create_publisher<
message_type>(topic_name, 5);
 
 
   
  rclcpp::Rate rate(10);
  while (true)
  {
    msg.data = "asdf";
    publisher_->publish(msg);
    RCLCPP_INFO(node->get_logger(), "[%s]: Spinning", node->get_name());
    rclcpp::spin_some(node);
    rate.sleep();
  }
}
Definition example.cpp:33
 
The main class for ROS topic subscription, message timeout handling etc.
Definition subscriber_handler.h:92
 
void construct_object(Class &object, Types... args)
Helper function for object construstion e.g. in case of member objects. This function is useful to av...
Definition subscriber_handler.h:468
 
typename SubscriberHandler::message_type message_type
Helper alias for convenient extraction of handled message type from a SubscribeHandlerPtr.
Definition subscriber_handler.h:456
 
A helper class to simplify setup of SubscriberHandler construction. This class is passed to the Subsc...
Definition subscriber_handler.h:33
 
Defines SubscriberHandler and related convenience classes for subscribing to ROS topics.