Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Replace std_msgs with test_msgs in executors test #1310

Merged
merged 1 commit into from
Sep 11, 2020
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 2 additions & 1 deletion rclcpp/test/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -498,7 +498,8 @@ ament_add_gtest(
TIMEOUT 180)
if(TARGET test_executors)
ament_target_dependencies(test_executors
"rcl")
"rcl"
"test_msgs")
target_link_libraries(test_executors ${PROJECT_NAME})
endif()

Expand Down
22 changes: 11 additions & 11 deletions rclcpp/test/rclcpp/executors/test_executors.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@
#include "rclcpp/duration.hpp"
#include "rclcpp/rclcpp.hpp"

#include "std_msgs/msg/empty.hpp"
#include "test_msgs/msg/empty.hpp"

using namespace std::chrono_literals;

Expand Down Expand Up @@ -61,10 +61,10 @@ class TestExecutors : public ::testing::Test
callback_count = 0;

const std::string topic_name = std::string("topic_") + test_name.str();
publisher = node->create_publisher<std_msgs::msg::Empty>(topic_name, rclcpp::QoS(10));
auto callback = [this](std_msgs::msg::Empty::SharedPtr) {this->callback_count++;};
publisher = node->create_publisher<test_msgs::msg::Empty>(topic_name, rclcpp::QoS(10));
auto callback = [this](test_msgs::msg::Empty::SharedPtr) {this->callback_count++;};
subscription =
node->create_subscription<std_msgs::msg::Empty>(
node->create_subscription<test_msgs::msg::Empty>(
topic_name, rclcpp::QoS(10), std::move(callback));
}

Expand All @@ -76,8 +76,8 @@ class TestExecutors : public ::testing::Test
}

rclcpp::Node::SharedPtr node;
rclcpp::Publisher<std_msgs::msg::Empty>::SharedPtr publisher;
rclcpp::Subscription<std_msgs::msg::Empty>::SharedPtr subscription;
rclcpp::Publisher<test_msgs::msg::Empty>::SharedPtr publisher;
rclcpp::Subscription<test_msgs::msg::Empty>::SharedPtr subscription;
int callback_count;
};

Expand Down Expand Up @@ -293,7 +293,7 @@ TYPED_TEST(TestExecutors, testSpinUntilFutureCompleteNoTimeout) {

// Do some work for longer than the future needs.
for (int i = 0; i < 100; ++i) {
this->publisher->publish(std_msgs::msg::Empty());
this->publisher->publish(test_msgs::msg::Empty());
std::this_thread::sleep_for(1ms);
if (spin_exited) {
break;
Expand Down Expand Up @@ -338,7 +338,7 @@ TYPED_TEST(TestExecutors, testSpinUntilFutureCompleteWithTimeout) {

// Do some work for longer than timeout needs.
for (int i = 0; i < 100; ++i) {
this->publisher->publish(std_msgs::msg::Empty());
this->publisher->publish(test_msgs::msg::Empty());
std::this_thread::sleep_for(1ms);
if (spin_exited) {
break;
Expand Down Expand Up @@ -376,7 +376,7 @@ TYPED_TEST(TestExecutors, testSpinUntilFutureCompleteInterrupted) {
});

// Do some minimal work
this->publisher->publish(std_msgs::msg::Empty());
this->publisher->publish(test_msgs::msg::Empty());
std::this_thread::sleep_for(1ms);

// Force interruption
Expand Down Expand Up @@ -473,7 +473,7 @@ TYPED_TEST(TestExecutorsStable, spinAll) {
!spin_exited &&
(std::chrono::steady_clock::now() - start < 1s))
{
this->publisher->publish(std_msgs::msg::Empty());
this->publisher->publish(test_msgs::msg::Empty());
std::this_thread::sleep_for(1ms);
}

Expand Down Expand Up @@ -514,7 +514,7 @@ TYPED_TEST(TestExecutorsStable, spinSome) {
!spin_exited &&
(std::chrono::steady_clock::now() - start < 1s))
{
this->publisher->publish(std_msgs::msg::Empty());
this->publisher->publish(test_msgs::msg::Empty());
std::this_thread::sleep_for(1ms);
}

Expand Down