ros2_tracing/tracetools_test/src/test_pong.cpp

64 lines
1.8 KiB
C++
Raw Normal View History

2019-06-18 09:10:05 +02:00
// Copyright 2019 Robert Bosch GmbH
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include <memory>
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"
class PongNode : public rclcpp::Node
{
public:
2019-06-05 15:35:46 +02:00
explicit PongNode(rclcpp::NodeOptions options)
: Node("pong_node", options)
{
sub_ = this->create_subscription<std_msgs::msg::String>(
"ping",
rclcpp::QoS(10),
std::bind(&PongNode::callback, this, std::placeholders::_1));
pub_ = this->create_publisher<std_msgs::msg::String>(
"pong",
rclcpp::QoS(10));
}
private:
2019-06-05 15:35:46 +02:00
void callback(const std_msgs::msg::String::SharedPtr msg)
{
RCLCPP_INFO(this->get_logger(), "[output] %s", msg->data.c_str());
auto next_msg = std::make_shared<std_msgs::msg::String>();
next_msg->data = "some random pong string";
pub_->publish(*next_msg);
rclcpp::shutdown();
}
rclcpp::Subscription<std_msgs::msg::String>::SharedPtr sub_;
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 pong_node = std::make_shared<PongNode>(rclcpp::NodeOptions());
exec.add_node(pong_node);
2019-06-05 15:35:46 +02:00
printf("spinning\n");
exec.spin();
2019-06-05 15:35:46 +02:00
// Will actually be called inside the node's callback
rclcpp::shutdown();
return 0;
}