diff --git a/test_communication/test/test_publisher.cpp b/test_communication/test/test_publisher.cpp index 6c31fa12..36bee08b 100644 --- a/test_communication/test/test_publisher.cpp +++ b/test_communication/test/test_publisher.cpp @@ -44,7 +44,7 @@ void publish( // publish all messages one by one, shorter sleep between each message while (rclcpp::ok() && message_index < messages.size()) { printf("publishing message #%zu\n", message_index + 1); - publisher->publish(messages[message_index]); + publisher->publish(*messages[message_index]); ++message_index; message_rate.sleep(); } diff --git a/test_communication/test/test_publisher_subscriber.cpp b/test_communication/test/test_publisher_subscriber.cpp index 908e8fd5..cbe1557c 100644 --- a/test_communication/test/test_publisher_subscriber.cpp +++ b/test_communication/test/test_publisher_subscriber.cpp @@ -43,7 +43,7 @@ void publish( // publish all messages one by one, shorter sleep between each message while (rclcpp::ok() && message_index < messages.size()) { printf("publishing message #%zu\n", message_index + 1); - publisher->publish(messages[message_index]); + publisher->publish(*messages[message_index]); ++message_index; message_rate.sleep(); } diff --git a/test_communication/test/test_publisher_subscriber_serialized.cpp b/test_communication/test/test_publisher_subscriber_serialized.cpp index bf5c721c..1ed09315 100644 --- a/test_communication/test/test_publisher_subscriber_serialized.cpp +++ b/test_communication/test/test_publisher_subscriber_serialized.cpp @@ -70,11 +70,11 @@ TEST_F(CLASSNAME(TestMessageSerialization, RMW_IMPLEMENTATION), serialized_callb auto publisher = node->create_publisher( "test_publisher_subscriber_serialized_topic"); - auto msg = std::make_shared(); + test_msgs::msg::BasicTypes msg; rclcpp::Rate loop_rate(10); for (auto i = 0u; i < 10; ++i) { - msg->uint8_value = i; + msg.uint8_value = i; publisher->publish(msg); rclcpp::spin_some(node); loop_rate.sleep(); diff --git a/test_communication/test/test_subscription_valid_data.cpp b/test_communication/test/test_subscription_valid_data.cpp index 411d231c..2cb2158f 100644 --- a/test_communication/test/test_subscription_valid_data.cpp +++ b/test_communication/test/test_subscription_valid_data.cpp @@ -15,6 +15,7 @@ #include #include #include +#include #include "rclcpp/rclcpp.hpp" @@ -52,9 +53,9 @@ int main(int argc, char ** argv) // publish a few messages, all with data > 0 while (rclcpp::ok() && index <= 5) { printf("publishing message #%u\n", index); - auto msg = std::make_shared(); + auto msg = std::make_unique(); msg->data = index; - publisher->publish(msg); + publisher->publish(std::move(msg)); ++index; message_rate.sleep(); rclcpp::spin_some(node); diff --git a/test_rclcpp/test/pub_sub_fixtures.hpp b/test_rclcpp/test/pub_sub_fixtures.hpp index f890c6c5..def65553 100644 --- a/test_rclcpp/test/pub_sub_fixtures.hpp +++ b/test_rclcpp/test/pub_sub_fixtures.hpp @@ -36,7 +36,7 @@ single_message_pub_sub_fixture( ) > create_subscription_func, std::function< - void(typename rclcpp::Publisher::SharedPtr, typename MessageT::SharedPtr) + void(typename rclcpp::Publisher::SharedPtr, MessageT) > publish_func, rmw_qos_profile_t custom_qos = rmw_qos_profile_default, std::function pre_subscription_hook = nullptr, @@ -49,8 +49,8 @@ single_message_pub_sub_fixture( auto publisher = node->create_publisher( topic_name, custom_qos); - auto msg = std::make_shared(); - msg->data = 0; + MessageT msg; + msg.data = 0; rclcpp::executors::SingleThreadedExecutor executor; // optionally call the pre subscription hook @@ -78,9 +78,9 @@ single_message_pub_sub_fixture( // this is necessary because sometimes the first message does not go through // this is very common with Connext due to a race condition size_t retry = 0; - msg->data = 0; + msg.data = 0; while (retry < max_retries && counter == 0) { - msg->data++; + msg.data++; // call custom publish function publish_func(publisher, msg); diff --git a/test_rclcpp/test/test_avoid_ros_namespace_conventions_qos.cpp b/test_rclcpp/test/test_avoid_ros_namespace_conventions_qos.cpp index 55536a2a..4d864829 100644 --- a/test_rclcpp/test/test_avoid_ros_namespace_conventions_qos.cpp +++ b/test_rclcpp/test/test_avoid_ros_namespace_conventions_qos.cpp @@ -65,7 +65,7 @@ TEST( auto publish_func = []( rclcpp::Publisher::SharedPtr publisher, - test_rclcpp::msg::UInt32::SharedPtr msg) + test_rclcpp::msg::UInt32 msg) { publisher->publish(msg); }; diff --git a/test_rclcpp/test/test_intra_process.cpp b/test_rclcpp/test/test_intra_process.cpp index 290b23bf..dd91e7bf 100644 --- a/test_rclcpp/test/test_intra_process.cpp +++ b/test_rclcpp/test/test_intra_process.cpp @@ -60,8 +60,8 @@ TEST(CLASSNAME(test_intra_process_within_one_node, RMW_IMPLEMENTATION), nominal_ ASSERT_TRUE(message_info.from_intra_process); }; - auto msg = std::make_shared(); - msg->data = 0; + test_rclcpp::msg::UInt32 msg; + msg.data = 0; rclcpp::executors::SingleThreadedExecutor executor; { @@ -83,7 +83,7 @@ TEST(CLASSNAME(test_intra_process_within_one_node, RMW_IMPLEMENTATION), nominal_ // TODO(gerkey): fix nondeterministic startup behavior std::this_thread::sleep_for(std::chrono::milliseconds(1)); - msg->data = 1; + msg.data = 1; publisher->publish(msg); ASSERT_EQ(0, counter); @@ -107,13 +107,13 @@ TEST(CLASSNAME(test_intra_process_within_one_node, RMW_IMPLEMENTATION), nominal_ executor.spin_node_some(node); ASSERT_EQ(1, counter); - msg->data = 2; + msg.data = 2; publisher->publish(msg); - msg->data = 3; + msg.data = 3; publisher->publish(msg); - msg->data = 4; + msg.data = 4; publisher->publish(msg); - msg->data = 5; + msg.data = 5; publisher->publish(msg); ASSERT_EQ(1, counter); @@ -157,7 +157,7 @@ TEST(CLASSNAME(test_intra_process_within_one_node, RMW_IMPLEMENTATION), nominal_ } // the subscriber goes out of scope and should be not receive any callbacks anymore - msg->data = 6; + msg.data = 6; publisher->publish(msg); std::this_thread::sleep_for(std::chrono::milliseconds(25)); diff --git a/test_rclcpp/test/test_multithreaded.cpp b/test_rclcpp/test/test_multithreaded.cpp index f33263f7..c1b0cc60 100644 --- a/test_rclcpp/test/test_multithreaded.cpp +++ b/test_rclcpp/test/test_multithreaded.cpp @@ -79,8 +79,8 @@ static inline void multi_consumer_pub_sub_test(bool intra_process) int subscriptions_size = static_cast(subscriptions.size()); executor.add_node(node); - auto msg = std::make_shared(); - msg->data = 0; + test_rclcpp::msg::UInt32 msg; + msg.data = 0; // wait a moment for everything to initialize test_rclcpp::wait_for_subscriber(node, node_topic_name); @@ -88,7 +88,7 @@ static inline void multi_consumer_pub_sub_test(bool intra_process) // sanity check that no callbacks have fired EXPECT_EQ(0, counter.load()); - ++msg->data; + ++msg.data; pub->publish(msg); // test spin_some @@ -110,19 +110,19 @@ static inline void multi_consumer_pub_sub_test(bool intra_process) // reset counter counter.store(0); - msg->data = 0; + msg.data = 0; ASSERT_TRUE(std::numeric_limits::max() > (5 * subscriptions.size())); const int expected_count = static_cast(5 * subscriptions.size()); std::mutex publish_mutex; auto publish_callback = [ - msg, &pub, &executor, &counter, &expected_count, &sleep_per_loop, &publish_mutex]( + &msg, &pub, &executor, &counter, &expected_count, &sleep_per_loop, &publish_mutex]( rclcpp::TimerBase & timer) -> void { std::lock_guard lock(publish_mutex); - ++msg->data; - if (msg->data > 5) { + ++msg.data; + if (msg.data > 5) { timer.cancel(); // wait for the last callback to fire before cancelling while (counter.load() != expected_count) { @@ -278,7 +278,6 @@ static inline void multi_access_publisher(bool intra_process) const size_t num_messages = 5 * std::min(executor.get_number_of_threads(), 16); auto pub = node->create_publisher(node_topic_name, num_messages); // callback groups? - auto msg = std::make_shared(); std::atomic_uint subscription_counter(0); auto sub_callback = [&subscription_counter](const test_rclcpp::msg::UInt32::SharedPtr msg) @@ -302,9 +301,10 @@ static inline void multi_access_publisher(bool intra_process) std::atomic_uint timer_counter(0); auto timer_callback = - [&executor, &pub, &msg, &timer_counter, &subscription_counter, &num_messages]( + [&executor, &pub, &timer_counter, &subscription_counter, &num_messages]( rclcpp::TimerBase & timer) { + auto msg = std::make_unique(); if (timer_counter.load() >= num_messages) { timer.cancel(); // Wait for pending subscription callbacks to trigger. @@ -316,7 +316,7 @@ static inline void multi_access_publisher(bool intra_process) } msg->data = ++timer_counter; printf("Publishing message %u\n", timer_counter.load()); - pub->publish(msg); + pub->publish(std::move(msg)); }; std::vector timers; // timers will fire simultaneously in each thread diff --git a/test_rclcpp/test/test_publisher.cpp b/test_rclcpp/test/test_publisher.cpp index 98c5b61c..f85fcac6 100644 --- a/test_rclcpp/test/test_publisher.cpp +++ b/test_rclcpp/test/test_publisher.cpp @@ -60,7 +60,7 @@ TEST(CLASSNAME(test_publisher, RMW_IMPLEMENTATION), publish_with_const_reference auto publish_func = []( rclcpp::Publisher::SharedPtr publisher, - test_rclcpp::msg::UInt32::SharedPtr msg) + test_rclcpp::msg::UInt32 msg) { publisher->publish(msg); }; diff --git a/test_rclcpp/test/test_repeated_publisher_subscriber.cpp b/test_rclcpp/test/test_repeated_publisher_subscriber.cpp index e1a7e7d3..817260e7 100644 --- a/test_rclcpp/test/test_repeated_publisher_subscriber.cpp +++ b/test_rclcpp/test/test_repeated_publisher_subscriber.cpp @@ -39,8 +39,8 @@ TEST(CLASSNAME(test_repeated_publisher_subscriber, RMW_IMPLEMENTATION), subscrip { }; - auto msg = std::make_shared(); - msg->data = 0; + test_rclcpp::msg::UInt32 msg; + msg.data = 0; rclcpp::executors::SingleThreadedExecutor executor; { @@ -56,7 +56,7 @@ TEST(CLASSNAME(test_repeated_publisher_subscriber, RMW_IMPLEMENTATION), subscrip fflush(stdout); executor.spin_node_some(node); - msg->data = 1; + msg.data = 1; publisher->publish(msg); std::this_thread::sleep_for(std::chrono::milliseconds(50)); @@ -83,7 +83,7 @@ TEST(CLASSNAME(test_repeated_publisher_subscriber, RMW_IMPLEMENTATION), subscrip fflush(stdout); executor.spin_node_some(node); - msg->data = 2; + msg.data = 2; publisher->publish(msg); std::this_thread::sleep_for(std::chrono::milliseconds(50)); diff --git a/test_rclcpp/test/test_spin.cpp b/test_rclcpp/test/test_spin.cpp index d3b7e2ae..57a1049a 100644 --- a/test_rclcpp/test/test_spin.cpp +++ b/test_rclcpp/test/test_spin.cpp @@ -199,7 +199,6 @@ TEST(CLASSNAME(test_spin, RMW_IMPLEMENTATION), cancel) { auto node = rclcpp::Node::make_shared("cancel"); rclcpp::executors::SingleThreadedExecutor executor; auto pub = node->create_publisher("cancel", 10); - auto msg = std::make_shared(); auto subscription_callback = [](test_rclcpp::msg::UInt32::ConstSharedPtr) { @@ -209,11 +208,11 @@ TEST(CLASSNAME(test_spin, RMW_IMPLEMENTATION), cancel) { auto subscription = node->create_subscription( "cancel", subscription_callback, 10); - auto cancel_callback = [&executor, &pub, &msg]() + auto cancel_callback = [&executor, &pub]() { executor.cancel(); // Try to publish after canceling. The callback should never trigger. - pub->publish(msg); + pub->publish(test_rclcpp::msg::UInt32()); }; auto timer = node->create_wall_timer(std::chrono::milliseconds(5), cancel_callback); executor.add_node(node); diff --git a/test_rclcpp/test/test_subscription.cpp b/test_rclcpp/test/test_subscription.cpp index 1785df4e..ef28c1e4 100644 --- a/test_rclcpp/test/test_subscription.cpp +++ b/test_rclcpp/test/test_subscription.cpp @@ -80,8 +80,8 @@ TEST(CLASSNAME(test_subscription, RMW_IMPLEMENTATION), subscription_and_spinning sub_called.set_value(); }; - auto msg = std::make_shared(); - msg->data = 0; + test_rclcpp::msg::UInt32 msg; + msg.data = 0; rclcpp::executors::SingleThreadedExecutor executor; executor.add_node(node); @@ -103,7 +103,7 @@ TEST(CLASSNAME(test_subscription, RMW_IMPLEMENTATION), subscription_and_spinning executor.spin_some(); ASSERT_EQ(0, counter); - msg->data = 1; + msg.data = 1; publisher->publish(msg); ASSERT_EQ(0, counter); @@ -120,13 +120,13 @@ TEST(CLASSNAME(test_subscription, RMW_IMPLEMENTATION), subscription_and_spinning executor.spin_some(); ASSERT_EQ(1, counter); - msg->data = 2; + msg.data = 2; publisher->publish(msg); - msg->data = 3; + msg.data = 3; publisher->publish(msg); - msg->data = 4; + msg.data = 4; publisher->publish(msg); - msg->data = 5; + msg.data = 5; publisher->publish(msg); ASSERT_EQ(1, counter); @@ -160,7 +160,7 @@ TEST(CLASSNAME(test_subscription, RMW_IMPLEMENTATION), subscription_and_spinning } // the subscriber goes out of scope and should be not receive any callbacks anymore - msg->data = 6; + msg.data = 6; publisher->publish(msg); // check that no further callbacks have been invoked @@ -198,11 +198,9 @@ TEST(CLASSNAME(test_subscription, RMW_IMPLEMENTATION), subscription_shared_ptr_c auto publish_func = []( rclcpp::Publisher::SharedPtr publisher, - test_rclcpp::msg::UInt32::SharedPtr msg) + test_rclcpp::msg::UInt32 msg) { - // Create a ConstSharedPtr message to publish - test_rclcpp::msg::UInt32::ConstSharedPtr const_msg(msg); - publisher->publish(const_msg); + publisher->publish(msg); }; // call the test template single_message_pub_sub_fixture( @@ -246,11 +244,9 @@ TEST(CLASSNAME(test_subscription, RMW_IMPLEMENTATION), auto publish_func = []( rclcpp::Publisher::SharedPtr publisher, - test_rclcpp::msg::UInt32::SharedPtr msg) + test_rclcpp::msg::UInt32 msg) { - // Create a ConstSharedPtr message to publish - test_rclcpp::msg::UInt32::ConstSharedPtr const_msg(msg); - publisher->publish(const_msg); + publisher->publish(msg); }; // call the test template single_message_pub_sub_fixture( @@ -280,11 +276,9 @@ TEST(CLASSNAME(test_subscription, RMW_IMPLEMENTATION), auto publish_func = []( rclcpp::Publisher::SharedPtr publisher, - test_rclcpp::msg::UInt32::SharedPtr msg) + test_rclcpp::msg::UInt32 msg) { - // Create a ConstSharedPtr message to publish - test_rclcpp::msg::UInt32::ConstSharedPtr const_msg(msg); - publisher->publish(const_msg); + publisher->publish(msg); }; // call the test template single_message_pub_sub_fixture( @@ -318,7 +312,7 @@ TEST(CLASSNAME(test_subscription, RMW_IMPLEMENTATION), subscription_shared_ptr_c auto publish_func = []( rclcpp::Publisher::SharedPtr publisher, - test_rclcpp::msg::UInt32::SharedPtr msg) + test_rclcpp::msg::UInt32 msg) { publisher->publish(msg); }; @@ -352,11 +346,9 @@ TEST(CLASSNAME(test_subscription, RMW_IMPLEMENTATION), spin_before_subscription) auto publish_func = []( rclcpp::Publisher::SharedPtr publisher, - test_rclcpp::msg::UInt32::SharedPtr msg) + test_rclcpp::msg::UInt32 msg) { - // Create a ConstSharedPtr message to publish - test_rclcpp::msg::UInt32::ConstSharedPtr const_msg(msg); - publisher->publish(const_msg); + publisher->publish(msg); }; // code for custom "pre subscription" hook auto pre_subscription_hook = diff --git a/test_security/test/test_secure_publisher.cpp b/test_security/test/test_secure_publisher.cpp index 1dea6c77..c985b546 100644 --- a/test_security/test/test_secure_publisher.cpp +++ b/test_security/test/test_secure_publisher.cpp @@ -45,7 +45,7 @@ int8_t attempt_publish( // publish all messages one by one, shorter sleep between each message while (rclcpp::ok() && message_index < messages.size()) { printf("publishing message #%zu\n", message_index + 1); - publisher->publish(messages[message_index]); + publisher->publish(*messages[message_index]); ++message_index; message_rate.sleep(); }