Switch IntraProcessMessage to test_msgs/Empty (#1017)

Signed-off-by: Stephen Brawner <brawner@gmail.com>
This commit is contained in:
brawner 2020-03-20 12:36:19 -07:00 committed by GitHub
parent 3361e68bb9
commit 626e722a63
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
10 changed files with 64 additions and 79 deletions

View file

@ -329,10 +329,10 @@ if(BUILD_TESTING)
ament_add_gtest(test_publisher test/test_publisher.cpp) ament_add_gtest(test_publisher test/test_publisher.cpp)
if(TARGET test_publisher) if(TARGET test_publisher)
ament_target_dependencies(test_publisher ament_target_dependencies(test_publisher
"rcl_interfaces"
"rmw" "rmw"
"rosidl_generator_cpp" "rosidl_generator_cpp"
"rosidl_typesupport_cpp" "rosidl_typesupport_cpp"
"test_msgs"
) )
target_link_libraries(test_publisher ${PROJECT_NAME}) target_link_libraries(test_publisher ${PROJECT_NAME})
endif() endif()
@ -343,6 +343,7 @@ if(BUILD_TESTING)
"rmw" "rmw"
"rosidl_generator_cpp" "rosidl_generator_cpp"
"rosidl_typesupport_cpp" "rosidl_typesupport_cpp"
"test_msgs"
) )
target_link_libraries(test_publisher_subscription_count_api ${PROJECT_NAME}) target_link_libraries(test_publisher_subscription_count_api ${PROJECT_NAME})
endif() endif()
@ -384,6 +385,7 @@ if(BUILD_TESTING)
"rmw" "rmw"
"rosidl_generator_cpp" "rosidl_generator_cpp"
"rosidl_typesupport_cpp" "rosidl_typesupport_cpp"
"test_msgs"
) )
target_link_libraries(test_subscription ${PROJECT_NAME}) target_link_libraries(test_subscription ${PROJECT_NAME})
endif() endif()
@ -394,6 +396,7 @@ if(BUILD_TESTING)
"rmw" "rmw"
"rosidl_generator_cpp" "rosidl_generator_cpp"
"rosidl_typesupport_cpp" "rosidl_typesupport_cpp"
"test_msgs"
) )
target_link_libraries(test_subscription_publisher_count_api ${PROJECT_NAME}) target_link_libraries(test_subscription_publisher_count_api ${PROJECT_NAME})
endif() endif()

View file

@ -33,8 +33,6 @@
#include "rcl/publisher.h" #include "rcl/publisher.h"
#include "rcl/subscription.h" #include "rcl/subscription.h"
#include "rcl_interfaces/msg/intra_process_message.hpp"
#include "rclcpp/contexts/default_context.hpp" #include "rclcpp/contexts/default_context.hpp"
#include "rclcpp/create_client.hpp" #include "rclcpp/create_client.hpp"
#include "rclcpp/create_publisher.hpp" #include "rclcpp/create_publisher.hpp"

View file

@ -26,8 +26,6 @@
#include "rclcpp/scope_exit.hpp" #include "rclcpp/scope_exit.hpp"
#include "rclcpp/utilities.hpp" #include "rclcpp/utilities.hpp"
#include "rcl_interfaces/msg/intra_process_message.hpp"
#include "rcutils/logging_macros.h" #include "rcutils/logging_macros.h"
using rclcpp::exceptions::throw_from_rcl_error; using rclcpp::exceptions::throw_from_rcl_error;

View file

@ -24,7 +24,6 @@
#include <string> #include <string>
#include <vector> #include <vector>
#include "rcl_interfaces/msg/intra_process_message.hpp"
#include "rcutils/logging_macros.h" #include "rcutils/logging_macros.h"
#include "rmw/impl/cpp/demangle.hpp" #include "rmw/impl/cpp/demangle.hpp"

View file

