ros2_tracing/tracetools_test/src/test_subscription.cpp

42 lines
859 B
C++
Raw Normal View History

2019-05-31 16:43:04 +02:00
#include <memory>
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"
class SubNode : public rclcpp::Node
{
public:
2019-06-05 15:35:46 +02:00
explicit SubNode(rclcpp::NodeOptions options)
: Node("sub_node", options)
{
sub_ = this->create_subscription<std_msgs::msg::String>(
"the_topic",
rclcpp::QoS(10),
std::bind(&SubNode::callback, this, std::placeholders::_1));
}
2019-05-31 16:43:04 +02:00
private:
2019-06-05 15:35:46 +02:00
void callback(const std_msgs::msg::String::SharedPtr msg)
{
// Nothing
(void)msg;
}
2019-05-31 16:43:04 +02:00
2019-06-05 15:35:46 +02:00
rclcpp::Subscription<std_msgs::msg::String>::SharedPtr sub_;
2019-05-31 16:43:04 +02:00
};
2019-06-05 15:35:46 +02:00
int main(int argc, char * argv[])
2019-05-31 16:43:04 +02:00
{
2019-06-05 15:35:46 +02:00
rclcpp::init(argc, argv);
2019-05-31 16:43:04 +02:00
2019-06-05 15:35:46 +02:00
rclcpp::executors::SingleThreadedExecutor exec;
auto sub_node = std::make_shared<SubNode>(rclcpp::NodeOptions());
exec.add_node(sub_node);
2019-05-31 16:43:04 +02:00
2019-06-05 15:35:46 +02:00
printf("spinning once\n");
exec.spin_once();
2019-05-31 16:43:04 +02:00
2019-06-05 15:35:46 +02:00
rclcpp::shutdown();
return 0;
2019-05-31 16:43:04 +02:00
}