Replace std_msgs with test_msgs in executors test (#1310)

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>
This commit is contained in:
Jacob Perron 2020-09-11 13:42:10 -07:00 committed by brawner
parent d2d4c599e0
commit 9f11b1d6a2
2 changed files with 9 additions and 8 deletions

View file

@ -491,7 +491,8 @@ ament_add_gtest(
TIMEOUT 180) TIMEOUT 180)
if(TARGET test_executors) if(TARGET test_executors)
ament_target_dependencies(test_executors ament_target_dependencies(test_executors
"rcl") "rcl"
"test_msgs")
target_link_libraries(test_executors ${PROJECT_NAME}) target_link_libraries(test_executors ${PROJECT_NAME})
endif() endif()

View file

@ -33,7 +33,7 @@
#include "rclcpp/duration.hpp" #include "rclcpp/duration.hpp"
#include "rclcpp/rclcpp.hpp" #include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/empty.hpp" #include "test_msgs/msg/empty.hpp"
using namespace std::chrono_literals; using namespace std::chrono_literals;
@ -61,10 +61,10 @@ public:
callback_count = 0; callback_count = 0;
const std::string topic_name = std::string("topic_") + test_name.str(); const std::string topic_name = std::string("topic_") + test_name.str();
publisher = node->create_publisher<std_msgs::msg::Empty>(topic_name, rclcpp::QoS(10)); publisher = node->create_publisher<test_msgs::msg::Empty>(topic_name, rclcpp::QoS(10));
auto callback = [this](std_msgs::msg::Empty::SharedPtr) {this->callback_count++;}; auto callback = [this](test_msgs::msg::Empty::SharedPtr) {this->callback_count++;};
subscription = subscription =
node->create_subscription<std_msgs::msg::Empty>( node->create_subscription<test_msgs::msg::Empty>(
topic_name, rclcpp::QoS(10), std::move(callback)); topic_name, rclcpp::QoS(10), std::move(callback));
} }
@ -76,8 +76,8 @@ public:
} }
rclcpp::Node::SharedPtr node; rclcpp::Node::SharedPtr node;
rclcpp::Publisher<std_msgs::msg::Empty>::SharedPtr publisher; rclcpp::Publisher<test_msgs::msg::Empty>::SharedPtr publisher;
rclcpp::Subscription<std_msgs::msg::Empty>::SharedPtr subscription; rclcpp::Subscription<test_msgs::msg::Empty>::SharedPtr subscription;
int callback_count; int callback_count;
}; };
@ -323,7 +323,7 @@ TYPED_TEST(TestExecutorsStable, spinSome) {
!spin_exited && !spin_exited &&
(std::chrono::steady_clock::now() - start < 1s)) (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); std::this_thread::sleep_for(1ms);
} }