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.
|
|
|
|
|
2019-06-03 11:16:05 +02:00
|
|
|
#include <memory>
|
|
|
|
|
|
|
|
#include "rclcpp/rclcpp.hpp"
|
|
|
|
#include "std_msgs/msg/string.hpp"
|
|
|
|
|
2019-06-19 15:46:44 +02:00
|
|
|
#define NODE_NAME "test_pong"
|
|
|
|
#define SUB_TOPIC_NAME "ping"
|
|
|
|
#define PUB_TOPIC_NAME "pong"
|
|
|
|
|
2019-06-03 11:16:05 +02:00
|
|
|
class PongNode : public rclcpp::Node
|
|
|
|
{
|
|
|
|
public:
|
2019-06-28 09:35:08 +02:00
|
|
|
PongNode(rclcpp::NodeOptions options, bool do_only_one)
|
|
|
|
: Node(NODE_NAME, options), do_only_one_(do_only_one)
|
2019-06-05 15:35:46 +02:00
|
|
|
{
|
|
|
|
sub_ = this->create_subscription<std_msgs::msg::String>(
|
2019-06-19 15:46:44 +02:00
|
|
|
SUB_TOPIC_NAME,
|
2019-06-05 15:35:46 +02:00
|
|
|
rclcpp::QoS(10),
|
|
|
|
std::bind(&PongNode::callback, this, std::placeholders::_1));
|
|
|
|
pub_ = this->create_publisher<std_msgs::msg::String>(
|
2019-06-19 15:46:44 +02:00
|
|
|
PUB_TOPIC_NAME,
|
2019-06-05 15:35:46 +02:00
|
|
|
rclcpp::QoS(10));
|
|
|
|
}
|
2019-06-03 11:16:05 +02:00
|
|
|
|
2019-06-28 09:35:08 +02:00
|
|
|
explicit PongNode(rclcpp::NodeOptions options)
|
|
|
|
: PongNode(options, true) {}
|
|
|
|
|
2019-06-03 11:16:05 +02:00
|
|
|
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);
|
2019-06-28 09:35:08 +02:00
|
|
|
if (do_only_one_) {
|
|
|
|
rclcpp::shutdown();
|
|
|
|
}
|
2019-06-05 15:35:46 +02:00
|
|
|
}
|
|
|
|
|
|
|
|
rclcpp::Subscription<std_msgs::msg::String>::SharedPtr sub_;
|
|
|
|
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr pub_;
|
2019-06-28 09:35:08 +02:00
|
|
|
bool do_only_one_;
|
2019-06-03 11:16:05 +02:00
|
|
|
};
|
|
|
|
|
2019-06-05 15:35:46 +02:00
|
|
|
int main(int argc, char * argv[])
|
2019-06-03 11:16:05 +02:00
|
|
|
{
|
2019-08-16 10:24:20 +02:00
|
|
|
bool do_only_one = true;
|
2019-08-16 10:27:26 +02:00
|
|
|
for (int i = 0; i < argc; ++i) {
|
|
|
|
if (strncmp(argv[i], "do_more", 7) == 0) {
|
2019-08-16 10:24:20 +02:00
|
|
|
do_only_one = false;
|
|
|
|
}
|
|
|
|
}
|
2019-06-28 09:35:08 +02:00
|
|
|
|
2019-06-05 15:35:46 +02:00
|
|
|
rclcpp::init(argc, argv);
|
2019-06-03 11:16:05 +02:00
|
|
|
|
2019-06-05 15:35:46 +02:00
|
|
|
rclcpp::executors::SingleThreadedExecutor exec;
|
2019-06-28 09:35:08 +02:00
|
|
|
auto pong_node = std::make_shared<PongNode>(rclcpp::NodeOptions(), do_only_one);
|
2019-06-05 15:35:46 +02:00
|
|
|
exec.add_node(pong_node);
|
2019-06-03 11:16:05 +02:00
|
|
|
|
2019-06-05 15:35:46 +02:00
|
|
|
printf("spinning\n");
|
|
|
|
exec.spin();
|
2019-06-03 11:16:05 +02:00
|
|
|
|
2019-06-05 15:35:46 +02:00
|
|
|
// Will actually be called inside the node's callback
|
|
|
|
rclcpp::shutdown();
|
|
|
|
return 0;
|
2019-06-03 11:16:05 +02:00
|
|
|
}
|