ros2_tracing/tracetools_test/src/test_publisher.cpp

35 lines
688 B
C++
Raw Normal View History

2019-06-05 15:35:46 +02:00
#include <memory>
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"
class PubNode : public rclcpp::Node
{
public:
2019-06-05 15:35:46 +02:00
explicit PubNode(rclcpp::NodeOptions options)
: Node("pub_node", options)
{
pub_ = this->create_publisher<std_msgs::msg::String>(
"the_topic",
rclcpp::QoS(10));
}
private:
2019-06-05 15:35:46 +02:00
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr pub_;
};
2019-06-05 15:35:46 +02:00
int main(int argc, char * argv[])
{
2019-06-05 15:35:46 +02:00
rclcpp::init(argc, argv);
2019-06-05 15:35:46 +02:00
rclcpp::executors::SingleThreadedExecutor exec;
auto pub_node = std::make_shared<PubNode>(rclcpp::NodeOptions());
exec.add_node(pub_node);
2019-06-05 15:35:46 +02:00
printf("spinning once\n");
exec.spin_once();
2019-06-05 15:35:46 +02:00
rclcpp::shutdown();
return 0;
}