@@ -615,7 +615,7 @@ class TestIntraprocessExecutors : public ::testing::Test
615615 test_name << test_info->test_case_name () << " _" << test_info->name ();
616616 node = std::make_shared<rclcpp::Node>(" node" , test_name.str ());
617617
618- callback_count = 0 ;
618+ callback_count = 0u ;
619619
620620 const std::string topic_name = std::string (" topic_" ) + test_name.str ();
621621
@@ -624,7 +624,7 @@ class TestIntraprocessExecutors : public ::testing::Test
624624 publisher = node->create_publisher <test_msgs::msg::Empty>(topic_name, rclcpp::QoS (1 ), po);
625625
626626 auto callback = [this ](test_msgs::msg::Empty::ConstSharedPtr) {
627- this ->callback_count .fetch_add (1 );
627+ this ->callback_count .fetch_add (1u );
628628 };
629629
630630 rclcpp::SubscriptionOptions so;
@@ -646,7 +646,7 @@ class TestIntraprocessExecutors : public ::testing::Test
646646 rclcpp::Node::SharedPtr node;
647647 rclcpp::Publisher<test_msgs::msg::Empty>::SharedPtr publisher;
648648 rclcpp::Subscription<test_msgs::msg::Empty>::SharedPtr subscription;
649- std::atomic_int callback_count;
649+ std::atomic_size_t callback_count;
650650};
651651
652652TYPED_TEST_SUITE (TestIntraprocessExecutors, ExecutorTypes, ExecutorTypeNames);
@@ -662,7 +662,7 @@ TYPED_TEST(TestIntraprocessExecutors, testIntraprocessRetrigger) {
662662 ExecutorType executor;
663663 executor.add_node (this ->node );
664664
665- EXPECT_EQ (0 , this ->callback_count .load ());
665+ EXPECT_EQ (0u , this ->callback_count .load ());
666666 this ->publisher ->publish (test_msgs::msg::Empty ());
667667
668668 // Wait for up to 5 seconds for the first message to come available.
@@ -676,7 +676,7 @@ TYPED_TEST(TestIntraprocessExecutors, testIntraprocessRetrigger) {
676676 EXPECT_EQ (1u , this ->callback_count .load ());
677677
678678 // reset counter
679- this ->callback_count .store (0 );
679+ this ->callback_count .store (0u );
680680
681681 for (size_t ii = 0 ; ii < kNumMessages ; ++ii) {
682682 this ->publisher ->publish (test_msgs::msg::Empty ());
0 commit comments