@@ -858,7 +858,7 @@ class TestIntraprocessExecutors : public ::testing::Test
858858 test_name << test_info->test_case_name () << " _" << test_info->name ();
859859 node = std::make_shared<rclcpp::Node>(" node" , test_name.str ());
860860
861- callback_count = 0 ;
861+ callback_count = 0u ;
862862
863863 const std::string topic_name = std::string (" topic_" ) + test_name.str ();
864864
@@ -867,7 +867,7 @@ class TestIntraprocessExecutors : public ::testing::Test
867867 publisher = node->create_publisher <test_msgs::msg::Empty>(topic_name, rclcpp::QoS (1 ), po);
868868
869869 auto callback = [this ](test_msgs::msg::Empty::ConstSharedPtr) {
870- this ->callback_count .fetch_add (1 );
870+ this ->callback_count .fetch_add (1u );
871871 };
872872
873873 rclcpp::SubscriptionOptions so;
@@ -889,7 +889,7 @@ class TestIntraprocessExecutors : public ::testing::Test
889889 rclcpp::Node::SharedPtr node;
890890 rclcpp::Publisher<test_msgs::msg::Empty>::SharedPtr publisher;
891891 rclcpp::Subscription<test_msgs::msg::Empty>::SharedPtr subscription;
892- std::atomic_int callback_count;
892+ std::atomic_size_t callback_count;
893893};
894894
895895TYPED_TEST_SUITE (TestIntraprocessExecutors, ExecutorTypes, ExecutorTypeNames);
@@ -905,7 +905,7 @@ TYPED_TEST(TestIntraprocessExecutors, testIntraprocessRetrigger) {
905905 ExecutorType executor;
906906 executor.add_node (this ->node );
907907
908- EXPECT_EQ (0 , this ->callback_count .load ());
908+ EXPECT_EQ (0u , this ->callback_count .load ());
909909 this ->publisher ->publish (test_msgs::msg::Empty ());
910910
911911 // Wait for up to 5 seconds for the first message to come available.
@@ -919,7 +919,7 @@ TYPED_TEST(TestIntraprocessExecutors, testIntraprocessRetrigger) {
919919 EXPECT_EQ (1u , this ->callback_count .load ());
920920
921921 // reset counter
922- this ->callback_count .store (0 );
922+ this ->callback_count .store (0u );
923923
924924 for (size_t ii = 0 ; ii < kNumMessages ; ++ii) {
925925 this ->publisher ->publish (test_msgs::msg::Empty ());
0 commit comments