Merge branch 'extract-test-constants' into 'master'

Extract test constants

See merge request micro-ROS/ros2_tracing!6
This commit is contained in:
Ingo Lütkebohle 2019-06-19 14:13:03 +00:00
commit 1dd870749a
8 changed files with 48 additions and 20 deletions

View file

@ -20,18 +20,22 @@
using namespace std::chrono_literals;
#define NODE_NAME "test_ping"
#define SUB_TOPIC_NAME "pong"
#define PUB_TOPIC_NAME "ping"
class PingNode : public rclcpp::Node
{
public:
explicit PingNode(rclcpp::NodeOptions options)
: Node("test_ping", options)
: Node(NODE_NAME, options)
{
sub_ = this->create_subscription<std_msgs::msg::String>(
"pong",
SUB_TOPIC_NAME,
rclcpp::QoS(10),
std::bind(&PingNode::callback, this, std::placeholders::_1));
pub_ = this->create_publisher<std_msgs::msg::String>(
"ping",
PUB_TOPIC_NAME,
rclcpp::QoS(10));
timer_ = this->create_wall_timer(
500ms,

View file

@ -17,18 +17,22 @@
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"
#define NODE_NAME "test_pong"
#define SUB_TOPIC_NAME "ping"
#define PUB_TOPIC_NAME "pong"
class PongNode : public rclcpp::Node
{
public:
explicit PongNode(rclcpp::NodeOptions options)
: Node("test_pong", options)
: Node(NODE_NAME, options)
{
sub_ = this->create_subscription<std_msgs::msg::String>(
"ping",
SUB_TOPIC_NAME,
rclcpp::QoS(10),
std::bind(&PongNode::callback, this, std::placeholders::_1));
pub_ = this->create_publisher<std_msgs::msg::String>(
"pong",
PUB_TOPIC_NAME,
rclcpp::QoS(10));
}

View file

@ -17,14 +17,17 @@
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"
#define NODE_NAME "test_publisher"
#define TOPIC_NAME "the_topic"
class PubNode : public rclcpp::Node
{
public:
explicit PubNode(rclcpp::NodeOptions options)
: Node("test_publisher", options)
: Node(NODE_NAME, options)
{
pub_ = this->create_publisher<std_msgs::msg::String>(
"the_topic",
TOPIC_NAME,
rclcpp::QoS(10));
}

View file

@ -17,14 +17,17 @@
#include "rclcpp/rclcpp.hpp"
#include "std_srvs/srv/empty.hpp"
#define NODE_NAME "test_service"
#define SERVICE_NAME "the_service"
class ServiceNode : public rclcpp::Node
{
public:
explicit ServiceNode(rclcpp::NodeOptions options)
: Node("test_service", options)
: Node(NODE_NAME, options)
{
srv_ = this->create_service<std_srvs::srv::Empty>(
"the_service",
SERVICE_NAME,
std::bind(
&ServiceNode::service_callback,
this,

View file

@ -20,14 +20,18 @@
using namespace std::chrono_literals;
#define NODE_NAME "test_service_ping"
#define SERVICE_NAME "pong"
#define CLIENT_NAME "ping"
class PingNode : public rclcpp::Node
{
public:
explicit PingNode(rclcpp::NodeOptions options)
: Node("test_service_ping", options)
: Node(NODE_NAME, options)
{
srv_ = this->create_service<std_srvs::srv::Empty>(
"pong",
SERVICE_NAME,
std::bind(
&PingNode::service_callback,
this,
@ -35,7 +39,7 @@ public:
std::placeholders::_2,
std::placeholders::_3));
client_ = this->create_client<std_srvs::srv::Empty>(
"ping");
CLIENT_NAME);
timer_ = this->create_wall_timer(
500ms,
std::bind(&PingNode::timer_callback, this));

View file

@ -17,21 +17,25 @@
#include "rclcpp/rclcpp.hpp"
#include "std_srvs/srv/empty.hpp"
#define NODE_NAME "test_service_pong"
#define SERVICE_NAME "ping"
#define CLIENT_NAME "pong"
class PongNode : public rclcpp::Node
{
public:
explicit PongNode(rclcpp::NodeOptions options)
: Node("test_service_pong", options)
: Node(NODE_NAME, options)
{
srv_ = this->create_service<std_srvs::srv::Empty>(
"ping",
SERVICE_NAME,
std::bind(
&PongNode::service_callback,
this,
std::placeholders::_1,
std::placeholders::_2,
std::placeholders::_3));
client_ = this->create_client<std_srvs::srv::Empty>("pong");
client_ = this->create_client<std_srvs::srv::Empty>(CLIENT_NAME);
}
private:

View file

@ -17,14 +17,17 @@
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"
#define NODE_NAME "test_subscription"
#define TOPIC_NAME "the_topic"
class SubNode : public rclcpp::Node
{
public:
explicit SubNode(rclcpp::NodeOptions options)
: Node("test_subscription", options)
: Node(NODE_NAME, options)
{
sub_ = this->create_subscription<std_msgs::msg::String>(
"the_topic",
TOPIC_NAME,
rclcpp::QoS(10),
std::bind(&SubNode::callback, this, std::placeholders::_1));
}

View file

@ -19,15 +19,18 @@
using namespace std::chrono_literals;
#define NODE_NAME "test_timer"
#define TIMER_PERIOD 1ms
class TimerNode : public rclcpp::Node
{
public:
explicit TimerNode(rclcpp::NodeOptions options)
: Node("test_timer", options)
: Node(NODE_NAME, options)
{
is_done_ = false;
timer_ = this->create_wall_timer(
1ms,
TIMER_PERIOD,
std::bind(&TimerNode::timer_callback, this));
}