Add option to make ping pong test run over and over

This commit is contained in:
Christophe Bedard 2019-06-28 09:35:08 +02:00
parent 209b174dfb
commit 8cbb2a6fe5
2 changed files with 24 additions and 8 deletions

View file

@ -27,8 +27,8 @@ using namespace std::chrono_literals;
class PingNode : public rclcpp::Node class PingNode : public rclcpp::Node
{ {
public: public:
explicit PingNode(rclcpp::NodeOptions options) PingNode(rclcpp::NodeOptions options, bool do_only_one)
: Node(NODE_NAME, options) : Node(NODE_NAME, options), do_only_one_(do_only_one)
{ {
sub_ = this->create_subscription<std_msgs::msg::String>( sub_ = this->create_subscription<std_msgs::msg::String>(
SUB_TOPIC_NAME, SUB_TOPIC_NAME,
@ -42,11 +42,16 @@ public:
std::bind(&PingNode::timer_callback, this)); std::bind(&PingNode::timer_callback, this));
} }
explicit PingNode(rclcpp::NodeOptions options)
: PingNode(options, true) {}
private: private:
void callback(const std_msgs::msg::String::SharedPtr msg) void callback(const std_msgs::msg::String::SharedPtr msg)
{ {
RCLCPP_INFO(this->get_logger(), "[output] %s", msg->data.c_str()); RCLCPP_INFO(this->get_logger(), "[output] %s", msg->data.c_str());
rclcpp::shutdown(); if (do_only_one_) {
rclcpp::shutdown();
}
} }
void timer_callback() void timer_callback()
@ -59,14 +64,17 @@ private:
rclcpp::Subscription<std_msgs::msg::String>::SharedPtr sub_; rclcpp::Subscription<std_msgs::msg::String>::SharedPtr sub_;
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr pub_; rclcpp::Publisher<std_msgs::msg::String>::SharedPtr pub_;
rclcpp::TimerBase::SharedPtr timer_; rclcpp::TimerBase::SharedPtr timer_;
bool do_only_one_;
}; };
int main(int argc, char * argv[]) int main(int argc, char * argv[])
{ {
bool do_only_one = argc == 1;
rclcpp::init(argc, argv); rclcpp::init(argc, argv);
rclcpp::executors::SingleThreadedExecutor exec; rclcpp::executors::SingleThreadedExecutor exec;
auto ping_node = std::make_shared<PingNode>(rclcpp::NodeOptions()); auto ping_node = std::make_shared<PingNode>(rclcpp::NodeOptions(), do_only_one);
exec.add_node(ping_node); exec.add_node(ping_node);
printf("spinning\n"); printf("spinning\n");

View file

@ -24,8 +24,8 @@
class PongNode : public rclcpp::Node class PongNode : public rclcpp::Node
{ {
public: public:
explicit PongNode(rclcpp::NodeOptions options) PongNode(rclcpp::NodeOptions options, bool do_only_one)
: Node(NODE_NAME, options) : Node(NODE_NAME, options), do_only_one_(do_only_one)
{ {
sub_ = this->create_subscription<std_msgs::msg::String>( sub_ = this->create_subscription<std_msgs::msg::String>(
SUB_TOPIC_NAME, SUB_TOPIC_NAME,
@ -36,6 +36,9 @@ public:
rclcpp::QoS(10)); rclcpp::QoS(10));
} }
explicit PongNode(rclcpp::NodeOptions options)
: PongNode(options, true) {}
private: private:
void callback(const std_msgs::msg::String::SharedPtr msg) void callback(const std_msgs::msg::String::SharedPtr msg)
{ {
@ -43,19 +46,24 @@ private:
auto next_msg = std::make_shared<std_msgs::msg::String>(); auto next_msg = std::make_shared<std_msgs::msg::String>();
next_msg->data = "some random pong string"; next_msg->data = "some random pong string";
pub_->publish(*next_msg); pub_->publish(*next_msg);
rclcpp::shutdown(); if (do_only_one_) {
rclcpp::shutdown();
}
} }
rclcpp::Subscription<std_msgs::msg::String>::SharedPtr sub_; rclcpp::Subscription<std_msgs::msg::String>::SharedPtr sub_;
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr pub_; rclcpp::Publisher<std_msgs::msg::String>::SharedPtr pub_;
bool do_only_one_;
}; };
int main(int argc, char * argv[]) int main(int argc, char * argv[])
{ {
bool do_only_one = argc == 1;
rclcpp::init(argc, argv); rclcpp::init(argc, argv);
rclcpp::executors::SingleThreadedExecutor exec; rclcpp::executors::SingleThreadedExecutor exec;
auto pong_node = std::make_shared<PongNode>(rclcpp::NodeOptions()); auto pong_node = std::make_shared<PongNode>(rclcpp::NodeOptions(), do_only_one);
exec.add_node(pong_node); exec.add_node(pong_node);
printf("spinning\n"); printf("spinning\n");