Skip to content

Commit

Permalink
Replace std_msgs with test_msgs in executors test (#1310)
Browse files Browse the repository at this point in the history
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 <jacob@openrobotics.org>
  • Loading branch information
jacobperron authored and brawner committed Oct 19, 2020
1 parent d2d4c59 commit 9f11b1d
Show file tree
Hide file tree
Showing 2 changed files with 9 additions and 8 deletions.
3 changes: 2 additions & 1 deletion rclcpp/test/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -491,7 +491,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
14 changes: 7 additions & 7 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 @@ -323,7 +323,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

0 comments on commit 9f11b1d

Please sign in to comment.