From 9a469a203bf8db9fafe9bdfb4169c458e57ac3df Mon Sep 17 00:00:00 2001 From: Chris Lalancette Date: Fri, 8 Dec 2023 12:27:16 -0500 Subject: [PATCH] Cleanup header includes in test_quality_of_service. (#533) Noticed while doing other debugging. Signed-off-by: Chris Lalancette --- .../include/test_quality_of_service/qos_utilities.hpp | 5 ++--- test_quality_of_service/test/qos_test_publisher.cpp | 5 +++++ test_quality_of_service/test/qos_test_subscriber.cpp | 6 ++---- test_quality_of_service/test/qos_utilities.cpp | 5 ++++- 4 files changed, 13 insertions(+), 8 deletions(-) diff --git a/test_quality_of_service/include/test_quality_of_service/qos_utilities.hpp b/test_quality_of_service/include/test_quality_of_service/qos_utilities.hpp index 9ae01663..ce2c7d0a 100644 --- a/test_quality_of_service/include/test_quality_of_service/qos_utilities.hpp +++ b/test_quality_of_service/include/test_quality_of_service/qos_utilities.hpp @@ -16,17 +16,16 @@ #define TEST_QUALITY_OF_SERVICE__QOS_UTILITIES_HPP_ #include +#include #include -#include #include +#include #include #include "gtest/gtest.h" #include "rcutils/macros.h" #include "rclcpp/rclcpp.hpp" -#include "std_msgs/msg/string.hpp" -#include "test_quality_of_service/visibility_control.hpp" #ifdef RMW_IMPLEMENTATION # define CLASSNAME_(NAME, SUFFIX) NAME ## __ ## SUFFIX diff --git a/test_quality_of_service/test/qos_test_publisher.cpp b/test_quality_of_service/test/qos_test_publisher.cpp index 2132214b..a2201c50 100644 --- a/test_quality_of_service/test/qos_test_publisher.cpp +++ b/test_quality_of_service/test/qos_test_publisher.cpp @@ -12,8 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include +#include #include +#include "rclcpp/rclcpp.hpp" +#include "std_msgs/msg/string.hpp" + #include "test_quality_of_service/qos_test_publisher.hpp" #include "test_quality_of_service/qos_test_node.hpp" diff --git a/test_quality_of_service/test/qos_test_subscriber.cpp b/test_quality_of_service/test/qos_test_subscriber.cpp index 5d0471c4..ac6c755c 100644 --- a/test_quality_of_service/test/qos_test_subscriber.cpp +++ b/test_quality_of_service/test/qos_test_subscriber.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include +#include #include #include @@ -22,8 +22,6 @@ #include "test_quality_of_service/qos_test_node.hpp" #include "test_quality_of_service/qos_test_subscriber.hpp" -using std::placeholders::_1; - QosTestSubscriber::QosTestSubscriber( const std::string & name, const std::string & topic, @@ -49,7 +47,7 @@ void QosTestSubscriber::setup_start() subscription_ = create_subscription( topic_, qos_options_, - std::bind(&QosTestSubscriber::listen_to_message, this, _1), + std::bind(&QosTestSubscriber::listen_to_message, this, std::placeholders::_1), sub_options_); } } diff --git a/test_quality_of_service/test/qos_utilities.cpp b/test_quality_of_service/test/qos_utilities.cpp index c228d7d2..90697e3b 100644 --- a/test_quality_of_service/test/qos_utilities.cpp +++ b/test_quality_of_service/test/qos_utilities.cpp @@ -12,11 +12,14 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include +#include #include #include #include #include +#include + +#include "rclcpp/rclcpp.hpp" #include "test_quality_of_service/qos_test_publisher.hpp" #include "test_quality_of_service/qos_test_subscriber.hpp"