@ -15,7 +15,6 @@
#include "rclcpp/type_support_decl.hpp" #include "rclcpp/type_support_decl.hpp"
#include "rclcpp/visibility_control.hpp" #include "rclcpp/visibility_control.hpp"
#include "rcl_interfaces/msg/intra_process_message.hpp"
#include "rcl_interfaces/msg/list_parameters_result.hpp" #include "rcl_interfaces/msg/list_parameters_result.hpp"
#include "rcl_interfaces/msg/parameter_descriptor.hpp" #include "rcl_interfaces/msg/parameter_descriptor.hpp"
#include "rcl_interfaces/msg/parameter_event.hpp" #include "rcl_interfaces/msg/parameter_event.hpp"
@ -27,14 +26,6 @@
#include "rcl_interfaces/srv/set_parameters.hpp" #include "rcl_interfaces/srv/set_parameters.hpp"
#include "rcl_interfaces/srv/set_parameters_atomically.hpp" #include "rcl_interfaces/srv/set_parameters_atomically.hpp"
const rosidl_message_type_support_t *
rclcpp::type_support::get_intra_process_message_msg_type_support()
{
return rosidl_typesupport_cpp::get_message_type_support_handle<
rcl_interfaces::msg::IntraProcessMessage
>();
}
const rosidl_message_type_support_t * const rosidl_message_type_support_t *
rclcpp::type_support::get_parameter_event_msg_type_support() rclcpp::type_support::get_parameter_event_msg_type_support()
{ {

View file

@ -23,12 +23,8 @@
#include "rclcpp/rclcpp.hpp" #include "rclcpp/rclcpp.hpp"
#include "rclcpp/executors.hpp" #include "rclcpp/executors.hpp"
#include "rcl_interfaces/msg/intra_process_message.hpp"
using namespace std::chrono_literals; using namespace std::chrono_literals;
using rcl_interfaces::msg::IntraProcessMessage;
class TestMultiThreadedExecutor : public ::testing::Test class TestMultiThreadedExecutor : public ::testing::Test
{ {
protected: protected:

View file

@ -21,7 +21,7 @@
#include "rclcpp/exceptions.hpp" #include "rclcpp/exceptions.hpp"
#include "rclcpp/rclcpp.hpp" #include "rclcpp/rclcpp.hpp"
#include "rcl_interfaces/msg/intra_process_message.hpp" #include "test_msgs/msg/empty.hpp"
class TestPublisher : public ::testing::Test class TestPublisher : public ::testing::Test
{ {
@ -93,16 +93,16 @@ protected:
*/ */
TEST_F(TestPublisher, construction_and_destruction) { TEST_F(TestPublisher, construction_and_destruction) {
initialize(); initialize();
using rcl_interfaces::msg::IntraProcessMessage; using test_msgs::msg::Empty;
{ {
auto publisher = node->create_publisher<IntraProcessMessage>("topic", 42); auto publisher = node->create_publisher<Empty>("topic", 42);
(void)publisher; (void)publisher;
} }
{ {
ASSERT_THROW( ASSERT_THROW(
{ {
auto publisher = node->create_publisher<IntraProcessMessage>("invalid_topic?", 42); auto publisher = node->create_publisher<Empty>("invalid_topic?", 42);
}, rclcpp::exceptions::InvalidTopicNameError); }, rclcpp::exceptions::InvalidTopicNameError);
} }
} }
@ -112,33 +112,33 @@ TEST_F(TestPublisher, construction_and_destruction) {
*/ */
TEST_F(TestPublisher, various_creation_signatures) { TEST_F(TestPublisher, various_creation_signatures) {
initialize(); initialize();
using rcl_interfaces::msg::IntraProcessMessage; using test_msgs::msg::Empty;
{ {
auto publisher = node->create_publisher<IntraProcessMessage>("topic", 42); auto publisher = node->create_publisher<Empty>("topic", 42);
(void)publisher; (void)publisher;
} }
{ {
auto publisher = node->create_publisher<IntraProcessMessage>("topic", rclcpp::QoS(42)); auto publisher = node->create_publisher<Empty>("topic", rclcpp::QoS(42));
(void)publisher; (void)publisher;
} }
{ {
auto publisher = auto publisher =
node->create_publisher<IntraProcessMessage>("topic", rclcpp::QoS(rclcpp::KeepLast(42))); node->create_publisher<Empty>("topic", rclcpp::QoS(rclcpp::KeepLast(42)));
(void)publisher; (void)publisher;
} }
{ {
auto publisher = auto publisher =
node->create_publisher<IntraProcessMessage>("topic", rclcpp::QoS(rclcpp::KeepAll())); node->create_publisher<Empty>("topic", rclcpp::QoS(rclcpp::KeepAll()));
(void)publisher; (void)publisher;
} }
{ {
auto publisher = auto publisher =
node->create_publisher<IntraProcessMessage>("topic", 42, rclcpp::PublisherOptions()); node->create_publisher<Empty>("topic", 42, rclcpp::PublisherOptions());
(void)publisher; (void)publisher;
} }
{ {
auto publisher = auto publisher =
rclcpp::create_publisher<IntraProcessMessage>(node, "topic", 42, rclcpp::PublisherOptions()); rclcpp::create_publisher<Empty>(node, "topic", 42, rclcpp::PublisherOptions());
(void)publisher; (void)publisher;
} }
} }
@ -149,10 +149,10 @@ TEST_F(TestPublisher, various_creation_signatures) {
TEST_P(TestPublisherInvalidIntraprocessQos, test_publisher_throws) { TEST_P(TestPublisherInvalidIntraprocessQos, test_publisher_throws) {
initialize(rclcpp::NodeOptions().use_intra_process_comms(true)); initialize(rclcpp::NodeOptions().use_intra_process_comms(true));
rclcpp::QoS qos = GetParam().qos; rclcpp::QoS qos = GetParam().qos;
using rcl_interfaces::msg::IntraProcessMessage; using test_msgs::msg::Empty;
{ {
ASSERT_THROW( ASSERT_THROW(
{auto publisher = node->create_publisher<IntraProcessMessage>("topic", qos);}, {auto publisher = node->create_publisher<Empty>("topic", qos);},
std::invalid_argument); std::invalid_argument);
} }
} }
@ -183,15 +183,15 @@ INSTANTIATE_TEST_CASE_P(
Testing publisher construction and destruction for subnodes. Testing publisher construction and destruction for subnodes.
*/ */
TEST_F(TestPublisherSub, construction_and_destruction) { TEST_F(TestPublisherSub, construction_and_destruction) {
using rcl_interfaces::msg::IntraProcessMessage; using test_msgs::msg::Empty;
{ {
auto publisher = subnode->create_publisher<IntraProcessMessage>("topic", 42); auto publisher = subnode->create_publisher<Empty>("topic", 42);
EXPECT_STREQ(publisher->get_topic_name(), "/ns/sub_ns/topic"); EXPECT_STREQ(publisher->get_topic_name(), "/ns/sub_ns/topic");
} }
{ {
auto publisher = subnode->create_publisher<IntraProcessMessage>("/topic", 42); auto publisher = subnode->create_publisher<Empty>("/topic", 42);
EXPECT_STREQ(publisher->get_topic_name(), "/topic"); EXPECT_STREQ(publisher->get_topic_name(), "/topic");
} }
@ -199,7 +199,7 @@ TEST_F(TestPublisherSub, construction_and_destruction) {
{ {
ASSERT_THROW( ASSERT_THROW(
{ {
auto publisher = subnode->create_publisher<IntraProcessMessage>("invalid_topic?", 42); auto publisher = subnode->create_publisher<Empty>("invalid_topic?", 42);
}, rclcpp::exceptions::InvalidTopicNameError); }, rclcpp::exceptions::InvalidTopicNameError);
} }
} }

View file

@ -22,9 +22,9 @@
#include "rclcpp/publisher.hpp" #include "rclcpp/publisher.hpp"
#include "rclcpp/rclcpp.hpp" #include "rclcpp/rclcpp.hpp"
#include "rcl_interfaces/msg/intra_process_message.hpp" #include "test_msgs/msg/empty.hpp"
using rcl_interfaces::msg::IntraProcessMessage; using test_msgs::msg::Empty;
/** /**
* Parameterized test. * Parameterized test.
@ -62,7 +62,7 @@ protected:
std::chrono::milliseconds TestPublisherSubscriptionCount::offset = std::chrono::milliseconds(2000); std::chrono::milliseconds TestPublisherSubscriptionCount::offset = std::chrono::milliseconds(2000);
void OnMessage(const rcl_interfaces::msg::IntraProcessMessage::SharedPtr msg) void OnMessage(const test_msgs::msg::Empty::SharedPtr msg)
{ {
(void)msg; (void)msg;
} }
@ -74,12 +74,12 @@ TEST_P(TestPublisherSubscriptionCount, increasing_and_decreasing_counts)
"my_node", "my_node",
"/ns", "/ns",
parameters.node_options[0]); parameters.node_options[0]);
auto publisher = node->create_publisher<IntraProcessMessage>("/topic", 10); auto publisher = node->create_publisher<Empty>("/topic", 10);
EXPECT_EQ(publisher->get_subscription_count(), 0u); EXPECT_EQ(publisher->get_subscription_count(), 0u);
EXPECT_EQ(publisher->get_intra_process_subscription_count(), 0u); EXPECT_EQ(publisher->get_intra_process_subscription_count(), 0u);
{ {
auto sub = node->create_subscription<IntraProcessMessage>("/topic", 10, &OnMessage); auto sub = node->create_subscription<Empty>("/topic", 10, &OnMessage);
rclcpp::sleep_for(offset); rclcpp::sleep_for(offset);
EXPECT_EQ(publisher->get_subscription_count(), 1u); EXPECT_EQ(publisher->get_subscription_count(), 1u);
EXPECT_EQ( EXPECT_EQ(
@ -91,7 +91,7 @@ TEST_P(TestPublisherSubscriptionCount, increasing_and_decreasing_counts)
"/ns", "/ns",
parameters.node_options[1]); parameters.node_options[1]);
auto another_sub = auto another_sub =
another_node->create_subscription<IntraProcessMessage>("/topic", 10, &OnMessage); another_node->create_subscription<Empty>("/topic", 10, &OnMessage);
rclcpp::sleep_for(offset); rclcpp::sleep_for(offset);
EXPECT_EQ(publisher->get_subscription_count(), 2u); EXPECT_EQ(publisher->get_subscription_count(), 2u);

View file

@ -21,12 +21,12 @@
#include "rclcpp/exceptions.hpp" #include "rclcpp/exceptions.hpp"
#include "rclcpp/rclcpp.hpp" #include "rclcpp/rclcpp.hpp"
#include "rcl_interfaces/msg/intra_process_message.hpp" #include "test_msgs/msg/empty.hpp"
class TestSubscription : public ::testing::Test class TestSubscription : public ::testing::Test
{ {
public: public:
void OnMessage(const rcl_interfaces::msg::IntraProcessMessage::SharedPtr msg) void OnMessage(const test_msgs::msg::Empty::SharedPtr msg)
{ {
(void)msg; (void)msg;
} }
@ -72,7 +72,7 @@ class TestSubscriptionInvalidIntraprocessQos
class TestSubscriptionSub : public ::testing::Test class TestSubscriptionSub : public ::testing::Test
{ {
public: public:
void OnMessage(const rcl_interfaces::msg::IntraProcessMessage::SharedPtr msg) void OnMessage(const test_msgs::msg::Empty::SharedPtr msg)
{ {
(void)msg; (void)msg;
} }
@ -105,7 +105,7 @@ public:
{ {
} }
void OnMessage(const rcl_interfaces::msg::IntraProcessMessage::SharedPtr msg) void OnMessage(const test_msgs::msg::Empty::SharedPtr msg)
{ {
(void)msg; (void)msg;
} }
@ -114,15 +114,15 @@ public:
{ {
auto callback = std::bind( auto callback = std::bind(
&SubscriptionClassNodeInheritance::OnMessage, this, std::placeholders::_1); &SubscriptionClassNodeInheritance::OnMessage, this, std::placeholders::_1);
using rcl_interfaces::msg::IntraProcessMessage; using test_msgs::msg::Empty;
auto sub = this->create_subscription<IntraProcessMessage>("topic", 10, callback); auto sub = this->create_subscription<Empty>("topic", 10, callback);
} }
}; };
class SubscriptionClass class SubscriptionClass
{ {
public: public:
void OnMessage(const rcl_interfaces::msg::IntraProcessMessage::SharedPtr msg) void OnMessage(const test_msgs::msg::Empty::SharedPtr msg)
{ {
(void)msg; (void)msg;
} }
@ -131,8 +131,8 @@ public:
{ {
auto node = std::make_shared<rclcpp::Node>("test_subscription_member_callback", "/ns"); auto node = std::make_shared<rclcpp::Node>("test_subscription_member_callback", "/ns");
auto callback = std::bind(&SubscriptionClass::OnMessage, this, std::placeholders::_1); auto callback = std::bind(&SubscriptionClass::OnMessage, this, std::placeholders::_1);
using rcl_interfaces::msg::IntraProcessMessage; using test_msgs::msg::Empty;
auto sub = node->create_subscription<IntraProcessMessage>("topic", 10, callback); auto sub = node->create_subscription<Empty>("topic", 10, callback);
} }
}; };
@ -141,18 +141,18 @@ public:
*/ */
TEST_F(TestSubscription, construction_and_destruction) { TEST_F(TestSubscription, construction_and_destruction) {
initialize(); initialize();
using rcl_interfaces::msg::IntraProcessMessage; using test_msgs::msg::Empty;
auto callback = [](const IntraProcessMessage::SharedPtr msg) { auto callback = [](const Empty::SharedPtr msg) {
(void)msg; (void)msg;
}; };
{ {
auto sub = node->create_subscription<IntraProcessMessage>("topic", 10, callback); auto sub = node->create_subscription<Empty>("topic", 10, callback);
} }
{ {
ASSERT_THROW( ASSERT_THROW(
{ {
auto sub = node->create_subscription<IntraProcessMessage>("invalid_topic?", 10, callback); auto sub = node->create_subscription<Empty>("invalid_topic?", 10, callback);
}, rclcpp::exceptions::InvalidTopicNameError); }, rclcpp::exceptions::InvalidTopicNameError);
} }
} }
@ -161,22 +161,22 @@ TEST_F(TestSubscription, construction_and_destruction) {
Testing subscription construction and destruction for subnodes. Testing subscription construction and destruction for subnodes.
*/ */
TEST_F(TestSubscriptionSub, construction_and_destruction) { TEST_F(TestSubscriptionSub, construction_and_destruction) {
using rcl_interfaces::msg::IntraProcessMessage; using test_msgs::msg::Empty;
auto callback = [](const IntraProcessMessage::SharedPtr msg) { auto callback = [](const Empty::SharedPtr msg) {
(void)msg; (void)msg;
}; };
{ {
auto sub = subnode->create_subscription<IntraProcessMessage>("topic", 1, callback); auto sub = subnode->create_subscription<Empty>("topic", 1, callback);
EXPECT_STREQ(sub->get_topic_name(), "/ns/sub_ns/topic"); EXPECT_STREQ(sub->get_topic_name(), "/ns/sub_ns/topic");
} }
{ {
auto sub = subnode->create_subscription<IntraProcessMessage>("/topic", 1, callback); auto sub = subnode->create_subscription<Empty>("/topic", 1, callback);
EXPECT_STREQ(sub->get_topic_name(), "/topic"); EXPECT_STREQ(sub->get_topic_name(), "/topic");
} }
{ {
auto sub = subnode->create_subscription<IntraProcessMessage>("~/topic", 1, callback); auto sub = subnode->create_subscription<Empty>("~/topic", 1, callback);
std::string expected_topic_name = std::string expected_topic_name =
std::string(node->get_namespace()) + "/" + node->get_name() + "/topic"; std::string(node->get_namespace()) + "/" + node->get_name() + "/topic";
EXPECT_STREQ(sub->get_topic_name(), expected_topic_name.c_str()); EXPECT_STREQ(sub->get_topic_name(), expected_topic_name.c_str());
@ -185,7 +185,7 @@ TEST_F(TestSubscriptionSub, construction_and_destruction) {
{ {
ASSERT_THROW( ASSERT_THROW(
{ {
auto sub = node->create_subscription<IntraProcessMessage>("invalid_topic?", 1, callback); auto sub = node->create_subscription<Empty>("invalid_topic?", 1, callback);
}, rclcpp::exceptions::InvalidTopicNameError); }, rclcpp::exceptions::InvalidTopicNameError);
} }
} }
@ -195,33 +195,33 @@ TEST_F(TestSubscriptionSub, construction_and_destruction) {
*/ */
TEST_F(TestSubscription, various_creation_signatures) { TEST_F(TestSubscription, various_creation_signatures) {
initialize(); initialize();
using rcl_interfaces::msg::IntraProcessMessage; using test_msgs::msg::Empty;
auto cb = [](rcl_interfaces::msg::IntraProcessMessage::SharedPtr) {}; auto cb = [](test_msgs::msg::Empty::SharedPtr) {};
{ {
auto sub = node->create_subscription<IntraProcessMessage>("topic", 1, cb); auto sub = node->create_subscription<Empty>("topic", 1, cb);
(void)sub; (void)sub;
} }
{ {
auto sub = node->create_subscription<IntraProcessMessage>("topic", rclcpp::QoS(1), cb); auto sub = node->create_subscription<Empty>("topic", rclcpp::QoS(1), cb);
(void)sub; (void)sub;
} }
{ {
auto sub = auto sub =
node->create_subscription<IntraProcessMessage>("topic", rclcpp::QoS(rclcpp::KeepLast(1)), cb); node->create_subscription<Empty>("topic", rclcpp::QoS(rclcpp::KeepLast(1)), cb);
(void)sub; (void)sub;
} }
{ {
auto sub = auto sub =
node->create_subscription<IntraProcessMessage>("topic", rclcpp::QoS(rclcpp::KeepAll()), cb); node->create_subscription<Empty>("topic", rclcpp::QoS(rclcpp::KeepAll()), cb);
(void)sub; (void)sub;
} }
{ {
auto sub = node->create_subscription<IntraProcessMessage>( auto sub = node->create_subscription<Empty>(
"topic", 42, cb, rclcpp::SubscriptionOptions()); "topic", 42, cb, rclcpp::SubscriptionOptions());
(void)sub; (void)sub;
} }
{ {
auto sub = rclcpp::create_subscription<IntraProcessMessage>( auto sub = rclcpp::create_subscription<Empty>(
node, "topic", 42, cb, rclcpp::SubscriptionOptions()); node, "topic", 42, cb, rclcpp::SubscriptionOptions());
(void)sub; (void)sub;
} }
@ -232,7 +232,7 @@ TEST_F(TestSubscription, various_creation_signatures) {
*/ */
TEST_F(TestSubscription, callback_bind) { TEST_F(TestSubscription, callback_bind) {
initialize(); initialize();
using rcl_interfaces::msg::IntraProcessMessage; using test_msgs::msg::Empty;
{ {
// Member callback for plain class // Member callback for plain class
SubscriptionClass subscriptionObject; SubscriptionClass subscriptionObject;
@ -248,7 +248,7 @@ TEST_F(TestSubscription, callback_bind) {
// Regression test for https://github.com/ros2/rclcpp/issues/479 where the TEST_F GTest macro // Regression test for https://github.com/ros2/rclcpp/issues/479 where the TEST_F GTest macro
// was interfering with rclcpp's `function_traits`. // was interfering with rclcpp's `function_traits`.
auto callback = std::bind(&TestSubscription::OnMessage, this, std::placeholders::_1); auto callback = std::bind(&TestSubscription::OnMessage, this, std::placeholders::_1);
auto sub = node->create_subscription<IntraProcessMessage>("topic", 1, callback); auto sub = node->create_subscription<Empty>("topic", 1, callback);
} }
} }
@ -258,7 +258,7 @@ TEST_F(TestSubscription, callback_bind) {
TEST_P(TestSubscriptionInvalidIntraprocessQos, test_subscription_throws) { TEST_P(TestSubscriptionInvalidIntraprocessQos, test_subscription_throws) {
initialize(rclcpp::NodeOptions().use_intra_process_comms(true)); initialize(rclcpp::NodeOptions().use_intra_process_comms(true));
rclcpp::QoS qos = GetParam().qos; rclcpp::QoS qos = GetParam().qos;
using rcl_interfaces::msg::IntraProcessMessage; using test_msgs::msg::Empty;
{ {
auto callback = std::bind( auto callback = std::bind(
&TestSubscriptionInvalidIntraprocessQos::OnMessage, &TestSubscriptionInvalidIntraprocessQos::OnMessage,
@ -266,7 +266,7 @@ TEST_P(TestSubscriptionInvalidIntraprocessQos, test_subscription_throws) {
std::placeholders::_1); std::placeholders::_1);
ASSERT_THROW( ASSERT_THROW(
{auto subscription = node->create_subscription<IntraProcessMessage>( {auto subscription = node->create_subscription<Empty>(
"topic", "topic",
qos, qos,
callback);}, callback);},

View file

@ -21,9 +21,9 @@
#include "rclcpp/exceptions.hpp" #include "rclcpp/exceptions.hpp"
#include "rclcpp/rclcpp.hpp" #include "rclcpp/rclcpp.hpp"
#include "rcl_interfaces/msg/intra_process_message.hpp" #include "test_msgs/msg/empty.hpp"
using rcl_interfaces::msg::IntraProcessMessage; using test_msgs::msg::Empty;
struct TestParameters struct TestParameters
{ {
@ -53,7 +53,7 @@ protected:
std::chrono::milliseconds TestSubscriptionPublisherCount::offset = std::chrono::milliseconds(2000); std::chrono::milliseconds TestSubscriptionPublisherCount::offset = std::chrono::milliseconds(2000);
void OnMessage(const rcl_interfaces::msg::IntraProcessMessage::SharedPtr msg) void OnMessage(const test_msgs::msg::Empty::SharedPtr msg)
{ {
(void)msg; (void)msg;
} }
@ -65,11 +65,11 @@ TEST_P(TestSubscriptionPublisherCount, increasing_and_decreasing_counts)
"my_node", "my_node",
"/ns", "/ns",
node_options); node_options);
auto subscription = node->create_subscription<IntraProcessMessage>("/topic", 10, &OnMessage); auto subscription = node->create_subscription<Empty>("/topic", 10, &OnMessage);
EXPECT_EQ(subscription->get_publisher_count(), 0u); EXPECT_EQ(subscription->get_publisher_count(), 0u);
{ {
auto pub = node->create_publisher<IntraProcessMessage>("/topic", 10); auto pub = node->create_publisher<Empty>("/topic", 10);
rclcpp::sleep_for(offset); rclcpp::sleep_for(offset);
EXPECT_EQ(subscription->get_publisher_count(), 1u); EXPECT_EQ(subscription->get_publisher_count(), 1u);
{ {
@ -78,7 +78,7 @@ TEST_P(TestSubscriptionPublisherCount, increasing_and_decreasing_counts)
"/ns", "/ns",
node_options); node_options);
auto another_pub = auto another_pub =
another_node->create_publisher<IntraProcessMessage>("/topic", 10); another_node->create_publisher<Empty>("/topic", 10);
rclcpp::sleep_for(offset); rclcpp::sleep_for(offset);
EXPECT_EQ(subscription->get_publisher_count(), 2u); EXPECT_EQ(subscription->get_publisher_count(), 2u);