Skip to content

Commit

Permalink
warning: comparison of integer expressions of different signedness (#…
Browse files Browse the repository at this point in the history
…2219)

  #2167 (comment)

Signed-off-by: Tomoya Fujita <Tomoya.Fujita@sony.com>
(cherry picked from commit fe2e0e4)
  • Loading branch information
fujitatomoya authored and mergify[bot] committed Jun 22, 2023
1 parent 5f7485f commit fe85e51
Showing 1 changed file with 5 additions and 5 deletions.
10 changes: 5 additions & 5 deletions rclcpp/test/rclcpp/executors/test_executors.cpp
Expand Up @@ -615,7 +615,7 @@ class TestIntraprocessExecutors : public ::testing::Test
test_name << test_info->test_case_name() << "_" << test_info->name();
node = std::make_shared<rclcpp::Node>("node", test_name.str());

callback_count = 0;
callback_count = 0u;

const std::string topic_name = std::string("topic_") + test_name.str();

Expand All @@ -624,7 +624,7 @@ class TestIntraprocessExecutors : public ::testing::Test
publisher = node->create_publisher<test_msgs::msg::Empty>(topic_name, rclcpp::QoS(1), po);

auto callback = [this](test_msgs::msg::Empty::ConstSharedPtr) {
this->callback_count.fetch_add(1);
this->callback_count.fetch_add(1u);
};

rclcpp::SubscriptionOptions so;
Expand All @@ -646,7 +646,7 @@ class TestIntraprocessExecutors : public ::testing::Test
rclcpp::Node::SharedPtr node;
rclcpp::Publisher<test_msgs::msg::Empty>::SharedPtr publisher;
rclcpp::Subscription<test_msgs::msg::Empty>::SharedPtr subscription;
std::atomic_int callback_count;
std::atomic_size_t callback_count;
};

TYPED_TEST_SUITE(TestIntraprocessExecutors, ExecutorTypes, ExecutorTypeNames);
Expand All @@ -662,7 +662,7 @@ TYPED_TEST(TestIntraprocessExecutors, testIntraprocessRetrigger) {
ExecutorType executor;
executor.add_node(this->node);

EXPECT_EQ(0, this->callback_count.load());
EXPECT_EQ(0u, this->callback_count.load());
this->publisher->publish(test_msgs::msg::Empty());

// Wait for up to 5 seconds for the first message to come available.
Expand All @@ -676,7 +676,7 @@ TYPED_TEST(TestIntraprocessExecutors, testIntraprocessRetrigger) {
EXPECT_EQ(1u, this->callback_count.load());

// reset counter
this->callback_count.store(0);
this->callback_count.store(0u);

for (size_t ii = 0; ii < kNumMessages; ++ii) {
this->publisher->publish(test_msgs::msg::Empty());
Expand Down

0 comments on commit fe85e51

Please sign in to comment.