From 72e22d871c1bfbf9fa44a499376976aa33ae416a Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Fri, 11 Sep 2020 12:15:41 -0700 Subject: [PATCH] Replace std_msgs with test_msgs in executors test Without this change, I am unable to build locally. std_msgs is not declared as a test dependency or find_package'd anywhere, so I'm not sure why CI ever passed the build phase. Signed-off-by: Jacob Perron --- rclcpp/test/CMakeLists.txt | 3 ++- .../test/rclcpp/executors/test_executors.cpp | 22 +++++++++---------- 2 files changed, 13 insertions(+), 12 deletions(-) diff --git a/rclcpp/test/CMakeLists.txt b/rclcpp/test/CMakeLists.txt index 62f53da5cd..1d28d6e737 100644 --- a/rclcpp/test/CMakeLists.txt +++ b/rclcpp/test/CMakeLists.txt @@ -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() diff --git a/rclcpp/test/rclcpp/executors/test_executors.cpp b/rclcpp/test/rclcpp/executors/test_executors.cpp index fe611a53d6..dd306ba938 100644 --- a/rclcpp/test/rclcpp/executors/test_executors.cpp +++ b/rclcpp/test/rclcpp/executors/test_executors.cpp @@ -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; @@ -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(topic_name, rclcpp::QoS(10)); - auto callback = [this](std_msgs::msg::Empty::SharedPtr) {this->callback_count++;}; + publisher = node->create_publisher(topic_name, rclcpp::QoS(10)); + auto callback = [this](test_msgs::msg::Empty::SharedPtr) {this->callback_count++;}; subscription = - node->create_subscription( + node->create_subscription( topic_name, rclcpp::QoS(10), std::move(callback)); } @@ -76,8 +76,8 @@ class TestExecutors : public ::testing::Test } rclcpp::Node::SharedPtr node; - rclcpp::Publisher::SharedPtr publisher; - rclcpp::Subscription::SharedPtr subscription; + rclcpp::Publisher::SharedPtr publisher; + rclcpp::Subscription::SharedPtr subscription; int callback_count; }; @@ -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; @@ -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; @@ -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 @@ -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); } @@ -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); }